Initial commit

This commit is contained in:
Thomas Klaehn 2019-10-09 13:45:38 +02:00
commit 2461dbfb92
117 changed files with 68364 additions and 0 deletions

2
.gitignore vendored Normal file
View File

@ -0,0 +1,2 @@
exe/
obj/

53
.vscode/launch.json vendored Normal file
View File

@ -0,0 +1,53 @@
{
// Use IntelliSense to learn about possible attributes.
// Hover to view descriptions of existing attributes.
// For more information, visit: https://go.microsoft.com/fwlink/?linkid=830387
"version": "0.2.0",
"configurations": [
{
"name": "Launch TCM",
"type": "cppdbg",
"request": "launch",
"program": "${workspaceFolder}/exe/blinky.axf",
"args": [],
"stopAtEntry": true,
"cwd": "${workspaceFolder}",
"environment": [],
"MIMode": "gdb",
"miDebuggerPath": "arm-none-eabi-gdb",
// "debugServerPath": "JLinkGDBServerCLExe",
// "debugServerArgs": "-select USB -device Cortex-R4 -endian little -if JTAG -speed 1000 -ir -LocalhostOnly",
// "serverStarted": "Listening on TCP/IP port 2331",
"logging": {
"engineLogging": true,
"exceptions": true,
"moduleLoad": true,
"programOutput": true,
"trace": true,
"traceResponse": true
},
"setupCommands": [
{
"description": "Connect to gdb server.",
"text": "target remote localhost:3333",
"ignoreFailures": false
},
{
"description": "Load executable into debugger.",
"text": "file ${workspaceFolder}/exe/blinky.axf",
"ignoreFailures": false
},
{
"description": "Set stack pointer",
"text": "set $sp = g_pfnVectors[0]",
"ignoreFailures": false
},
{
"description": "Set program counter",
"text": "set $pc = g_pfnVectors[1]",
"ignoreFailures": false
}
]
}
]
}

33
.vscode/tasks.json vendored Normal file
View File

@ -0,0 +1,33 @@
{
"version": "2.0.0",
"type": "shell",
"command": "make",
"echoCommand": true,
"problemMatcher": {
"base": "$gcc",
},
"presentation": {
"focus": true,
"reveal": "always",
"panel": "shared",
"clear": true,
},
"tasks": [
{
"label": "all",
"args": ["all"],
"group": {
"kind": "build",
"isDefault": true
}
},
{
"label": "clean",
"args": ["clean"],
"group": {
"kind": "build",
"isDefault": true
}
}
]
}

43
Makefile Normal file
View File

@ -0,0 +1,43 @@
ROOT=../../..
include $/makedefs
VPATH+=common
IPATH=.
IPATH+=inc
IPATH+=driverlib
IPATH+=common
all: ${OBJDIR} ${BINDIR}
all: ${BINDIR}/blinky.axf
clean:
rm -rf ${OBJDIR} ${wildcard *~}
rm -rf ${BINDIR} ${wildcard *~}
${OBJDIR}:
@mkdir -p ${OBJDIR}
${BINDIR}:
@mkdir -p ${BINDIR}
${BINDIR}/blinky.axf: ${OBJDIR}/main.o
${BINDIR}/blinky.axf: ${OBJDIR}/pinmux.o
${BINDIR}/blinky.axf: ${OBJDIR}/gpio_if.o
${BINDIR}/blinky.axf: ${OBJDIR}/gpio.o
${BINDIR}/blinky.axf: ${OBJDIR}/utils.o
${BINDIR}/blinky.axf: ${OBJDIR}/interrupt.o
${BINDIR}/blinky.axf: ${OBJDIR}/pin.o
${BINDIR}/blinky.axf: ${OBJDIR}/prcm.o
${BINDIR}/blinky.axf: ${OBJDIR}/cpu.o
${BINDIR}/blinky.axf: ${OBJDIR}/startup_${COMPILER}.o
SCATTERgcc_blinky=gnu.ld
ENTRY_blinky=ResetISR
ifneq (${MAKECMDGOALS},clean)
-include ${wildcard ${OBJDIR}/*.d} __dummy__
endif

36
README.md Normal file
View File

@ -0,0 +1,36 @@
# CC3200
## Overview
All digital pins of the device can be used as general-purpose input/output
(GPIO). GPIOs can be used for various purposes. The GPIO module on the CC3200
consists of four GPIO blocks:
* GPIO A0
* GPIO A1
* GPIO A2
* GPIO A3
Each GPIO block provides eight GPIOs. The GPIO module supports 30 programmable
GPIO pins, depending on the peripheral used.
## Application details
The objective of this application is to showcase GPIO control using Driverlib
API calls. The LEDs connected to the GPIOs on the LaunchPad are used to
indicate GPIO output. The GPIOs are driven high and low periodically in order
to turn the LEDs on and off.
## Source Files briefly explained
* **main.c**: Contains the core logic to drive GPIOs and inturn blink the LEDs.
* **gpio\_if.c**: Contains the Driverlib API calls to drive the GPIOs
* **pinmux.c**: Generated by the PinMUX utility. GPIO pins are brought out on
the device boundry using the Driverlib Pinmux API calls.
* **startup\_\*.c** - Initialize vector table and IDE related functions
## Usage
1. Run the reference application.
* Open the project in CCS/IAR. Build the application and debug to load to the device, or flash the binary using [UniFlash](http://processors.wiki.ti.com/index.php/CC3100_%26_CC3200_UniFlash_Quick_Start_Guide).
2. Verify the LaunchPad LEDs (D5, D6 and D7) toggle on and off.

229
common/button_if.c Normal file
View File

@ -0,0 +1,229 @@
//*****************************************************************************
// button_if.c
//
// CC3200 Launchpad button interface APIs
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#include <stdlib.h>
#include "hw_types.h"
#include "hw_ints.h"
#include "rom.h"
#include "rom_map.h"
#include "gpio.h"
#include "interrupt.h"
#include "pin.h"
#include "hw_memmap.h"
#ifdef SL_PLATFORM_MULTI_THREADED /* If OS-based application */
#include "osi.h"
#endif
#include "button_if.h"
P_INT_HANDLER g_S2InterruptHdl;
P_INT_HANDLER g_S3InterruptHdl;
//*****************************************************************************
//
//! GPIO Interrupt Handler for S3 button
//!
//! \param None
//!
//! \return None
//
//*****************************************************************************
void GPIOs3IntHandler()
{
unsigned long ulPinState = GPIOIntStatus(GPIOA1_BASE,1);
if(ulPinState & GPIO_PIN_5)
{
Button_IF_DisableInterrupt(SW3);
g_S3InterruptHdl();
}
}
//*****************************************************************************
//
//! GPIO Interrupt Handler for S2 button
//!
//! \param None
//!
//! \return None
//
//*****************************************************************************
void GPIOs2IntHandler()
{
unsigned long ulPinState = GPIOIntStatus(GPIOA2_BASE,1);
if(ulPinState & GPIO_PIN_6)
{
Button_IF_DisableInterrupt(SW2);
g_S2InterruptHdl();
}
}
//*****************************************************************************
//
//! \brief Initialize Push Button GPIO
//!
//! \param[in] S2InterruptHdl GPIO Interrupt Handler for SW2 LP button
//! \param[in] S3InterruptHdl GPIO Interrupt Handler for SW3 LP button
//!
//! \return none
//!
//! \brief Initializes Push Button Ports and Pins
//
//*****************************************************************************
void Button_IF_Init(P_INT_HANDLER S2InterruptHdl,P_INT_HANDLER S3InterruptHdl )
{
if(S3InterruptHdl != NULL)
{
//
// Set Interrupt Type for GPIO
//
MAP_GPIOIntTypeSet(GPIOA1_BASE,GPIO_PIN_5,GPIO_FALLING_EDGE);
g_S3InterruptHdl = S3InterruptHdl;
//
// Register Interrupt handler
//
#if defined(USE_TIRTOS) || defined(USE_FREERTOS) || defined(SL_PLATFORM_MULTI_THREADED)
// USE_TIRTOS: if app uses TI-RTOS (either networking/non-networking)
// USE_FREERTOS: if app uses Free-RTOS (either networking/non-networking)
// SL_PLATFORM_MULTI_THREADED: if app uses any OS + networking(simplelink)
osi_InterruptRegister(INT_GPIOA1,(P_OSI_INTR_ENTRY)GPIOs3IntHandler, \
INT_PRIORITY_LVL_1);
#else
MAP_IntPrioritySet(INT_GPIOA1, INT_PRIORITY_LVL_1);
MAP_GPIOIntRegister(GPIOA1_BASE, GPIOs3IntHandler);
#endif
//
// Enable Interrupt
//
MAP_GPIOIntClear(GPIOA1_BASE,GPIO_PIN_5);
MAP_GPIOIntEnable(GPIOA1_BASE,GPIO_INT_PIN_5);
}
if(S2InterruptHdl != NULL)
{
//
// Set Interrupt Type for GPIO
//
MAP_GPIOIntTypeSet(GPIOA2_BASE,GPIO_PIN_6,GPIO_FALLING_EDGE);
g_S2InterruptHdl = S2InterruptHdl;
//
// Register Interrupt handler
//
#if defined(USE_TIRTOS) || defined(USE_FREERTOS) || defined(SL_PLATFORM_MULTI_THREADED)
// USE_TIRTOS: if app uses TI-RTOS (either networking/non-networking)
// USE_FREERTOS: if app uses Free-RTOS (either networking/non-networking)
// SL_PLATFORM_MULTI_THREADED: if app uses any OS + networking(simplelink)
osi_InterruptRegister(INT_GPIOA2,(P_OSI_INTR_ENTRY)GPIOs2IntHandler, \
INT_PRIORITY_LVL_1);
#else
MAP_IntPrioritySet(INT_GPIOA2, INT_PRIORITY_LVL_1);
MAP_GPIOIntRegister(GPIOA2_BASE, GPIOs2IntHandler);
#endif
//
// Enable Interrupt
//
MAP_GPIOIntClear(GPIOA2_BASE,GPIO_PIN_6);
MAP_GPIOIntEnable(GPIOA2_BASE,GPIO_INT_PIN_6);
}
}
//*****************************************************************************
//
//! \brief Enables Push Button GPIO Interrupt
//!
//! \param[in] ucSwitch Push Button Swich Enum - SW2,SW3
//!
//! \return none
//!
//
//*****************************************************************************
void Button_IF_EnableInterrupt(unsigned char ucSwitch)
{
if(ucSwitch & SW2)
{
//Enable GPIO Interrupt
MAP_GPIOIntClear(GPIOA2_BASE,GPIO_PIN_6);
MAP_IntPendClear(INT_GPIOA2);
MAP_IntEnable(INT_GPIOA2);
MAP_GPIOIntEnable(GPIOA2_BASE,GPIO_PIN_6);
}
if(ucSwitch & SW3)
{
//Enable GPIO Interrupt
MAP_GPIOIntClear(GPIOA1_BASE,GPIO_PIN_5);
MAP_IntPendClear(INT_GPIOA1);
MAP_IntEnable(INT_GPIOA1);
MAP_GPIOIntEnable(GPIOA1_BASE,GPIO_PIN_5);
}
}
//*****************************************************************************
//
//! \brief Disables Push Button GPIO Interrupt
//!
//! \param[in] ucSwitch Push Button Swich Enum - SW2,SW3
//!
//! \return none
//!
//
//*****************************************************************************
void Button_IF_DisableInterrupt(unsigned char ucSwitch)
{
if(ucSwitch & SW2)
{
//Clear and Disable GPIO Interrupt
MAP_GPIOIntDisable(GPIOA2_BASE,GPIO_PIN_6);
MAP_GPIOIntClear(GPIOA2_BASE,GPIO_PIN_6);
MAP_IntDisable(INT_GPIOA2);
}
if(ucSwitch & SW3)
{
//Clear and Disable GPIO Interrupt
MAP_GPIOIntDisable(GPIOA1_BASE,GPIO_PIN_5);
MAP_GPIOIntClear(GPIOA1_BASE,GPIO_PIN_5);
MAP_IntDisable(INT_GPIOA1);
}
}

79
common/button_if.h Normal file
View File

@ -0,0 +1,79 @@
//*****************************************************************************
// button_if.h
//
// CC3200 Launchpad button interface function prototypes
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#ifndef __BUTTONIF_H__
#define __BUTTONIF_H__
//*****************************************************************************
//
// If building with a C++ compiler, make all of the definitions in this header
// have a C binding.
//
//*****************************************************************************
#ifdef __cplusplus
extern "C"
{
#endif
typedef enum
{
NO_SW,
SW1 = 0x1, /* SW1/Reset Button */
SW2 = 0x2, /* SW2/GP22/Pin15 */
SW3 = 0x4 /* SW3/GP13/Pin4 */
}eSwNum;
typedef void (*P_INT_HANDLER)(void);
void GPIOs2IntHandler();
void GPIOs3IntHandler();
void Button_IF_Init(P_INT_HANDLER S2InterruptHdl,P_INT_HANDLER S1InterruptHdl );
void Button_IF_EnableInterrupt(unsigned char ucSwitch);
void Button_IF_DisableInterrupt(unsigned char ucSwitch);
//*****************************************************************************
//
// Mark the end of the C bindings section for C++ compilers.
//
//*****************************************************************************
#ifdef __cplusplus
}
#endif
#endif // __GPIOIF_H__

165
common/common.h Normal file
View File

@ -0,0 +1,165 @@
//*****************************************************************************
// common.h
//
// Contains the common macro/enum definitions used by different networking apps
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#ifndef __COMMON__H__
#define __COMMON__H__
//*****************************************************************************
//
// If building with a C++ compiler, make all of the definitions in this header
// have a C binding.
//
//*****************************************************************************
#ifdef __cplusplus
extern "C"
{
#endif
//
// Values for below macros shall be modified as per access-point(AP) properties
// SimpleLink device will connect to following AP when application is executed
//
#define SSID_NAME "cc3200demo" /* AP SSID */
#define SECURITY_TYPE SL_SEC_TYPE_OPEN/* Security type (OPEN or WEP or WPA*/
#define SECURITY_KEY "" /* Password of the secured AP */
#define SSID_LEN_MAX 32
#define BSSID_LEN_MAX 6
#ifdef NOTERM
#define UART_PRINT(x,...)
#define DBG_PRINT(x,...)
#define ERR_PRINT(x)
#else
#define UART_PRINT Report
#define DBG_PRINT Report
#define ERR_PRINT(x) Report("Error [%d] at line [%d] in function [%s] \n\r",x,__LINE__,__FUNCTION__)
#endif
// Loop forever, user can change it as per application's requirement
#define LOOP_FOREVER() \
{\
while(1); \
}
// check the error code and handle it
#define ASSERT_ON_ERROR(error_code)\
{\
if(error_code < 0) \
{\
ERR_PRINT(error_code);\
return error_code;\
}\
}
#define SPAWN_TASK_PRIORITY 9
#define SL_STOP_TIMEOUT 200
#define UNUSED(x) ((x) = (x))
#define SUCCESS 0
#define FAILURE -1
// Status bits - These are used to set/reset the corresponding bits in
// given variable
typedef enum{
STATUS_BIT_NWP_INIT = 0, // If this bit is set: Network Processor is
// powered up
STATUS_BIT_CONNECTION, // If this bit is set: the device is connected to
// the AP or client is connected to device (AP)
STATUS_BIT_IP_LEASED, // If this bit is set: the device has leased IP to
// any connected client
STATUS_BIT_IP_AQUIRED, // If this bit is set: the device has acquired an IP
STATUS_BIT_SMARTCONFIG_START, // If this bit is set: the SmartConfiguration
// process is started from SmartConfig app
STATUS_BIT_P2P_DEV_FOUND, // If this bit is set: the device (P2P mode)
// found any p2p-device in scan
STATUS_BIT_P2P_REQ_RECEIVED, // If this bit is set: the device (P2P mode)
// found any p2p-negotiation request
STATUS_BIT_CONNECTION_FAILED, // If this bit is set: the device(P2P mode)
// connection to client(or reverse way) is failed
STATUS_BIT_PING_DONE // If this bit is set: the device has completed
// the ping operation
}e_StatusBits;
#define CLR_STATUS_BIT_ALL(status_variable) (status_variable = 0)
#define SET_STATUS_BIT(status_variable, bit) status_variable |= (1<<(bit))
#define CLR_STATUS_BIT(status_variable, bit) status_variable &= ~(1<<(bit))
#define CLR_STATUS_BIT_ALL(status_variable) (status_variable = 0)
#define GET_STATUS_BIT(status_variable, bit) (0 != (status_variable & (1<<(bit))))
#define IS_NW_PROCSR_ON(status_variable) GET_STATUS_BIT(status_variable,\
STATUS_BIT_NWP_INIT)
#define IS_CONNECTED(status_variable) GET_STATUS_BIT(status_variable,\
STATUS_BIT_CONNECTION)
#define IS_IP_LEASED(status_variable) GET_STATUS_BIT(status_variable,\
STATUS_BIT_IP_LEASED)
#define IS_IP_ACQUIRED(status_variable) GET_STATUS_BIT(status_variable,\
STATUS_BIT_IP_AQUIRED)
#define IS_SMART_CFG_START(status_variable) GET_STATUS_BIT(status_variable,\
STATUS_BIT_SMARTCONFIG_START)
#define IS_P2P_DEV_FOUND(status_variable) GET_STATUS_BIT(status_variable,\
STATUS_BIT_P2P_DEV_FOUND)
#define IS_P2P_REQ_RCVD(status_variable) GET_STATUS_BIT(status_variable,\
STATUS_BIT_P2P_REQ_RECEIVED)
#define IS_CONNECT_FAILED(status_variable) GET_STATUS_BIT(status_variable,\
STATUS_BIT_CONNECTION_FAILED)
#define IS_PING_DONE(status_variable) GET_STATUS_BIT(status_variable,\
STATUS_BIT_PING_DONE)
//*****************************************************************************
//
// Mark the end of the C bindings section for C++ compilers.
//
//*****************************************************************************
#ifdef __cplusplus
}
#endif
#endif //__COMMON__H__

474
common/gpio_if.c Normal file
View File

@ -0,0 +1,474 @@
//*****************************************************************************
// gpio_if.c
//
// GPIO interface APIs, this common interface file helps to configure,
// set/toggle only 3 GPIO pins which are connected to 3 LEDs of CC32xx Launchpad
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
// Standard includes
#include <stdio.h>
// Driverlib includes
#include "hw_types.h"
#include "hw_ints.h"
#include "hw_memmap.h"
#include "hw_apps_rcm.h"
#include "interrupt.h"
#include "pin.h"
#include "gpio.h"
#include "prcm.h"
#include "rom.h"
#include "rom_map.h"
// OS includes
#if defined(USE_TIRTOS) || defined(USE_FREERTOS) || defined(SL_PLATFORM_MULTI_THREADED)
#include <stdlib.h>
#include "osi.h"
#endif
// Common interface include
#include "gpio_if.h"
//****************************************************************************
// GLOBAL VARIABLES
//****************************************************************************
static unsigned long ulReg[]=
{
GPIOA0_BASE,
GPIOA1_BASE,
GPIOA2_BASE,
GPIOA3_BASE,
GPIOA4_BASE
};
//*****************************************************************************
// Variables to store TIMER Port,Pin values
//*****************************************************************************
unsigned int g_uiLED1Port = 0,g_uiLED2Port = 0,g_uiLED3Port = 0;
unsigned char g_ucLED1Pin,g_ucLED2Pin,g_ucLED3Pin;
#define GPIO_LED1 9
#define GPIO_LED2 10
#define GPIO_LED3 11
//****************************************************************************
// LOCAL FUNCTION DEFINITIONS
//****************************************************************************
static unsigned char
GetPeripheralIntNum(unsigned int uiGPIOPort)
{
switch(uiGPIOPort)
{
case GPIOA0_BASE:
return INT_GPIOA0;
case GPIOA1_BASE:
return INT_GPIOA1;
case GPIOA2_BASE:
return INT_GPIOA2;
case GPIOA3_BASE:
return INT_GPIOA3;
default:
return INT_GPIOA0;
}
}
//*****************************************************************************
//
//! GPIO Enable & Configuration
//!
//! \param ucPins is the bit-pack representation of 3 LEDs
//! LSB:GP09-GP10-GP11:MSB
//!
//! \return None
//
//*****************************************************************************
void
GPIO_IF_LedConfigure(unsigned char ucPins)
{
if(ucPins & LED1)
{
GPIO_IF_GetPortNPin(GPIO_LED1,
&g_uiLED1Port,
&g_ucLED1Pin);
}
if(ucPins & LED2)
{
GPIO_IF_GetPortNPin(GPIO_LED2,
&g_uiLED2Port,
&g_ucLED2Pin);
}
if(ucPins & LED3)
{
GPIO_IF_GetPortNPin(GPIO_LED3,
&g_uiLED3Port,
&g_ucLED3Pin);
}
}
//*****************************************************************************
//
//! Turn LED On
//!
//! \param ledNum is the LED Number
//!
//! \return none
//!
//! \brief Turns a specific LED Off
//
//*****************************************************************************
void
GPIO_IF_LedOn(char ledNum)
{
switch(ledNum)
{
case MCU_ON_IND:
case MCU_EXECUTE_SUCCESS_IND:
case MCU_GREEN_LED_GPIO:
{
/* Switch ON GREEN LED */
GPIO_IF_Set(GPIO_LED3, g_uiLED3Port, g_ucLED3Pin, 1);
break;
}
case MCU_SENDING_DATA_IND:
case MCU_EXECUTE_FAIL_IND:
case MCU_ORANGE_LED_GPIO:
{
/* Switch ON ORANGE LED */
GPIO_IF_Set(GPIO_LED2, g_uiLED2Port, g_ucLED2Pin, 1);
break;
}
case MCU_ASSOCIATED_IND:
case MCU_IP_ALLOC_IND:
case MCU_SERVER_INIT_IND:
case MCU_CLIENT_CONNECTED_IND:
case MCU_RED_LED_GPIO:
{
/* Switch ON RED LED */
GPIO_IF_Set(GPIO_LED1, g_uiLED1Port, g_ucLED1Pin, 1);
break;
}
case MCU_ALL_LED_IND:
{
/* Switch ON ALL LEDs LED */
GPIO_IF_Set(GPIO_LED3, g_uiLED3Port, g_ucLED3Pin, 1);
GPIO_IF_Set(GPIO_LED2, g_uiLED2Port, g_ucLED2Pin, 1);
GPIO_IF_Set(GPIO_LED1, g_uiLED1Port, g_ucLED1Pin, 1);
break;
}
default:
break;
}
}
//*****************************************************************************
//
//! Turn LED Off
//!
//! \param ledNum is the LED Number
//!
//! \return none
//!
//! \brief Turns a specific LED Off
//
//*****************************************************************************
void
GPIO_IF_LedOff(char ledNum)
{
switch(ledNum)
{
case MCU_ON_IND:
case MCU_EXECUTE_SUCCESS_IND:
case MCU_GREEN_LED_GPIO:
{
/* Switch OFF GREEN LED */
GPIO_IF_Set(GPIO_LED3, g_uiLED3Port, g_ucLED3Pin, 0);
break;
}
case MCU_SENDING_DATA_IND:
case MCU_EXECUTE_FAIL_IND:
case MCU_ORANGE_LED_GPIO:
{
/* Switch OFF ORANGE LED */
GPIO_IF_Set(GPIO_LED2, g_uiLED2Port, g_ucLED2Pin, 0);
break;
}
case MCU_ASSOCIATED_IND:
case MCU_IP_ALLOC_IND:
case MCU_SERVER_INIT_IND:
case MCU_CLIENT_CONNECTED_IND:
case MCU_RED_LED_GPIO:
{
/* Switch OFF RED LED */
GPIO_IF_Set(GPIO_LED1, g_uiLED1Port, g_ucLED1Pin, 0);
break;
}
case MCU_ALL_LED_IND:
{
/* Switch OFF ALL LEDs LED */
GPIO_IF_Set(GPIO_LED3, g_uiLED3Port, g_ucLED3Pin, 0);
GPIO_IF_Set(GPIO_LED2, g_uiLED2Port, g_ucLED2Pin, 0);
GPIO_IF_Set(GPIO_LED1, g_uiLED1Port, g_ucLED1Pin, 0);
break;
}
default:
break;
}
}
//*****************************************************************************
//
//! \brief This function returns LED current Status
//!
//! \param[in] ucGPIONum is the GPIO to which the LED is connected
//! MCU_GREEN_LED_GPIO\MCU_ORANGE_LED_GPIO\MCU_RED_LED_GPIO
//!
//!
//! \return 1: LED ON, 0: LED OFF
//
//*****************************************************************************
unsigned char
GPIO_IF_LedStatus(unsigned char ucGPIONum)
{
unsigned char ucLEDStatus;
switch(ucGPIONum)
{
case MCU_GREEN_LED_GPIO:
{
ucLEDStatus = GPIO_IF_Get(ucGPIONum, g_uiLED3Port, g_ucLED3Pin);
break;
}
case MCU_ORANGE_LED_GPIO:
{
ucLEDStatus = GPIO_IF_Get(ucGPIONum, g_uiLED2Port, g_ucLED2Pin);
break;
}
case MCU_RED_LED_GPIO:
{
ucLEDStatus = GPIO_IF_Get(ucGPIONum, g_uiLED1Port, g_ucLED1Pin);
break;
}
default:
ucLEDStatus = 0;
}
return ucLEDStatus;
}
//*****************************************************************************
//
//! Toggle the Led state
//!
//! \param ledNum is the LED Number
//!
//! \return none
//!
//! \brief Toggles a board LED
//
//*****************************************************************************
void GPIO_IF_LedToggle(unsigned char ucLedNum)
{
unsigned char ucLEDStatus = GPIO_IF_LedStatus(ucLedNum);
if(ucLEDStatus == 1)
{
GPIO_IF_LedOff(ucLedNum);
}
else
{
GPIO_IF_LedOn(ucLedNum);
}
}
//****************************************************************************
//
//! Get the port and pin of a given GPIO
//!
//! \param ucPin is the pin to be set-up as a GPIO (0:39)
//! \param puiGPIOPort is the pointer to store GPIO port address return value
//! \param pucGPIOPin is the pointer to store GPIO pin return value
//!
//! This function
//! 1. Return the GPIO port address and pin for a given external pin number
//!
//! \return None.
//
//****************************************************************************
void
GPIO_IF_GetPortNPin(unsigned char ucPin,
unsigned int *puiGPIOPort,
unsigned char *pucGPIOPin)
{
//
// Get the GPIO pin from the external Pin number
//
*pucGPIOPin = 1 << (ucPin % 8);
//
// Get the GPIO port from the external Pin number
//
*puiGPIOPort = (ucPin / 8);
*puiGPIOPort = ulReg[*puiGPIOPort];
}
//****************************************************************************
//
//! Configures the GPIO selected as input to generate interrupt on activity
//!
//! \param uiGPIOPort is the GPIO port address
//! \param ucGPIOPin is the GPIO pin of the specified port
//! \param uiIntType is the type of the interrupt (refer gpio.h)
//! \param pfnIntHandler is the interrupt handler to register
//!
//! This function
//! 1. Sets GPIO interrupt type
//! 2. Registers Interrupt handler
//! 3. Enables Interrupt
//!
//! \return None
//
//****************************************************************************
void
GPIO_IF_ConfigureNIntEnable(unsigned int uiGPIOPort,
unsigned char ucGPIOPin,
unsigned int uiIntType,
void (*pfnIntHandler)(void))
{
//
// Set GPIO interrupt type
//
MAP_GPIOIntTypeSet(uiGPIOPort,ucGPIOPin,uiIntType);
//
// Register Interrupt handler
//
#if defined(USE_TIRTOS) || defined(USE_FREERTOS) || defined(SL_PLATFORM_MULTI_THREADED)
// USE_TIRTOS: if app uses TI-RTOS (either networking/non-networking)
// USE_FREERTOS: if app uses Free-RTOS (either networking/non-networking)
// SL_PLATFORM_MULTI_THREADED: if app uses any OS + networking(simplelink)
osi_InterruptRegister(GetPeripheralIntNum(uiGPIOPort),
pfnIntHandler, INT_PRIORITY_LVL_1);
#else
MAP_IntPrioritySet(GetPeripheralIntNum(uiGPIOPort), INT_PRIORITY_LVL_1);
MAP_GPIOIntRegister(uiGPIOPort,pfnIntHandler);
#endif
//
// Enable Interrupt
//
MAP_GPIOIntClear(uiGPIOPort,ucGPIOPin);
MAP_GPIOIntEnable(uiGPIOPort,ucGPIOPin);
}
//****************************************************************************
//
//! Set a value to the specified GPIO pin
//!
//! \param ucPin is the GPIO pin to be set (0:39)
//! \param uiGPIOPort is the GPIO port address
//! \param ucGPIOPin is the GPIO pin of the specified port
//! \param ucGPIOValue is the value to be set
//!
//! This function
//! 1. Sets a value to the specified GPIO pin
//!
//! \return None.
//
//****************************************************************************
void
GPIO_IF_Set(unsigned char ucPin,
unsigned int uiGPIOPort,
unsigned char ucGPIOPin,
unsigned char ucGPIOValue)
{
//
// Set the corresponding bit in the bitmask
//
ucGPIOValue = ucGPIOValue << (ucPin % 8);
//
// Invoke the API to set the value
//
MAP_GPIOPinWrite(uiGPIOPort,ucGPIOPin,ucGPIOValue);
}
//****************************************************************************
//
//! Set a value to the specified GPIO pin
//!
//! \param ucPin is the GPIO pin to be set (0:39)
//! \param uiGPIOPort is the GPIO port address
//! \param ucGPIOPin is the GPIO pin of the specified port
//!
//! This function
//! 1. Gets a value of the specified GPIO pin
//!
//! \return value of the GPIO pin
//
//****************************************************************************
unsigned char
GPIO_IF_Get(unsigned char ucPin,
unsigned int uiGPIOPort,
unsigned char ucGPIOPin)
{
unsigned char ucGPIOValue;
long lGPIOStatus;
//
// Invoke the API to Get the value
//
lGPIOStatus = MAP_GPIOPinRead(uiGPIOPort,ucGPIOPin);
//
// Set the corresponding bit in the bitmask
//
ucGPIOValue = lGPIOStatus >> (ucPin % 8);
return ucGPIOValue;
}
//*****************************************************************************
//
// Close the Doxygen group.
//! @}
//
//*****************************************************************************

115
common/gpio_if.h Normal file
View File

@ -0,0 +1,115 @@
//*****************************************************************************
// gpio_if.h
//
// Defines and Macros for the GPIO interface.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#ifndef __GPIOIF_H__
#define __GPIOIF_H__
//*****************************************************************************
//
// If building with a C++ compiler, make all of the definitions in this header
// have a C binding.
//
//*****************************************************************************
#ifdef __cplusplus
extern "C"
{
#endif
typedef enum
{
NO_LED,
LED1 = 0x1, /* RED LED D7/GP9/Pin64 */
LED2 = 0x2, /* ORANGE LED D6/GP10/Pin1 */
LED3 = 0x4 /* GREEN LED D5/GP11/Pin2 */
} ledEnum;
typedef enum
{
NO_LED_IND = NO_LED,
MCU_SENDING_DATA_IND = LED1,
MCU_ASSOCIATED_IND, /* Device associated to an AP */
MCU_IP_ALLOC_IND, /* Device acquired an IP */
MCU_SERVER_INIT_IND, /* Device connected to remote server */
MCU_CLIENT_CONNECTED_IND, /* Any client connects to device */
MCU_ON_IND, /* Device SLHost invoked successfully */
MCU_EXECUTE_SUCCESS_IND, /* Task executed sucessfully */
MCU_EXECUTE_FAIL_IND, /* Task execution failed */
MCU_RED_LED_GPIO, /* GP09 for LED RED as per LP 3.0 */
MCU_ORANGE_LED_GPIO,/* GP10 for LED ORANGE as per LP 3.0 */
MCU_GREEN_LED_GPIO, /* GP11 for LED GREEN as per LP 3.0 */
MCU_ALL_LED_IND
} ledNames;
//*****************************************************************************
//
// API Function prototypes
//
//*****************************************************************************
extern void GPIO_IF_GetPortNPin(unsigned char ucPin,
unsigned int *puiGPIOPort,
unsigned char *pucGPIOPin);
extern void GPIO_IF_ConfigureNIntEnable(unsigned int uiGPIOPort,
unsigned char ucGPIOPin,
unsigned int uiIntType,
void (*pfnIntHandler)(void));
extern void GPIO_IF_Set(unsigned char ucPin,
unsigned int uiGPIOPort,
unsigned char ucGPIOPin,
unsigned char ucGPIOValue);
extern unsigned char GPIO_IF_Get(unsigned char ucPin,
unsigned int uiGPIOPort,
unsigned char ucGPIOPin);
extern void GPIO_IF_LedConfigure(unsigned char ucPins);
extern void GPIO_IF_LedOn(char ledNum);
extern void GPIO_IF_LedOff(char ledNum);
extern unsigned char GPIO_IF_LedStatus(unsigned char ucGPIONum);
extern void GPIO_IF_LedToggle(unsigned char ucLedNum);
//*****************************************************************************
//
// Mark the end of the C bindings section for C++ compilers.
//
//*****************************************************************************
#ifdef __cplusplus
}
#endif
#endif // __GPIOIF_H__

434
common/i2c_if.c Normal file
View File

@ -0,0 +1,434 @@
//*****************************************************************************
// i2c_if.c
//
// I2C interface APIs. Operates in a polled mode.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
// Standard includes
#include <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
// Driverlib includes
#include "hw_types.h"
#include "hw_memmap.h"
#include "hw_ints.h"
#include "hw_i2c.h"
#include "i2c.h"
#include "pin.h"
#include "rom.h"
#include "rom_map.h"
#include "prcm.h"
// Common interface include
#include "i2c_if.h"
//*****************************************************************************
// MACRO DEFINITIONS
//*****************************************************************************
#define I2C_BASE I2CA0_BASE
#define SYS_CLK 80000000
#define FAILURE -1
#define SUCCESS 0
#define RETERR_IF_TRUE(condition) {if(condition) return FAILURE;}
#define RET_IF_ERR(Func) {int iRetVal = (Func); \
if (SUCCESS != iRetVal) \
return iRetVal;}
//****************************************************************************
// LOCAL FUNCTION DEFINITIONS
//****************************************************************************
static int I2CTransact(unsigned long ulCmd);
//****************************************************************************
//
//! Invokes the transaction over I2C
//!
//! \param ulCmd is the command to be executed over I2C
//!
//! This function works in a polling mode,
//! 1. Initiates the transfer of the command.
//! 2. Waits for the I2C transaction completion
//! 3. Check for any error in transaction
//! 4. Clears the master interrupt
//!
//! \return 0: Success, < 0: Failure.
//
//****************************************************************************
static int
I2CTransact(unsigned long ulCmd)
{
//
// Clear all interrupts
//
MAP_I2CMasterIntClearEx(I2C_BASE,MAP_I2CMasterIntStatusEx(I2C_BASE,false));
//
// Set the time-out. Not to be used with breakpoints.
//
MAP_I2CMasterTimeoutSet(I2C_BASE, I2C_TIMEOUT_VAL);
//
// Initiate the transfer.
//
MAP_I2CMasterControl(I2C_BASE, ulCmd);
//
// Wait until the current byte has been transferred.
// Poll on the raw interrupt status.
//
while((MAP_I2CMasterIntStatusEx(I2C_BASE, false)
& (I2C_MASTER_INT_DATA | !I2C_MASTER_INT_TIMEOUT)) == 0)
{
if (MAP_I2CMasterIntStatusEx(I2C_BASE, false) & I2C_MASTER_INT_TIMEOUT) return -1;
}
//
// Check for any errors in transfer
//
if(MAP_I2CMasterErr(I2C_BASE) != I2C_MASTER_ERR_NONE)
{
switch(ulCmd)
{
case I2C_MASTER_CMD_BURST_SEND_START:
case I2C_MASTER_CMD_BURST_SEND_CONT:
case I2C_MASTER_CMD_BURST_SEND_STOP:
MAP_I2CMasterControl(I2C_BASE,
I2C_MASTER_CMD_BURST_SEND_ERROR_STOP);
break;
case I2C_MASTER_CMD_BURST_RECEIVE_START:
case I2C_MASTER_CMD_BURST_RECEIVE_CONT:
case I2C_MASTER_CMD_BURST_RECEIVE_FINISH:
MAP_I2CMasterControl(I2C_BASE,
I2C_MASTER_CMD_BURST_RECEIVE_ERROR_STOP);
break;
default:
break;
}
return FAILURE;
}
return SUCCESS;
}
//****************************************************************************
//
//! Invokes the I2C driver APIs to write to the specified address
//!
//! \param ucDevAddr is the 7-bit I2C slave address
//! \param pucData is the pointer to the data to be written
//! \param ucLen is the length of data to be written
//! \param ucStop determines if the transaction is followed by stop bit
//!
//! This function works in a polling mode,
//! 1. Writes the device register address to be written to.
//! 2. In a loop, writes all the bytes over I2C
//!
//! \return 0: Success, < 0: Failure.
//
//****************************************************************************
int
I2C_IF_Write(unsigned char ucDevAddr,
unsigned char *pucData,
unsigned char ucLen,
unsigned char ucStop)
{
RETERR_IF_TRUE(pucData == NULL);
RETERR_IF_TRUE(ucLen == 0);
//
// Set I2C codec slave address
//
MAP_I2CMasterSlaveAddrSet(I2C_BASE, ucDevAddr, false);
//
// Write the first byte to the controller.
//
MAP_I2CMasterDataPut(I2C_BASE, *pucData);
//
// Initiate the transfer.
//
RET_IF_ERR(I2CTransact(I2C_MASTER_CMD_BURST_SEND_START));
//
// Decrement the count and increment the data pointer
// to facilitate the next transfer
//
ucLen--;
pucData++;
//
// Loop until the completion of transfer or error
//
while(ucLen)
{
//
// Write the next byte of data
//
MAP_I2CMasterDataPut(I2C_BASE, *pucData);
//
// Transact over I2C to send byte
//
RET_IF_ERR(I2CTransact(I2C_MASTER_CMD_BURST_SEND_CONT));
//
// Decrement the count and increment the data pointer
// to facilitate the next transfer
//
ucLen--;
pucData++;
}
//
// If stop bit is to be sent, send it.
//
if(ucStop == true)
{
RET_IF_ERR(I2CTransact(I2C_MASTER_CMD_BURST_SEND_STOP));
}
return SUCCESS;
}
//****************************************************************************
//
//! Invokes the I2C driver APIs to read from the device. This assumes the
//! device local address to read from is set using the I2CWrite API.
//!
//! \param ucDevAddr is the 7-bit I2C slave address
//! \param pucData is the pointer to the read data to be placed
//! \param ucLen is the length of data to be read
//!
//! This function works in a polling mode,
//! 1. Writes the device register address to be written to.
//! 2. In a loop, reads all the bytes over I2C
//!
//! \return 0: Success, < 0: Failure.
//
//****************************************************************************
int
I2C_IF_Read(unsigned char ucDevAddr,
unsigned char *pucData,
unsigned char ucLen)
{
unsigned long ulCmdID;
RETERR_IF_TRUE(pucData == NULL);
RETERR_IF_TRUE(ucLen == 0);
//
// Set I2C codec slave address
//
MAP_I2CMasterSlaveAddrSet(I2C_BASE, ucDevAddr, true);
//
// Check if its a single receive or burst receive
//
if(ucLen == 1)
{
//
// Configure for a single receive
//
ulCmdID = I2C_MASTER_CMD_SINGLE_RECEIVE;
}
else
{
//
// Initiate a burst receive sequence
//
ulCmdID = I2C_MASTER_CMD_BURST_RECEIVE_START;
}
//
// Initiate the transfer.
//
RET_IF_ERR(I2CTransact(ulCmdID));
//
// Decrement the count and increment the data pointer
// to facilitate the next transfer
//
ucLen--;
//
// Loop until the completion of reception or error
//
while(ucLen)
{
//
// Receive the byte over I2C
//
*pucData = MAP_I2CMasterDataGet(I2C_BASE);
//
// Decrement the count and increment the data pointer
// to facilitate the next transfer
//
ucLen--;
pucData++;
if(ucLen)
{
//
// Continue the reception
//
RET_IF_ERR(I2CTransact(I2C_MASTER_CMD_BURST_RECEIVE_CONT));
}
else
{
//
// Complete the last reception
//
RET_IF_ERR(I2CTransact(I2C_MASTER_CMD_BURST_RECEIVE_FINISH));
}
}
//
// Receive the byte over I2C
//
*pucData = MAP_I2CMasterDataGet(I2C_BASE);
return SUCCESS;
}
//****************************************************************************
//
//! Invokes the I2C driver APIs to read from a specified address the device.
//! This assumes the device local address to be of 8-bit. For other
//! combinations use I2CWrite followed by I2CRead.
//!
//! \param ucDevAddr is the 7-bit I2C slave address
//! \param pucWrDataBuf is the pointer to the data to be written (reg addr)
//! \param ucWrLen is the length of data to be written
//! \param pucRdDataBuf is the pointer to the read data to be placed
//! \param ucRdLen is the length of data to be read
//!
//! This function works in a polling mode,
//! 1. Writes the data over I2C (device register address to be read from).
//! 2. In a loop, reads all the bytes over I2C
//!
//! \return 0: Success, < 0: Failure.
//
//****************************************************************************
int
I2C_IF_ReadFrom(unsigned char ucDevAddr,
unsigned char *pucWrDataBuf,
unsigned char ucWrLen,
unsigned char *pucRdDataBuf,
unsigned char ucRdLen)
{
//
// Write the register address to be read from.
// Stop bit implicitly assumed to be 0.
//
RET_IF_ERR(I2C_IF_Write(ucDevAddr,pucWrDataBuf,ucWrLen,0));
//
// Read the specified length of data
//
RET_IF_ERR(I2C_IF_Read(ucDevAddr, pucRdDataBuf, ucRdLen));
return SUCCESS;
}
//****************************************************************************
//
//! Enables and configures the I2C peripheral
//!
//! \param ulMode is the mode configuration of I2C
//! The parameter \e ulMode is one of the following
//! - \b I2C_MASTER_MODE_STD for 100 Kbps standard mode.
//! - \b I2C_MASTER_MODE_FST for 400 Kbps fast mode.
//!
//! This function works in a polling mode,
//! 1. Powers ON the I2C peripheral.
//! 2. Configures the I2C peripheral
//!
//! \return 0: Success, < 0: Failure.
//
//****************************************************************************
int
I2C_IF_Open(unsigned long ulMode)
{
//
// Enable I2C Peripheral
//
//MAP_HwSemaphoreLock(HWSEM_I2C, HWSEM_WAIT_FOR_EVER);
MAP_PRCMPeripheralClkEnable(PRCM_I2CA0, PRCM_RUN_MODE_CLK);
MAP_PRCMPeripheralReset(PRCM_I2CA0);
MAP_I2CMasterEnable(I2CA0_BASE);
// Clear all interrupts.
MAP_I2CMasterIntClearEx(I2CA0_BASE, MAP_I2CMasterIntStatusEx(I2CA0_BASE, false));
// Enable interrupts.
MAP_I2CMasterIntEnableEx(I2CA0_BASE,
I2C_MASTER_INT_TIMEOUT | // timeout
I2C_MASTER_INT_DATA // data transaction complete
);
//
// Configure I2C module in the specified mode
//
switch(ulMode)
{
case I2C_MASTER_MODE_STD: /* 100000 */
MAP_I2CMasterInitExpClk(I2C_BASE,SYS_CLK,false);
break;
case I2C_MASTER_MODE_FST: /* 400000 */
MAP_I2CMasterInitExpClk(I2C_BASE,SYS_CLK,true);
break;
default:
MAP_I2CMasterInitExpClk(I2C_BASE,SYS_CLK,true);
break;
}
//
// Disables the multi-master mode
//
//MAP_I2CMasterDisable(I2C_BASE);
return SUCCESS;
}
//****************************************************************************
//
//! Disables the I2C peripheral
//!
//! \param None
//!
//! This function works in a polling mode,
//! 1. Powers OFF the I2C peripheral.
//!
//! \return 0: Success, < 0: Failure.
//
//****************************************************************************
int
I2C_IF_Close()
{
//
// Power OFF the I2C peripheral
//
MAP_PRCMPeripheralClkDisable(PRCM_I2CA0, PRCM_RUN_MODE_CLK);
return SUCCESS;
}

99
common/i2c_if.h Normal file
View File

@ -0,0 +1,99 @@
//*****************************************************************************
// i2c_if.h
//
// Defines and Macros for the I2C interface.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#ifndef __I2C_IF_H__
#define __I2C_IF_H__
//*****************************************************************************
//
// If building with a C++ compiler, make all of the definitions in this header
// have a C binding.
//
//*****************************************************************************
#ifdef __cplusplus
extern "C"
{
#endif
#define I2C_MRIS_CLKTOUT 0x2
//*****************************************************************************
//
// I2C transaction time-out value.
// Set to value 0x7D. (@100KHz it is 20ms, @400Khz it is 5 ms)
//
//*****************************************************************************
#define I2C_TIMEOUT_VAL 0x7D
//*****************************************************************************
//
// Values that can be passed to I2COpen as the ulMode parameter.
//
//*****************************************************************************
#define I2C_MASTER_MODE_STD 0
#define I2C_MASTER_MODE_FST 1
//*****************************************************************************
//
// API Function prototypes
//
//*****************************************************************************
extern int I2C_IF_Open(unsigned long ulMode);
extern int I2C_IF_Close();
extern int I2C_IF_Write(unsigned char ucDevAddr,
unsigned char *pucData,
unsigned char ucLen,
unsigned char ucStop);
extern int I2C_IF_Read(unsigned char ucDevAddr,
unsigned char *pucData,
unsigned char ucLen);
extern int I2C_IF_ReadFrom(unsigned char ucDevAddr,
unsigned char *pucWrDataBuf,
unsigned char ucWrLen,
unsigned char *pucRdDataBuf,
unsigned char ucRdLen);
//*****************************************************************************
//
// Mark the end of the C bindings section for C++ compilers.
//
//*****************************************************************************
#ifdef __cplusplus
}
#endif
#endif // __I2C_IF_H__

255
common/i2s_if.c Normal file
View File

@ -0,0 +1,255 @@
//*****************************************************************************
// i2s_if.c
//
// I2S interface APIs.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
//*****************************************************************************
//
//! \addtogroup microphone
//! @{
//
//*****************************************************************************
/* Standard includes. */
#include <stdio.h>
/* Hardware & driverlib library includes. */
#include "hw_types.h"
#include "hw_mcasp.h"
#include "hw_ints.h"
#include "hw_memmap.h"
#include "debug.h"
#include "prcm.h"
#include "rom.h"
#include "rom_map.h"
#include "udma.h"
#include "interrupt.h"
#include "prcm.h"
#include "uart.h"
#include "pin.h"
#include "i2s.h"
// common interface includes
#include "common.h"
/* Demo app includes. */
#include "i2s_if.h"
#include "gpio_if.h"
//*****************************************************************************
//
//! Returns the pointer to transfer Audio samples to be rendered
//!
//! \param None
//!
//! This function
//! 1. Returns the pointer to the data buffer
//!
//! \return None.
//
//*****************************************************************************
unsigned int* AudioRendererGetDMADataPtr()
{
return (unsigned int *)(I2S_TX_DMA_PORT);
}
//*****************************************************************************
//
//! Returns the pointer to transfer Audio samples to be captured
//!
//! \param None
//!
//! This function
//! 1. Returns the pointer to the data buffer
//!
//! \return None.
//
//*****************************************************************************
unsigned int* AudioCapturerGetDMADataPtr()
{
return (unsigned int *)(I2S_RX_DMA_PORT);
}
//*****************************************************************************
//
//! Initialize the audio capture or render
//!
//! \param None
//!
//! This function initializes
//! 1. Initializes the McASP module
//!
//! \return None.
//
//*****************************************************************************
void AudioInit()
{
//
// Initialising the McASP
//
MAP_PRCMPeripheralClkEnable(PRCM_I2S,PRCM_RUN_MODE_CLK);
}
//*****************************************************************************
//
//! Setup the Audio capturer callback routine and the interval of callback.
//! On the invocation the callback is expected to fill the AFIFO with enough
//! number of samples for one callback interval.
//!
//! \param pfnAppCbHndlr is the callback handler that is invoked when
//! \e ucCallbackEvtSamples space is available in the audio FIFO
//! \param ucCallbackEvtSamples is used to configure the callback interval
//!
//! This function initializes
//! 1. Initializes the interrupt callback routine
//! 2. Sets up the AFIFO to interrupt at the configured interval
//!
//! \return 0 - Success
//! -1 - Failure
//
//*****************************************************************************
long AudioSetupDMAMode(void (*pfnAppCbHndlr)(void),
unsigned long ulCallbackEvtSamples,
unsigned char RxTx)
{
MAP_I2SIntEnable(I2S_BASE,I2S_INT_XDATA);
#ifdef USE_TIRTOS
long lRetVal = -1;
lRetVal = osi_InterruptRegister(INT_I2S, pfnAppCbHndlr, INT_PRIORITY_LVL_1);
ASSERT_ON_ERROR(lRetVal);
#else
MAP_I2SIntRegister(I2S_BASE,pfnAppCbHndlr);
#endif
if(RxTx == I2S_MODE_RX_TX)
{
MAP_I2SRxFIFOEnable(I2S_BASE,8,1);
}
if(RxTx & I2S_MODE_TX)
{
MAP_I2STxFIFOEnable(I2S_BASE,8,1);
}
return SUCCESS;
}
//*****************************************************************************
//
//! Initialize the AudioCaptureRendererConfigure
//!
//! \param[in] bitsPerSample - Number of bits per sample
//! \param[in] bitRate - Bit rate
//! \param[in] noOfChannels - Number of channels
//! \param[in] RxTx - Play or record or both
//! \param[in] dma - 1 for dma and 0 for non-dma mode
//!
//!
//! \return None.
//
//*****************************************************************************
void AudioCaptureRendererConfigure(unsigned char bitsPerSample,
unsigned short bitRate,
unsigned char noOfChannels,
unsigned char RxTx,
unsigned char dma)
{
unsigned long bitClk;
bitClk = bitsPerSample * bitRate * noOfChannels;
if(dma)
{
if(bitsPerSample == 16)
{
MAP_PRCMI2SClockFreqSet(512000);
MAP_I2SConfigSetExpClk(I2S_BASE,512000,bitClk,I2S_SLOT_SIZE_16|
I2S_PORT_DMA);
}
}
if(RxTx == I2S_MODE_RX_TX)
{
MAP_I2SSerializerConfig(I2S_BASE,I2S_DATA_LINE_1,I2S_SER_MODE_RX,
I2S_INACT_LOW_LEVEL);
}
if(RxTx & I2S_MODE_TX)
{
MAP_I2SSerializerConfig(I2S_BASE,I2S_DATA_LINE_0,I2S_SER_MODE_TX,
I2S_INACT_LOW_LEVEL);
}
}
//*****************************************************************************
//
//! Initialize the Audio_Start
//!
//! \param[in] RxTx - Flag for play or record or both
//!
//! This function initializes
//! 1. Enable the McASP module for TX and RX
//!
//! \return None.
//
//*****************************************************************************
void Audio_Start(unsigned char RxTx)
{
if(RxTx == I2S_MODE_RX_TX)
{
MAP_I2SEnable(I2S_BASE,I2S_MODE_TX_RX_SYNC);
}
else if(RxTx & I2S_MODE_TX)
{
MAP_I2SEnable(I2S_BASE,I2S_MODE_TX_ONLY);
}
}
//*****************************************************************************
//
// Close the Doxygen group.
//! @}
//
//*****************************************************************************

141
common/i2s_if.h Normal file
View File

@ -0,0 +1,141 @@
//*****************************************************************************
// mcasp_if.h
//
// MCASP interface APIs.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
//*****************************************************************************
//
// mcasp_if.h - Defines and prototypes for MultiChannel Audio Serial Port.
//
//*****************************************************************************
#ifndef __MCASP_IF_H__
#define __MCASP_IF_H__
//*****************************************************************************
//
// If building with a C++ compiler, make all of the definitions in this header
// have a C binding.
//
//*****************************************************************************
#ifdef __cplusplus
extern "C"
{
#endif
#define WFIFO_NUMDMA_WORDS 1
#define MCASP_DMA_PORT_ADDR 0x4401E200
//
// Update the sampling freq, channels, sample length appropriately
//
typedef enum {
SAMPLING_FREQ_8_KHZ = 8000,
SAMPLING_FREQ_11_X_KHZ = 11025,
SAMPLING_FREQ_16_KHZ = 16000,
SAMPLING_FREQ_22_X_KHZ = 22050,
SAMPLING_FREQ_32_KHZ = 32000,
SAMPLING_FREQ_44_1_KHZ = 44100,
SAMPLING_FREQ_48_KHZ = 48000
} tESamplFreq;
typedef enum {
CH_MONO = 1,
CH_STEREO = 2
} tENumChannels;
typedef enum {
BIT_8_PCM = 8,
BIT_16_PCM = 16,
BIT_24_PCM = 24,
BIT_32_PCM = 32
} tESampleLen;
#define I2S_MODE_RX 0x01
#define I2S_MODE_TX 0x02
#define I2S_MODE_RX_TX 0x03
//
// Audio Renderer Interface APIs
//
extern void AudioRendererInit();
extern void AudioCapturerInit();
extern void AudioInit();
extern void McASPInit();
extern void AudioRendererSetupCPUMode(void (*pfnAppCbHndlr)(void));
extern void AudioRendererSetupDMAMode(void (*pfnAppCbHndlr)(void),
unsigned long ulCallbackEvtSamples);
extern void AudioCapturerSetupCPUMode(void (*pfnAppCbHndlr)(void));
extern long AudioCapturerSetupDMAMode(void (*pfnAppCbHndlr)(void),
unsigned long ulCallbackEvtSamples);
extern long AudioSetupDMAMode(void (*pfnAppCbHndlr)(void),
unsigned long ulCallbackEvtSamples,
unsigned char RxTx);
extern unsigned int* AudioRendererGetDMADataPtr();
extern unsigned int* AudioCapturerGetDMADataPtr();
extern void AudioCapturerConfigure(int iSamplingFrequency,
short sNumOfChannels,
short sBitsPerSample);
extern void AudioRendererConfigure(int iSamplingFrequency,
short sNumOfChannels,
short sBitsPerSample);
extern void AudioRendererStart();
extern void AudioCapturerStart();
extern void AudioRendererStop();
extern void AudioRendererDeInit();
extern unsigned int BitClockConfigure(int iSamplingFrequency,
short sNumOfChannels,
short sBitsPerSample);
extern void AudioCaptureRendererConfigure(unsigned char bitsPerSample,
unsigned short bitRate,
unsigned char noOfChannels,
unsigned char RxTx,
unsigned char dma);
extern void Audio_Start(unsigned char RxTx);
//*****************************************************************************
//
// Mark the end of the C bindings section for C++ compilers.
//
//*****************************************************************************
#ifdef __cplusplus
}
#endif
#endif // __MCASP_IF_H__

108
common/network_common.c Normal file
View File

@ -0,0 +1,108 @@
//*****************************************************************************
// network_common.c
//
// Networking common callback for CC3200 device
//
// Copyright (C) 2016 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#include <stdlib.h>
// Simplelink includes
#include "simplelink.h"
//*****************************************************************************
// SimpleLink Asynchronous Event Handlers -- Start
//*****************************************************************************
//*****************************************************************************
//
//! \brief This function serves as first level handler for HTTP GET/POST tokens
//! It runs under driver context and performs only operation that can run
//! from this context. For operations that can't is sets an indication of
//! received token and preempts the provisioning context.
//!
//! \param pSlHttpServerEvent Pointer indicating http server event
//! \param pSlHttpServerResponse Pointer indicating http server response
//!
//! \return None
//!
//*****************************************************************************
_SlEventPropogationStatus_e sl_Provisioning_HttpServerEventHdl(
SlHttpServerEvent_t *apSlHttpServerEvent,
SlHttpServerResponse_t *apSlHttpServerResponse)
{
// Unused in this application
return EVENT_PROPAGATION_CONTINUE;
}
//*****************************************************************************
//
//! \brief This function serves as first level network application events handler.
//! It runs under driver context and performs only operation that can run
//! from this context. For operations that can't is sets an indication of
//! received token and preempts the provisioning context.
//!
//! \param apEventInfo Pointer to the net app event information
//!
//! \return None
//!
//*****************************************************************************
_SlEventPropogationStatus_e sl_Provisioning_NetAppEventHdl(SlNetAppEvent_t *apNetAppEvent)
{
// Unused in this application
return EVENT_PROPAGATION_CONTINUE;
}
//*****************************************************************************
//
//! \brief This function serves as first level WLAN events handler.
//! It runs under driver context and performs only operation that can run
//! from this context. For operations that can't is sets an indication of
//! received token and preempts the provisioning context.
//!
//! \param apEventInfo Pointer to the WLAN event information
//!
//! \return None
//!
//*****************************************************************************
_SlEventPropogationStatus_e sl_Provisioning_WlanEventHdl(SlWlanEvent_t *apEventInfo)
{
// Unused in this application
return EVENT_PROPAGATION_CONTINUE;
}
//*****************************************************************************
// SimpleLink Asynchronous Event Handlers -- End
//*****************************************************************************

1273
common/network_if.c Normal file

File diff suppressed because it is too large Load Diff

83
common/network_if.h Normal file
View File

@ -0,0 +1,83 @@
//*****************************************************************************
// network_if.h
//
// Networking interface macro and function prototypes for CC3200 device
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#ifndef __NETWORK_IF__H__
#define __NETWORK_IF__H__
//*****************************************************************************
//
// If building with a C++ compiler, make all of the definitions in this header
// have a C binding.
//
//*****************************************************************************
#ifdef __cplusplus
extern "C"
{
#endif
//*****************************************************************************
//
// API Function prototypes
//
//*****************************************************************************
extern long Network_IF_InitDriver(unsigned int uiMode);
extern long Network_IF_DeInitDriver(void);
extern long Network_IF_ConnectAP(char * pcSsid, SlSecParams_t SecurityParams);
extern long Network_IF_DisconnectFromAP();
extern long Network_IF_IpConfigGet(unsigned long *aucIP, unsigned long *aucSubnetMask,
unsigned long *aucDefaultGateway, unsigned long *aucDNSServer);
extern long Network_IF_GetHostIP( char* pcHostName,unsigned long * pDestinationIP);
extern unsigned long Network_IF_CurrentMCUState();
extern void Network_IF_UnsetMCUMachineState(char stat);
extern void Network_IF_SetMCUMachineState(char stat);
extern void Network_IF_ResetMCUStateMachine();
extern unsigned short itoa(short cNum, char *cString);
//*****************************************************************************
//
// Mark the end of the C bindings section for C++ compilers.
//
//*****************************************************************************
#ifdef __cplusplus
}
#endif
#endif

264
common/startup_ccs.c Normal file
View File

@ -0,0 +1,264 @@
//*****************************************************************************
// startup_ccs.c
//
// Startup code for use with TI's Code Composer Studio.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#ifndef USE_TIRTOS /* if project uses TI-RTOS then no need to include startup file */
//*****************************************************************************
//
// Forward declaration of the default fault handlers.
//
//*****************************************************************************
void ResetISR(void);
static void NmiSR(void);
static void FaultISR(void);
static void IntDefaultHandler(void);
static void BusFaultHandler(void);
//*****************************************************************************
//
// External declaration for the reset handler that is to be called when the
// processor is started
//
//*****************************************************************************
extern void _c_int00(void);
#ifdef USE_FREERTOS
extern void vPortSVCHandler(void);
extern void xPortPendSVHandler(void);
extern void xPortSysTickHandler(void);
#endif
//*****************************************************************************
//
// Linker variable that marks the top of the stack.
//
//*****************************************************************************
extern unsigned long __STACK_END;
//*****************************************************************************
// The vector table. Note that the proper constructs must be placed on this to
// ensure that it ends up at physical address 0x0000.0000 or at the start of
// the program if located at a start address other than 0.
//
//*****************************************************************************
#pragma DATA_SECTION(g_pfnVectors, ".intvecs")
void (* const g_pfnVectors[256])(void) =
{
(void (*)(void))((unsigned long)&__STACK_END),
// The initial stack pointer
ResetISR, // The reset handler
NmiSR, // The NMI handler
FaultISR, // The hard fault handler
IntDefaultHandler, // The MPU fault handler
BusFaultHandler, // The bus fault handler
IntDefaultHandler, // The usage fault handler
0, // Reserved
0, // Reserved
0, // Reserved
0, // Reserved
#ifdef USE_FREERTOS
vPortSVCHandler, // SVCall handler
#else
IntDefaultHandler, // SVCall handler
#endif
IntDefaultHandler, // Debug monitor handler
0, // Reserved
#ifdef USE_FREERTOS
xPortPendSVHandler, // The PendSV handler
xPortSysTickHandler, // The SysTick handler
#else
IntDefaultHandler, // The PendSV handler
IntDefaultHandler, // The SysTick handler
#endif
IntDefaultHandler, // GPIO Port A0
IntDefaultHandler, // GPIO Port A1
IntDefaultHandler, // GPIO Port A2
IntDefaultHandler, // GPIO Port A3
0, // Reserved
IntDefaultHandler, // UART0 Rx and Tx
IntDefaultHandler, // UART1 Rx and Tx
0, // Reserved
IntDefaultHandler, // I2C0 Master and Slave
0,0,0,0,0, // Reserved
IntDefaultHandler, // ADC Channel 0
IntDefaultHandler, // ADC Channel 1
IntDefaultHandler, // ADC Channel 2
IntDefaultHandler, // ADC Channel 3
IntDefaultHandler, // Watchdog Timer
IntDefaultHandler, // Timer 0 subtimer A
IntDefaultHandler, // Timer 0 subtimer B
IntDefaultHandler, // Timer 1 subtimer A
IntDefaultHandler, // Timer 1 subtimer B
IntDefaultHandler, // Timer 2 subtimer A
IntDefaultHandler, // Timer 2 subtimer B
0,0,0,0, // Reserved
IntDefaultHandler, // Flash
0,0,0,0,0, // Reserved
IntDefaultHandler, // Timer 3 subtimer A
IntDefaultHandler, // Timer 3 subtimer B
0,0,0,0,0,0,0,0,0, // Reserved
IntDefaultHandler, // uDMA Software Transfer
IntDefaultHandler, // uDMA Error
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
IntDefaultHandler, // SHA
0,0, // Reserved
IntDefaultHandler, // AES
0, // Reserved
IntDefaultHandler, // DES
0,0,0,0,0, // Reserved
IntDefaultHandler, // SDHost
0, // Reserved
IntDefaultHandler, // I2S
0, // Reserved
IntDefaultHandler, // Camera
0,0,0,0,0,0,0, // Reserved
IntDefaultHandler, // NWP to APPS Interrupt
IntDefaultHandler, // Power, Reset and Clock module
0,0, // Reserved
IntDefaultHandler, // Shared SPI
IntDefaultHandler, // Generic SPI
IntDefaultHandler, // Link SPI
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0 // Reserved
};
//*****************************************************************************
//
// This is the code that gets called when the processor first starts execution
// following a reset event. Only the absolutely necessary set is performed,
// after which the application supplied entry() routine is called. Any fancy
// actions (such as making decisions based on the reset cause register, and
// resetting the bits in that register) are left solely in the hands of the
// application.
//
//*****************************************************************************
void
ResetISR(void)
{
//
// Jump to the CCS C initialization routine.
//
__asm(" .global _c_int00\n"
" b.w _c_int00");
}
//*****************************************************************************
//
// This is the code that gets called when the processor receives a NMI. This
// simply enters an infinite loop, preserving the system state for examination
// by a debugger.
//
//*****************************************************************************
static void
NmiSR(void)
{
//
// Enter an infinite loop.
//
while(1)
{
}
}
//*****************************************************************************
//
// This is the code that gets called when the processor receives a fault
// interrupt. This simply enters an infinite loop, preserving the system state
// for examination by a debugger.
//
//*****************************************************************************
static void
FaultISR(void)
{
//
// Enter an infinite loop.
//
while(1)
{
}
}
//*****************************************************************************
//
// This is the code that gets called when the processor receives an unexpected
// interrupt. This simply enters an infinite loop, preserving the system state
// for examination by a debugger.
//
//*****************************************************************************
static void
BusFaultHandler(void)
{
//
// Go into an infinite loop.
//
while(1)
{
}
}
//*****************************************************************************
//
// This is the code that gets called when the processor receives an unexpected
// interrupt. This simply enters an infinite loop, preserving the system state
// for examination by a debugger.
//
//*****************************************************************************
static void
IntDefaultHandler(void)
{
//
// Go into an infinite loop.
//
while(1)
{
}
}
#endif

269
common/startup_ewarm.c Normal file
View File

@ -0,0 +1,269 @@
//*****************************************************************************
// startup_ewarm.c
//
// Startup code for use with IAR IDE.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#include "hw_types.h"
#include "hw_ints.h"
#include "interrupt.h"
//*****************************************************************************
//
// Forward declaration of the default fault handlers.
//
//*****************************************************************************
void ResetISR(void);
static void NmiSR(void);
static void FaultISR(void);
static void IntDefaultHandler(void);
static void BusFaultHandler(void);
#ifdef USE_FREERTOS
extern void vPortSVCHandler(void);
extern void xPortPendSVHandler(void);
extern void xPortSysTickHandler(void);
#endif
//*****************************************************************************
//
// The entry point for the application startup code.
//
//*****************************************************************************
extern void __iar_program_start(void);
//*****************************************************************************
//
// Reserve space for the system stack.
//
//*****************************************************************************
static unsigned long pulStack[1024] @ ".noinit";
//*****************************************************************************
//
// The vector table. Note that the proper constructs must be placed on this to
// ensure that it ends up at physical address 0x0000.0000.
//
//*****************************************************************************
__root const uVectorEntry __vector_table[256] @ ".intvec" =
{
{ .ulPtr = (unsigned long)pulStack + sizeof(pulStack) },
// The initial stack pointer
ResetISR, // The reset handler
NmiSR, // The NMI handler
FaultISR, // The hard fault handler
IntDefaultHandler, // The MPU fault handler
BusFaultHandler, // The bus fault handler
IntDefaultHandler, // The usage fault handler
0, // Reserved
0, // Reserved
0, // Reserved
0, // Reserved
#ifdef USE_FREERTOS
vPortSVCHandler, // SVCall handler
#else
IntDefaultHandler, // SVCall handler
#endif
IntDefaultHandler, // Debug monitor handler
0, // Reserved
#ifdef USE_FREERTOS
xPortPendSVHandler, // The PendSV handler
xPortSysTickHandler, // The SysTick handler
#else
IntDefaultHandler, // The PendSV handler
IntDefaultHandler, // The SysTick handler
#endif
IntDefaultHandler, // GPIO Port A0
IntDefaultHandler, // GPIO Port A1
IntDefaultHandler, // GPIO Port A2
IntDefaultHandler, // GPIO Port A3
0, // Reserved
IntDefaultHandler, // UART0 Rx and Tx
IntDefaultHandler, // UART1 Rx and Tx
0, // Reserved
IntDefaultHandler, // I2C0 Master and Slave
0,0,0,0,0, // Reserved
IntDefaultHandler, // ADC Channel 0
IntDefaultHandler, // ADC Channel 1
IntDefaultHandler, // ADC Channel 2
IntDefaultHandler, // ADC Channel 3
IntDefaultHandler, // Watchdog Timer
IntDefaultHandler, // Timer 0 subtimer A
IntDefaultHandler, // Timer 0 subtimer B
IntDefaultHandler, // Timer 1 subtimer A
IntDefaultHandler, // Timer 1 subtimer B
IntDefaultHandler, // Timer 2 subtimer A
IntDefaultHandler, // Timer 2 subtimer B
0,0,0,0, // Reserved
IntDefaultHandler, // Flash
0,0,0,0,0, // Reserved
IntDefaultHandler, // Timer 3 subtimer A
IntDefaultHandler, // Timer 3 subtimer B
0,0,0,0,0,0,0,0,0, // Reserved
IntDefaultHandler, // uDMA Software Transfer
IntDefaultHandler, // uDMA Error
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
IntDefaultHandler, // SHA
0,0, // Reserved
IntDefaultHandler, // AES
0, // Reserved
IntDefaultHandler, // DES
0,0,0,0,0, // Reserved
IntDefaultHandler, // SDHost
0, // Reserved
IntDefaultHandler, // I2S
0, // Reserved
IntDefaultHandler, // Camera
0,0,0,0,0,0,0, // Reserved
IntDefaultHandler, // NWP to APPS Interrupt
IntDefaultHandler, // Power, Reset and Clock module
0,0, // Reserved
IntDefaultHandler, // Shared SPI
IntDefaultHandler, // Generic SPI
IntDefaultHandler, // Link SPI
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0 // Reserved
};
//*****************************************************************************
//
//! This is the code that gets called when the processor first starts execution
//! following a reset event. Only the absolutely necessary set is performed,
//! after which the application supplied entry() routine is called. Any fancy
//! actions (such as making decisions based on the reset cause register, and
//! resetting the bits in that register) are left solely in the hands of the
//! application.
//
//*****************************************************************************
void
ResetISR(void)
{
//
// Call the application's entry point.
//
__iar_program_start();
}
//*****************************************************************************
//
//! This is the code that gets called when the processor receives a NMI. This
//! simply enters an infinite loop, preserving the system state for examination
//! by a debugger.
//
//*****************************************************************************
static void
NmiSR(void)
{
//
// Enter an infinite loop.
//
while(1)
{
}
}
//*****************************************************************************
//
//! This is the code that gets called when the processor receives a fault
//! interrupt. This simply enters an infinite loop, preserving the system state
//! for examination by a debugger.
//
//*****************************************************************************
static void
FaultISR(void)
{
//
// Enter an infinite loop.
//
while(1)
{
}
}
//*****************************************************************************
//
//! This is the code that gets called when the processor receives an unexpected
//! interrupt. This simply enters an infinite loop, preserving the system state
//! for examination by a debugger.
//
//*****************************************************************************
static void
BusFaultHandler(void)
{
//
// Go into an infinite loop.
//
while(1)
{
}
}
//*****************************************************************************
//
//! This is the code that gets called when the processor receives an unexpected
//! interrupt. This simply enters an infinite loop, preserving the system state
//! for examination by a debugger.
//
//*****************************************************************************
static void
IntDefaultHandler(void)
{
//
// Go into an infinite loop.
//
while(1)
{
}
}

361
common/startup_gcc.c Normal file
View File

@ -0,0 +1,361 @@
//*****************************************************************************
// startup_gcc.c
//
// Startup code for use with GCC.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#include <stdint.h>
#include "hw_nvic.h"
#include "hw_types.h"
//*****************************************************************************
//
// Heap block pointers defined by linker script
//
//*****************************************************************************
static char *heap_end = 0;
extern unsigned long _heap;
extern unsigned long _eheap;
//*****************************************************************************
//
// Forward declaration of the default fault handlers.
//
//*****************************************************************************
void ResetISR(void);
static void NmiSR(void);
static void FaultISR(void);
static void IntDefaultHandler(void);
static void BusFaultHandler(void);
//*****************************************************************************
//
// External declaration for the reset handler that is to be called when the
// processor is started
//
//*****************************************************************************
extern void _c_int00(void);
extern void vPortSVCHandler(void);
extern void xPortPendSVHandler(void);
extern void xPortSysTickHandler(void);
//*****************************************************************************
//
// The entry point for the application.
//
//*****************************************************************************
extern int main(void);
//*****************************************************************************
//
// Reserve space for the system stack.
//
//*****************************************************************************
static uint32_t pui32Stack[1024];
//*****************************************************************************
//
// The vector table. Note that the proper constructs must be placed on this to
// ensure that it ends up at physical address 0x0000.0000.
//
//*****************************************************************************
__attribute__ ((section(".intvecs")))
void (* const g_pfnVectors[256])(void) =
{
(void (*)(void))((uint32_t)pui32Stack + sizeof(pui32Stack)),
// The initial stack pointer
ResetISR, // The reset handler
NmiSR, // The NMI handler
FaultISR, // The hard fault handler
IntDefaultHandler, // The MPU fault handler
BusFaultHandler, // The bus fault handler
IntDefaultHandler, // The usage fault handler
0, // Reserved
0, // Reserved
0, // Reserved
0, // Reserved
#ifdef USE_FREERTOS
vPortSVCHandler, // SVCall handler
#else
IntDefaultHandler, // SVCall handler
#endif
IntDefaultHandler, // Debug monitor handler
0, // Reserved
#ifdef USE_FREERTOS
xPortPendSVHandler, // The PendSV handler
xPortSysTickHandler, // The SysTick handler
#else
IntDefaultHandler, // The PendSV handler
IntDefaultHandler, // The SysTick handler
#endif
IntDefaultHandler, // GPIO Port A0
IntDefaultHandler, // GPIO Port A1
IntDefaultHandler, // GPIO Port A2
IntDefaultHandler, // GPIO Port A3
0, // Reserved
IntDefaultHandler, // UART0 Rx and Tx
IntDefaultHandler, // UART1 Rx and Tx
0, // Reserved
IntDefaultHandler, // I2C0 Master and Slave
0,0,0,0,0, // Reserved
IntDefaultHandler, // ADC Channel 0
IntDefaultHandler, // ADC Channel 1
IntDefaultHandler, // ADC Channel 2
IntDefaultHandler, // ADC Channel 3
IntDefaultHandler, // Watchdog Timer
IntDefaultHandler, // Timer 0 subtimer A
IntDefaultHandler, // Timer 0 subtimer B
IntDefaultHandler, // Timer 1 subtimer A
IntDefaultHandler, // Timer 1 subtimer B
IntDefaultHandler, // Timer 2 subtimer A
IntDefaultHandler, // Timer 2 subtimer B
0,0,0,0, // Reserved
IntDefaultHandler, // Flash
0,0,0,0,0, // Reserved
IntDefaultHandler, // Timer 3 subtimer A
IntDefaultHandler, // Timer 3 subtimer B
0,0,0,0,0,0,0,0,0, // Reserved
IntDefaultHandler, // uDMA Software Transfer
IntDefaultHandler, // uDMA Error
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
IntDefaultHandler, // SHA
0,0, // Reserved
IntDefaultHandler, // AES
0, // Reserved
IntDefaultHandler, // DES
0,0,0,0,0, // Reserved
IntDefaultHandler, // SDHost
0, // Reserved
IntDefaultHandler, // I2S
0, // Reserved
IntDefaultHandler, // Camera
0,0,0,0,0,0,0, // Reserved
IntDefaultHandler, // NWP to APPS Interrupt
IntDefaultHandler, // Power, Reset and Clock module
0,0, // Reserved
IntDefaultHandler, // Shared SPI
IntDefaultHandler, // Generic SPI
IntDefaultHandler, // Link SPI
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0,0,0,0,0,0,0,0,0, // Reserved
0,0 // Reserved
};
//*****************************************************************************
//
// The following are constructs created by the linker, indicating where the
// the "data" and "bss" segments reside in memory. The initializers for the
// for the "data" segment resides immediately following the "text" segment.
//
//*****************************************************************************
extern uint32_t _etext;
extern uint32_t _data;
extern uint32_t _edata;
extern uint32_t _bss;
extern uint32_t _ebss;
extern uint32_t __init_data;
//*****************************************************************************
//
// This is the code that gets called when the processor first starts execution
// following a reset event. Only the absolutely necessary set is performed,
// after which the application supplied entry() routine is called. Any fancy
// actions (such as making decisions based on the reset cause register, and
// resetting the bits in that register) are left solely in the hands of the
// application.
//
//*****************************************************************************
void
ResetISR(void)
{
uint32_t *pui32Src, *pui32Dest;
//
// Copy the data segment initializers
//
pui32Src = &__init_data;
for(pui32Dest = &_data; pui32Dest < &_edata; )
{
*pui32Dest++ = *pui32Src++;
}
//
// Zero fill the bss segment.
//
__asm(" ldr r0, =_bss\n"
" ldr r1, =_ebss\n"
" mov r2, #0\n"
" .thumb_func\n"
"zero_loop:\n"
" cmp r0, r1\n"
" it lt\n"
" strlt r2, [r0], #4\n"
" blt zero_loop");
//
// Call the application's entry point.
//
main();
}
//*****************************************************************************
//
// This is the code that gets called when the processor receives a NMI. This
// simply enters an infinite loop, preserving the system state for examination
// by a debugger.
//
//*****************************************************************************
static void
NmiSR(void)
{
//
// Enter an infinite loop.
//
while(1)
{
}
}
//*****************************************************************************
//
// This is the code that gets called when the processor receives a fault
// interrupt. This simply enters an infinite loop, preserving the system state
// for examination by a debugger.
//
//*****************************************************************************
static void
FaultISR(void)
{
//
// Enter an infinite loop.
//
while(1)
{
}
}
//*****************************************************************************
//
// This is the code that gets called when the processor receives an unexpected
// interrupt. This simply enters an infinite loop, preserving the system state
// for examination by a debugger.
//
//*****************************************************************************
static void
BusFaultHandler(void)
{
//
// Go into an infinite loop.
//
while(1)
{
}
}
//*****************************************************************************
//
// This is the code that gets called when the processor receives an unexpected
// interrupt. This simply enters an infinite loop, preserving the system state
// for examination by a debugger.
//
//*****************************************************************************
static void
IntDefaultHandler(void)
{
//
// Go into an infinite loop.
//
while(1)
{
}
}
//*****************************************************************************
//
// This function is used by dynamic memory allocation API(s) in newlib
// library
//
//*****************************************************************************
void * _sbrk(unsigned int incr)
{
char *prev_heap_end;
//
// Check if this function is calld for the
// first time and the heap end pointer
//
if (heap_end == 0)
{
heap_end = (char *)&_heap;
}
//
// Check if we have enough heap memory available
//
prev_heap_end = heap_end;
if (heap_end + incr > (char *)&_eheap)
{
//
// Return error
//
return 0;
}
//
// Set the new heap end pointer
//
heap_end += incr;
//
// Return the pointer to the newly allocated memory
//
return prev_heap_end;
}

330
common/timer_if.c Normal file
View File

@ -0,0 +1,330 @@
//*****************************************************************************
// timer_if.c
//
// timer interface file: contains different interface functions for timer APIs
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
// Driverlib includes
#include "hw_types.h"
#include "hw_memmap.h"
#include "hw_ints.h"
#include "debug.h"
#include "interrupt.h"
#include "timer.h"
#include "rom.h"
#include "rom_map.h"
#include "prcm.h"
// TI-RTOS includes
#if defined(USE_TIRTOS) || defined(USE_FREERTOS) || defined(SL_PLATFORM_MULTI_THREADED)
#include <stdlib.h>
#include "osi.h"
#endif
#include "timer_if.h"
static unsigned char
GetPeripheralIntNum(unsigned long ulBase, unsigned long ulTimer)
{
if(ulTimer == TIMER_A)
{
switch(ulBase)
{
case TIMERA0_BASE:
return INT_TIMERA0A;
case TIMERA1_BASE:
return INT_TIMERA1A;
case TIMERA2_BASE:
return INT_TIMERA2A;
case TIMERA3_BASE:
return INT_TIMERA3A;
default:
return INT_TIMERA0A;
}
}
else if(ulTimer == TIMER_B)
{
switch(ulBase)
{
case TIMERA0_BASE:
return INT_TIMERA0B;
case TIMERA1_BASE:
return INT_TIMERA1B;
case TIMERA2_BASE:
return INT_TIMERA2B;
case TIMERA3_BASE:
return INT_TIMERA3B;
default:
return INT_TIMERA0B;
}
}
else
{
return INT_TIMERA0A;
}
}
//*****************************************************************************
//
//! Initializing the Timer
//!
//! \param ePeripheral is the peripheral which need to be initialized.
//! \param ulBase is the base address for the timer.
//! \param ulConfig is the configuration for the timer.
//! \param ulTimer selects amoung the TIMER_A or TIMER_B or TIMER_BOTH.
//! \param ulValue is the timer prescale value which must be between 0 and
//! 255 (inclusive) for 16/32-bit timers and between 0 and 65535 (inclusive)
//! for 32/64-bit timers.
//! This function
//! 1. Enables and reset the peripheral for the timer.
//! 2. Configures and set the prescale value for the timer.
//!
//! \return none
//
//*****************************************************************************
void Timer_IF_Init( unsigned long ePeripheral, unsigned long ulBase, unsigned
long ulConfig, unsigned long ulTimer, unsigned long ulValue)
{
//
// Initialize GPT A0 (in 32 bit mode) as periodic down counter.
//
MAP_PRCMPeripheralClkEnable(ePeripheral, PRCM_RUN_MODE_CLK);
MAP_PRCMPeripheralReset(ePeripheral);
MAP_TimerConfigure(ulBase,ulConfig);
MAP_TimerPrescaleSet(ulBase,ulTimer,ulValue);
}
//*****************************************************************************
//
//! setting up the timer
//!
//! \param ulBase is the base address for the timer.
//! \param ulTimer selects between the TIMER_A or TIMER_B or TIMER_BOTH.
//! \param TimerBaseIntHandler is the pointer to the function that handles the
//! interrupt for the Timer
//!
//! This function
//! 1. Register the function handler for the timer interrupt.
//! 2. enables the timer interrupt.
//!
//! \return none
//
//*****************************************************************************
void Timer_IF_IntSetup(unsigned long ulBase, unsigned long ulTimer,
void (*TimerBaseIntHandler)(void))
{
//
// Setup the interrupts for the timer timeouts.
//
#if defined(USE_TIRTOS) || defined(USE_FREERTOS) || defined(SL_PLATFORM_MULTI_THREADED)
// USE_TIRTOS: if app uses TI-RTOS (either networking/non-networking)
// USE_FREERTOS: if app uses Free-RTOS (either networking/non-networking)
// SL_PLATFORM_MULTI_THREADED: if app uses any OS + networking(simplelink)
if(ulTimer == TIMER_BOTH)
{
osi_InterruptRegister(GetPeripheralIntNum(ulBase, TIMER_A),
TimerBaseIntHandler, INT_PRIORITY_LVL_1);
osi_InterruptRegister(GetPeripheralIntNum(ulBase, TIMER_B),
TimerBaseIntHandler, INT_PRIORITY_LVL_1);
}
else
{
osi_InterruptRegister(GetPeripheralIntNum(ulBase, ulTimer),
TimerBaseIntHandler, INT_PRIORITY_LVL_1);
}
#else
MAP_IntPrioritySet(GetPeripheralIntNum(ulBase, ulTimer), INT_PRIORITY_LVL_1);
MAP_TimerIntRegister(ulBase, ulTimer, TimerBaseIntHandler);
#endif
if(ulTimer == TIMER_BOTH)
{
MAP_TimerIntEnable(ulBase, TIMER_TIMA_TIMEOUT|TIMER_TIMB_TIMEOUT);
}
else
{
MAP_TimerIntEnable(ulBase, ((ulTimer == TIMER_A) ? TIMER_TIMA_TIMEOUT :
TIMER_TIMB_TIMEOUT));
}
}
//*****************************************************************************
//
//! clears the timer interrupt
//!
//! \param ulBase is the base address for the timer.
//!
//! This function
//! 1. clears the interrupt with given base.
//!
//! \return none
//
//*****************************************************************************
void Timer_IF_InterruptClear(unsigned long ulBase)
{
unsigned long ulInts;
ulInts = MAP_TimerIntStatus(ulBase, true);
//
// Clear the timer interrupt.
//
MAP_TimerIntClear(ulBase, ulInts);
}
//*****************************************************************************
//
//! starts the timer
//!
//! \param ulBase is the base address for the timer.
//! \param ulTimer selects amoung the TIMER_A or TIMER_B or TIMER_BOTH.
//! \param ulValue is the time delay in mSec after that run out,
//! timer gives an interrupt.
//!
//! This function
//! 1. Load the Timer with the specified value.
//! 2. enables the timer.
//!
//! \return none
//!
//! \Note- HW Timer runs on 80MHz clock
//
//*****************************************************************************
void Timer_IF_Start(unsigned long ulBase, unsigned long ulTimer,
unsigned long ulValue)
{
MAP_TimerLoadSet(ulBase,ulTimer,MILLISECONDS_TO_TICKS(ulValue));
//
// Enable the GPT
//
MAP_TimerEnable(ulBase,ulTimer);
}
//*****************************************************************************
//
//! disable the timer
//!
//! \param ulBase is the base address for the timer.
//! \param ulTimer selects amoung the TIMER_A or TIMER_B or TIMER_BOTH.
//!
//! This function
//! 1. disables the interupt.
//!
//! \return none
//
//*****************************************************************************
void Timer_IF_Stop(unsigned long ulBase, unsigned long ulTimer)
{
//
// Disable the GPT
//
MAP_TimerDisable(ulBase,ulTimer);
}
//*****************************************************************************
//
//! De-Initialize the timer
//!
//! \param uiGPTBaseAddr
//! \param ulTimer
//!
//! This function
//! 1. disable the timer interrupts
//! 2. unregister the timer interrupt
//!
//! \return None.
//
//*****************************************************************************
void Timer_IF_DeInit(unsigned long ulBase,unsigned long ulTimer)
{
//
// Disable the timer interrupt
//
MAP_TimerIntDisable(ulBase,TIMER_TIMA_TIMEOUT|TIMER_TIMB_TIMEOUT);
//
// Unregister the timer interrupt
//
MAP_TimerIntUnregister(ulBase,ulTimer);
}
//*****************************************************************************
//
//! starts the timer
//!
//! \param ulBase is the base address for the timer.
//! \param ulTimer selects between the TIMER A and TIMER B.
//! \param ulValue is timer reload value (mSec) after which the timer will run out and gives an interrupt.
//!
//! This function
//! 1. Reload the Timer with the specified value.
//!
//! \return none
//
//*****************************************************************************
void Timer_IF_ReLoad(unsigned long ulBase, unsigned long ulTimer,
unsigned long ulValue)
{
MAP_TimerLoadSet(ulBase,ulTimer,MILLISECONDS_TO_TICKS(ulValue));
}
//*****************************************************************************
//
//! starts the timer
//!
//! \param ulBase is the base address for the timer.
//! \param ulTimer selects amoung the TIMER_A or TIMER_B or TIMER_BOTH.
//!
//! This function
//! 1. returns the timer value.
//!
//! \return Timer Value.
//
//*****************************************************************************
unsigned int Timer_IF_GetCount(unsigned long ulBase, unsigned long ulTimer)
{
unsigned long ulCounter;
ulCounter = MAP_TimerValueGet(ulBase, ulTimer);
return 0xFFFFFFFF - ulCounter;
}
//*****************************************************************************
//
// Close the Doxygen group.
//! @}
//
//*****************************************************************************

81
common/timer_if.h Normal file
View File

@ -0,0 +1,81 @@
//*****************************************************************************
// timer_if.h
//
// timer interface header file: Prototypes and Macros for timer APIs
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#ifndef __TIMER_IF_H__
#define __TIMER_IF_H__
//*****************************************************************************
//
// If building with a C++ compiler, make all of the definitions in this header
// have a C binding.
//
//*****************************************************************************
#ifdef __cplusplus
extern "C"
{
#endif
/****************************************************************************/
/* MACROS */
/****************************************************************************/
#define SYS_CLK 80000000
#define MILLISECONDS_TO_TICKS(ms) ((SYS_CLK/1000) * (ms))
#define PERIODIC_TEST_LOOPS 5
extern void Timer_IF_Init( unsigned long ePeripheralc, unsigned long ulBase,
unsigned long ulConfig, unsigned long ulTimer, unsigned long ulValue);
extern void Timer_IF_IntSetup(unsigned long ulBase, unsigned long ulTimer,
void (*TimerBaseIntHandler)(void));
extern void Timer_IF_InterruptClear(unsigned long ulBase);
extern void Timer_IF_Start(unsigned long ulBase, unsigned long ulTimer,
unsigned long ulValue);
extern void Timer_IF_Stop(unsigned long ulBase, unsigned long ulTimer);
extern void Timer_IF_ReLoad(unsigned long ulBase, unsigned long ulTimer,
unsigned long ulValue);
extern unsigned int Timer_IF_GetCount(unsigned long ulBase, unsigned long ulTimer);
void Timer_IF_DeInit(unsigned long ulBase,unsigned long ulTimer);
//*****************************************************************************
//
// Mark the end of the C bindings section for C++ compilers.
//
//*****************************************************************************
#ifdef __cplusplus
}
#endif
#endif // __TIMER_IF_H__

337
common/uart_if.c Normal file
View File

@ -0,0 +1,337 @@
//*****************************************************************************
// uart_if.c
//
// uart interface file: Prototypes and Macros for UARTLogger
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
// Standard includes
#include <stdarg.h>
#include <stdlib.h>
#include <stdio.h>
#include <string.h>
// Driverlib includes
#include "hw_types.h"
#include "hw_memmap.h"
#include "prcm.h"
#include "pin.h"
#include "uart.h"
#include "rom.h"
#include "rom_map.h"
#if defined(USE_FREERTOS) || defined(USE_TI_RTOS)
#include "osi.h"
#endif
#include "uart_if.h"
#define IS_SPACE(x) (x == 32 ? 1 : 0)
//*****************************************************************************
// Global variable indicating command is present
//*****************************************************************************
static unsigned long __Errorlog;
//*****************************************************************************
// Global variable indicating input length
//*****************************************************************************
unsigned int ilen=1;
//*****************************************************************************
//
//! Initialization
//!
//! This function
//! 1. Configures the UART to be used.
//!
//! \return none
//
//*****************************************************************************
void
InitTerm()
{
#ifndef NOTERM
MAP_UARTConfigSetExpClk(CONSOLE,MAP_PRCMPeripheralClockGet(CONSOLE_PERIPH),
UART_BAUD_RATE, (UART_CONFIG_WLEN_8 | UART_CONFIG_STOP_ONE |
UART_CONFIG_PAR_NONE));
#endif
__Errorlog = 0;
}
//*****************************************************************************
//
//! Outputs a character string to the console
//!
//! \param str is the pointer to the string to be printed
//!
//! This function
//! 1. prints the input string character by character on to the console.
//!
//! \return none
//
//*****************************************************************************
void
Message(const char *str)
{
#ifndef NOTERM
if(str != NULL)
{
while(*str!='\0')
{
MAP_UARTCharPut(CONSOLE,*str++);
}
}
#endif
}
//*****************************************************************************
//
//! Clear the console window
//!
//! This function
//! 1. clears the console window.
//!
//! \return none
//
//*****************************************************************************
void
ClearTerm()
{
Message("\33[2J\r");
}
//*****************************************************************************
//
//! Error Function
//!
//! \param
//!
//! \return none
//!
//*****************************************************************************
void
Error(char *pcFormat, ...)
{
#ifndef NOTERM
char cBuf[256];
va_list list;
va_start(list,pcFormat);
vsnprintf(cBuf,256,pcFormat,list);
Message(cBuf);
#endif
__Errorlog++;
}
//*****************************************************************************
//
//! Get the Command string from UART
//!
//! \param pucBuffer is the command store to which command will be populated
//! \param ucBufLen is the length of buffer store available
//!
//! \return Length of the bytes received. -1 if buffer length exceeded.
//!
//*****************************************************************************
int
GetCmd(char *pcBuffer, unsigned int uiBufLen)
{
char cChar;
int iLen = 0;
//
// Wait to receive a character over UART
//
while(MAP_UARTCharsAvail(CONSOLE) == false)
{
#if defined(USE_FREERTOS) || defined(USE_TI_RTOS)
osi_Sleep(1);
#endif
}
cChar = MAP_UARTCharGetNonBlocking(CONSOLE);
//
// Echo the received character
//
MAP_UARTCharPut(CONSOLE, cChar);
iLen = 0;
//
// Checking the end of Command
//
while((cChar != '\r') && (cChar !='\n') )
{
//
// Handling overflow of buffer
//
if(iLen >= uiBufLen)
{
return -1;
}
//
// Copying Data from UART into a buffer
//
if(cChar != '\b')
{
*(pcBuffer + iLen) = cChar;
iLen++;
}
else
{
//
// Deleting last character when you hit backspace
//
if(iLen)
{
iLen--;
}
}
//
// Wait to receive a character over UART
//
while(MAP_UARTCharsAvail(CONSOLE) == false)
{
#if defined(USE_FREERTOS) || defined(USE_TI_RTOS)
osi_Sleep(1);
#endif
}
cChar = MAP_UARTCharGetNonBlocking(CONSOLE);
//
// Echo the received character
//
MAP_UARTCharPut(CONSOLE, cChar);
}
*(pcBuffer + iLen) = '\0';
Report("\n\r");
return iLen;
}
//*****************************************************************************
//
//! Trim the spaces from left and right end of given string
//!
//! \param Input string on which trimming happens
//!
//! \return length of trimmed string
//
//*****************************************************************************
int TrimSpace(char * pcInput)
{
size_t size;
char *endStr, *strData = pcInput;
char index = 0;
size = strlen(strData);
if (!size)
return 0;
endStr = strData + size - 1;
while (endStr >= strData && IS_SPACE(*endStr))
endStr--;
*(endStr + 1) = '\0';
while (*strData && IS_SPACE(*strData))
{
strData++;
index++;
}
memmove(pcInput,strData,strlen(strData)+1);
return strlen(pcInput);
}
//*****************************************************************************
//
//! prints the formatted string on to the console
//!
//! \param format is a pointer to the character string specifying the format in
//! the following arguments need to be interpreted.
//! \param [variable number of] arguments according to the format in the first
//! parameters
//! This function
//! 1. prints the formatted error statement.
//!
//! \return count of characters printed
//
//*****************************************************************************
int Report(const char *pcFormat, ...)
{
int iRet = 0;
#ifndef NOTERM
char *pcBuff, *pcTemp;
int iSize = 256;
va_list list;
pcBuff = (char*)malloc(iSize);
if(pcBuff == NULL)
{
return -1;
}
while(1)
{
va_start(list,pcFormat);
iRet = vsnprintf(pcBuff,iSize,pcFormat,list);
va_end(list);
if(iRet > -1 && iRet < iSize)
{
break;
}
else
{
iSize*=2;
if((pcTemp=realloc(pcBuff,iSize))==NULL)
{
Message("Could not reallocate memory\n\r");
iRet = -1;
break;
}
else
{
pcBuff=pcTemp;
}
}
}
Message(pcBuff);
free(pcBuff);
#endif
return iRet;
}

94
common/uart_if.h Normal file
View File

@ -0,0 +1,94 @@
//*****************************************************************************
// uart_if.h
//
// uart interface header file: Prototypes and Macros for UARTLogger
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#ifndef __uart_if_H__
#define __uart_if_H__
//*****************************************************************************
//
// If building with a C++ compiler, make all of the definitions in this header
// have a C binding.
//
//*****************************************************************************
#ifdef __cplusplus
extern "C"
{
#endif
/****************************************************************************/
/* MACROS */
/****************************************************************************/
#define UART_BAUD_RATE 115200
#define SYSCLK 80000000
#define CONSOLE UARTA0_BASE
#define CONSOLE_PERIPH PRCM_UARTA0
//
// Define the size of UART IF buffer for RX
//
#define UART_IF_BUFFER 64
//
// Define the UART IF buffer
//
extern unsigned char g_ucUARTBuffer[];
/****************************************************************************/
/* FUNCTION PROTOTYPES */
/****************************************************************************/
extern void DispatcherUARTConfigure(void);
extern void DispatcherUartSendPacket(unsigned char *inBuff, unsigned short usLength);
extern int GetCmd(char *pcBuffer, unsigned int uiBufLen);
extern void InitTerm(void);
extern void ClearTerm(void);
extern void Message(const char *format);
extern void Error(char *format,...);
extern int TrimSpace(char * pcInput);
extern int Report(const char *format, ...);
//*****************************************************************************
//
// Mark the end of the C bindings section for C++ compilers.
//
//*****************************************************************************
#ifdef __cplusplus
}
#endif
#endif

370
common/udma_if.c Normal file
View File

@ -0,0 +1,370 @@
//*****************************************************************************
// udma_if.c
//
// uDMA interface file
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#include <stdio.h>
#include <string.h>
// Driverlib includes
#include "hw_ints.h"
#include "hw_memmap.h"
#include "hw_uart.h"
#include "hw_types.h"
#include "hw_udma.h"
#include "rom.h"
#include "rom_map.h"
#include "gpio.h"
#include "udma.h"
#include "interrupt.h"
#include "prcm.h"
#include "uart.h"
// TI-RTOS includes
#if defined(USE_TIRTOS) || defined(USE_FREERTOS) || defined(SL_PLATFORM_MULTI_THREADED)
#include <stdlib.h>
#include "osi.h"
#endif
#include "udma_if.h"
#define MAX_NUM_CH 64 //32*2 entries
#define CTL_TBL_SIZE 64 //32*2 entries
#define UDMA_CH5_BITID (1<<5)
//*****************************************************************************
// GLOBAL VARIABLES -- Start
//*****************************************************************************
volatile unsigned char iDone;
tAppCallbackHndl gfpAppCallbackHndl[MAX_NUM_CH];
#if defined(gcc)
tDMAControlTable gpCtlTbl[CTL_TBL_SIZE] __attribute__(( aligned(1024)));
#endif
#if defined(ccs)
#pragma DATA_ALIGN(gpCtlTbl, 1024)
tDMAControlTable gpCtlTbl[CTL_TBL_SIZE];
#endif
#if defined(ewarm)
#pragma data_alignment=1024
tDMAControlTable gpCtlTbl[CTL_TBL_SIZE];
#endif
//*****************************************************************************
// GLOBAL VARIABLES -- End
//*****************************************************************************
//*****************************************************************************
//
//! DMA software interrupt handler
//!
//! \param None
//!
//! This function
//! 1. Invoked when DMA operation is complete
//!
//! \return None.
//
//*****************************************************************************
void
DmaSwIntHandler(void)
{
unsigned long uiIntStatus;
iDone = 1;
uiIntStatus = MAP_uDMAIntStatus();
MAP_uDMAIntClear(uiIntStatus);
}
//*****************************************************************************
//
//! DMA error interrupt handler
//!
//! \param None
//!
//! This function
//! 1. Invoked when DMA operation is in error
//!
//! \return None.
//
//*****************************************************************************
void
DmaErrorIntHandler(void)
{
MAP_uDMAIntClear(MAP_uDMAIntStatus());
}
//*****************************************************************************
//
//! Initialize the DMA controller
//!
//! \param None
//!
//! This function initializes
//! 1. Initializes the McASP module
//!
//! \return None.
//
//*****************************************************************************
void UDMAInit()
{
unsigned int uiLoopCnt;
//
// Enable McASP at the PRCM module
//
MAP_PRCMPeripheralClkEnable(PRCM_UDMA,PRCM_RUN_MODE_CLK);
MAP_PRCMPeripheralReset(PRCM_UDMA);
//
// Register interrupt handlers
//
#if defined(USE_TIRTOS) || defined(USE_FREERTOS) || defined(SL_PLATFORM_MULTI_THREADED)
// USE_TIRTOS: if app uses TI-RTOS (either networking/non-networking)
// USE_FREERTOS: if app uses Free-RTOS (either networking/non-networking)
// SL_PLATFORM_MULTI_THREADED: if app uses any OS + networking(simplelink)
osi_InterruptRegister(INT_UDMA, DmaSwIntHandler, INT_PRIORITY_LVL_1);
osi_InterruptRegister(INT_UDMAERR, DmaErrorIntHandler, INT_PRIORITY_LVL_1);
#else
MAP_IntPrioritySet(INT_UDMA, INT_PRIORITY_LVL_1);
MAP_uDMAIntRegister(UDMA_INT_SW, DmaSwIntHandler);
MAP_IntPrioritySet(INT_UDMAERR, INT_PRIORITY_LVL_1);
MAP_uDMAIntRegister(UDMA_INT_ERR, DmaErrorIntHandler);
#endif
//
// Enable uDMA using master enable
//
MAP_uDMAEnable();
//
// Set Control Table
//
memset(gpCtlTbl,0,sizeof(tDMAControlTable)*CTL_TBL_SIZE);
MAP_uDMAControlBaseSet(gpCtlTbl);
//
// Reset App Callbacks
//
for(uiLoopCnt = 0; uiLoopCnt < MAX_NUM_CH; uiLoopCnt++)
{
gfpAppCallbackHndl[uiLoopCnt] = NULL;
}
}
//*****************************************************************************
//
//! Configures the uDMA channel
//!
//! \param uiChannel is the DMA channel to be selected
//! \param pfpAppCb is the application callback to be invoked on transfer
//!
//! This function
//! 1. Configures the uDMA channel
//!
//! \return None.
//
//*****************************************************************************
void UDMAChannelSelect(unsigned int uiChannel, tAppCallbackHndl pfpAppCb)
{
if((uiChannel & 0xFF) >= MAX_NUM_CH)
{
return;
}
MAP_uDMAChannelAssign(uiChannel);
MAP_uDMAChannelAttributeDisable(uiChannel,UDMA_ATTR_ALTSELECT);
gfpAppCallbackHndl[(uiChannel & 0xFF)] = pfpAppCb;
}
//*****************************************************************************
//
//! Sets up the Auto Memory transfer
//!
//! \param ulChannel. DMA Channel to be used
//! \param pvSrcBuf. Pointer to the source buffer
//! \param pvDstBuf. Pointer to the destination buffer
//! \param size. Items to be transfered(should not exceed 1024).
//!
//! This function
//! 1. Configures the uDMA channel
//!
//! \return None.
//
//*****************************************************************************
void UDMASetupAutoMemTransfer(unsigned long ulChannel, void *pvSrcBuf,
void *pvDstBuf, unsigned long size)
{
UDMASetupTransfer(ulChannel, UDMA_MODE_AUTO, size,
UDMA_SIZE_8, UDMA_ARB_8, pvSrcBuf,
UDMA_SRC_INC_8, pvDstBuf, UDMA_DST_INC_8);
}
//*****************************************************************************
//
//! Sets up the Ping Pong mode of transfer
//!
//! \param ulChannel. DMA Channel to be used
//! \param pvSrcBuf1.Pointer to the Source Buffer for Primary Control Structure
//! \param pvDstBuf1.Pointer to the Destination Buffer for Primary Structure
//! \param pvSrcBuf2.Pointer to the Source Buffer for alternate Control Structure
//! \param pvDstBuf2. Pointer to the Destination Buffer for alternate Structure
//! \param size. Total size to be transferred(should not exceed 1024).
//!
//! This function
//! 1. Configures the uDMA channel
//!
//! \return None.
//
//*****************************************************************************
void UDMASetupPingPongTransfer(unsigned long ulChannel, void *pvSrcBuf1,
void *pvDstBuf1, void *pvSrcBuf2,
void *pvDstBuf2, unsigned long size)
{
UDMASetupTransfer(ulChannel, UDMA_MODE_PINGPONG, size, UDMA_SIZE_8,
UDMA_ARB_8, pvSrcBuf1, UDMA_SRC_INC_8,
pvDstBuf1, UDMA_DST_INC_8);
UDMASetupTransfer(ulChannel|UDMA_ALT_SELECT, UDMA_MODE_PINGPONG, size,
UDMA_SIZE_8, UDMA_ARB_8, pvSrcBuf2, UDMA_SRC_INC_8,
pvDstBuf2, UDMA_DST_INC_8);
}
//*****************************************************************************
//
//! Start the DMA SW transfer
//!
//! \param None
//!
//! This function
//! 1. Starts the SW controlled uDMA transfer
//!
//! \return None.
//
//*****************************************************************************
void UDMAStartTransfer(unsigned long ulChannel)
{
//
// Request for channel transfer
//
MAP_uDMAChannelRequest(ulChannel);
}
//*****************************************************************************
//
//! Stop the DMA transfer
//!
//! \param None
//!
//! This function
//! 1. Stops the uDMA transfer on specified channel
//!
//! \return None.
//
//*****************************************************************************
void UDMAStopTransfer(unsigned long ulChannel)
{
//
// Disable the channel
//
MAP_uDMAChannelDisable(ulChannel);
}
//*****************************************************************************
//
//! De-Initialize the DMA controller
//!
//! \param None
//!
//! This function
//! 1. De-Initializes the uDMA module
//!
//! \return None.
//
//*****************************************************************************
void UDMADeInit()
{
//
// UnRegister interrupt handlers
//
MAP_uDMAIntUnregister(UDMA_INT_SW);
MAP_uDMAIntUnregister(UDMA_INT_ERR);
//
// Disable the uDMA
//
MAP_uDMADisable();
}
//*****************************************************************************
//
//! Does the actual Memory transfer
//!
//! \param ulChannel. DMA Channel to be used
//! \param ulMode. DMA Mode to be used
//! \param ulItemCount. Items to be transfered in DMA Transfer(should not exceed 1024)
//! \param ulArbSize. Arbitration Size to be set
//! \param pvSrcBuf. Pointer to the source Buffer
//! \param ulSrcInc. Source Increment
//! \param pvDstBuf. Pointer to the Destination Buffer
//! \param ulDstInc. Destination Increment
//!
//! This function
//! 1. Sets up the uDMA registers to perform the actual transfer
//!
//! \return None.
//
//*****************************************************************************
void UDMASetupTransfer(unsigned long ulChannel, unsigned long ulMode,
unsigned long ulItemCount, unsigned long ulItemSize,
unsigned long ulArbSize, void *pvSrcBuf,
unsigned long ulSrcInc, void *pvDstBuf,
unsigned long ulDstInc)
{
MAP_uDMAChannelControlSet(ulChannel, ulItemSize | ulSrcInc | ulDstInc | ulArbSize);
MAP_uDMAChannelAttributeEnable(ulChannel,UDMA_ATTR_USEBURST);
MAP_uDMAChannelTransferSet(ulChannel, ulMode, pvSrcBuf, pvDstBuf, ulItemCount);
MAP_uDMAChannelEnable(ulChannel);
}
//*****************************************************************************
//
// Close the Doxygen group.
//! @}
//
//*****************************************************************************

95
common/udma_if.h Normal file
View File

@ -0,0 +1,95 @@
//*****************************************************************************
// udma_if.h
//
// uDMA interface MACRO and function prototypes
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#ifndef __UDMA_IF_H__
#define __UDMA_IF_H__
//*****************************************************************************
//
// If building with a C++ compiler, make all of the definitions in this header
// have a C binding.
//
//*****************************************************************************
#ifdef __cplusplus
extern "C"
{
#endif
#define PRINT_DBG printf
typedef void (*tAppCallbackHndl)(void);
#define MAX_NUM_CH 64 //32*2 entries
#define CTL_TBL_SIZE 64 //32*2 entries
#define UDMA_CH5_BITID (1<<5)
//
// UDMA Interface APIs
//
void UDMAInit();
void UDMAChannelSelect(unsigned int uiChannel, tAppCallbackHndl pfpAppCb);
void UDMASetupAutoMemTransfer(
unsigned long ulChannel,
void *pvSrcBuf,
void *pvDstBuf,
unsigned long size);
void UDMASetupPingPongTransfer(
unsigned long ulChannel,
void *pvSrcBuf1,
void *pvDstBuf1,
void *pvSrcBuf2,
void *pvDstBuf2,
unsigned long size);
void UDMAStartTransfer(unsigned long ulChannel);
void UDMAStopTransfer(unsigned long ulChannel);
void UDMADeInit();
void UDMASetupTransfer(unsigned long ulChannel, unsigned long ulMode,
unsigned long ulItemCount, unsigned long ulItemSize,
unsigned long ulArbSize, void *pvSrcBuf,
unsigned long ulSrcInc, void *pvDstBuf, unsigned long ulDstInc);
//*****************************************************************************
//
// Mark the end of the C bindings section for C++ compilers.
//
//*****************************************************************************
#ifdef __cplusplus
}
#endif
#endif // __UDMA_IF_H__

212
common/utils_if.c Normal file
View File

@ -0,0 +1,212 @@
//*****************************************************************************
// utils_if.c
//
// Contains utility routines.
//
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#include <stdint.h>
#include <stdbool.h>
#include "hw_types.h"
#include "hw_memmap.h"
#include "rom.h"
#include "rom_map.h"
#include "hwspinlock.h"
#include "prcm.h"
#include "spi.h"
//*****************************************************************************
//
//! \addtogroup utils_if_api
//! @{
//
//*****************************************************************************
//*****************************************************************************
// Defines.
//*****************************************************************************
#define INSTR_READ_STATUS 0x05
#define INSTR_DEEP_POWER_DOWN 0xB9
#define STATUS_BUSY 0x01
#define MAX_SEMAPHORE_TAKE_TRIES (4000000)
//****************************************************************************
//
//! Put SPI flash into Deep Power Down mode
//!
//! Note:SPI flash is a shared resource between MCU and Network processing
//! units. This routine should only be exercised after all the network
//! processing has been stopped. To stop network processing use sl_stop API
//! \param None
//!
//! \return Status, 0:Pass, -1:Fail
//
//****************************************************************************
int Utils_SpiFlashDeepPowerDown(void)
{
unsigned long ulStatus=0;
//
// Acquire SSPI HwSpinlock.
//
if (0 != MAP_HwSpinLockTryAcquire(HWSPINLOCK_SSPI, MAX_SEMAPHORE_TAKE_TRIES))
{
return -1;
}
//
// Enable clock for SSPI module
//
MAP_PRCMPeripheralClkEnable(PRCM_SSPI, PRCM_RUN_MODE_CLK);
//
// Reset SSPI at PRCM level and wait for reset to complete
//
MAP_PRCMPeripheralReset(PRCM_SSPI);
while(MAP_PRCMPeripheralStatusGet(PRCM_SSPI)== false)
{
}
//
// Reset SSPI at module level
//
MAP_SPIReset(SSPI_BASE);
//
// Configure SSPI module
//
MAP_SPIConfigSetExpClk(SSPI_BASE,PRCMPeripheralClockGet(PRCM_SSPI),
20000000,SPI_MODE_MASTER,SPI_SUB_MODE_0,
(SPI_SW_CTRL_CS |
SPI_4PIN_MODE |
SPI_TURBO_OFF |
SPI_CS_ACTIVELOW |
SPI_WL_8));
//
// Enable SSPI module
//
MAP_SPIEnable(SSPI_BASE);
//
// Enable chip select for the spi flash.
//
MAP_SPICSEnable(SSPI_BASE);
//
// Wait for spi flash.
//
do
{
//
// Send the status register read instruction and read back a dummy byte.
//
MAP_SPIDataPut(SSPI_BASE,INSTR_READ_STATUS);
MAP_SPIDataGet(SSPI_BASE,&ulStatus);
//
// Write a dummy byte then read back the actual status.
//
MAP_SPIDataPut(SSPI_BASE,0xFF);
MAP_SPIDataGet(SSPI_BASE,&ulStatus);
}
while((ulStatus & 0xFF )== STATUS_BUSY);
//
// Disable chip select for the spi flash.
//
MAP_SPICSDisable(SSPI_BASE);
//
// Start another CS enable sequence for Power down command.
//
MAP_SPICSEnable(SSPI_BASE);
//
// Send Deep Power Down command to spi flash
//
MAP_SPIDataPut(SSPI_BASE,INSTR_DEEP_POWER_DOWN);
//
// Disable chip select for the spi flash.
//
MAP_SPICSDisable(SSPI_BASE);
//
// Release SSPI HwSpinlock.
//
MAP_HwSpinLockRelease(HWSPINLOCK_SSPI);
//
// Return as Pass.
//
return 0;
}
//****************************************************************************
//
//! Used to trigger a hibernate cycle for the SOC
//!
//! Note:This routine should only be exercised after all the network
//! processing has been stopped. To stop network processing use sl_stop API
//! \param None
//!
//! \return None
//
//****************************************************************************
void Utils_TriggerHibCycle(void)
{
//
// Configure the HIB module RTC wake time
//
MAP_PRCMHibernateIntervalSet(330);
//
// Enable the HIB RTC
//
MAP_PRCMHibernateWakeupSourceEnable(PRCM_HIB_SLOW_CLK_CTR);
//
// Enter HIBernate mode
//
MAP_PRCMHibernateEnter();
}
//*****************************************************************************
//
// Close the Doxygen group.
//! @}
//
//*****************************************************************************

70
common/utils_if.h Normal file
View File

@ -0,0 +1,70 @@
//*****************************************************************************
// utils_if.h
//
// Utils interface MACRO and function prototypes
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#ifndef __UTILS_IF_H__
#define __UTILS_IF_H__
//*****************************************************************************
//
// If building with a C++ compiler, make all of the definitions in this header
// have a C binding.
//
//*****************************************************************************
#ifdef __cplusplus
extern "C"
{
#endif
//
// Utils Interface APIs
//
int Utils_SpiFlashDeepPowerDown(void);
void Utils_TriggerHibCycle(void);
//*****************************************************************************
//
// Mark the end of the C bindings section for C++ compilers.
//
//*****************************************************************************
#ifdef __cplusplus
}
#endif
#endif // __UTILS_IF_H__

145
common/wdt_if.c Normal file
View File

@ -0,0 +1,145 @@
//*****************************************************************************
// wdt_if.c
//
// watchdog timer interface APIs
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#include <stdio.h>
#include "hw_types.h"
#include "hw_ints.h"
#include "hw_memmap.h"
#include "prcm.h"
#include "wdt.h"
#include "rom.h"
#include "rom_map.h"
#include "interrupt.h"
#include "wdt_if.h"
#if defined(USE_TIRTOS) || defined(USE_FREERTOS) || defined(SL_PLATFORM_MULTI_THREADED)
#include "osi.h"
#endif
/****************************************************************************/
/* FUNCTION DEFINITIONS */
/****************************************************************************/
//****************************************************************************
//
//! Initialize the watchdog timer
//!
//! \param fpAppWDTCB is the WDT interrupt handler to be registered
//! \param uiReloadVal is the reload value to be set to the WDT
//!
//! This function
//! 1. Initializes the WDT
//!
//! \return None.
//
//****************************************************************************
void WDT_IF_Init(fAPPWDTDevCallbk fpAppWDTCB,
unsigned int uiReloadVal)
{
//
// Enable the peripherals used by this example.
//
MAP_PRCMPeripheralClkEnable(PRCM_WDT, PRCM_RUN_MODE_CLK);
//
// Unlock to be able to configure the registers
//
MAP_WatchdogUnlock(WDT_BASE);
if(fpAppWDTCB != NULL)
{
#if defined(USE_TIRTOS) || defined(USE_FREERTOS) || defined(SL_PLATFORM_MULTI_THREADED)
// USE_TIRTOS: if app uses TI-RTOS (either networking/non-networking)
// USE_FREERTOS: if app uses Free-RTOS (either networking/non-networking)
// SL_PLATFORM_MULTI_THREADED: if app uses any OS + networking(simplelink)
osi_InterruptRegister(INT_WDT, fpAppWDTCB, INT_PRIORITY_LVL_1);
#else
MAP_IntPrioritySet(INT_WDT, INT_PRIORITY_LVL_1);
MAP_WatchdogIntRegister(WDT_BASE,fpAppWDTCB);
#endif
}
//
// Set the watchdog timer reload value
//
MAP_WatchdogReloadSet(WDT_BASE,uiReloadVal);
//
// Start the timer. Once the timer is started, it cannot be disable.
//
MAP_WatchdogEnable(WDT_BASE);
}
//****************************************************************************
//
//! DeInitialize the watchdog timer
//!
//! \param None
//!
//! This function
//! 1. DeInitializes the WDT
//!
//! \return None.
//
//****************************************************************************
void WDT_IF_DeInit()
{
//
// Unlock to be able to configure the registers
//
MAP_WatchdogUnlock(WDT_BASE);
//
// Disable stalling of the watchdog timer during debug events
//
MAP_WatchdogStallDisable(WDT_BASE);
//
// Clear the interrupt
//
MAP_WatchdogIntClear(WDT_BASE);
//
// Unregister the interrupt
//
MAP_WatchdogIntUnregister(WDT_BASE);
}
//*****************************************************************************
//
// Close the Doxygen group.
//! @}
//
//*****************************************************************************

79
common/wdt_if.h Normal file
View File

@ -0,0 +1,79 @@
//*****************************************************************************
// wdt_if.h
//
// Defines and Macros for the WDT interface.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#ifndef __WDTIF_H__
#define __WDTIF_H__
//*****************************************************************************
//
// If building with a C++ compiler, make all of the definitions in this header
// have a C binding.
//
//*****************************************************************************
#ifdef __cplusplus
extern "C"
{
#endif
//*****************************************************************************
//
// Typedef that can be passed to InitializeGPTOneShot as the fAPPDevCallbk
// parameter.
//
//*****************************************************************************
typedef void (*fAPPWDTDevCallbk)();
//*****************************************************************************
//
// API Function prototypes
//
//*****************************************************************************
extern void WDT_IF_Init(fAPPWDTDevCallbk fpAppWDTCB,
unsigned int uiReloadVal);
extern void WDT_IF_DeInit();
//*****************************************************************************
//
// Mark the end of the C bindings section for C++ compilers.
//
//*****************************************************************************
#ifdef __cplusplus
}
#endif
#endif // __WDTIF_H__

692
driverlib/adc.c Normal file
View File

@ -0,0 +1,692 @@
//*****************************************************************************
//
// adc.c
//
// Driver for the ADC module.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
//*****************************************************************************
//
//! \addtogroup ADC_Analog_to_Digital_Converter_api
//! @{
//
//*****************************************************************************
#include "inc/hw_types.h"
#include "inc/hw_memmap.h"
#include "inc/hw_ints.h"
#include "inc/hw_adc.h"
#include "inc/hw_apps_config.h"
#include "interrupt.h"
#include "adc.h"
//*****************************************************************************
//
//! Enables the ADC
//!
//! \param ulBase is the base address of the ADC
//!
//! This function sets the ADC global enable
//!
//! \return None.
//
//*****************************************************************************
void ADCEnable(unsigned long ulBase)
{
//
// Set the global enable bit in the control register.
//
HWREG(ulBase + ADC_O_ADC_CTRL) |= 0x1;
}
//*****************************************************************************
//
//! Disable the ADC
//!
//! \param ulBase is the base address of the ADC
//!
//! This function clears the ADC global enable
//!
//! \return None.
//
//*****************************************************************************
void ADCDisable(unsigned long ulBase)
{
//
// Clear the global enable bit in the control register.
//
HWREG(ulBase + ADC_O_ADC_CTRL) &= ~0x1 ;
}
//*****************************************************************************
//
//! Enables specified ADC channel
//!
//! \param ulBase is the base address of the ADC
//! \param ulChannel is one of the valid ADC channels
//!
//! This function enables specified ADC channel and configures the
//! pin as analog pin.
//!
//! \return None.
//
//*****************************************************************************
void ADCChannelEnable(unsigned long ulBase, unsigned long ulChannel)
{
unsigned long ulCh;
ulCh = (ulChannel == ADC_CH_0)? 0x02 :
(ulChannel == ADC_CH_1)? 0x04 :
(ulChannel == ADC_CH_2)? 0x08 : 0x10;
HWREG(ulBase + ADC_O_ADC_CH_ENABLE) |= ulCh;
}
//*****************************************************************************
//
//! Disables specified ADC channel
//!
//! \param ulBase is the base address of the ADC
//! \param ulChannel is one of the valid ADC channelsber
//!
//! This function disables specified ADC channel.
//!
//! \return None.
//
//*****************************************************************************
void ADCChannelDisable(unsigned long ulBase, unsigned long ulChannel)
{
unsigned long ulCh;
ulCh = (ulChannel == ADC_CH_0)? 0x02 :
(ulChannel == ADC_CH_1)? 0x04 :
(ulChannel == ADC_CH_2)? 0x08 : 0x10;
HWREG(ulBase + ADC_O_ADC_CH_ENABLE) &= ~ulCh;
}
//*****************************************************************************
//
//! Enables and registers ADC interrupt handler for specified channel
//!
//! \param ulBase is the base address of the ADC
//! \param ulChannel is one of the valid ADC channels
//! \param pfnHandler is a pointer to the function to be called when the
//! ADC channel interrupt occurs.
//!
//! This function enables and registers ADC interrupt handler for specified
//! channel. Individual interrupt for each channel should be enabled using
//! \sa ADCIntEnable(). It is the interrupt handler's responsibility to clear
//! the interrupt source.
//!
//! The parameter \e ulChannel should be one of the following
//!
//! - \b ADC_CH_0 for channel 0
//! - \b ADC_CH_1 for channel 1
//! - \b ADC_CH_2 for channel 2
//! - \b ADC_CH_3 for channel 3
//!
//! \return None.
//
//*****************************************************************************
void ADCIntRegister(unsigned long ulBase, unsigned long ulChannel,
void (*pfnHandler)(void))
{
unsigned long ulIntNo;
//
// Get the interrupt number associted with the specified channel
//
ulIntNo = (ulChannel == ADC_CH_0)? INT_ADCCH0 :
(ulChannel == ADC_CH_1)? INT_ADCCH1 :
(ulChannel == ADC_CH_2)? INT_ADCCH2 : INT_ADCCH3;
//
// Register the interrupt handler
//
IntRegister(ulIntNo,pfnHandler);
//
// Enable ADC interrupt
//
IntEnable(ulIntNo);
}
//*****************************************************************************
//
//! Disables and unregisters ADC interrupt handler for specified channel
//!
//! \param ulBase is the base address of the ADC
//! \param ulChannel is one of the valid ADC channels
//!
//! This function disables and unregisters ADC interrupt handler for specified
//! channel. This function also masks off the interrupt in the interrupt
//! controller so that the interrupt handler no longer is called.
//!
//! The parameter \e ulChannel should be one of the following
//!
//! - \b ADC_CH_0 for channel 0
//! - \b ADC_CH_1 for channel 1
//! - \b ADC_CH_2 for channel 2
//! - \b ADC_CH_3 for channel 3
//!
//! \return None.
//
//*****************************************************************************
void ADCIntUnregister(unsigned long ulBase, unsigned long ulChannel)
{
unsigned long ulIntNo;
//
// Get the interrupt number associted with the specified channel
//
ulIntNo = (ulChannel == ADC_CH_0)? INT_ADCCH0 :
(ulChannel == ADC_CH_1)? INT_ADCCH1 :
(ulChannel == ADC_CH_2)? INT_ADCCH2 : INT_ADCCH3;
//
// Disable ADC interrupt
//
IntDisable(ulIntNo);
//
// Unregister the interrupt handler
//
IntUnregister(ulIntNo);
}
//*****************************************************************************
//
//! Enables individual interrupt sources for specified channel
//!
//!
//! \param ulBase is the base address of the ADC
//! \param ulChannel is one of the valid ADC channels
//! \param ulIntFlags is the bit mask of the interrupt sources to be enabled.
//!
//! This function enables the indicated ADC interrupt sources. Only the
//! sources that are enabled can be reflected to the processor interrupt;
//! disabled sources have no effect on the processor.
//!
//! The parameter \e ulChannel should be one of the following
//!
//! - \b ADC_CH_0 for channel 0
//! - \b ADC_CH_1 for channel 1
//! - \b ADC_CH_2 for channel 2
//! - \b ADC_CH_3 for channel 3
//!
//! The \e ulIntFlags parameter is the logical OR of any of the following:
//! - \b ADC_DMA_DONE for DMA done
//! - \b ADC_FIFO_OVERFLOW for FIFO over flow
//! - \b ADC_FIFO_UNDERFLOW for FIFO under flow
//! - \b ADC_FIFO_EMPTY for FIFO empty
//! - \b ADC_FIFO_FULL for FIFO full
//!
//! \return None.
//
//*****************************************************************************
void ADCIntEnable(unsigned long ulBase, unsigned long ulChannel,
unsigned long ulIntFlags)
{
unsigned long ulOffset;
unsigned long ulDmaMsk;
//
// Enable DMA Done interrupt
//
if(ulIntFlags & ADC_DMA_DONE)
{
ulDmaMsk = (ulChannel == ADC_CH_0)?0x00001000:
(ulChannel == ADC_CH_1)?0x00002000:
(ulChannel == ADC_CH_2)?0x00004000:0x00008000;
HWREG(APPS_CONFIG_BASE + APPS_CONFIG_O_DMA_DONE_INT_MASK_CLR) = ulDmaMsk;
}
ulIntFlags = ulIntFlags & 0x0F;
//
// Get the interrupt enable register offset for specified channel
//
ulOffset = ADC_O_adc_ch0_irq_en + ulChannel;
//
// Unmask the specified interrupts
//
HWREG(ulBase + ulOffset) |= (ulIntFlags & 0xf);
}
//*****************************************************************************
//
//! Disables individual interrupt sources for specified channel
//!
//!
//! \param ulBase is the base address of the ADC.
//! \param ulChannel is one of the valid ADC channels
//! \param ulIntFlags is the bit mask of the interrupt sources to be enabled.
//!
//! This function disables the indicated ADC interrupt sources. Only the
//! sources that are enabled can be reflected to the processor interrupt;
//! disabled sources have no effect on the processor.
//!
//! The parameters\e ulIntFlags and \e ulChannel should be as explained in
//! ADCIntEnable().
//!
//! \return None.
//
//*****************************************************************************
void ADCIntDisable(unsigned long ulBase, unsigned long ulChannel,
unsigned long ulIntFlags)
{
unsigned long ulOffset;
unsigned long ulDmaMsk;
//
// Disable DMA Done interrupt
//
if(ulIntFlags & ADC_DMA_DONE)
{
ulDmaMsk = (ulChannel == ADC_CH_0)?0x00001000:
(ulChannel == ADC_CH_1)?0x00002000:
(ulChannel == ADC_CH_2)?0x00004000:0x00008000;
HWREG(APPS_CONFIG_BASE + APPS_CONFIG_O_DMA_DONE_INT_MASK_SET) = ulDmaMsk;
}
//
// Get the interrupt enable register offset for specified channel
//
ulOffset = ADC_O_adc_ch0_irq_en + ulChannel;
//
// Unmask the specified interrupts
//
HWREG(ulBase + ulOffset) &= ~ulIntFlags;
}
//*****************************************************************************
//
//! Gets the current channel interrupt status
//!
//! \param ulBase is the base address of the ADC
//! \param ulChannel is one of the valid ADC channels
//!
//! This function returns the interrupt status of the specified ADC channel.
//!
//! The parameter \e ulChannel should be as explained in \sa ADCIntEnable().
//!
//! \return Return the ADC channel interrupt status, enumerated as a bit
//! field of values described in ADCIntEnable()
//
//*****************************************************************************
unsigned long ADCIntStatus(unsigned long ulBase, unsigned long ulChannel)
{
unsigned long ulOffset;
unsigned long ulDmaMsk;
unsigned long ulIntStatus;
//
// Get DMA Done interrupt status
//
ulDmaMsk = (ulChannel == ADC_CH_0)?0x00001000:
(ulChannel == ADC_CH_1)?0x00002000:
(ulChannel == ADC_CH_2)?0x00004000:0x00008000;
ulIntStatus = HWREG(APPS_CONFIG_BASE +
APPS_CONFIG_O_DMA_DONE_INT_STS_MASKED)& ulDmaMsk;
//
// Get the interrupt enable register offset for specified channel
//
ulOffset = ADC_O_adc_ch0_irq_status + ulChannel;
//
// Read ADC interrupt status
//
ulIntStatus |= HWREG(ulBase + ulOffset) & 0xf;
//
// Return the current interrupt status
//
return(ulIntStatus);
}
//*****************************************************************************
//
//! Clears the current channel interrupt sources
//!
//! \param ulBase is the base address of the ADC
//! \param ulChannel is one of the valid ADC channels
//! \param ulIntFlags is the bit mask of the interrupt sources to be cleared.
//!
//! This function clears individual interrupt source for the specified
//! ADC channel.
//!
//! The parameter \e ulChannel should be as explained in \sa ADCIntEnable().
//!
//! \return None.
//
//*****************************************************************************
void ADCIntClear(unsigned long ulBase, unsigned long ulChannel,
unsigned long ulIntFlags)
{
unsigned long ulOffset;
unsigned long ulDmaMsk;
//
// Clear DMA Done interrupt
//
if(ulIntFlags & ADC_DMA_DONE)
{
ulDmaMsk = (ulChannel == ADC_CH_0)?0x00001000:
(ulChannel == ADC_CH_1)?0x00002000:
(ulChannel == ADC_CH_2)?0x00004000:0x00008000;
HWREG(APPS_CONFIG_BASE + APPS_CONFIG_O_DMA_DONE_INT_ACK) = ulDmaMsk;
}
//
// Get the interrupt enable register offset for specified channel
//
ulOffset = ADC_O_adc_ch0_irq_status + ulChannel;
//
// Clear the specified interrupts
//
HWREG(ulBase + ulOffset) = (ulIntFlags & ~(ADC_DMA_DONE));
}
//*****************************************************************************
//
//! Enables the ADC DMA operation for specified channel
//!
//! \param ulBase is the base address of the ADC
//! \param ulChannel is one of the valid ADC channels
//!
//! This function enables the DMA operation for specified ADC channel
//!
//! The parameter \e ulChannel should be one of the following
//!
//! - \b ADC_CH_0 for channel 0
//! - \b ADC_CH_1 for channel 1
//! - \b ADC_CH_2 for channel 2
//! - \b ADC_CH_3 for channel 3
//!
//! \return None.
//
//*****************************************************************************
void ADCDMAEnable(unsigned long ulBase, unsigned long ulChannel)
{
unsigned long ulBitMask;
//
// Get the bit mask for enabling DMA for specified channel
//
ulBitMask = (ulChannel == ADC_CH_0)?0x01:
(ulChannel == ADC_CH_1)?0x04:
(ulChannel == ADC_CH_2)?0x10:0x40;
//
// Enable DMA request for the specified channel
//
HWREG(ulBase + ADC_O_adc_dma_mode_en) |= ulBitMask;
}
//*****************************************************************************
//
//! Disables the ADC DMA operation for specified channel
//!
//! \param ulBase is the base address of the ADC
//! \param ulChannel is one of the valid ADC channels
//!
//! This function disables the DMA operation for specified ADC channel
//!
//! The parameter \e ulChannel should be one of the following
//!
//! - \b ADC_CH_0 for channel 0
//! - \b ADC_CH_1 for channel 1
//! - \b ADC_CH_2 for channel 2
//! - \b ADC_CH_3 for channel 3
//!
//! \return None.
//
//*****************************************************************************
void ADCDMADisable(unsigned long ulBase, unsigned long ulChannel)
{
unsigned long ulBitMask;
//
// Get the bit mask for disabling DMA for specified channel
//
ulBitMask = (ulChannel == ADC_CH_0)?0x01:
(ulChannel == ADC_CH_1)?0x04:
(ulChannel == ADC_CH_2)?0x10:0x40;
//
// Disable DMA request for the specified channel
//
HWREG(ulBase + ADC_O_adc_dma_mode_en) &= ~ulBitMask;
}
//*****************************************************************************
//
//! Configures the ADC internal timer
//!
//! \param ulBase is the base address of the ADC
//! \param ulValue is wrap arround value of the timer
//!
//! This function Configures the ADC internal timer. The ADC timer is a 17 bit
//! used to timestamp the ADC data samples internally.
//! User can read the timestamp along with the sample from the FIFO register(s).
//! Each sample in the FIFO contains 14 bit actual data and 18 bit timestamp
//!
//! The parameter \e ulValue can take any value between 0 - 2^17
//!
//! \returns None.
//
//*****************************************************************************
void ADCTimerConfig(unsigned long ulBase, unsigned long ulValue)
{
unsigned long ulReg;
//
// Read the currrent config
//
ulReg = HWREG(ulBase + ADC_O_adc_timer_configuration);
//
// Mask and set timer count field
//
ulReg = ((ulReg & ~0x1FFFF) | (ulValue & 0x1FFFF));
//
// Set the timer count value
//
HWREG(ulBase + ADC_O_adc_timer_configuration) = ulReg;
}
//*****************************************************************************
//
//! Resets ADC internal timer
//!
//! \param ulBase is the base address of the ADC
//!
//! This function resets 17-bit ADC internal timer
//!
//! \returns None.
//
//*****************************************************************************
void ADCTimerReset(unsigned long ulBase)
{
//
// Reset the timer
//
HWREG(ulBase + ADC_O_adc_timer_configuration) |= (1 << 24);
}
//*****************************************************************************
//
//! Enables ADC internal timer
//!
//! \param ulBase is the base address of the ADC
//!
//! This function enables 17-bit ADC internal timer
//!
//! \returns None.
//
//*****************************************************************************
void ADCTimerEnable(unsigned long ulBase)
{
//
// Enable the timer
//
HWREG(ulBase + ADC_O_adc_timer_configuration) |= (1 << 25);
}
//*****************************************************************************
//
//! Disables ADC internal timer
//!
//! \param ulBase is the base address of the ADC
//!
//! This function disables 17-bit ADC internal timer
//!
//! \returns None.
//
//*****************************************************************************
void ADCTimerDisable(unsigned long ulBase)
{
//
// Disable the timer
//
HWREG(ulBase + ADC_O_adc_timer_configuration) &= ~(1 << 25);
}
//*****************************************************************************
//
//! Gets the current value of ADC internal timer
//!
//! \param ulBase is the base address of the ADC
//!
//! This function the current value of 17-bit ADC internal timer
//!
//! \returns Return the current value of ADC internal timer.
//
//*****************************************************************************
unsigned long ADCTimerValueGet(unsigned long ulBase)
{
return(HWREG(ulBase + ADC_O_adc_timer_current_count));
}
//*****************************************************************************
//
//! Gets the current FIFO level for specified ADC channel
//!
//! \param ulBase is the base address of the ADC
//! \param ulChannel is one of the valid ADC channels.
//!
//! This function returns the current FIFO level for specified ADC channel.
//!
//! The parameter \e ulChannel should be one of the following
//!
//! - \b ADC_CH_0 for channel 0
//! - \b ADC_CH_1 for channel 1
//! - \b ADC_CH_2 for channel 2
//! - \b ADC_CH_3 for channel 3
//!
//! \returns Return the current FIFO level for specified channel
//
//*****************************************************************************
unsigned char ADCFIFOLvlGet(unsigned long ulBase, unsigned long ulChannel)
{
unsigned long ulOffset;
//
// Get the fifo level register offset for specified channel
//
ulOffset = ADC_O_adc_ch0_fifo_lvl + ulChannel;
//
// Return FIFO level
//
return(HWREG(ulBase + ulOffset) & 0x7);
}
//*****************************************************************************
//
//! Reads FIFO for specified ADC channel
//!
//! \param ulBase is the base address of the ADC
//! \param ulChannel is one of the valid ADC channels.
//!
//! This function returns one data sample from the channel fifo as specified by
//! \e ulChannel parameter.
//!
//! The parameter \e ulChannel should be one of the following
//!
//! - \b ADC_CH_0 for channel 0
//! - \b ADC_CH_1 for channel 1
//! - \b ADC_CH_2 for channel 2
//! - \b ADC_CH_3 for channel 3
//!
//! \returns Return one data sample from the channel fifo.
//
//*****************************************************************************
unsigned long ADCFIFORead(unsigned long ulBase, unsigned long ulChannel)
{
unsigned long ulOffset;
//
// Get the fifo register offset for specified channel
//
ulOffset = ADC_O_channel0FIFODATA + ulChannel;
//
// Return FIFO level
//
return(HWREG(ulBase + ulOffset));
}
//*****************************************************************************
//
// Close the Doxygen group.
//! @}
//
//*****************************************************************************

117
driverlib/adc.h Normal file
View File

@ -0,0 +1,117 @@
//*****************************************************************************
//
// adc.h
//
// Defines and Macros for the ADC.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#ifndef __ADC_H__
#define __ADC_H__
//*****************************************************************************
//
// If building with a C++ compiler, make all of the definitions in this header
// have a C binding.
//
//*****************************************************************************
#ifdef __cplusplus
extern "C"
{
#endif
//*****************************************************************************
// Values that can be passed to APIs as ulChannel parameter
//*****************************************************************************
#define ADC_CH_0 0x00000000
#define ADC_CH_1 0x00000008
#define ADC_CH_2 0x00000010
#define ADC_CH_3 0x00000018
//*****************************************************************************
//
// Values that can be passed to ADCIntEnable(), ADCIntDisable()
// and ADCIntClear() as ulIntFlags, and returned from ADCIntStatus()
//
//*****************************************************************************
#define ADC_DMA_DONE 0x00000010
#define ADC_FIFO_OVERFLOW 0x00000008
#define ADC_FIFO_UNDERFLOW 0x00000004
#define ADC_FIFO_EMPTY 0x00000002
#define ADC_FIFO_FULL 0x00000001
//*****************************************************************************
//
// API Function prototypes
//
//*****************************************************************************
extern void ADCEnable(unsigned long ulBase);
extern void ADCDisable(unsigned long ulBase);
extern void ADCChannelEnable(unsigned long ulBase,unsigned long ulChannel);
extern void ADCChannelDisable(unsigned long ulBase,unsigned long ulChannel);
extern void ADCIntRegister(unsigned long ulBase, unsigned long ulChannel,
void (*pfnHandler)(void));
extern void ADCIntUnregister(unsigned long ulBase, unsigned long ulChannel);
extern void ADCIntEnable(unsigned long ulBase, unsigned long ulChannel,
unsigned long ulIntFlags);
extern void ADCIntDisable(unsigned long ulBase, unsigned long ulChannel,
unsigned long ulIntFlags);
extern unsigned long ADCIntStatus(unsigned long ulBase,unsigned long ulChannel);
extern void ADCIntClear(unsigned long ulBase, unsigned long ulChannel,
unsigned long ulIntFlags);
extern void ADCDMAEnable(unsigned long ulBase, unsigned long ulChannel);
extern void ADCDMADisable(unsigned long ulBase, unsigned long ulChannel);
extern void ADCTimerConfig(unsigned long ulBase, unsigned long ulValue);
extern void ADCTimerEnable(unsigned long ulBase);
extern void ADCTimerDisable(unsigned long ulBase);
extern void ADCTimerReset(unsigned long ulBase);
extern unsigned long ADCTimerValueGet(unsigned long ulBase);
extern unsigned char ADCFIFOLvlGet(unsigned long ulBase,
unsigned long ulChannel);
extern unsigned long ADCFIFORead(unsigned long ulBase,
unsigned long ulChannel);
//*****************************************************************************
//
// Mark the end of the C bindings section for C++ compilers.
//
//*****************************************************************************
#ifdef __cplusplus
}
#endif
#endif // __ADC_H__

1360
driverlib/aes.c Normal file

File diff suppressed because it is too large Load Diff

218
driverlib/aes.h Normal file
View File

@ -0,0 +1,218 @@
//*****************************************************************************
//
// aes.h
//
// Defines and Macros for the AES module.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#ifndef __DRIVERLIB_AES_H__
#define __DRIVERLIB_AES_H__
//*****************************************************************************
//
// If building with a C++ compiler, make all of the definitions in this header
// have a C binding.
//
//*****************************************************************************
#ifdef __cplusplus
extern "C"
{
#endif
//*****************************************************************************
//
// The following defines are used to specify the operation direction in the
// ui32Config argument in the AESConfig function. Only one is permitted.
//
//*****************************************************************************
#define AES_CFG_DIR_ENCRYPT 0x00000004
#define AES_CFG_DIR_DECRYPT 0x00000000
//*****************************************************************************
//
// The following defines are used to specify the key size in the ui32Config
// argument in the AESConfig function. Only one is permitted.
//
//*****************************************************************************
#define AES_CFG_KEY_SIZE_128BIT 0x00000008
#define AES_CFG_KEY_SIZE_192BIT 0x00000010
#define AES_CFG_KEY_SIZE_256BIT 0x00000018
//*****************************************************************************
//
// The following defines are used to specify the mode of operation in the
// ui32Config argument in the AESConfig function. Only one is permitted.
//
//*****************************************************************************
#define AES_CFG_MODE_M 0x2007fe60
#define AES_CFG_MODE_ECB 0x00000000
#define AES_CFG_MODE_CBC 0x00000020
#define AES_CFG_MODE_CTR 0x00000040
#define AES_CFG_MODE_ICM 0x00000200
#define AES_CFG_MODE_CFB 0x00000400
#define AES_CFG_MODE_XTS_TWEAKJL \
0x00000800
#define AES_CFG_MODE_XTS_K2IJL \
0x00001000
#define AES_CFG_MODE_XTS_K2ILJ0 \
0x00001800
#define AES_CFG_MODE_F8 0x00002000
#define AES_CFG_MODE_F9 0x20004000
#define AES_CFG_MODE_CBCMAC 0x20008000
#define AES_CFG_MODE_GCM_HLY0ZERO \
0x20010040
#define AES_CFG_MODE_GCM_HLY0CALC \
0x20020040
#define AES_CFG_MODE_GCM_HY0CALC \
0x20030040
#define AES_CFG_MODE_CCM 0x20040040
//*****************************************************************************
//
// The following defines are used to specify the counter width in the
// ui32Config argument in the AESConfig function. It is only required to
// be defined when using CTR, CCM, or GCM modes. Only one length is permitted.
//
//*****************************************************************************
#define AES_CFG_CTR_WIDTH_32 0x00000000
#define AES_CFG_CTR_WIDTH_64 0x00000080
#define AES_CFG_CTR_WIDTH_96 0x00000100
#define AES_CFG_CTR_WIDTH_128 0x00000180
//*****************************************************************************
//
// The following defines are used to define the width of the length field for
// CCM operation through the ui32Config argument in the AESConfig function.
// This value is also known as L. Only one is permitted.
//
//*****************************************************************************
#define AES_CFG_CCM_L_2 0x00080000
#define AES_CFG_CCM_L_4 0x00180000
#define AES_CFG_CCM_L_8 0x00380000
//*****************************************************************************
//
// The following defines are used to define the length of the authentication
// field for CCM operations through the ui32Config argument in the AESConfig
// function. This value is also known as M. Only one is permitted.
//
//*****************************************************************************
#define AES_CFG_CCM_M_4 0x00400000
#define AES_CFG_CCM_M_6 0x00800000
#define AES_CFG_CCM_M_8 0x00c00000
#define AES_CFG_CCM_M_10 0x01000000
#define AES_CFG_CCM_M_12 0x01400000
#define AES_CFG_CCM_M_14 0x01800000
#define AES_CFG_CCM_M_16 0x01c00000
//*****************************************************************************
//
// Interrupt flags for use with the AESIntEnable, AESIntDisable, and
// AESIntStatus functions.
//
//*****************************************************************************
#define AES_INT_CONTEXT_IN 0x00000001
#define AES_INT_CONTEXT_OUT 0x00000008
#define AES_INT_DATA_IN 0x00000002
#define AES_INT_DATA_OUT 0x00000004
#define AES_INT_DMA_CONTEXT_IN 0x00010000
#define AES_INT_DMA_CONTEXT_OUT 0x00020000
#define AES_INT_DMA_DATA_IN 0x00040000
#define AES_INT_DMA_DATA_OUT 0x00080000
//*****************************************************************************
//
// Defines used when enabling and disabling DMA requests in the
// AESEnableDMA and AESDisableDMA functions.
//
//*****************************************************************************
#define AES_DMA_DATA_IN 0x00000040
#define AES_DMA_DATA_OUT 0x00000020
#define AES_DMA_CONTEXT_IN 0x00000080
#define AES_DMA_CONTEXT_OUT 0x00000100
//*****************************************************************************
//
// Function prototypes.
//
//*****************************************************************************
extern void AESConfigSet(uint32_t ui32Base, uint32_t ui32Config);
extern void AESKey1Set(uint32_t ui32Base, uint8_t *pui8Key,
uint32_t ui32Keysize);
extern void AESKey2Set(uint32_t ui32Base, uint8_t *pui8Key,
uint32_t ui32Keysize);
extern void AESKey3Set(uint32_t ui32Base, uint8_t *pui8Key);
extern void AESIVSet(uint32_t ui32Base, uint8_t *pui8IVdata);
extern void AESIVGet(uint32_t ui32Base, uint8_t *pui8IVdata);
extern void AESTagRead(uint32_t ui32Base, uint8_t *pui8TagData);
extern void AESDataLengthSet(uint32_t ui32Base, uint64_t ui64Length);
extern void AESAuthDataLengthSet(uint32_t ui32Base, uint32_t ui32Length);
extern bool AESDataReadNonBlocking(uint32_t ui32Base, uint8_t *pui8Dest,
uint8_t ui8Length);
extern void AESDataRead(uint32_t ui32Base, uint8_t *pui8Dest,
uint8_t ui8Length);
extern bool AESDataWriteNonBlocking(uint32_t ui32Base, uint8_t *pui8Src,
uint8_t ui8Length);
extern void AESDataWrite(uint32_t ui32Base, uint8_t *pui8Src,
uint8_t ui8Length);
extern bool AESDataProcess(uint32_t ui32Base, uint8_t *pui8Src,
uint8_t *pui8Dest,
uint32_t ui32Length);
extern bool AESDataMAC(uint32_t ui32Base, uint8_t *pui8Src,
uint32_t ui32Length,
uint8_t *pui8Tag);
extern bool AESDataProcessAE(uint32_t ui32Base, uint8_t *pui8Src,
uint8_t *pui8Dest, uint32_t ui32Length,
uint8_t *pui8AuthSrc, uint32_t ui32AuthLength,
uint8_t *pui8Tag);
extern uint32_t AESIntStatus(uint32_t ui32Base, bool bMasked);
extern void AESIntEnable(uint32_t ui32Base, uint32_t ui32IntFlags);
extern void AESIntDisable(uint32_t ui32Base, uint32_t ui32IntFlags);
extern void AESIntClear(uint32_t ui32Base, uint32_t ui32IntFlags);
extern void AESIntRegister(uint32_t ui32Base, void(*pfnHandler)(void));
extern void AESIntUnregister(uint32_t ui32Base);
extern void AESDMAEnable(uint32_t ui32Base, uint32_t ui32Flags);
extern void AESDMADisable(uint32_t ui32Base, uint32_t ui32Flags);
//*****************************************************************************
//
// Mark the end of the C bindings section for C++ compilers.
//
//*****************************************************************************
#ifdef __cplusplus
}
#endif
#endif // __DRIVERLIB_AES_H__

602
driverlib/camera.c Normal file
View File

@ -0,0 +1,602 @@
//*****************************************************************************
//
// camera.c
//
// Driver for the camera controller module
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
//*****************************************************************************
//
//! \addtogroup camera_api
//! @{
//
//*****************************************************************************
#include "inc/hw_types.h"
#include "inc/hw_ints.h"
#include "inc/hw_memmap.h"
#include "inc/hw_camera.h"
#include "inc/hw_apps_config.h"
#include "interrupt.h"
#include "camera.h"
//******************************************************************************
//
//! Resets the Camera core
//!
//! \param ulBase is the base address of the camera module.
//!
//! This function resets the camera core
//!
//! \return None.
//
//******************************************************************************
void CameraReset(unsigned long ulBase)
{
//
// Reset the camera
//
HWREG(ulBase + CAMERA_O_CC_SYSCONFIG) = CAMERA_CC_SYSCONFIG_SOFT_RESET;
//
// Wait for reset completion
//
while(!(HWREG(ulBase + CAMERA_O_CC_SYSSTATUS)&
CAMERA_CC_SYSSTATUS_RESET_DONE2))
{
}
}
//******************************************************************************
//
//! Configures camera parameters
//!
//! \param ulBase is the base address of the camera module.
//! \param ulHSPol sets the HSync polarity
//! \param ulVSPol sets the VSync polarity
//! \param ulFlags are configuration flags
//!
//! This function sets different camera parameters.
//!
//! The parameter \e ulHSPol should be on the follwoing:
//! - \b CAM_HS_POL_HI
//! - \b CAM_HS_POL_LO
//!
//! The parameter \e ulVSPol should be on the follwoing:
//! - \b CAM_VS_POL_HI
//! - \b CAM_VS_POL_LO
//!
//! The parameter \e ulFlags can be logical OR of one or more of the follwoing
//! or 0:
//! - \b CAM_PCLK_RISE_EDGE
//! - \b CAM_PCLK_FALL_EDGE
//! - \b CAM_ORDERCAM_SWAP
//! - \b CAM_NOBT_SYNCHRO
//! - \b CAM_IF_SYNCHRO
//!
//! \return None.
//
//******************************************************************************
void CameraParamsConfig(unsigned long ulBase, unsigned long ulHSPol,
unsigned long ulVSPol, unsigned long ulFlags)
{
unsigned long ulReg;
//
// Read the register
//
ulReg = HWREG(ulBase + CAMERA_O_CC_CTRL);
//
// Set the requested parameter
//
ulFlags = (ulFlags|ulHSPol|ulVSPol);
ulReg = ((ulReg & ~(CAMERA_CC_CTRL_NOBT_SYNCHRO |
CAMERA_CC_CTRL_NOBT_HS_POL |
CAMERA_CC_CTRL_NOBT_VS_POL |
CAMERA_CC_CTRL_BT_CORRECT |
CAMERA_CC_CTRL_PAR_ORDERCAM |
CAMERA_CC_CTRL_PAR_CLK_POL )) | ulFlags);
//
// Write the configuration
//
HWREG(ulBase + CAMERA_O_CC_CTRL)=ulReg;
}
//******************************************************************************
//
//! Set the internal clock divider
//!
//! \param ulBase is the base address of the camera module.
//! \param ulCamClkIn is input to camera module
//! \param ulXClk defines the output required
//!
//! This function sets the internal clock divider based on \e ulCamClkIn to
//! generate XCLK as specified be \e ulXClk. Maximum suppoter division is 30
//!
//! \return None.
//
//******************************************************************************
void CameraXClkConfig(unsigned long ulBase, unsigned long ulCamClkIn,
unsigned long ulXClk)
{
unsigned long ulReg;
unsigned long ucDiv;
//
// Read the register
//
ulReg = HWREG(ulBase + CAMERA_O_CC_CTRL_XCLK);
//
// Mask XCLK divider value
//
ulReg &= ~(CAMERA_CC_CTRL_XCLK_XCLK_DIV_M);
//
// Compute the divider
//
ucDiv = ((ulCamClkIn)/ulXClk);
//
// Max supported division is 30
//
if(ucDiv > 30)
{
return;
}
//
// Set and write back the configuration
//
ulReg |= ucDiv;
HWREG(ulBase + CAMERA_O_CC_CTRL_XCLK) = ulReg;
}
//******************************************************************************
//
//! Sets the internal divide in specified mode
//!
//! \param ulBase is the base address of the camera module.
//! \param bXClkFlags decides the divide mode
//!
//! This function sets the internal divide in specified mode.
//!
//! The parameter \e bXClkFlags should be one of the following :
//!
//! - \b CAM_XCLK_STABLE_LO
//! - \b CAM_XCLK_STABLE_HI
//! - \b CAM_XCLK_DIV_BYPASS
//!
//! \return None.
//
//******************************************************************************
void CameraXClkSet(unsigned long ulBase, unsigned char bXClkFlags)
{
unsigned long ulReg;
//
// Read and Mask XTAL Divider config.
//
ulReg = (HWREG(ulBase + CAMERA_O_CC_CTRL_XCLK) &
~(CAMERA_CC_CTRL_XCLK_XCLK_DIV_M));
//
// Set config. base on parameter flag
//
switch(bXClkFlags)
{
case CAM_XCLK_STABLE_HI : ulReg |= 0x00000001;
break;
case CAM_XCLK_DIV_BYPASS: ulReg |= 0x0000001F;
break;
}
//
// Write the config.
//
HWREG(ulBase + CAMERA_O_CC_CTRL_XCLK) = ulReg;
}
//******************************************************************************
//
//! Enable camera DMA
//!
//! \param ulBase is the base address of the camera module.
//!
//! This function enables transfer request to DMA from camera. DMA specific
//! configuration has to be done seperately.
//!
//! \return None.
//
//******************************************************************************
void CameraDMAEnable(unsigned long ulBase)
{
//
// Enable DMA
//
HWREG(ulBase + CAMERA_O_CC_CTRL_DMA) |= CAMERA_CC_CTRL_DMA_DMA_EN;
}
//******************************************************************************
//
//! Disable camera DMA
//!
//! \param ulBase is the base address of the camera module.
//!
//! This function masks transfer request to DMA from camera.
//!
//! \return None.
//
//******************************************************************************
void CameraDMADisable(unsigned long ulBase)
{
//
// Disable DMA
//
HWREG(ulBase + CAMERA_O_CC_CTRL_DMA) &= ~CAMERA_CC_CTRL_DMA_DMA_EN;
}
//******************************************************************************
//
//! Sets the FIFO threshold for DMA transfer request
//!
//! \param ulBase is the base address of the camera module.
//! \param ulThreshold specifies the FIFO threshold
//!
//! This function sets the FIFO threshold for DMA transfer request.
//! Parameter \e ulThreshold can range from 1 - 64
//!
//! \return None.
//
//******************************************************************************
void CameraThresholdSet(unsigned long ulBase, unsigned long ulThreshold)
{
//
// Read and Mask DMA threshold field
//
HWREG(ulBase + CAMERA_O_CC_CTRL_DMA) &= ~CAMERA_CC_CTRL_DMA_FIFO_THRESHOLD_M;
//
// Write the new threshold value
//
HWREG(ulBase + CAMERA_O_CC_CTRL_DMA) |= (ulThreshold -1);
}
//******************************************************************************
//
//! Register camera interrupt handler
//!
//! \param ulBase is the base address of the camera module.
//! \param pfnHandler hold pointer to interrupt handler
//!
//! This function registers and enables global camera interrupt from the
//! interrupt controller. Individual camera interrupts source
//! should be enabled using \sa CameraIntEnable().
//!
//! \return None.
//
//******************************************************************************
void CameraIntRegister(unsigned long ulBase, void (*pfnHandler)(void))
{
//
// Register the interrupt handler.
//
IntRegister(INT_CAMERA, pfnHandler);
//
// Enable the Camera interrupt.
//
IntEnable(INT_CAMERA);
}
//******************************************************************************
//
//! Un-Register camera interrupt handler
//!
//! \param ulBase is the base address of the camera module.
//!
//! This function unregisters and disables global camera interrupt from the
//! interrupt controller.
//!
//! \return None.
//
//******************************************************************************
void CameraIntUnregister(unsigned long ulBase)
{
//
// Disable the interrupt.
//
IntDisable(INT_CAMERA);
//
// Unregister the interrupt handler.
//
IntUnregister(INT_CAMERA);
}
//******************************************************************************
//! Enables individual camera interrupt sources.
//!
//! \param ulBase is the base address of the camera module.
//! \param ulIntFlags is the bit mask of the interrupt sources to be enabled.
//!
//! This function enables individual camera interrupt sources.
//!
//! the parameter \e ulIntFlags should be logical OR of one or more of the
//! following:
//!
//! - \b CAM_INT_DMA
//! - \b CAM_INT_FE
//! - \b CAM_INT_FSC_ERR
//! - \b CAM_INT_FIFO_NOEMPTY
//! - \b CAM_INT_FIFO_FULL
//! - \b CAM_INT_FIFO_THR
//! - \b CAM_INT_FIFO_OF
//! - \b CAN_INT_FIFO_UR
//!
//! \return None.
//
//******************************************************************************
void CameraIntEnable(unsigned long ulBase, unsigned long ulIntFlags)
{
//
// unmask Camera DMA done interrupt
//
if(ulIntFlags & CAM_INT_DMA)
{
HWREG(APPS_CONFIG_BASE + APPS_CONFIG_O_DMA_DONE_INT_MASK_CLR) = ((1<<8));
}
//
// Enable specific camera interrupts
//
HWREG(ulBase + CAMERA_O_CC_IRQENABLE) |= ulIntFlags;
}
//******************************************************************************
//! Disables individual camera interrupt sources.
//!
//! \param ulBase is the base address of the camera module.
//! \param ulIntFlags is the bit mask of the interrupt sources to be disabled.
//!
//! This function disables individual camera interrupt sources.
//!
//! The parameter \e ulIntFlags should be logical OR of one or more of the
//! values as defined in CameraIntEnable().
//!
//! \return None.
//
//******************************************************************************
void CameraIntDisable(unsigned long ulBase, unsigned long ulIntFlags)
{
//
// Mask Camera DMA done interrupt
//
if(ulIntFlags & CAM_INT_DMA)
{
HWREG(APPS_CONFIG_BASE + APPS_CONFIG_O_DMA_DONE_INT_MASK_SET) = ((1<<8));
}
//
// Disable specific camera interrupts
//
HWREG(ulBase + CAMERA_O_CC_IRQENABLE) &= ~ulIntFlags;
}
//******************************************************************************
//
//! Returns the current interrupt status,
//!
//! \param ulBase is the base address of the camera module.
//! \param ulBase is the base address of the camera module.
//!
//! This functions returns the current interrupt status for the camera.
//!
//! \return Returns the current interrupt status, enumerated as a bit field of
//! values described in CameraIntEnable().
//******************************************************************************
unsigned long CameraIntStatus(unsigned long ulBase)
{
unsigned ulIntFlag;
//
// Read camera interrupt
//
ulIntFlag = HWREG(ulBase + CAMERA_O_CC_IRQSTATUS);
//
//
// Read camera DMA doner interrupt
//
if(HWREG(APPS_CONFIG_BASE + APPS_CONFIG_O_DMA_DONE_INT_STS_MASKED) & (1<<8))
{
ulIntFlag |= CAM_INT_DMA;
}
//
// Return status
//
return(ulIntFlag);
}
//******************************************************************************
//! Clears individual camera interrupt sources.
//!
//! \param ulBase is the base address of the camera module.
//! \param ulIntFlags is the bit mask of the interrupt sources to be Clears.
//!
//! This function Clears individual camera interrupt sources.
//!
//! The parameter \e ulIntFlags should be logical OR of one or more of the
//! values as defined in CameraIntEnable().
//!
//! \return None.
//
//******************************************************************************
void CameraIntClear(unsigned long ulBase, unsigned long ulIntFlags)
{
//
// Clear DMA done int status
//
if(ulIntFlags & CAM_INT_DMA)
{
HWREG(APPS_CONFIG_BASE + APPS_CONFIG_O_DMA_DONE_INT_ACK) = ((1<<8));
}
//
// Clear the interrupts
//
HWREG(ulBase + CAMERA_O_CC_IRQSTATUS) = ulIntFlags;
}
//******************************************************************************
//
//! Starts image capture
//!
//! \param ulBase is the base address of the camera module.
//!
//! This function starts the image capture over the configured camera interface
//! This function should be called after configuring the camera module
//! completele
//!
//! \return None.
//
//******************************************************************************
void CameraCaptureStart(unsigned long ulBase)
{
//
// Set the mode
//
HWREG(ulBase + CAMERA_O_CC_CTRL) &= ~0xF;
//
// Enable image capture
//
HWREG(ulBase + CAMERA_O_CC_CTRL) |= CAMERA_CC_CTRL_CC_EN;
}
//******************************************************************************
//
//! Stops image capture
//!
//! \param ulBase is the base address of the camera module.
//! \param bImmediate is \b true to stop capture imeediately else \b flase.
//!
//! This function stops the image capture over the camera interface.
//! The capture is stopped either immediatelt or at the end of current frame
//! based on \e bImmediate parameter.
//!
//! \return None.
//
//******************************************************************************
void CameraCaptureStop(unsigned long ulBase, tBoolean bImmediate)
{
if(bImmediate)
{
//
// Stop capture immediately
//
HWREG(ulBase + CAMERA_O_CC_CTRL) &= ~CAMERA_CC_CTRL_CC_FRAME_TRIG;
}
else
{
//
// Stop capture at the end of frame
//
HWREG(ulBase + CAMERA_O_CC_CTRL) |= CAMERA_CC_CTRL_CC_FRAME_TRIG;
}
//
// Request camera to stop capture
//
HWREG(ulBase + CAMERA_O_CC_CTRL) &= ~CAMERA_CC_CTRL_CC_EN;
}
//******************************************************************************
//
//! Reads the camera buffer (FIFO)
//!
//! \param ulBase is the base address of the camera module.
//! \param pBuffer is the pointer to the read buffer
//! \param ucSize specifies the size to data to be read
//!
//! This function reads the camera buffer (FIFO).
//!
//! \return None.
//
//******************************************************************************
void CameraBufferRead(unsigned long ulBase, unsigned long *pBuffer,
unsigned char ucSize)
{
unsigned char *pCamBuff;
unsigned char i;
//
// Initilize a pointer to ecamera buffer
//
pCamBuff = (unsigned char *)CAM_BUFFER_ADDR;
//
// Read out requested data
//
for(i=0; i < ucSize; i++)
{
*(pBuffer+i) = *(pCamBuff + i);
}
}
//*****************************************************************************
//
// Close the Doxygen group.
//! @}
//
//*****************************************************************************

131
driverlib/camera.h Normal file
View File

@ -0,0 +1,131 @@
//*****************************************************************************
//
// camera.h
//
// Prototypes and macros for the camera controller module.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#ifndef __CAMERA_H__
#define __CAMERA_H__
//*****************************************************************************
//
// If building with a C++ compiler, make all of the definitions in this header
// have a C binding.
//
//*****************************************************************************
#ifdef __cplusplus
extern "C"
{
#endif
//*****************************************************************************
// Macro defining Camera buffer address
//*****************************************************************************
#define CAM_BUFFER_ADDR 0x44018100
//*****************************************************************************
// Value that can be passed to CameraXClkSet().
//*****************************************************************************
#define CAM_XCLK_STABLE_LO 0x00
#define CAM_XCLK_STABLE_HI 0x01
#define CAM_XCLK_DIV_BYPASS 0x02
//*****************************************************************************
// Value that can be passed to CameraIntEnable(), CameraIntDisable,
// CameraIntClear() or returned from CameraIntStatus().
//*****************************************************************************
#define CAM_INT_DMA 0x80000000
#define CAM_INT_FE 0x00010000
#define CAM_INT_FIFO_NOEMPTY 0x00000010
#define CAM_INT_FIFO_FULL 0x00000008
#define CAM_INT_FIFO_THR 0x00000004
#define CAM_INT_FIFO_OF 0x00000002
#define CAN_INT_FIFO_UR 0x00000001
//*****************************************************************************
// Value that can be passed to CameraXClkConfig().
//*****************************************************************************
#define CAM_HS_POL_HI 0x00000000
#define CAM_HS_POL_LO 0x00000200
#define CAM_VS_POL_HI 0x00000000
#define CAM_VS_POL_LO 0x00000100
#define CAM_PCLK_RISE_EDGE 0x00000000
#define CAM_PCLK_FALL_EDGE 0x00000400
#define CAM_ORDERCAM_SWAP 0x00000800
#define CAM_NOBT_SYNCHRO 0x00002000
#define CAM_IF_SYNCHRO 0x00080000
//*****************************************************************************
//
// API Function prototypes
//
//*****************************************************************************
extern void CameraReset(unsigned long ulBase);
extern void CameraParamsConfig(unsigned long ulBase, unsigned long ulHSPol,
unsigned long ulVSPol, unsigned long ulFlags);
extern void CameraXClkConfig(unsigned long ulBase, unsigned long ulCamClkIn,
unsigned long ulXClk);
extern void CameraXClkSet(unsigned long ulBase, unsigned char bXClkFlags);
extern void CameraDMAEnable(unsigned long ulBase);
extern void CameraDMADisable(unsigned long ulBase);
extern void CameraThresholdSet(unsigned long ulBase, unsigned long ulThreshold);
extern void CameraIntRegister(unsigned long ulBase, void (*pfnHandler)(void));
extern void CameraIntUnregister(unsigned long ulBase);
extern void CameraIntEnable(unsigned long ulBase, unsigned long ulIntFlags);
extern void CameraIntDisable(unsigned long ulBase, unsigned long ulIntFlags);
extern unsigned long CameraIntStatus(unsigned long ulBase);
extern void CameraIntClear(unsigned long ulBase, unsigned long ulIntFlags);
extern void CameraCaptureStop(unsigned long ulBase, tBoolean bImmediate);
extern void CameraCaptureStart(unsigned long ulBase);
extern void CameraBufferRead(unsigned long ulBase,unsigned long *pBuffer,
unsigned char ucSize);
//*****************************************************************************
//
// Mark the end of the C bindings section for C++ compilers.
//
//*****************************************************************************
#ifdef __cplusplus
}
#endif
#endif //__CAMERA_H__

412
driverlib/cpu.c Normal file
View File

@ -0,0 +1,412 @@
//*****************************************************************************
//
// cpu.c
//
// Instruction wrappers for special CPU instructions needed by the
// drivers.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#include "cpu.h"
//*****************************************************************************
//
// Wrapper function for the CPSID instruction. Returns the state of PRIMASK
// on entry.
//
//*****************************************************************************
#if defined(gcc)
unsigned long __attribute__((naked))
CPUcpsid(void)
{
unsigned long ulRet;
//
// Read PRIMASK and disable interrupts.
//
__asm(" mrs r0, PRIMASK\n"
" cpsid i\n"
" dsb \n"
" isb \n"
" bx lr\n"
: "=r" (ulRet));
//
// The return is handled in the inline assembly, but the compiler will
// still complain if there is not an explicit return here (despite the fact
// that this does not result in any code being produced because of the
// naked attribute).
//
return(ulRet);
}
#endif
#if defined(ewarm)
unsigned long
CPUcpsid(void)
{
//
// Read PRIMASK and disable interrupts.
//
__asm(" mrs r0, PRIMASK\n"
" cpsid i\n"
" dsb \n"
" isb \n");
//
// "Warning[Pe940]: missing return statement at end of non-void function"
// is suppressed here to avoid putting a "bx lr" in the inline assembly
// above and a superfluous return statement here.
//
#pragma diag_suppress=Pe940
}
#pragma diag_default=Pe940
#endif
#if defined(ccs)
unsigned long
CPUcpsid(void)
{
//
// Read PRIMASK and disable interrupts.
//
__asm(" mrs r0, PRIMASK\n"
" cpsid i\n"
" dsb \n"
" isb \n"
" bx lr\n");
//
// The following keeps the compiler happy, because it wants to see a
// return value from this function. It will generate code to return
// a zero. However, the real return is the "bx lr" above, so the
// return(0) is never executed and the function returns with the value
// you expect in R0.
//
return(0);
}
#endif
//*****************************************************************************
//
// Wrapper function returning the state of PRIMASK (indicating whether
// interrupts are enabled or disabled).
//
//*****************************************************************************
#if defined(gcc)
unsigned long __attribute__((naked))
CPUprimask(void)
{
unsigned long ulRet;
//
// Read PRIMASK and disable interrupts.
//
__asm(" mrs r0, PRIMASK\n"
" bx lr\n"
: "=r" (ulRet));
//
// The return is handled in the inline assembly, but the compiler will
// still complain if there is not an explicit return here (despite the fact
// that this does not result in any code being produced because of the
// naked attribute).
//
return(ulRet);
}
#endif
#if defined(ewarm)
unsigned long
CPUprimask(void)
{
//
// Read PRIMASK and disable interrupts.
//
__asm(" mrs r0, PRIMASK\n");
//
// "Warning[Pe940]: missing return statement at end of non-void function"
// is suppressed here to avoid putting a "bx lr" in the inline assembly
// above and a superfluous return statement here.
//
#pragma diag_suppress=Pe940
}
#pragma diag_default=Pe940
#endif
#if defined(ccs)
unsigned long
CPUprimask(void)
{
//
// Read PRIMASK and disable interrupts.
//
__asm(" mrs r0, PRIMASK\n"
" bx lr\n");
//
// The following keeps the compiler happy, because it wants to see a
// return value from this function. It will generate code to return
// a zero. However, the real return is the "bx lr" above, so the
// return(0) is never executed and the function returns with the value
// you expect in R0.
//
return(0);
}
#endif
//*****************************************************************************
//
// Wrapper function for the CPSIE instruction. Returns the state of PRIMASK
// on entry.
//
//*****************************************************************************
#if defined(gcc)
unsigned long __attribute__((naked))
CPUcpsie(void)
{
unsigned long ulRet;
//
// Read PRIMASK and enable interrupts.
//
__asm(" mrs r0, PRIMASK\n"
" cpsie i\n"
" dsb \n"
" isb \n"
" bx lr\n"
: "=r" (ulRet));
//
// The return is handled in the inline assembly, but the compiler will
// still complain if there is not an explicit return here (despite the fact
// that this does not result in any code being produced because of the
// naked attribute).
//
return(ulRet);
}
#endif
#if defined(ewarm)
unsigned long
CPUcpsie(void)
{
//
// Read PRIMASK and enable interrupts.
//
__asm(" mrs r0, PRIMASK\n"
" cpsie i\n"
" dsb \n"
" isb \n");
//
// "Warning[Pe940]: missing return statement at end of non-void function"
// is suppressed here to avoid putting a "bx lr" in the inline assembly
// above and a superfluous return statement here.
//
#pragma diag_suppress=Pe940
}
#pragma diag_default=Pe940
#endif
#if defined(ccs)
unsigned long
CPUcpsie(void)
{
//
// Read PRIMASK and enable interrupts.
//
__asm(" mrs r0, PRIMASK\n"
" cpsie i\n"
" dsb \n"
" isb \n"
" bx lr\n");
//
// The following keeps the compiler happy, because it wants to see a
// return value from this function. It will generate code to return
// a zero. However, the real return is the "bx lr" above, so the
// return(0) is never executed and the function returns with the value
// you expect in R0.
//
return(0);
}
#endif
//*****************************************************************************
//
// Wrapper function for the WFI instruction.
//
//*****************************************************************************
#if defined(gcc)
void __attribute__((naked))
CPUwfi(void)
{
//
// Wait for the next interrupt.
//
__asm(" dsb \n"
" isb \n"
" wfi \n"
" bx lr\n");
}
#endif
#if defined(ewarm)
void
CPUwfi(void)
{
//
// Wait for the next interrupt.
//
__asm(" dsb \n"
" isb \n"
" wfi \n");
}
#endif
#if defined(ccs)
void
CPUwfi(void)
{
//
// Wait for the next interrupt.
//
__asm(" dsb \n"
" isb \n"
" wfi \n");
}
#endif
//*****************************************************************************
//
// Wrapper function for writing the BASEPRI register.
//
//*****************************************************************************
#if defined(gcc)
void __attribute__((naked))
CPUbasepriSet(unsigned long ulNewBasepri)
{
//
// Set the BASEPRI register
//
__asm(" msr BASEPRI, r0\n"
" dsb \n"
" isb \n"
" bx lr\n");
}
#endif
#if defined(ewarm)
void
CPUbasepriSet(unsigned long ulNewBasepri)
{
//
// Set the BASEPRI register
//
__asm(" msr BASEPRI, r0\n"
" dsb \n"
" isb \n");
}
#endif
#if defined(ccs)
void
CPUbasepriSet(unsigned long ulNewBasepri)
{
//
// Set the BASEPRI register
//
__asm(" msr BASEPRI, r0\n"
" dsb \n"
" isb \n");
}
#endif
//*****************************************************************************
//
// Wrapper function for reading the BASEPRI register.
//
//*****************************************************************************
#if defined(gcc)
unsigned long __attribute__((naked))
CPUbasepriGet(void)
{
unsigned long ulRet;
//
// Read BASEPRI
//
__asm(" mrs r0, BASEPRI\n"
" bx lr\n"
: "=r" (ulRet));
//
// The return is handled in the inline assembly, but the compiler will
// still complain if there is not an explicit return here (despite the fact
// that this does not result in any code being produced because of the
// naked attribute).
//
return(ulRet);
}
#endif
#if defined(ewarm)
unsigned long
CPUbasepriGet(void)
{
//
// Read BASEPRI
//
__asm(" mrs r0, BASEPRI\n");
//
// "Warning[Pe940]: missing return statement at end of non-void function"
// is suppressed here to avoid putting a "bx lr" in the inline assembly
// above and a superfluous return statement here.
//
#pragma diag_suppress=Pe940
}
#pragma diag_default=Pe940
#endif
#if defined(ccs)
unsigned long
CPUbasepriGet(void)
{
//
// Read BASEPRI
//
__asm(" mrs r0, BASEPRI\n"
" bx lr\n");
//
// The following keeps the compiler happy, because it wants to see a
// return value from this function. It will generate code to return
// a zero. However, the real return is the "bx lr" above, so the
// return(0) is never executed and the function returns with the value
// you expect in R0.
//
return(0);
}
#endif

75
driverlib/cpu.h Normal file
View File

@ -0,0 +1,75 @@
//*****************************************************************************
//
// cpu.h
//
// Prototypes for the CPU instruction wrapper functions.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#ifndef __CPU_H__
#define __CPU_H__
//*****************************************************************************
//
// If building with a C++ compiler, make all of the definitions in this header
// have a C binding.
//
//*****************************************************************************
#ifdef __cplusplus
extern "C"
{
#endif
//*****************************************************************************
//
// Prototypes.
//
//*****************************************************************************
extern unsigned long CPUcpsid(void);
extern unsigned long CPUcpsie(void);
extern unsigned long CPUprimask(void);
extern void CPUwfi(void);
extern unsigned long CPUbasepriGet(void);
extern void CPUbasepriSet(unsigned long ulNewBasepri);
//*****************************************************************************
//
// Mark the end of the C bindings section for C++ compilers.
//
//*****************************************************************************
#ifdef __cplusplus
}
#endif
#endif // __CPU_H__

305
driverlib/crc.c Normal file
View File

@ -0,0 +1,305 @@
//*****************************************************************************
//
// crc.c
//
// Driver for the CRC module.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
//*****************************************************************************
//
//! \addtogroup CRC_Cyclic_Redundancy_Check_api
//! @{
//
//*****************************************************************************
#include <stdbool.h>
#include <stdint.h>
#include "inc/hw_dthe.h"
#include "inc/hw_memmap.h"
#include "inc/hw_types.h"
#include "driverlib/crc.h"
#include "driverlib/debug.h"
//*****************************************************************************
//
//! Set the configuration of CRC functionality with the EC module.
//!
//! \param ui32Base is the base address of the EC module.
//! \param ui32CRCConfig is the configuration of the CRC engine.
//!
//! This function configures the operation of the CRC engine within the EC
//! module. The configuration is specified with the \e ui32CRCConfig argument.
//! It is the logical OR of any of the following options:
//!
//! CRC Initialization Value
//! - \b EC_CRC_CFG_INIT_SEED - Initialize with seed value
//! - \b EC_CRC_CFG_INIT_0 - Initialize to all '0s'
//! - \b EC_CRC_CFG_INIT_1 - Initialize to all '1s'
//!
//! Input Data Size
//! - \b EC_CRC_CFG_SIZE_8BIT - Input data size of 8 bits
//! - \b EC_CRC_CFG_SIZE_32BIT - Input data size of 32 bits
//!
//! Post Process Reverse/Inverse
//! - \b EC_CRC_CFG_RESINV - Result inverse enable
//! - \b EC_CRC_CFG_OBR - Output reverse enable
//!
//! Input Bit Reverse
//! - \b EC_CRC_CFG_IBR - Bit reverse enable
//!
//! Endian Control
//! - \b EC_CRC_CFG_ENDIAN_SBHW - Swap byte in half-word
//! - \b EC_CRC_CFG_ENDIAN_SHW - Swap half-word
//!
//! Operation Type
//! - \b EC_CRC_CFG_TYPE_P8005 - Polynomial 0x8005
//! - \b EC_CRC_CFG_TYPE_P1021 - Polynomial 0x1021
//! - \b EC_CRC_CFG_TYPE_P4C11DB7 - Polynomial 0x4C11DB7
//! - \b EC_CRC_CFG_TYPE_P1EDC6F41 - Polynomial 0x1EDC6F41
//! - \b EC_CRC_CFG_TYPE_TCPCHKSUM - TCP checksum
//!
//! \return None.
//
//*****************************************************************************
void
CRCConfigSet(uint32_t ui32Base, uint32_t ui32CRCConfig)
{
//
// Check the arguments.
//
ASSERT(ui32Base == DTHE_BASE);
ASSERT((ui32CRCConfig & CRC_CFG_INIT_SEED) ||
(ui32CRCConfig & CRC_CFG_INIT_0) ||
(ui32CRCConfig & CRC_CFG_INIT_1) ||
(ui32CRCConfig & CRC_CFG_SIZE_8BIT) ||
(ui32CRCConfig & CRC_CFG_SIZE_32BIT) ||
(ui32CRCConfig & CRC_CFG_RESINV) ||
(ui32CRCConfig & CRC_CFG_OBR) ||
(ui32CRCConfig & CRC_CFG_IBR) ||
(ui32CRCConfig & CRC_CFG_ENDIAN_SBHW) ||
(ui32CRCConfig & CRC_CFG_ENDIAN_SHW) ||
(ui32CRCConfig & CRC_CFG_TYPE_P8005) ||
(ui32CRCConfig & CRC_CFG_TYPE_P1021) ||
(ui32CRCConfig & CRC_CFG_TYPE_P4C11DB7) ||
(ui32CRCConfig & CRC_CFG_TYPE_P1EDC6F41) ||
(ui32CRCConfig & CRC_CFG_TYPE_TCPCHKSUM));
//
// Write the control register with the configuration.
//
HWREG(ui32Base + DTHE_O_CRC_CTRL) = ui32CRCConfig;
}
//*****************************************************************************
//
//! Write the seed value for CRC operations in the EC module.
//!
//! \param ui32Base is the base address of the EC module.
//! \param ui32Seed is the seed value.
//!
//! This function writes the seed value for use with CRC operations in the
//! EC module. This value is the start value for CRC operations. If this
//! value is not written, then the residual seed from the previous operation
//! is used as the starting value.
//!
//! \note The seed must be written only if \b EC_CRC_CFG_INIT_SEED is
//! set with the CRCConfigSet() function.
//
//*****************************************************************************
void
CRCSeedSet(uint32_t ui32Base, uint32_t ui32Seed)
{
//
// Check the arguments.
//
ASSERT(ui32Base == DTHE_BASE);
//
// Write the seed value to the seed register.
//
HWREG(ui32Base + DTHE_O_CRC_SEED) = ui32Seed;
}
//*****************************************************************************
//
//! Write data into the EC module for CRC operations.
//!
//! \param ui32Base is the base address of the EC module.
//! \param ui32Data is the data to be written.
//!
//! This function writes either 8 or 32 bits of data into the EC module for
//! CRC operations. The distinction between 8 and 32 bits of data is made
//! when the \b EC_CRC_CFG_SIZE_8BIT or \b EC_CRC_CFG_SIZE_32BIT flag
//! is set using the CRCConfigSet() function.
//!
//! When writing 8 bits of data, ensure the data is in the least signficant
//! byte position. The remaining bytes should be written with zero. For
//! example, when writing 0xAB, \e ui32Data should be 0x000000AB.
//!
//! \return None
//
//*****************************************************************************
void
CRCDataWrite(uint32_t ui32Base, uint32_t ui32Data)
{
//
// Check the arguments.
//
ASSERT(ui32Base == DTHE_BASE);
//
// Write the data
//
HWREG(DTHE_BASE + DTHE_O_CRC_DIN) = ui32Data;
}
//*****************************************************************************
//
//! Reads the result of a CRC operation in the EC module.
//!
//! \param ui32Base is the base address of the EC module.
//!
//! This function reads either the unmodified CRC result or the post
//! processed CRC result from the EC module. The post-processing options
//! are selectable through \b EC_CRC_CFG_RESINV and \b EC_CRC_CFG_OBR
//! parameters in the CRCConfigSet() function.
//!
//! \return The CRC result.
//
//*****************************************************************************
uint32_t
CRCResultRead(uint32_t ui32Base)
{
//
// Check the arguments.
//
ASSERT(ui32Base == DTHE_BASE);
//
// return value.
//
return(HWREG(DTHE_BASE + DTHE_O_CRC_RSLT_PP));
}
//*****************************************************************************
//
//! Process data to generate a CRC with the EC module.
//!
//! \param ui32Base is the base address of the EC module.
//! \param puiDataIn is a pointer to an array of data that is processed.
//! \param ui32DataLength is the number of data items that are processed
//! to produce the CRC.
//! \param ui32Config the config parameter to determine the CRC mode
//!
//! This function processes an array of data to produce a CRC result.
//! This function takes the CRC mode as the parameter.
//!
//! The data in the array pointed to be \e pui32DataIn is either an array
//! of bytes or an array or words depending on the selection of the input
//! data size options \b EC_CRC_CFG_SIZE_8BIT and
//! \b EC_CRC_CFG_SIZE_32BIT.
//!
//! This function returns either the unmodified CRC result or the
//! post- processed CRC result from the EC module. The post-processing
//! options are selectable through \b EC_CRC_CFG_RESINV and
//! \b EC_CRC_CFG_OBR parameters.
//!
//! \return The CRC result.
//
//*****************************************************************************
uint32_t
CRCDataProcess(uint32_t ui32Base, void *puiDataIn,
uint32_t ui32DataLength, uint32_t ui32Config)
{
uint8_t *pui8DataIn;
uint32_t *pui32DataIn;
//
// Check the arguments.
//
ASSERT(ui32Base == DTHE_BASE);
//
// See if the CRC is operating in 8-bit or 32-bit mode.
//
if(ui32Config & DTHE_CRC_CTRL_SIZE)
{
//
// The CRC is operating in 8-bit mode, so create an 8-bit pointer to
// the data.
//
pui8DataIn = (uint8_t *)puiDataIn;
//
// Loop through the input data.
//
while(ui32DataLength--)
{
//
// Write the next data byte.
//
HWREG(ui32Base + DTHE_O_CRC_DIN) = *pui8DataIn++;
}
}
else
{
//
// The CRC is operating in 32-bit mode, so loop through the input data.
//
pui32DataIn = (uint32_t *)puiDataIn;
while(ui32DataLength--)
{
//
// Write the next data word.
//
HWREG(ui32Base + DTHE_O_CRC_DIN) = *pui32DataIn++;
}
}
//
// Return the result.
//
return(CRCResultRead(ui32Base));
}
//*****************************************************************************
//
// Close the Doxygen group.
//! @}
//
//*****************************************************************************

98
driverlib/crc.h Normal file
View File

@ -0,0 +1,98 @@
//*****************************************************************************
//
// crc.h
//
// Defines and Macros for CRC module.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#ifndef __DRIVERLIB_CRC_H__
#define __DRIVERLIB_CRC_H__
//*****************************************************************************
//
// If building with a C++ compiler, make all of the definitions in this header
// have a C binding.
//
//*****************************************************************************
#ifdef __cplusplus
extern "C"
{
#endif
//*****************************************************************************
//
// The following defines are used in the ui32Config argument of the
// ECConfig function.
//
//*****************************************************************************
#define CRC_CFG_INIT_SEED 0x00000000 // Initialize with seed
#define CRC_CFG_INIT_0 0x00004000 // Initialize to all '0s'
#define CRC_CFG_INIT_1 0x00006000 // Initialize to all '1s'
#define CRC_CFG_SIZE_8BIT 0x00001000 // Input Data Size
#define CRC_CFG_SIZE_32BIT 0x00000000 // Input Data Size
#define CRC_CFG_RESINV 0x00000200 // Result Inverse Enable
#define CRC_CFG_OBR 0x00000100 // Output Reverse Enable
#define CRC_CFG_IBR 0x00000080 // Bit reverse enable
#define CRC_CFG_ENDIAN_SBHW 0x00000000 // Swap byte in half-word
#define CRC_CFG_ENDIAN_SHW 0x00000010 // Swap half-word
#define CRC_CFG_TYPE_P8005 0x00000000 // Polynomial 0x8005
#define CRC_CFG_TYPE_P1021 0x00000001 // Polynomial 0x1021
#define CRC_CFG_TYPE_P4C11DB7 0x00000002 // Polynomial 0x4C11DB7
#define CRC_CFG_TYPE_P1EDC6F41 0x00000003 // Polynomial 0x1EDC6F41
#define CRC_CFG_TYPE_TCPCHKSUM 0x00000008 // TCP checksum
//*****************************************************************************
//
// Function prototypes.
//
//*****************************************************************************
extern void CRCConfigSet(uint32_t ui32Base, uint32_t ui32CRCConfig);
extern uint32_t CRCDataProcess(uint32_t ui32Base, void *puiDataIn,
uint32_t ui32DataLength, uint32_t ui32Config);
extern void CRCDataWrite(uint32_t ui32Base, uint32_t ui32Data);
extern uint32_t CRCResultRead(uint32_t ui32Base);
extern void CRCSeedSet(uint32_t ui32Base, uint32_t ui32Seed);
//*****************************************************************************
//
// Mark the end of the C bindings section for C++ compilers.
//
//*****************************************************************************
#ifdef __cplusplus
}
#endif
#endif // __DRIVERLIB_CRC_H__

67
driverlib/debug.h Normal file
View File

@ -0,0 +1,67 @@
//*****************************************************************************
//
// debug.h
//
// Macros for assisting debug of the driver library.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#ifndef __DEBUG_H__
#define __DEBUG_H__
//*****************************************************************************
//
// Prototype for the function that is called when an invalid argument is passed
// to an API. This is only used when doing a DEBUG build.
//
//*****************************************************************************
extern void __error__(char *pcFilename, unsigned long ulLine);
//*****************************************************************************
//
// The ASSERT macro, which does the actual assertion checking. Typically, this
// will be for procedure arguments.
//
//*****************************************************************************
#ifdef DEBUG
#define ASSERT(expr) \
if(!(expr)) \
{ \
__error__(__FILE__, __LINE__); \
} \
#else
#define ASSERT(expr)
#endif
#endif // __DEBUG_H__

887
driverlib/des.c Normal file
View File

@ -0,0 +1,887 @@
//*****************************************************************************
//
// des.c
//
// Driver for the DES data transformation.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
//*****************************************************************************
//
//! \addtogroup DES_Data_Encryption_Standard_api
//! @{
//
//*****************************************************************************
#include <stdbool.h>
#include <stdint.h>
#include "inc/hw_des.h"
#include "inc/hw_dthe.h"
#include "inc/hw_ints.h"
#include "inc/hw_memmap.h"
#include "inc/hw_types.h"
#include "debug.h"
#include "des.h"
#include "interrupt.h"
//*****************************************************************************
//
//! Configures the DES module for operation.
//!
//! \param ui32Base is the base address of the DES module.
//! \param ui32Config is the configuration of the DES module.
//!
//! This function configures the DES module for operation.
//!
//! The \e ui32Config parameter is a bit-wise OR of a number of configuration
//! flags. The valid flags are grouped below based on their function.
//!
//! The direction of the operation is specified with one of the following two
//! flags. Only one is permitted.
//!
//! - \b DES_CFG_DIR_ENCRYPT - Encryption
//! - \b DES_CFG_DIR_DECRYPT - Decryption
//!
//! The operational mode of the DES engine is specified with one of the
//! following flags. Only one is permitted.
//!
//! - \b DES_CFG_MODE_ECB - Electronic Codebook Mode
//! - \b DES_CFG_MODE_CBC - Cipher-Block Chaining Mode
//! - \b DES_CFG_MODE_CFB - Cipher Feedback Mode
//!
//! The selection of single DES or triple DES is specified with one of the
//! following two flags. Only one is permitted.
//!
//! - \b DES_CFG_SINGLE - Single DES
//! - \b DES_CFG_TRIPLE - Triple DES
//!
//! \return None.
//
//*****************************************************************************
void
DESConfigSet(uint32_t ui32Base, uint32_t ui32Config)
{
//
// Check the arguments.
//
ASSERT(ui32Base == DES_BASE);
//
// Backup the save context field.
//
ui32Config |= (HWREG(ui32Base + DES_O_CTRL) & DES_CTRL_CONTEXT);
//
// Write the control register.
//
HWREG(ui32Base + DES_O_CTRL) = ui32Config;
}
//*****************************************************************************
//
//! Sets the key used for DES operations.
//!
//! \param ui32Base is the base address of the DES module.
//! \param pui8Key is a pointer to an array that holds the key
//!
//! This function sets the key used for DES operations.
//!
//! \e pui8Key should be 64 bits long (2 words) if single DES is being used or
//! 192 bits (6 words) if triple DES is being used.
//!
//! \return None.
//
//*****************************************************************************
void
DESKeySet(uint32_t ui32Base, uint8_t *pui8Key)
{
//
// Check the arguments.
//
ASSERT(ui32Base == DES_BASE);
//
// Write the first part of the key.
//
HWREG(ui32Base + DES_O_KEY1_L) = * ((uint32_t *)(pui8Key + 0));
HWREG(ui32Base + DES_O_KEY1_H) = * ((uint32_t *)(pui8Key + 4));
//
// If we are performing triple DES, then write the key registers for
// the second and third rounds.
//
if(HWREG(ui32Base + DES_O_CTRL) & DES_CFG_TRIPLE)
{
HWREG(ui32Base + DES_O_KEY2_L) = * ((uint32_t *)(pui8Key + 8));
HWREG(ui32Base + DES_O_KEY2_H) = * ((uint32_t *)(pui8Key + 12));
HWREG(ui32Base + DES_O_KEY3_L) = * ((uint32_t *)(pui8Key + 16));
HWREG(ui32Base + DES_O_KEY3_H) = * ((uint32_t *)(pui8Key + 20));
}
}
//*****************************************************************************
//
//! Sets the initialization vector in the DES module.
//!
//! \param ui32Base is the base address of the DES module.
//! \param pui8IVdata is a pointer to an array of 64 bits (2 words) of data to
//! be written into the initialization vectors registers.
//!
//! This function sets the initialization vector in the DES module. It returns
//! true if the registers were successfully written. If the context registers
//! cannot be written at the time the function was called, then false is
//! returned.
//!
//! \return True or false.
//
//*****************************************************************************
bool
DESIVSet(uint32_t ui32Base, uint8_t *pui8IVdata)
{
//
// Check the arguments.
//
ASSERT(ui32Base == DES_BASE);
//
// Check to see if context registers can be overwritten. If not, return
// false.
//
if((HWREG(ui32Base + DES_O_CTRL) & DES_CTRL_CONTEXT) == 0)
{
return(false);
}
//
// Write the initialization vector registers.
//
HWREG(ui32Base + DES_O_IV_L) = *((uint32_t *) (pui8IVdata + 0));
HWREG(ui32Base + DES_O_IV_H) = *((uint32_t *) (pui8IVdata + 4));
//
// Return true to indicate the write was successful.
//
return(true);
}
//*****************************************************************************
//
//! Sets the crytographic data length in the DES module.
//!
//! \param ui32Base is the base address of the DES module.
//! \param ui32Length is the length of the data in bytes.
//!
//! This function writes the cryptographic data length into the DES module.
//! When this register is written, the engine is triggersed to start using
//! this context.
//!
//! \note Data lengths up to (2^32 - 1) bytes are allowed.
//!
//! \return None.
//
//*****************************************************************************
void
DESDataLengthSet(uint32_t ui32Base, uint32_t ui32Length)
{
//
// Check the arguments.
//
ASSERT(ui32Base == DES_BASE);
//
// Write the length register.
//
HWREG(ui32Base + DES_O_LENGTH) = ui32Length;
}
//*****************************************************************************
//
//! Reads plaintext/ciphertext from data registers without blocking
//!
//! \param ui32Base is the base address of the DES module.
//! \param pui8Dest is a pointer to an array of 2 words.
//! \param ui8Length the length can be from 1 to 8
//!
//! This function returns true if the data was ready when the function was
//! called. If the data was not ready, false is returned.
//!
//! \return True or false.
//
//*****************************************************************************
bool
DESDataReadNonBlocking(uint32_t ui32Base, uint8_t *pui8Dest, uint8_t ui8Length)
{
volatile uint32_t pui32Dest[2];
uint8_t ui8BytCnt;
uint8_t *pui8DestTemp;
//
// Check the arguments.
//
ASSERT(ui32Base == DES_BASE);
if((ui8Length == 0)||(ui8Length>8))
{
return(false);
}
//
// Check to see if the data is ready to be read.
//
if((DES_CTRL_OUTPUT_READY & (HWREG(ui32Base + DES_O_CTRL))) == 0)
{
return(false);
}
//
// Read two words of data from the data registers.
//
pui32Dest[0] = HWREG(DES_BASE + DES_O_DATA_L);
pui32Dest[1] = HWREG(DES_BASE + DES_O_DATA_H);
//
//Copy the data to a block memory
//
pui8DestTemp = (uint8_t *)pui32Dest;
for(ui8BytCnt = 0; ui8BytCnt < ui8Length ; ui8BytCnt++)
{
*(pui8Dest+ui8BytCnt) = *(pui8DestTemp+ui8BytCnt);
}
//
// Return true to indicate a successful write.
//
return(true);
}
//*****************************************************************************
//
//! Reads plaintext/ciphertext from data registers with blocking.
//!
//! \param ui32Base is the base address of the DES module.
//! \param pui8Dest is a pointer to an array of bytes.
//! \param ui8Length the length can be from 1 to 8
//!
//! This function waits until the DES module is finished and encrypted or
//! decrypted data is ready. The output data is then stored in the pui8Dest
//! array.
//!
//! \return None
//
//*****************************************************************************
void
DESDataRead(uint32_t ui32Base, uint8_t *pui8Dest, uint8_t ui8Length)
{
volatile uint32_t pui32Dest[2];
uint8_t ui8BytCnt;
uint8_t *pui8DestTemp;
//
// Check the arguments.
//
ASSERT(ui32Base == DES_BASE);
if((ui8Length == 0)||(ui8Length>8))
{
return;
}
//
// Wait for data output to be ready.
//
while((HWREG(ui32Base + DES_O_CTRL) & DES_CTRL_OUTPUT_READY) == 0)
{
}
//
// Read two words of data from the data registers.
//
pui32Dest[0] = HWREG(DES_BASE + DES_O_DATA_L);
pui32Dest[1] = HWREG(DES_BASE + DES_O_DATA_H);
//
//Copy the data to a block memory
//
pui8DestTemp = (uint8_t *)pui32Dest;
for(ui8BytCnt = 0; ui8BytCnt < ui8Length ; ui8BytCnt++)
{
*(pui8Dest+ui8BytCnt) = *(pui8DestTemp+ui8BytCnt);
}
}
//*****************************************************************************
//
//! Writes plaintext/ciphertext to data registers without blocking
//!
//! \param ui32Base is the base address of the DES module.
//! \param pui8Src is a pointer to an array of 2 words.
//! \param ui8Length the length can be from 1 to 8
//!
//! This function returns false if the DES module is not ready to accept
//! data. It returns true if the data was written successfully.
//!
//! \return true or false.
//
//*****************************************************************************
bool
DESDataWriteNonBlocking(uint32_t ui32Base, uint8_t *pui8Src, uint8_t ui8Length)
{
volatile uint32_t pui32Src[2]={0,0};
uint8_t ui8BytCnt;
uint8_t *pui8SrcTemp;
//
// Check the arguments.
//
ASSERT(ui32Base == DES_BASE);
if((ui8Length == 0)||(ui8Length>8))
{
return(false);
}
//
// Check if the DES module is ready to encrypt or decrypt data. If it
// is not, return false.
//
if(!(DES_CTRL_INPUT_READY & (HWREG(ui32Base + DES_O_CTRL))))
{
return(false);
}
//
// Copy the data to a block memory
//
pui8SrcTemp = (uint8_t *)pui32Src;
for(ui8BytCnt = 0; ui8BytCnt < ui8Length ; ui8BytCnt++)
{
*(pui8SrcTemp+ui8BytCnt) = *(pui8Src+ui8BytCnt);
}
//
// Write the data.
//
HWREG(DES_BASE + DES_O_DATA_L) = pui32Src[0];
HWREG(DES_BASE + DES_O_DATA_H) = pui32Src[1];
//
// Return true to indicate a successful write.
//
return(true);
}
//*****************************************************************************
//
//! Writes plaintext/ciphertext to data registers without blocking
//!
//! \param ui32Base is the base address of the DES module.
//! \param pui8Src is a pointer to an array of bytes.
//! \param ui8Length the length can be from 1 to 8
//!
//! This function waits until the DES module is ready before writing the
//! data contained in the pui8Src array.
//!
//! \return None.
//
//*****************************************************************************
void
DESDataWrite(uint32_t ui32Base, uint8_t *pui8Src, uint8_t ui8Length)
{
volatile uint32_t pui32Src[2]={0,0};
uint8_t ui8BytCnt;
uint8_t *pui8SrcTemp;
//
// Check the arguments.
//
ASSERT(ui32Base == DES_BASE);
if((ui8Length == 0)||(ui8Length>8))
{
return;
}
//
// Wait for the input ready bit to go high.
//
while(((HWREG(ui32Base + DES_O_CTRL) & DES_CTRL_INPUT_READY)) == 0)
{
}
//
//Copy the data to a block memory
//
pui8SrcTemp = (uint8_t *)pui32Src;
for(ui8BytCnt = 0; ui8BytCnt < ui8Length ; ui8BytCnt++)
{
*(pui8SrcTemp+ui8BytCnt) = *(pui8Src+ui8BytCnt);
}
//
// Write the data.
//
HWREG(DES_BASE + DES_O_DATA_L) = pui32Src[0];
HWREG(DES_BASE + DES_O_DATA_H) = pui32Src[1];
}
//*****************************************************************************
//
//! Processes blocks of data through the DES module.
//!
//! \param ui32Base is the base address of the DES module.
//! \param pui8Src is a pointer to an array of words that contains the
//! source data for processing.
//! \param pui8Dest is a pointer to an array of words consisting of the
//! processed data.
//! \param ui32Length is the length of the cryptographic data in bytes.
//! It must be a multiple of eight.
//!
//! This function takes the data contained in the pui8Src array and processes
//! it using the DES engine. The resulting data is stored in the
//! pui8Dest array. The function blocks until all of the data has been
//! processed. If processing is successful, the function returns true.
//!
//! \note This functions assumes that the DES module has been configured,
//! and initialization values and keys have been written.
//!
//! \return true or false.
//
//*****************************************************************************
bool
DESDataProcess(uint32_t ui32Base, uint8_t *pui8Src, uint8_t *pui8Dest,
uint32_t ui32Length)
{
uint32_t ui32Count, ui32BlkCount, ui32ByteCount;
//
// Check the arguments.
//
ASSERT(ui32Base == DES_BASE);
ASSERT((ui32Length % 8) == 0);
//
// Write the length register first. This triggers the engine to start
// using this context.
//
HWREG(ui32Base + DES_O_LENGTH) = ui32Length;
//
// Now loop until the blocks are written.
//
ui32BlkCount = ui32Length/8;
for(ui32Count = 0; ui32Count <ui32BlkCount; ui32Count ++)
{
//
// Check if the input ready is fine
//
while((DES_CTRL_INPUT_READY & (HWREG(ui32Base + DES_O_CTRL))) == 0)
{
}
//
// Write the data registers.
//
DESDataWriteNonBlocking(ui32Base, pui8Src + ui32Count*8 ,8);
//
// Wait for the output ready
//
while((DES_CTRL_OUTPUT_READY & (HWREG(ui32Base + DES_O_CTRL))) == 0)
{
}
//
// Read the data registers.
//
DESDataReadNonBlocking(ui32Base, pui8Dest + ui32Count*8 ,8);
}
//
//Now handle the residue bytes
//
ui32ByteCount = ui32Length%8;
if(ui32ByteCount)
{
//
// Check if the input ready is fine
//
while((DES_CTRL_INPUT_READY & (HWREG(ui32Base + DES_O_CTRL))) == 0)
{
}
//
// Write the data registers.
//
DESDataWriteNonBlocking(ui32Base, pui8Src + (8*ui32BlkCount) ,
ui32ByteCount);
//
// Wait for the output ready
//
while((DES_CTRL_OUTPUT_READY & (HWREG(ui32Base + DES_O_CTRL))) == 0)
{
}
//
// Read the data registers.
//
DESDataReadNonBlocking(ui32Base, pui8Dest + (8*ui32BlkCount) ,
ui32ByteCount);
}
//
// Return true to indicate the process was successful.
//
return(true);
}
//*****************************************************************************
//
//! Returns the current interrupt status of the DES module.
//!
//! \param ui32Base is the base address of the DES module.
//! \param bMasked is \b false if the raw interrupt status is required and
//! \b true if the masked interrupt status is required.
//!
//! This function gets the current interrupt status of the DES module.
//! The value returned is a logical OR of the following values:
//!
//! - \b DES_INT_CONTEXT_IN - Context interrupt
//! - \b DES_INT_DATA_IN - Data input interrupt
//! - \b DES_INT_DATA_OUT_INT - Data output interrupt
//! - \b DES_INT_DMA_CONTEXT_IN - Context DMA done interrupt
//! - \b DES_INT_DMA_DATA_IN - Data input DMA done interrupt
//! - \b DES_INT_DMA_DATA_OUT - Data output DMA done interrupt
//!
//! \return A bit mask of the current interrupt status.
//
//*****************************************************************************
uint32_t
DESIntStatus(uint32_t ui32Base, bool bMasked)
{
uint32_t ui32IntStatus;
//
// Check the arguments.
//
ASSERT(ui32Base == DES_BASE);
//
// Read the status register and return the value.
//
if(bMasked)
{
ui32IntStatus = HWREG(ui32Base + DES_O_IRQSTATUS);
ui32IntStatus &= HWREG(ui32Base + DES_O_IRQENABLE);
ui32IntStatus |= ((HWREG(DTHE_BASE + DTHE_O_DES_MIS) & 0x7) << 16);
return(ui32IntStatus);
}
else
{
ui32IntStatus = HWREG(ui32Base + DES_O_IRQSTATUS);
ui32IntStatus |= ((HWREG(DTHE_BASE + DTHE_O_DES_MIS) & 0xD) << 16);
return(ui32IntStatus);
}
}
//*****************************************************************************
//
//! Enables interrupts in the DES module.
//!
//! \param ui32Base is the base address of the DES module.
//! \param ui32IntFlags is a bit mask of the interrupts to be enabled.
//!
//! \e ui32IntFlags should be a logical OR of one or more of the following
//! values:
//!
//! - \b DES_INT_CONTEXT_IN - Context interrupt
//! - \b DES_INT_DATA_IN - Data input interrupt
//! - \b DES_INT_DATA_OUT - Data output interrupt
//! - \b DES_INT_DMA_CONTEXT_IN - Context DMA done interrupt
//! - \b DES_INT_DMA_DATA_IN - Data input DMA done interrupt
//! - \b DES_INT_DMA_DATA_OUT - Data output DMA done interrupt
//!
//! \return None.
//
//*****************************************************************************
void
DESIntEnable(uint32_t ui32Base, uint32_t ui32IntFlags)
{
//
// Check the arguments.
//
ASSERT(ui32Base == DES_BASE);
ASSERT((ui32IntFlags & DES_INT_CONTEXT_IN) ||
(ui32IntFlags & DES_INT_DATA_IN) ||
(ui32IntFlags & DES_INT_DATA_OUT) ||
(ui32IntFlags & DES_INT_DMA_CONTEXT_IN) ||
(ui32IntFlags & DES_INT_DMA_DATA_IN) ||
(ui32IntFlags & DES_INT_DMA_DATA_OUT));
//
// Enable the interrupts from the flags.
//
HWREG(DTHE_BASE + DTHE_O_DES_IM) &= ~((ui32IntFlags & 0x00070000) >> 16);
HWREG(ui32Base + DES_O_IRQENABLE) |= ui32IntFlags & 0x0000ffff;
}
//*****************************************************************************
//
//! Disables interrupts in the DES module.
//!
//! \param ui32Base is the base address of the DES module.
//! \param ui32IntFlags is a bit mask of the interrupts to be disabled.
//!
//! This function disables interrupt sources in the DES module.
//! \e ui32IntFlags should be a logical OR of one or more of the following
//! values:
//!
//! - \b DES_INT_CONTEXT_IN - Context interrupt
//! - \b DES_INT_DATA_IN - Data input interrupt
//! - \b DES_INT_DATA_OUT - Data output interrupt
//! - \b DES_INT_DMA_CONTEXT_IN - Context DMA done interrupt
//! - \b DES_INT_DMA_DATA_IN - Data input DMA done interrupt
//! - \b DES_INT_DMA_DATA_OUT - Data output DMA done interrupt
//!
//! \return None.
//
//*****************************************************************************
void
DESIntDisable(uint32_t ui32Base, uint32_t ui32IntFlags)
{
//
// Check the arguments.
//
ASSERT(ui32Base == DES_BASE);
ASSERT((ui32IntFlags & DES_INT_CONTEXT_IN) ||
(ui32IntFlags & DES_INT_DATA_IN) ||
(ui32IntFlags & DES_INT_DATA_OUT) ||
(ui32IntFlags & DES_INT_DMA_CONTEXT_IN) ||
(ui32IntFlags & DES_INT_DMA_DATA_IN) ||
(ui32IntFlags & DES_INT_DMA_DATA_OUT));
//
// Clear the interrupts from the flags.
//
HWREG(DTHE_BASE + DTHE_O_AES_IM) |= ((ui32IntFlags & 0x00070000) >> 16);
HWREG(ui32Base + DES_O_IRQENABLE) &= ~(ui32IntFlags & 0x0000ffff);
}
//*****************************************************************************
//
//! Clears interrupts in the DES module.
//!
//! \param ui32Base is the base address of the DES module.
//! \param ui32IntFlags is a bit mask of the interrupts to be disabled.
//!
//! This function disables interrupt sources in the DES module.
//! \e ui32IntFlags should be a logical OR of one or more of the following
//! values:
//!
//! - \b DES_INT_DMA_CONTEXT_IN - Context interrupt
//! - \b DES_INT_DMA_DATA_IN - Data input interrupt
//! - \b DES_INT_DMA_DATA_OUT - Data output interrupt
//!
//! \note The DMA done interrupts are the only interrupts that can be cleared.
//! The remaining interrupts can be disabled instead using DESIntDisable().
//!
//! \return None.
//
//*****************************************************************************
void
DESIntClear(uint32_t ui32Base, uint32_t ui32IntFlags)
{
//
// Check the arguments.
//
ASSERT(ui32Base == DES_BASE);
ASSERT((ui32IntFlags & DES_INT_DMA_CONTEXT_IN) ||
(ui32IntFlags & DES_INT_DMA_DATA_IN) ||
(ui32IntFlags & DES_INT_DMA_DATA_OUT));
HWREG(DTHE_BASE + DTHE_O_DES_IC) = ((ui32IntFlags & 0x00070000) >> 16);
}
//*****************************************************************************
//
//! Registers an interrupt handler for the DES module.
//!
//! \param ui32Base is the base address of the DES module.
//! \param pfnHandler is a pointer to the function to be called when the
//! enabled DES interrupts occur.
//!
//! This function registers the interrupt handler in the interrupt vector
//! table, and enables DES interrupts on the interrupt controller; specific DES
//! interrupt sources must be enabled using DESIntEnable(). The interrupt
//! handler being registered must clear the source of the interrupt using
//! DESIntClear().
//!
//! If the application is using a static interrupt vector table stored in
//! flash, then it is not necessary to register the interrupt handler this way.
//! Instead, IntEnable() should be used to enable DES interrupts on the
//! interrupt controller.
//!
//! \sa IntRegister() for important information about registering interrupt
//! handlers.
//!
//! \return None.
//
//*****************************************************************************
void
DESIntRegister(uint32_t ui32Base, void(*pfnHandler)(void))
{
//
// Check the arguments.
//
ASSERT(ui32Base == DES_BASE);
//
// Register the interrupt handler.
//
IntRegister(INT_DES, pfnHandler);
//
// Enable the interrupt.
//
IntEnable(INT_DES);
}
//*****************************************************************************
//
//! Unregisters an interrupt handler for the DES module.
//!
//! \param ui32Base is the base address of the DES module.
//!
//! This function unregisters the previously registered interrupt handler and
//! disables the interrupt in the interrupt controller.
//!
//! \sa IntRegister() for important information about registering interrupt
//! handlers.
//!
//! \return None.
//
//*****************************************************************************
void
DESIntUnregister(uint32_t ui32Base)
{
//
// Check the arguments.
//
ASSERT(ui32Base == DES_BASE);
//
// Disable the interrupt.
//
IntDisable(INT_DES);
//
// Unregister the interrupt handler.
//
IntUnregister(INT_DES);
}
//*****************************************************************************
//
//! Enables DMA request sources in the DES module.
//!
//! \param ui32Base is the base address of the DES module.
//! \param ui32Flags is a bit mask of the DMA requests to be enabled.
//!
//! This function enables DMA request sources in the DES module. The
//! \e ui32Flags parameter should be the logical OR of any of the following:
//!
//! - \b DES_DMA_CONTEXT_IN - Context In
//! - \b DES_DMA_DATA_OUT - Data Out
//! - \b DES_DMA_DATA_IN - Data In
//!
//! \return None.
//
//*****************************************************************************
void
DESDMAEnable(uint32_t ui32Base, uint32_t ui32Flags)
{
//
// Check the arguments.
//
ASSERT(ui32Base == DES_BASE);
ASSERT((ui32Flags & DES_DMA_CONTEXT_IN) ||
(ui32Flags & DES_DMA_DATA_OUT) ||
(ui32Flags & DES_DMA_DATA_IN));
//
// Set the data in and data out DMA request enable bits.
//
HWREG(ui32Base + DES_O_SYSCONFIG) |= ui32Flags;
}
//*****************************************************************************
//
//! Disables DMA request sources in the DES module.
//!
//! \param ui32Base is the base address of the DES module.
//! \param ui32Flags is a bit mask of the DMA requests to be disabled.
//!
//! This function disables DMA request sources in the DES module. The
//! \e ui32Flags parameter should be the logical OR of any of the following:
//!
//! - \b DES_DMA_CONTEXT_IN - Context In
//! - \b DES_DMA_DATA_OUT - Data Out
//! - \b DES_DMA_DATA_IN - Data In
//!
//! \return None.
//
//*****************************************************************************
void
DESDMADisable(uint32_t ui32Base, uint32_t ui32Flags)
{
//
// Check the arguments.
//
ASSERT(ui32Base == DES_BASE);
ASSERT((ui32Flags & DES_DMA_CONTEXT_IN) ||
(ui32Flags & DES_DMA_DATA_OUT) ||
(ui32Flags & DES_DMA_DATA_IN));
//
// Disable the DMA sources.
//
HWREG(ui32Base + DES_O_SYSCONFIG) &= ~ui32Flags;
}
//*****************************************************************************
//
// Close the Doxygen group.
//! @}
//
//*****************************************************************************

143
driverlib/des.h Normal file
View File

@ -0,0 +1,143 @@
//*****************************************************************************
//
// des.h
//
// Defines and Macros for the DES module.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#ifndef __DRIVERLIB_DES_H__
#define __DRIVERLIB_DES_H__
//*****************************************************************************
//
// If building with a C++ compiler, make all of the definitions in this header
// have a C binding.
//
//*****************************************************************************
#ifdef __cplusplus
extern "C"
{
#endif
//*****************************************************************************
//
// The following defines are used to specify the direction with the
// ui32Config argument in the DESConfig() function. Only one is permitted.
//
//*****************************************************************************
#define DES_CFG_DIR_DECRYPT 0x00000000
#define DES_CFG_DIR_ENCRYPT 0x00000004
//*****************************************************************************
//
// The following defines are used to specify the operational with the
// ui32Config argument in the DESConfig() function. Only one is permitted.
//
//*****************************************************************************
#define DES_CFG_MODE_ECB 0x00000000
#define DES_CFG_MODE_CBC 0x00000010
#define DES_CFG_MODE_CFB 0x00000020
//*****************************************************************************
//
// The following defines are used to select between single DES and triple DES
// with the ui32Config argument in the DESConfig() function. Only one is
// permitted.
//
//*****************************************************************************
#define DES_CFG_SINGLE 0x00000000
#define DES_CFG_TRIPLE 0x00000008
//*****************************************************************************
//
// The following defines are used with the DESIntEnable(), DESIntDisable() and
// DESIntStatus() functions.
//
//*****************************************************************************
#define DES_INT_CONTEXT_IN 0x00000001
#define DES_INT_DATA_IN 0x00000002
#define DES_INT_DATA_OUT 0x00000004
#define DES_INT_DMA_CONTEXT_IN 0x00010000
#define DES_INT_DMA_DATA_IN 0x00020000
#define DES_INT_DMA_DATA_OUT 0x00040000
//*****************************************************************************
//
// The following defines are used with the DESEnableDMA() and DESDisableDMA()
// functions.
//
//*****************************************************************************
#define DES_DMA_CONTEXT_IN 0x00000080
#define DES_DMA_DATA_OUT 0x00000040
#define DES_DMA_DATA_IN 0x00000020
//*****************************************************************************
//
// API Function prototypes
//
//*****************************************************************************
extern void DESConfigSet(uint32_t ui32Base, uint32_t ui32Config);
extern void DESDataRead(uint32_t ui32Base, uint8_t *pui8Dest,
uint8_t ui8Length);
extern bool DESDataReadNonBlocking(uint32_t ui32Base, uint8_t *pui8Dest,
uint8_t ui8Length);
extern bool DESDataProcess(uint32_t ui32Base, uint8_t *pui8Src,
uint8_t *pui8Dest, uint32_t ui32Length);
extern void DESDataWrite(uint32_t ui32Base, uint8_t *pui8Src,
uint8_t ui8Length);
extern bool DESDataWriteNonBlocking(uint32_t ui32Base, uint8_t *pui8Src,
uint8_t ui8Length);
extern void DESDMADisable(uint32_t ui32Base, uint32_t ui32Flags);
extern void DESDMAEnable(uint32_t ui32Base, uint32_t ui32Flags);
extern void DESIntClear(uint32_t ui32Base, uint32_t ui32IntFlags);
extern void DESIntDisable(uint32_t ui32Base, uint32_t ui32IntFlags);
extern void DESIntEnable(uint32_t ui32Base, uint32_t ui32IntFlags);
extern void DESIntRegister(uint32_t ui32Base, void(*pfnHandler)(void));
extern uint32_t DESIntStatus(uint32_t ui32Base, bool bMasked);
extern void DESIntUnregister(uint32_t ui32Base);
extern bool DESIVSet(uint32_t ui32Base, uint8_t *pui8IVdata);
extern void DESKeySet(uint32_t ui32Base, uint8_t *pui8Key);
extern void DESDataLengthSet(uint32_t ui32Base, uint32_t ui32Length);
//*****************************************************************************
//
// Mark the end of the C bindings section for C++ compilers.
//
//*****************************************************************************
#ifdef __cplusplus
}
#endif
#endif // __DRIVERLIB_DES_H__

863
driverlib/flash.c Normal file
View File

@ -0,0 +1,863 @@
//*****************************************************************************
//
// flash.c
//
// Driver for programming the on-chip flash.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
//*****************************************************************************
//
//! \addtogroup flash_api
//! @{
//
//*****************************************************************************
#include "inc/hw_types.h"
#include "inc/hw_flash_ctrl.h"
#include "inc/hw_memmap.h"
#include "inc/hw_ints.h"
#include "inc/hw_gprcm.h"
#include "inc/hw_hib1p2.h"
#include "inc/hw_hib3p3.h"
#include "inc/hw_common_reg.h"
#include "inc/hw_stack_die_ctrl.h"
#include "debug.h"
#include "flash.h"
#include "utils.h"
#include "interrupt.h"
#define HAVE_WRITE_BUFFER 1
//*****************************************************************************
//
// An array that maps the specified memory bank to the appropriate Flash
// Memory Protection Program Enable (FMPPE) register.
//
//*****************************************************************************
static const unsigned long g_pulFMPPERegs[] =
{
FLASH_FMPPE0,
FLASH_FMPPE1,
FLASH_FMPPE2,
FLASH_FMPPE3,
FLASH_FMPPE4,
FLASH_FMPPE5,
FLASH_FMPPE6,
FLASH_FMPPE7,
FLASH_FMPPE8,
FLASH_FMPPE9,
FLASH_FMPPE10,
FLASH_FMPPE11,
FLASH_FMPPE12,
FLASH_FMPPE13,
FLASH_FMPPE14,
FLASH_FMPPE15
};
//*****************************************************************************
//
// An array that maps the specified memory bank to the appropriate Flash
// Memory Protection Read Enable (FMPRE) register.
//
//*****************************************************************************
static const unsigned long g_pulFMPRERegs[] =
{
FLASH_FMPRE0,
FLASH_FMPRE1,
FLASH_FMPRE2,
FLASH_FMPRE3,
FLASH_FMPRE4,
FLASH_FMPRE5,
FLASH_FMPRE6,
FLASH_FMPRE7,
FLASH_FMPRE8,
FLASH_FMPRE9,
FLASH_FMPRE10,
FLASH_FMPRE11,
FLASH_FMPRE12,
FLASH_FMPRE13,
FLASH_FMPRE14,
FLASH_FMPRE15,
};
//*****************************************************************************
//
//! Flash Disable
//!
//! This function Disables the internal Flash.
//!
//! \return None.
//
//*****************************************************************************
void
FlashDisable()
{
//
// Wait for Flash Busy to get cleared
//
while((HWREG(GPRCM_BASE + GPRCM_O_TOP_DIE_ENABLE)
& GPRCM_TOP_DIE_ENABLE_FLASH_BUSY))
{
}
//
// Assert reset
//
HWREG(HIB1P2_BASE + HIB1P2_O_PORPOL_SPARE) = 0xFFFF0000;
//
// 50 usec Delay Loop
//
UtilsDelay((50*80)/3);
//
// Disable TDFlash
//
HWREG(GPRCM_BASE + GPRCM_O_TOP_DIE_ENABLE) = 0x0;
//
// 50 usec Delay Loop
//
UtilsDelay((50*80)/3);
HWREG(HIB1P2_BASE + HIB1P2_O_BGAP_DUTY_CYCLING_EXIT_CFG) = 0x1;
//
// 50 usec Delay Loop
//
UtilsDelay((50*80)/3);
}
//*****************************************************************************
//
//! Erases a block of flash.
//!
//! \param ulAddress is the start address of the flash block to be erased.
//!
//! This function will erase a 2 kB block of the on-chip flash. After erasing,
//! the block will be filled with 0xFF bytes. Read-only and execute-only
//! blocks cannot be erased.
//!
//! This function will not return until the block has been erased.
//!
//! \return Returns 0 on success, or -1 if an invalid block address was
//! specified or the block is write-protected.
//
//*****************************************************************************
long
FlashErase(unsigned long ulAddress)
{
//
// Check the arguments.
//
ASSERT(!(ulAddress & (FLASH_CTRL_ERASE_SIZE - 1)));
//
// Clear the flash access and error interrupts.
//
HWREG(FLASH_CONTROL_BASE + FLASH_CTRL_O_FCMISC)
= (FLASH_CTRL_FCMISC_AMISC | FLASH_CTRL_FCMISC_VOLTMISC |
FLASH_CTRL_FCMISC_ERMISC);
// Erase the block.
//
HWREG(FLASH_CONTROL_BASE + FLASH_CTRL_O_FMA) = ulAddress;
HWREG(FLASH_CONTROL_BASE + FLASH_CTRL_O_FMC)
= FLASH_CTRL_FMC_WRKEY | FLASH_CTRL_FMC_ERASE;
//
// Wait until the block has been erased.
//
while(HWREG(FLASH_CONTROL_BASE + FLASH_CTRL_O_FMC) & FLASH_CTRL_FMC_ERASE)
{
}
//
// Return an error if an access violation or erase error occurred.
//
if(HWREG(FLASH_CONTROL_BASE + FLASH_CTRL_O_FCRIS)
& (FLASH_CTRL_FCRIS_ARIS | FLASH_CTRL_FCRIS_VOLTRIS |
FLASH_CTRL_FCRIS_ERRIS))
{
return(-1);
}
//
// Success.
//
return(0);
}
//*****************************************************************************
//
//! Erases a block of flash but does not wait for completion.
//!
//! \param ulAddress is the start address of the flash block to be erased.
//!
//! This function will erase a 2 kB block of the on-chip flash. After erasing,
//! the block will be filled with 0xFF bytes. Read-only and execute-only
//! blocks cannot be erased.
//!
//! This function will return immediately after commanding the erase operation.
//! Applications making use of the function can determine completion state by
//! using a flash interrupt handler or by polling FlashIntStatus.
//!
//! \return None.
//
//*****************************************************************************
void
FlashEraseNonBlocking(unsigned long ulAddress)
{
//
// Check the arguments.
//
ASSERT(!(ulAddress & (FLASH_CTRL_ERASE_SIZE - 1)));
//
// Clear the flash access and error interrupts.
//
HWREG(FLASH_CONTROL_BASE + FLASH_CTRL_O_FCMISC) =
(FLASH_CTRL_FCMISC_AMISC | FLASH_CTRL_FCMISC_VOLTMISC |
FLASH_CTRL_FCMISC_ERMISC);
//
// Command the flash controller to erase the block.
//
HWREG(FLASH_CONTROL_BASE + FLASH_CTRL_O_FMA) = ulAddress;
HWREG(FLASH_CONTROL_BASE + FLASH_CTRL_O_FMC) = FLASH_CTRL_FMC_WRKEY | FLASH_CTRL_FMC_ERASE;
}
//*****************************************************************************
//
//! Erases a complele flash at shot.
//!
//! This function erases a complele flash at shot
//!
//! \return Returns 0 on success, or -1 if the block is write-protected.
//
//*****************************************************************************
long
FlashMassErase()
{
//
// Clear the flash access and error interrupts.
//
HWREG(FLASH_CONTROL_BASE + FLASH_CTRL_O_FCMISC) =
(FLASH_CTRL_FCMISC_AMISC | FLASH_CTRL_FCMISC_VOLTMISC |
FLASH_CTRL_FCMISC_ERMISC);
//
// Command the flash controller for mass erase.
//
HWREG(FLASH_CONTROL_BASE + FLASH_CTRL_O_FMC) =
FLASH_CTRL_FMC_WRKEY | FLASH_CTRL_FMC_MERASE1;
//
// Wait until mass erase completes.
//
while(HWREG(FLASH_CONTROL_BASE + FLASH_CTRL_O_FMC) & FLASH_CTRL_FMC_MERASE1)
{
}
//
// Return an error if an access violation or erase error occurred.
//
if(HWREG(FLASH_CONTROL_BASE + FLASH_CTRL_O_FCRIS)
& (FLASH_CTRL_FCRIS_ARIS | FLASH_CTRL_FCRIS_VOLTRIS |
FLASH_CTRL_FCRIS_ERRIS))
{
return -1;
}
//
// Success.
//
return 0;
}
//*****************************************************************************
//
//! Erases a complele flash at shot but does not wait for completion.
//!
//!
//! This function will not return until the Flash has been erased.
//!
//! \return None.
//
//*****************************************************************************
void
FlashMassEraseNonBlocking()
{
//
// Clear the flash access and error interrupts.
//
HWREG(FLASH_CONTROL_BASE + FLASH_CTRL_O_FCMISC) =
(FLASH_CTRL_FCMISC_AMISC | FLASH_CTRL_FCMISC_VOLTMISC |
FLASH_CTRL_FCMISC_ERMISC);
//
// Command the flash controller for mass erase.
//
HWREG(FLASH_CONTROL_BASE + FLASH_CTRL_O_FMC) =
FLASH_CTRL_FMC_WRKEY | FLASH_CTRL_FMC_MERASE1;
}
//*****************************************************************************
//
//! Programs flash.
//!
//! \param pulData is a pointer to the data to be programmed.
//! \param ulAddress is the starting address in flash to be programmed. Must
//! be a multiple of four.
//! \param ulCount is the number of bytes to be programmed. Must be a multiple
//! of four.
//!
//! This function will program a sequence of words into the on-chip flash.
//! Each word in a page of flash can only be programmed one time between an
//! erase of that page; programming a word multiple times will result in an
//! unpredictable value in that word of flash.
//!
//! Since the flash is programmed one word at a time, the starting address and
//! byte count must both be multiples of four. It is up to the caller to
//! verify the programmed contents, if such verification is required.
//!
//! This function will not return until the data has been programmed.
//!
//! \return Returns 0 on success, or -1 if a programming error is encountered.
//
//*****************************************************************************
long
FlashProgram(unsigned long *pulData, unsigned long ulAddress,
unsigned long ulCount)
{
//
// Check the arguments.
//
ASSERT(!(ulAddress & 3));
ASSERT(!(ulCount & 3));
//
// Clear the flash access and error interrupts.
//
HWREG(FLASH_CONTROL_BASE + FLASH_CTRL_O_FCMISC)
= (FLASH_CTRL_FCMISC_AMISC | FLASH_CTRL_FCMISC_VOLTMISC |
FLASH_CTRL_FCMISC_INVDMISC | FLASH_CTRL_FCMISC_PROGMISC);
//
// See if this device has a write buffer.
//
#if HAVE_WRITE_BUFFER
{
//
// Loop over the words to be programmed.
//
while(ulCount)
{
//
// Set the address of this block of words. for 1 MB
//
HWREG(FLASH_CONTROL_BASE + FLASH_CTRL_O_FMA) = ulAddress & ~(0x7F);
//
// Loop over the words in this 32-word block.
//
while(((ulAddress & 0x7C) ||
(HWREG(FLASH_CONTROL_BASE + FLASH_CTRL_O_FWBVAL) == 0)) &&
(ulCount != 0))
{
//
// Write this word into the write buffer.
//
HWREG(FLASH_CONTROL_BASE + FLASH_CTRL_O_FWBN
+ (ulAddress & 0x7C)) = *pulData++;
ulAddress += 4;
ulCount -= 4;
}
//
// Program the contents of the write buffer into flash.
//
HWREG(FLASH_CONTROL_BASE + FLASH_CTRL_O_FMC2)
= FLASH_CTRL_FMC2_WRKEY | FLASH_CTRL_FMC2_WRBUF;
//
// Wait until the write buffer has been programmed.
//
while(HWREG(FLASH_CONTROL_BASE + FLASH_CTRL_O_FMC2) & FLASH_CTRL_FMC2_WRBUF)
{
}
}
}
#else
{
//
// Loop over the words to be programmed.
//
while(ulCount)
{
//
// Program the next word.
//
HWREG(FLASH_CONTROL_BASE + FLASH_CTRL_O_FMA) = ulAddress;
HWREG(FLASH_CONTROL_BASE + FLASH_CTRL_O_FMD) = *pulData;
HWREG(FLASH_CONTROL_BASE + FLASH_CTRL_O_FMC) = FLASH_CTRL_FMC_WRKEY | FLASH_CTRL_FMC_WRITE;
//
// Wait until the word has been programmed.
//
while(HWREG(FLASH_CONTROL_BASE + FLASH_CTRL_O_FMC) & FLASH_CTRL_FMC_WRITE)
{
}
//
// Increment to the next word.
//
pulData++;
ulAddress += 4;
ulCount -= 4;
}
}
#endif
//
// Return an error if an access violation occurred.
//
if(HWREG(FLASH_CONTROL_BASE + FLASH_CTRL_O_FCRIS) & (FLASH_CTRL_FCRIS_ARIS | FLASH_CTRL_FCRIS_VOLTRIS |
FLASH_CTRL_FCRIS_INVDRIS | FLASH_CTRL_FCRIS_PROGRIS))
{
return(-1);
}
//
// Success.
//
return(0);
}
//*****************************************************************************
//
//! Programs flash but does not poll for completion.
//!
//! \param pulData is a pointer to the data to be programmed.
//! \param ulAddress is the starting address in flash to be programmed. Must
//! be a multiple of four.
//! \param ulCount is the number of bytes to be programmed. Must be a multiple
//! of four.
//!
//! This function will start programming one or more words into the on-chip
//! flash and return immediately. The number of words that can be programmed
//! in a single call depends the part on which the function is running. For
//! parts without support for a flash write buffer, only a single word may be
//! programmed on each call to this function (\e ulCount must be 1). If a
//! write buffer is present, up to 32 words may be programmed on condition
//! that the block being programmed does not straddle a 32 word address
//! boundary. For example, wherease 32 words can be programmed if the address
//! passed is 0x100 (a multiple of 128 bytes or 32 words), only 31 words could
//! be programmed at 0x104 since attempting to write 32 would cross the 32
//! word boundary at 0x180.
//!
//! Since the flash is programmed one word at a time, the starting address and
//! byte count must both be multiples of four. It is up to the caller to
//! verify the programmed contents, if such verification is required.
//!
//! This function will return immediately after commanding the erase operation.
//! Applications making use of the function can determine completion state by
//! using a flash interrupt handler or by polling FlashIntStatus.
//!
//! \return 0 if the write was started successfully, -1 if there was an error.
//
//*****************************************************************************
long
FlashProgramNonBlocking(unsigned long *pulData, unsigned long ulAddress,
unsigned long ulCount)
{
//
// Check the arguments.
//
ASSERT(!(ulAddress & 3));
ASSERT(!(ulCount & 3));
//
// Clear the flash access and error interrupts.
//
HWREG(FLASH_CONTROL_BASE + FLASH_CTRL_O_FCMISC)
= (FLASH_CTRL_FCMISC_AMISC | FLASH_CTRL_FCMISC_VOLTMISC |
FLASH_CTRL_FCMISC_INVDMISC | FLASH_CTRL_FCMISC_PROGMISC);
//
// See if this device has a write buffer.
//
#if HAVE_WRITE_BUFFER
{
//
// Make sure the address/count specified doesn't straddle a 32 word
// boundary.
//
if(((ulAddress + (ulCount - 1)) & ~0x7F) != (ulAddress & ~0x7F))
{
return(-1);
}
//
// Loop over the words to be programmed.
//
while(ulCount)
{
//
// Set the address of this block of words.
//
HWREG(FLASH_CONTROL_BASE + FLASH_CTRL_O_FMA) = ulAddress & ~(0x7F);
//
// Loop over the words in this 32-word block.
//
while(((ulAddress & 0x7C) || (HWREG(FLASH_CONTROL_BASE + FLASH_CTRL_O_FWBVAL) == 0)) &&
(ulCount != 0))
{
//
// Write this word into the write buffer.
//
HWREG(FLASH_CONTROL_BASE + FLASH_CTRL_O_FWBN + (ulAddress & 0x7C)) = *pulData++;
ulAddress += 4;
ulCount -= 4;
}
//
// Program the contents of the write buffer into flash.
//
HWREG(FLASH_CONTROL_BASE + FLASH_CTRL_O_FMC2) = FLASH_CTRL_FMC2_WRKEY | FLASH_CTRL_FMC2_WRBUF;
}
}
#else
{
//
// We don't have a write buffer so we can only write a single word.
//
if(ulCount > 1)
{
return(-1);
}
//
// Write a single word.
//
HWREG(FLASH_CONTROL_BASE + FLASH_CTRL_O_FMA) = ulAddress;
HWREG(FLASH_CONTROL_BASE + FLASH_CTRL_O_FMD) = *pulData;
HWREG(FLASH_CONTROL_BASE + FLASH_CTRL_O_FMC) = FLASH_CTRL_FMC_WRKEY | FLASH_CTRL_FMC_WRITE;
}
#endif
//
// Success.
//
return(0);
}
//*****************************************************************************
//
//! Gets the protection setting for a block of flash.
//!
//! \param ulAddress is the start address of the flash block to be queried.
//!
//! This function gets the current protection for the specified 2-kB block
//! of flash. Each block can be read/write, read-only, or execute-only.
//! Read/write blocks can be read, executed, erased, and programmed. Read-only
//! blocks can be read and executed. Execute-only blocks can only be executed;
//! processor and debugger data reads are not allowed.
//!
//! \return Returns the protection setting for this block. See
//! FlashProtectSet() for possible values.
//
//*****************************************************************************
tFlashProtection
FlashProtectGet(unsigned long ulAddress)
{
unsigned long ulFMPRE, ulFMPPE;
unsigned long ulBank;
//
// Check the argument.
//
ASSERT(!(ulAddress & (FLASH_PROTECT_SIZE - 1)));
//
// Calculate the Flash Bank from Base Address, and mask off the Bank
// from ulAddress for subsequent reference.
//
ulBank = (((ulAddress / FLASH_PROTECT_SIZE) / 32) % 16);
ulAddress &= ((FLASH_PROTECT_SIZE * 32) - 1);
//
// Read the appropriate flash protection registers for the specified
// flash bank.
//
ulFMPRE = HWREG(g_pulFMPRERegs[ulBank]);
ulFMPPE = HWREG(g_pulFMPPERegs[ulBank]);
//
// Check the appropriate protection bits for the block of memory that
// is specified by the address.
//
switch((((ulFMPRE >> (ulAddress / FLASH_PROTECT_SIZE)) &
FLASH_FMP_BLOCK_0) << 1) |
((ulFMPPE >> (ulAddress / FLASH_PROTECT_SIZE)) & FLASH_FMP_BLOCK_0))
{
//
// This block is marked as execute only (that is, it can not be erased
// or programmed, and the only reads allowed are via the instruction
// fetch interface).
//
case 0:
case 1:
{
return(FlashExecuteOnly);
}
//
// This block is marked as read only (that is, it can not be erased or
// programmed).
//
case 2:
{
return(FlashReadOnly);
}
//
// This block is read/write; it can be read, erased, and programmed.
//
case 3:
default:
{
return(FlashReadWrite);
}
}
}
//*****************************************************************************
//
//! Registers an interrupt handler for the flash interrupt.
//!
//! \param pfnHandler is a pointer to the function to be called when the flash
//! interrupt occurs.
//!
//! This sets the handler to be called when the flash interrupt occurs. The
//! flash controller can generate an interrupt when an invalid flash access
//! occurs, such as trying to program or erase a read-only block, or trying to
//! read from an execute-only block. It can also generate an interrupt when a
//! program or erase operation has completed. The interrupt will be
//! automatically enabled when the handler is registered.
//!
//! \sa IntRegister() for important information about registering interrupt
//! handlers.
//!
//! \return None.
//
//*****************************************************************************
void
FlashIntRegister(void (*pfnHandler)(void))
{
//
// Register the interrupt handler, returning an error if an error occurs.
//
IntRegister(INT_FLASH, pfnHandler);
//
// Enable the flash interrupt.
//
IntEnable(INT_FLASH);
}
//*****************************************************************************
//
//! Unregisters the interrupt handler for the flash interrupt.
//!
//! This function will clear the handler to be called when the flash interrupt
//! occurs. This will also mask off the interrupt in the interrupt controller
//! so that the interrupt handler is no longer called.
//!
//! \sa IntRegister() for important information about registering interrupt
//! handlers.
//!
//! \return None.
//
//*****************************************************************************
void
FlashIntUnregister(void)
{
//
// Disable the interrupt.
//
IntDisable(INT_FLASH);
//
// Unregister the interrupt handler.
//
IntUnregister(INT_FLASH);
}
//*****************************************************************************
//
//! Enables individual flash controller interrupt sources.
//!
//! \param ulIntFlags is a bit mask of the interrupt sources to be enabled.
//! Can be any of the \b FLASH_CTRL_PROGRAM or \b FLASH_CTRL_ACCESS values.
//!
//! Enables the indicated flash controller interrupt sources. Only the sources
//! that are enabled can be reflected to the processor interrupt; disabled
//! sources have no effect on the processor.
//!
//! \return None.
//
//*****************************************************************************
void
FlashIntEnable(unsigned long ulIntFlags)
{
//
// Enable the specified interrupts.
//
HWREG(FLASH_CONTROL_BASE + FLASH_CTRL_O_FCIM) |= ulIntFlags;
}
//*****************************************************************************
//
//! Disables individual flash controller interrupt sources.
//!
//! \param ulIntFlags is a bit mask of the interrupt sources to be disabled.
//! Can be any of the \b FLASH_CTRL_PROGRAM or \b FLASH_CTRL_ACCESS values.
//!
//! Disables the indicated flash controller interrupt sources. Only the
//! sources that are enabled can be reflected to the processor interrupt;
//! disabled sources have no effect on the processor.
//!
//! \return None.
//
//*****************************************************************************
void
FlashIntDisable(unsigned long ulIntFlags)
{
//
// Disable the specified interrupts.
//
HWREG(FLASH_CONTROL_BASE + FLASH_CTRL_O_FCIM) &= ~(ulIntFlags);
}
//*****************************************************************************
//
//! Gets the current interrupt status.
//!
//! \param bMasked is false if the raw interrupt status is required and true if
//! the masked interrupt status is required.
//!
//! This returns the interrupt status for the flash controller. Either the raw
//! interrupt status or the status of interrupts that are allowed to reflect to
//! the processor can be returned.
//!
//! \return The current interrupt status, enumerated as a bit field of
//! \b FLASH_CTRL_PROGRAM and \b FLASH_CTRL_ACCESS.
//
//*****************************************************************************
unsigned long
FlashIntStatus(tBoolean bMasked)
{
//
// Return either the interrupt status or the raw interrupt status as
// requested.
//
if(bMasked)
{
return(HWREG(FLASH_CONTROL_BASE + FLASH_CTRL_O_FCMISC));
}
else
{
return(HWREG(FLASH_CONTROL_BASE + FLASH_CTRL_O_FCRIS));
}
}
//*****************************************************************************
//
//! Clears flash controller interrupt sources.
//!
//! \param ulIntFlags is the bit mask of the interrupt sources to be cleared.
//! Can be any of the \b FLASH_CTRL_PROGRAM or \b FLASH_CTRL_AMISC values.
//!
//! The specified flash controller interrupt sources are cleared, so that they
//! no longer assert. This must be done in the interrupt handler to keep it
//! from being called again immediately upon exit.
//!
//! \note Because there is a write buffer in the Cortex-M3 processor, it may
//! take several clock cycles before the interrupt source is actually cleared.
//! Therefore, it is recommended that the interrupt source be cleared early in
//! the interrupt handler (as opposed to the very last action) to avoid
//! returning from the interrupt handler before the interrupt source is
//! actually cleared. Failure to do so may result in the interrupt handler
//! being immediately reentered (because the interrupt controller still sees
//! the interrupt source asserted).
//!
//! \return None.
//
//*****************************************************************************
void
FlashIntClear(unsigned long ulIntFlags)
{
//
// Clear the flash interrupt.
//
HWREG(FLASH_CONTROL_BASE + FLASH_CTRL_O_FCMISC) = ulIntFlags;
}
//*****************************************************************************
//
// Close the Doxygen group.
//! @}
//
//*****************************************************************************

115
driverlib/flash.h Normal file
View File

@ -0,0 +1,115 @@
//*****************************************************************************
//
// flash.h
//
// Prototypes for the flash driver.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#ifndef __FLASH_H__
#define __FLASH_H__
//*****************************************************************************
//
// If building with a C++ compiler, make all of the definitions in this header
// have a C binding.
//
//*****************************************************************************
#ifdef __cplusplus
extern "C"
{
#endif
//*****************************************************************************
//
// Values that can be passed to FlashProtectSet(), and returned by
// FlashProtectGet().
//
//*****************************************************************************
typedef enum
{
FlashReadWrite, // Flash can be read and written
FlashReadOnly, // Flash can only be read
FlashExecuteOnly // Flash can only be executed
}
tFlashProtection;
//*****************************************************************************
//
// Values passed to FlashIntEnable(), FlashIntDisable() and FlashIntClear() and
// returned from FlashIntStatus().
//
//*****************************************************************************
#define FLASH_INT_PROGRAM 0x00000002 // Programming Interrupt Mask
#define FLASH_INT_ACCESS 0x00000001 // Access Interrupt Mask
#define FLASH_INT_EEPROM 0x00000004 // EEPROM Interrupt Mask
#define FLASH_INT_VOLTAGE_ERR 0x00000200 // Voltage Error Interrupt Mask
#define FLASH_INT_DATA_ERR 0x00000400 // Invalid Data Interrupt Mask
#define FLASH_INT_ERASE_ERR 0x00000800 // Erase Error Interrupt Mask
#define FLASH_INT_PROGRAM_ERR 0x00002000 // Program Verify Error Interrupt Mask
//*****************************************************************************
//
// Prototypes for the APIs.
//
//*****************************************************************************
extern void FlashDisable(void);
extern long FlashErase(unsigned long ulAddress);
extern void FlashEraseNonBlocking(unsigned long ulAddress);
extern long FlashMassErase(void);
extern void FlashMassEraseNonBlocking(void);
extern long FlashProgram(unsigned long *pulData, unsigned long ulAddress,
unsigned long ulCount);
extern long FlashProgramNonBlocking(unsigned long *pulData,
unsigned long ulAddress,
unsigned long ulCount);
extern void FlashIntRegister(void (*pfnHandler)(void));
extern void FlashIntUnregister(void);
extern void FlashIntEnable(unsigned long ulIntFlags);
extern void FlashIntDisable(unsigned long ulIntFlags);
extern unsigned long FlashIntStatus(tBoolean bMasked);
extern void FlashIntClear(unsigned long ulIntFlags);
extern tFlashProtection FlashProtectGet(unsigned long ulAddress);
//*****************************************************************************
//
// Mark the end of the C bindings section for C++ compilers.
//
//*****************************************************************************
#ifdef __cplusplus
}
#endif
#endif // __FLASH_H__

114
driverlib/gcc/Makefile Normal file
View File

@ -0,0 +1,114 @@
#******************************************************************************
#
# Makefile - Rules for building the driver library.
#
# Copyright (C) 2014 Texas Instruments Incorporated - http:#www.ti.com/
#
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
#
# 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.
#
# Neither the name of Texas Instruments Incorporated nor the names of
# its contributors may be used to endorse or promote products derived
# from this software without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
# A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
# OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
# SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
# LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
# DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
# THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
# (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
# OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
#
#*****************************************************************************
#
# The base directory
#
ROOT=../../
#
# Include the common make definitions.
#
include ${ROOT}/tools/gcc_scripts/makedefs
#
# Where to find header files that do not live in the source directory.
#
VPATH=..
#
# Where to find header files that do not live in the source directory.
#
IPATH= ..
IPATH+= ../../
#
# The default rule, which causes the driver library to be built.
#
all: ${OBJDIR} ${BINDIR}
all: ${BINDIR}/libdriver.a
#
# The rule to clean out all the build products.
#
clean:
@rm -rf ${OBJDIR} ${wildcard *~}
@rm -rf ${BINDIR} ${wildcard *~}
#
# The rule to create the target directories.
#
${OBJDIR}:
@mkdir -p ${OBJDIR}
${BINDIR}:
@mkdir -p ${BINDIR}
#
# Rules for building the driver library.
#
${BINDIR}/libdriver.a: ${OBJDIR}/adc.o
${BINDIR}/libdriver.a: ${OBJDIR}/aes.o
${BINDIR}/libdriver.a: ${OBJDIR}/camera.o
${BINDIR}/libdriver.a: ${OBJDIR}/cpu.o
${BINDIR}/libdriver.a: ${OBJDIR}/crc.o
${BINDIR}/libdriver.a: ${OBJDIR}/des.o
${BINDIR}/libdriver.a: ${OBJDIR}/flash.o
${BINDIR}/libdriver.a: ${OBJDIR}/gpio.o
${BINDIR}/libdriver.a: ${OBJDIR}/hwspinlock.o
${BINDIR}/libdriver.a: ${OBJDIR}/i2c.o
${BINDIR}/libdriver.a: ${OBJDIR}/interrupt.o
${BINDIR}/libdriver.a: ${OBJDIR}/i2s.o
${BINDIR}/libdriver.a: ${OBJDIR}/pin.o
${BINDIR}/libdriver.a: ${OBJDIR}/prcm.o
${BINDIR}/libdriver.a: ${OBJDIR}/sdhost.o
${BINDIR}/libdriver.a: ${OBJDIR}/shamd5.o
${BINDIR}/libdriver.a: ${OBJDIR}/spi.o
${BINDIR}/libdriver.a: ${OBJDIR}/systick.o
${BINDIR}/libdriver.a: ${OBJDIR}/timer.o
${BINDIR}/libdriver.a: ${OBJDIR}/uart.o
${BINDIR}/libdriver.a: ${OBJDIR}/udma.o
${BINDIR}/libdriver.a: ${OBJDIR}/utils.o
${BINDIR}/libdriver.a: ${OBJDIR}/wdt.o
#
# Include the automatically generated dependency files.
#
ifneq (${MAKECMDGOALS},clean)
-include ${wildcard ${OBJDIR}/*.d} __dummy__
endif

716
driverlib/gpio.c Normal file
View File

@ -0,0 +1,716 @@
//*****************************************************************************
//
// gpio.c
//
// Driver for the GPIO module.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
//*****************************************************************************
//
//! \addtogroup GPIO_General_Purpose_InputOutput_api
//! @{
//
//*****************************************************************************
#include "inc/hw_types.h"
#include "inc/hw_gpio.h"
#include "inc/hw_ints.h"
#include "inc/hw_memmap.h"
#include "inc/hw_common_reg.h"
#include "debug.h"
#include "gpio.h"
#include "interrupt.h"
//*****************************************************************************
//
//! \internal
//! Checks a GPIO base address.
//!
//! \param ulPort is the base address of the GPIO port.
//!
//! This function determines if a GPIO port base address is valid.
//!
//! \return Returns \b true if the base address is valid and \b false
//! otherwise.
//
//*****************************************************************************
#ifdef DEBUG
static tBoolean
GPIOBaseValid(unsigned long ulPort)
{
return((ulPort == GPIOA0_BASE) ||
(ulPort == GPIOA1_BASE) ||
(ulPort == GPIOA2_BASE) ||
(ulPort == GPIOA3_BASE) ||
(ulPort == GPIOA4_BASE));
}
#endif
//*****************************************************************************
//
//! \internal
//! Gets the GPIO interrupt number.
//!
//! \param ulPort is the base address of the GPIO port.
//!
//! Given a GPIO base address, returns the corresponding interrupt number.
//!
//! \return Returns a GPIO interrupt number, or -1 if \e ulPort is invalid.
//
//*****************************************************************************
static long
GPIOGetIntNumber(unsigned long ulPort)
{
unsigned int ulInt;
//
// Determine the GPIO interrupt number for the given module.
//
switch(ulPort)
{
case GPIOA0_BASE:
{
ulInt = INT_GPIOA0;
break;
}
case GPIOA1_BASE:
{
ulInt = INT_GPIOA1;
break;
}
case GPIOA2_BASE:
{
ulInt = INT_GPIOA2;
break;
}
case GPIOA3_BASE:
{
ulInt = INT_GPIOA3;
break;
}
default:
{
return(-1);
}
}
//
// Return GPIO interrupt number.
//
return(ulInt);
}
//*****************************************************************************
//
//! Sets the direction and mode of the specified pin(s).
//!
//! \param ulPort is the base address of the GPIO port
//! \param ucPins is the bit-packed representation of the pin(s).
//! \param ulPinIO is the pin direction and/or mode.
//!
//! This function will set the specified pin(s) on the selected GPIO port
//! as either an input or output under software control, or it will set the
//! pin to be under hardware control.
//!
//! The parameter \e ulPinIO is an enumerated data type that can be one of
//! the following values:
//!
//! - \b GPIO_DIR_MODE_IN
//! - \b GPIO_DIR_MODE_OUT
//!
//! where \b GPIO_DIR_MODE_IN specifies that the pin will be programmed as
//! a software controlled input, \b GPIO_DIR_MODE_OUT specifies that the pin
//! will be programmed as a software controlled output.
//!
//! The pin(s) are specified using a bit-packed byte, where each bit that is
//! set identifies the pin to be accessed, and where bit 0 of the byte
//! represents GPIO port pin 0, bit 1 represents GPIO port pin 1, and so on.
//!
//! \note GPIOPadConfigSet() must also be used to configure the corresponding
//! pad(s) in order for them to propagate the signal to/from the GPIO.
//!
//! \return None.
//
//*****************************************************************************
void
GPIODirModeSet(unsigned long ulPort, unsigned char ucPins,
unsigned long ulPinIO)
{
//
// Check the arguments.
//
ASSERT(GPIOBaseValid(ulPort));
ASSERT((ulPinIO == GPIO_DIR_MODE_IN) || (ulPinIO == GPIO_DIR_MODE_OUT));
//
// Set the pin direction and mode.
//
HWREG(ulPort + GPIO_O_GPIO_DIR) = ((ulPinIO & 1) ?
(HWREG(ulPort + GPIO_O_GPIO_DIR) | ucPins) :
(HWREG(ulPort + GPIO_O_GPIO_DIR) & ~(ucPins)));
}
//*****************************************************************************
//
//! Gets the direction and mode of a pin.
//!
//! \param ulPort is the base address of the GPIO port.
//! \param ucPin is the pin number.
//!
//! This function gets the direction and control mode for a specified pin on
//! the selected GPIO port. The pin can be configured as either an input or
//! output under software control, or it can be under hardware control. The
//! type of control and direction are returned as an enumerated data type.
//!
//! \return Returns one of the enumerated data types described for
//! GPIODirModeSet().
//
//*****************************************************************************
unsigned long
GPIODirModeGet(unsigned long ulPort, unsigned char ucPin)
{
unsigned long ulDir;
//
// Check the arguments.
//
ASSERT(GPIOBaseValid(ulPort));
ASSERT(ucPin < 8);
//
// Convert from a pin number to a bit position.
//
ucPin = 1 << ucPin;
//
// Return the pin direction and mode.
//
ulDir = HWREG(ulPort + GPIO_O_GPIO_DIR);
return(((ulDir & ucPin) ? 1 : 0));
}
//*****************************************************************************
//
//! Sets the interrupt type for the specified pin(s).
//!
//! \param ulPort is the base address of the GPIO port.
//! \param ucPins is the bit-packed representation of the pin(s).
//! \param ulIntType specifies the type of interrupt trigger mechanism.
//!
//! This function sets up the various interrupt trigger mechanisms for the
//! specified pin(s) on the selected GPIO port.
//!
//! The parameter \e ulIntType is an enumerated data type that can be one of
//! the following values:
//!
//! - \b GPIO_FALLING_EDGE
//! - \b GPIO_RISING_EDGE
//! - \b GPIO_BOTH_EDGES
//! - \b GPIO_LOW_LEVEL
//! - \b GPIO_HIGH_LEVEL
//!
//! The pin(s) are specified using a bit-packed byte, where each bit that is
//! set identifies the pin to be accessed, and where bit 0 of the byte
//! represents GPIO port pin 0, bit 1 represents GPIO port pin 1, and so on.
//!
//! \note In order to avoid any spurious interrupts, the user must
//! ensure that the GPIO inputs remain stable for the duration of
//! this function.
//!
//! \return None.
//
//*****************************************************************************
void
GPIOIntTypeSet(unsigned long ulPort, unsigned char ucPins,
unsigned long ulIntType)
{
//
// Check the arguments.
//
ASSERT(GPIOBaseValid(ulPort));
ASSERT((ulIntType == GPIO_FALLING_EDGE) ||
(ulIntType == GPIO_RISING_EDGE) || (ulIntType == GPIO_BOTH_EDGES) ||
(ulIntType == GPIO_LOW_LEVEL) || (ulIntType == GPIO_HIGH_LEVEL));
//
// Set the pin interrupt type.
//
HWREG(ulPort + GPIO_O_GPIO_IBE) = ((ulIntType & 1) ?
(HWREG(ulPort + GPIO_O_GPIO_IBE) | ucPins) :
(HWREG(ulPort + GPIO_O_GPIO_IBE) & ~(ucPins)));
HWREG(ulPort + GPIO_O_GPIO_IS) = ((ulIntType & 2) ?
(HWREG(ulPort + GPIO_O_GPIO_IS) | ucPins) :
(HWREG(ulPort + GPIO_O_GPIO_IS) & ~(ucPins)));
HWREG(ulPort + GPIO_O_GPIO_IEV) = ((ulIntType & 4) ?
(HWREG(ulPort + GPIO_O_GPIO_IEV) | ucPins) :
(HWREG(ulPort + GPIO_O_GPIO_IEV) & ~(ucPins)));
}
//*****************************************************************************
//
//! Gets the interrupt type for a pin.
//!
//! \param ulPort is the base address of the GPIO port.
//! \param ucPin is the pin number.
//!
//! This function gets the interrupt type for a specified pin on the selected
//! GPIO port. The pin can be configured as a falling edge, rising edge, or
//! both edge detected interrupt, or it can be configured as a low level or
//! high level detected interrupt. The type of interrupt detection mechanism
//! is returned as an enumerated data type.
//!
//! \return Returns one of the enumerated data types described for
//! GPIOIntTypeSet().
//
//*****************************************************************************
unsigned long
GPIOIntTypeGet(unsigned long ulPort, unsigned char ucPin)
{
unsigned long ulIBE, ulIS, ulIEV;
//
// Check the arguments.
//
ASSERT(GPIOBaseValid(ulPort));
ASSERT(ucPin < 8);
//
// Convert from a pin number to a bit position.
//
ucPin = 1 << ucPin;
//
// Return the pin interrupt type.
//
ulIBE = HWREG(ulPort + GPIO_O_GPIO_IBE);
ulIS = HWREG(ulPort + GPIO_O_GPIO_IS);
ulIEV = HWREG(ulPort + GPIO_O_GPIO_IEV);
return(((ulIBE & ucPin) ? 1 : 0) | ((ulIS & ucPin) ? 2 : 0) |
((ulIEV & ucPin) ? 4 : 0));
}
//*****************************************************************************
//
//! Enables the specified GPIO interrupts.
//!
//! \param ulPort is the base address of the GPIO port.
//! \param ulIntFlags is the bit mask of the interrupt sources to enable.
//!
//! This function enables the indicated GPIO interrupt sources. Only the
//! sources that are enabled can be reflected to the processor interrupt;
//! disabled sources have no effect on the processor.
//!
//! The \e ulIntFlags parameter is the logical OR of any of the following:
//!
//! - \b GPIO_INT_DMA - interrupt due to GPIO triggered DMA Done
//! - \b GPIO_INT_PIN_0 - interrupt due to activity on Pin 0.
//! - \b GPIO_INT_PIN_1 - interrupt due to activity on Pin 1.
//! - \b GPIO_INT_PIN_2 - interrupt due to activity on Pin 2.
//! - \b GPIO_INT_PIN_3 - interrupt due to activity on Pin 3.
//! - \b GPIO_INT_PIN_4 - interrupt due to activity on Pin 4.
//! - \b GPIO_INT_PIN_5 - interrupt due to activity on Pin 5.
//! - \b GPIO_INT_PIN_6 - interrupt due to activity on Pin 6.
//! - \b GPIO_INT_PIN_7 - interrupt due to activity on Pin 7.
//!
//! \return None.
//
//*****************************************************************************
void
GPIOIntEnable(unsigned long ulPort, unsigned long ulIntFlags)
{
//
// Check the arguments.
//
ASSERT(GPIOBaseValid(ulPort));
//
// Enable the interrupts.
//
HWREG(ulPort + GPIO_O_GPIO_IM) |= ulIntFlags;
}
//*****************************************************************************
//
//! Disables the specified GPIO interrupts.
//!
//! \param ulPort is the base address of the GPIO port.
//! \param ulIntFlags is the bit mask of the interrupt sources to disable.
//!
//! This function disables the indicated GPIO interrupt sources. Only the
//! sources that are enabled can be reflected to the processor interrupt;
//! disabled sources have no effect on the processor.
//!
//! The \e ulIntFlags parameter is the logical OR of any of the following:
//!
//! - \b GPIO_INT_DMA - interrupt due to GPIO triggered DMA Done
//! - \b GPIO_INT_PIN_0 - interrupt due to activity on Pin 0.
//! - \b GPIO_INT_PIN_1 - interrupt due to activity on Pin 1.
//! - \b GPIO_INT_PIN_2 - interrupt due to activity on Pin 2.
//! - \b GPIO_INT_PIN_3 - interrupt due to activity on Pin 3.
//! - \b GPIO_INT_PIN_4 - interrupt due to activity on Pin 4.
//! - \b GPIO_INT_PIN_5 - interrupt due to activity on Pin 5.
//! - \b GPIO_INT_PIN_6 - interrupt due to activity on Pin 6.
//! - \b GPIO_INT_PIN_7 - interrupt due to activity on Pin 7.
//!
//! \return None.
//
//*****************************************************************************
void
GPIOIntDisable(unsigned long ulPort, unsigned long ulIntFlags)
{
//
// Check the arguments.
//
ASSERT(GPIOBaseValid(ulPort));
//
// Disable the interrupts.
//
HWREG(ulPort + GPIO_O_GPIO_IM) &= ~(ulIntFlags);
}
//*****************************************************************************
//
//! Gets interrupt status for the specified GPIO port.
//!
//! \param ulPort is the base address of the GPIO port.
//! \param bMasked specifies whether masked or raw interrupt status is
//! returned.
//!
//! If \e bMasked is set as \b true, then the masked interrupt status is
//! returned; otherwise, the raw interrupt status will be returned.
//!
//! \return Returns the current interrupt status, enumerated as a bit field of
//! values described in GPIOIntEnable().
//
//*****************************************************************************
long
GPIOIntStatus(unsigned long ulPort, tBoolean bMasked)
{
//
// Check the arguments.
//
ASSERT(GPIOBaseValid(ulPort));
//
// Return the interrupt status.
//
if(bMasked)
{
return(HWREG(ulPort + GPIO_O_GPIO_MIS));
}
else
{
return(HWREG(ulPort + GPIO_O_GPIO_RIS));
}
}
//*****************************************************************************
//
//! Clears the interrupt for the specified pin(s).
//!
//! \param ulPort is the base address of the GPIO port.
//! \param ulIntFlags is a bit mask of the interrupt sources to be cleared.
//!
//! Clears the interrupt for the specified pin(s).
//!
//! The \e ulIntFlags parameter has the same definition as the \e ulIntFlags
//! parameter to GPIOIntEnable().
//!
//!
//! \return None.
//
//*****************************************************************************
void
GPIOIntClear(unsigned long ulPort, unsigned long ulIntFlags)
{
//
// Check the arguments.
//
ASSERT(GPIOBaseValid(ulPort));
//
// Clear the interrupts.
//
HWREG(ulPort + GPIO_O_GPIO_ICR) = ulIntFlags;
}
//*****************************************************************************
//
//! Registers an interrupt handler for a GPIO port.
//!
//! \param ulPort is the base address of the GPIO port.
//! \param pfnIntHandler is a pointer to the GPIO port interrupt handling
//! function.
//!
//! This function will ensure that the interrupt handler specified by
//! \e pfnIntHandler is called when an interrupt is detected from the selected
//! GPIO port. This function will also enable the corresponding GPIO interrupt
//! in the interrupt controller; individual pin interrupts and interrupt
//! sources must be enabled with GPIOIntEnable().
//!
//! \sa IntRegister() for important information about registering interrupt
//! handlers.
//!
//! \return None.
//
//*****************************************************************************
void
GPIOIntRegister(unsigned long ulPort, void (*pfnIntHandler)(void))
{
//
// Check the arguments.
//
ASSERT(GPIOBaseValid(ulPort));
//
// Get the interrupt number associated with the specified GPIO.
//
ulPort = GPIOGetIntNumber(ulPort);
//
// Register the interrupt handler.
//
IntRegister(ulPort, pfnIntHandler);
//
// Enable the GPIO interrupt.
//
IntEnable(ulPort);
}
//*****************************************************************************
//
//! Removes an interrupt handler for a GPIO port.
//!
//! \param ulPort is the base address of the GPIO port.
//!
//! This function will unregister the interrupt handler for the specified
//! GPIO port. This function will also disable the corresponding
//! GPIO port interrupt in the interrupt controller; individual GPIO interrupts
//! and interrupt sources must be disabled with GPIOIntDisable().
//!
//! \sa IntRegister() for important information about registering interrupt
//! handlers.
//!
//! \return None.
//
//*****************************************************************************
void
GPIOIntUnregister(unsigned long ulPort)
{
//
// Check the arguments.
//
ASSERT(GPIOBaseValid(ulPort));
//
// Get the interrupt number associated with the specified GPIO.
//
ulPort = GPIOGetIntNumber(ulPort);
//
// Disable the GPIO interrupt.
//
IntDisable(ulPort);
//
// Unregister the interrupt handler.
//
IntUnregister(ulPort);
}
//*****************************************************************************
//
//! Reads the values present of the specified pin(s).
//!
//! \param ulPort is the base address of the GPIO port.
//! \param ucPins is the bit-packed representation of the pin(s).
//!
//! The values at the specified pin(s) are read, as specified by \e ucPins.
//! Values are returned for both input and output pin(s), and the value
//! for pin(s) that are not specified by \e ucPins are set to 0.
//!
//! The pin(s) are specified using a bit-packed byte, where each bit that is
//! set identifies the pin to be accessed, and where bit 0 of the byte
//! represents GPIO port pin 0, bit 1 represents GPIO port pin 1, and so on.
//!
//! \return Returns a bit-packed byte providing the state of the specified
//! pin, where bit 0 of the byte represents GPIO port pin 0, bit 1 represents
//! GPIO port pin 1, and so on. Any bit that is not specified by \e ucPins
//! is returned as a 0. Bits 31:8 should be ignored.
//
//*****************************************************************************
long
GPIOPinRead(unsigned long ulPort, unsigned char ucPins)
{
//
// Check the arguments.
//
ASSERT(GPIOBaseValid(ulPort));
//
// Return the pin value(s).
//
return(HWREG(ulPort + (GPIO_O_GPIO_DATA + (ucPins << 2))));
}
//*****************************************************************************
//
//! Writes a value to the specified pin(s).
//!
//! \param ulPort is the base address of the GPIO port.
//! \param ucPins is the bit-packed representation of the pin(s).
//! \param ucVal is the value to write to the pin(s).
//!
//! Writes the corresponding bit values to the output pin(s) specified by
//! \e ucPins. Writing to a pin configured as an input pin has no effect.
//!
//! The pin(s) are specified using a bit-packed byte, where each bit that is
//! set identifies the pin to be accessed, and where bit 0 of the byte
//! represents GPIO port pin 0, bit 1 represents GPIO port pin 1, and so on.
//!
//! \return None.
//
//*****************************************************************************
void
GPIOPinWrite(unsigned long ulPort, unsigned char ucPins, unsigned char ucVal)
{
//
// Check the arguments.
//
ASSERT(GPIOBaseValid(ulPort));
//
// Write the pins.
//
HWREG(ulPort + (GPIO_O_GPIO_DATA + (ucPins << 2))) = ucVal;
}
//*****************************************************************************
//
//! Enables a GPIO port as a trigger to start a DMA transaction.
//!
//! \param ulPort is the base address of the GPIO port.
//!
//! This function enables a GPIO port to be used as a trigger to start a uDMA
//! transaction. The GPIO pin will still generate interrupts if the interrupt is
//! enabled for the selected pin.
//!
//! \return None.
//
//*****************************************************************************
void
GPIODMATriggerEnable(unsigned long ulPort)
{
//
// Check the arguments.
//
ASSERT(GPIOBaseValid(ulPort));
//
// Set the pin as a DMA trigger.
//
if(ulPort == GPIOA0_BASE)
{
HWREG(COMMON_REG_BASE + COMMON_REG_O_APPS_GPIO_TRIG_EN) |= 0x1;
}
else if(ulPort == GPIOA1_BASE)
{
HWREG(COMMON_REG_BASE + COMMON_REG_O_APPS_GPIO_TRIG_EN) |= 0x2;
}
else if(ulPort == GPIOA2_BASE)
{
HWREG(COMMON_REG_BASE + COMMON_REG_O_APPS_GPIO_TRIG_EN) |= 0x4;
}
else if(ulPort == GPIOA3_BASE)
{
HWREG(COMMON_REG_BASE + COMMON_REG_O_APPS_GPIO_TRIG_EN) |= 0x8;
}
}
//*****************************************************************************
//
//! Disables a GPIO port as a trigger to start a DMA transaction.
//!
//! \param ulPort is the base address of the GPIO port.
//!
//! This function disables a GPIO port to be used as a trigger to start a uDMA
//! transaction. This function can be used to disable this feature if it was
//! enabled via a call to GPIODMATriggerEnable().
//!
//! \return None.
//
//*****************************************************************************
void
GPIODMATriggerDisable(unsigned long ulPort)
{
//
// Check the arguments.
//
ASSERT(GPIOBaseValid(ulPort));
//
// Set the pin as a DMA trigger.
//
if(ulPort == GPIOA0_BASE)
{
HWREG(COMMON_REG_BASE + COMMON_REG_O_APPS_GPIO_TRIG_EN) &= ~0x1;
}
else if(ulPort == GPIOA1_BASE)
{
HWREG(COMMON_REG_BASE + COMMON_REG_O_APPS_GPIO_TRIG_EN) &= ~0x2;
}
else if(ulPort == GPIOA2_BASE)
{
HWREG(COMMON_REG_BASE + COMMON_REG_O_APPS_GPIO_TRIG_EN) &= ~0x4;
}
else if(ulPort == GPIOA3_BASE)
{
HWREG(COMMON_REG_BASE + COMMON_REG_O_APPS_GPIO_TRIG_EN) &= ~0x8;
}
}
//
// Close the Doxygen group.
//! @}
//
//*****************************************************************************

139
driverlib/gpio.h Normal file
View File

@ -0,0 +1,139 @@
//*****************************************************************************
//
// gpio.h
//
// Defines and Macros for GPIO API.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#ifndef __GPIO_H__
#define __GPIO_H__
//*****************************************************************************
//
// If building with a C++ compiler, make all of the definitions in this header
// have a C binding.
//
//*****************************************************************************
#ifdef __cplusplus
extern "C"
{
#endif
//*****************************************************************************
//
// The following values define the bit field for the ucPins argument to several
// of the APIs.
//
//*****************************************************************************
#define GPIO_PIN_0 0x00000001 // GPIO pin 0
#define GPIO_PIN_1 0x00000002 // GPIO pin 1
#define GPIO_PIN_2 0x00000004 // GPIO pin 2
#define GPIO_PIN_3 0x00000008 // GPIO pin 3
#define GPIO_PIN_4 0x00000010 // GPIO pin 4
#define GPIO_PIN_5 0x00000020 // GPIO pin 5
#define GPIO_PIN_6 0x00000040 // GPIO pin 6
#define GPIO_PIN_7 0x00000080 // GPIO pin 7
//*****************************************************************************
//
// Values that can be passed to GPIODirModeSet as the ulPinIO parameter, and
// returned from GPIODirModeGet.
//
//*****************************************************************************
#define GPIO_DIR_MODE_IN 0x00000000 // Pin is a GPIO input
#define GPIO_DIR_MODE_OUT 0x00000001 // Pin is a GPIO output
//*****************************************************************************
//
// Values that can be passed to GPIOIntTypeSet as the ulIntType parameter, and
// returned from GPIOIntTypeGet.
//
//*****************************************************************************
#define GPIO_FALLING_EDGE 0x00000000 // Interrupt on falling edge
#define GPIO_RISING_EDGE 0x00000004 // Interrupt on rising edge
#define GPIO_BOTH_EDGES 0x00000001 // Interrupt on both edges
#define GPIO_LOW_LEVEL 0x00000002 // Interrupt on low level
#define GPIO_HIGH_LEVEL 0x00000006 // Interrupt on high level
//*****************************************************************************
//
// Values that can be passed to GPIOIntEnable() and GPIOIntDisable() functions
// in the ulIntFlags parameter.
//
//*****************************************************************************
#define GPIO_INT_DMA 0x00000100
#define GPIO_INT_PIN_0 0x00000001
#define GPIO_INT_PIN_1 0x00000002
#define GPIO_INT_PIN_2 0x00000004
#define GPIO_INT_PIN_3 0x00000008
#define GPIO_INT_PIN_4 0x00000010
#define GPIO_INT_PIN_5 0x00000020
#define GPIO_INT_PIN_6 0x00000040
#define GPIO_INT_PIN_7 0x00000080
//*****************************************************************************
//
// Prototypes for the APIs.
//
//*****************************************************************************
extern void GPIODirModeSet(unsigned long ulPort, unsigned char ucPins,
unsigned long ulPinIO);
extern unsigned long GPIODirModeGet(unsigned long ulPort, unsigned char ucPin);
extern void GPIOIntTypeSet(unsigned long ulPort, unsigned char ucPins,
unsigned long ulIntType);
extern void GPIODMATriggerEnable(unsigned long ulPort);
extern void GPIODMATriggerDisable(unsigned long ulPort);
extern unsigned long GPIOIntTypeGet(unsigned long ulPort, unsigned char ucPin);
extern void GPIOIntEnable(unsigned long ulPort, unsigned long ulIntFlags);
extern void GPIOIntDisable(unsigned long ulPort, unsigned long ulIntFlags);
extern long GPIOIntStatus(unsigned long ulPort, tBoolean bMasked);
extern void GPIOIntClear(unsigned long ulPort, unsigned long ulIntFlags);
extern void GPIOIntRegister(unsigned long ulPort,
void (*pfnIntHandler)(void));
extern void GPIOIntUnregister(unsigned long ulPort);
extern long GPIOPinRead(unsigned long ulPort, unsigned char ucPins);
extern void GPIOPinWrite(unsigned long ulPort, unsigned char ucPins,
unsigned char ucVal);
//*****************************************************************************
//
// Mark the end of the C bindings section for C++ compilers.
//
//*****************************************************************************
#ifdef __cplusplus
}
#endif
#endif // __GPIO_H__

269
driverlib/hwspinlock.c Normal file
View File

@ -0,0 +1,269 @@
//*****************************************************************************
//
// hwspinlock.c
//
// Driver for the Apps-NWP spinlock
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
//*****************************************************************************
//
//! \addtogroup HwSpinLock_api
//! @{
//
//*****************************************************************************
#include <stdbool.h>
#include <stdint.h>
#include "inc/hw_types.h"
#include "inc/hw_memmap.h"
#include "inc/hw_ints.h"
#include "inc/hw_common_reg.h"
#include "hwspinlock.h"
//*****************************************************************************
// Global semaphore register list
//*****************************************************************************
static const uint32_t HwSpinLock_RegLst[]=
{
COMMON_REG_BASE + COMMON_REG_O_SPI_Properties_Register
};
//*****************************************************************************
//
//! Acquire specified spin lock.
//!
//! \param ui32LockID is one of the valid spin lock.
//!
//! This function acquires specified spin lock and will not retun util the
//! specified lock is acquired.
//!
//! The parameter \e ui32LockID should \b HWSPINLOCK_MCSPIS0.
//!
//! return None.
//
//*****************************************************************************
void HwSpinLockAcquire(uint32_t ui32LockID)
{
uint32_t ui32BitPos;
uint32_t ui32SemVal;
uint32_t ui32RegAddr;
//
// Extract the bit position from the
// LockID
//
ui32BitPos = ((ui32LockID >> 16) & 0x0FFF);
ui32RegAddr = HwSpinLock_RegLst[ui32LockID & 0xF];
//
// Set the corresponding
// ownership bits to 'b01
//
ui32SemVal = (0xFFFFFFFF ^ (0x2 << ui32BitPos));
//
// Retry untill we succeed
//
do
{
HWREG(ui32RegAddr) = ui32SemVal;
}
while( !(HWREG(ui32RegAddr) & (1 << ui32BitPos )) );
}
//*****************************************************************************
//
//! Try to acquire specified spin lock.
//!
//! \param ui32LockID is one of the valid spin lock.
//! \param ui32Retry is the number of reties.
//!
//! This function tries acquire specified spin lock in \e ui32Retry retries.
//!
//! The parameter \e ui32Retry can be any value between 0 and 2^32.
//!
//! return Returns 0 on success, -1 otherwise.
//
//*****************************************************************************
int32_t HwSpinLockTryAcquire(uint32_t ui32LockID, uint32_t ui32Retry)
{
uint32_t ui32BitPos;
uint32_t ui32SemVal;
uint32_t ui32RegAddr;
//
// Extract the bit position from the
// LockID
//
ui32BitPos = ((ui32LockID >> 16) & 0x0FFF);
ui32RegAddr = HwSpinLock_RegLst[ui32LockID & 0xF];
//
// Set the corresponding
// ownership bits to 'b01
//
ui32SemVal = (0xFFFFFFFF ^ (0x2 << ui32BitPos));
//
// Check for 0 retry.
//
if(ui32Retry == 0)
{
ui32Retry = 1;
}
//
// Retry the number of times specified
//
do
{
HWREG(ui32RegAddr) = ui32SemVal;
ui32Retry--;
}
while( !(HWREG(ui32RegAddr) & (1 << ui32BitPos )) && ui32Retry );
//
// Check the semaphore status
//
if(HWREG(ui32RegAddr) & (1 << ui32BitPos ))
{
return 0;
}
else
{
return -1;
}
}
//*****************************************************************************
//
//! Release a previously owned spin lock
//!
//! \param ui32LockID is one of the valid spin lock.
//!
//! This function releases previously owned spin lock.
//!
//! \return None.
//
//*****************************************************************************
void HwSpinLockRelease(uint32_t ui32LockID)
{
uint32_t ui32BitPos;
uint32_t ui32SemVal;
//
// Extract the bit position from the
// lock id.
//
ui32BitPos = ((ui32LockID >> 16) & 0x00FF);
//
// Release the spin lock, only if already owned
//
if(HWREG(HwSpinLock_RegLst[ui32LockID & 0xF]) & (1 << ui32BitPos ))
{
ui32SemVal = (0xFFFFFFFF & ~(0x3 << ui32BitPos));
HWREG(HwSpinLock_RegLst[ui32LockID & 0xF]) = ui32SemVal;
}
}
//*****************************************************************************
//
//! Get the current or previous ownership status.
//!
//! \param ui32LockID is one of the valid spin lock.
//! \param bCurrentStatus is \b true for current status, \b flase otherwise
//!
//! This function gets the current or previous ownership status of the
//! specified spin lock based on \e bCurrentStatus parameter.
//!
//! \return Returns \b HWSPINLOCK_OWNER_APPS, \b HWSPINLOCK_OWNER_NWP or
//! \b HWSPINLOCK_OWNER_NONE.
//
//*****************************************************************************
uint32_t HwSpinLockTest(uint32_t ui32LockID, bool bCurrentStatus)
{
uint32_t ui32BitPos;
uint32_t ui32SemVal;
if(bCurrentStatus)
{
//
// Extract the bit position from the
// lock id.
//
ui32BitPos = ((ui32LockID >> 16) & 0x00FF);
//
// return semaphore
//
return((HWREG(HwSpinLock_RegLst[ui32LockID & 0xF]) >> ui32BitPos ) & 0x3 );
}
else
{
//
// Extract the bit position
//
ui32BitPos = ((ui32LockID >> 24) & 0xFF);
//
// Identify which register to read
//
if(ui32LockID & 0xF > 4)
{
ui32SemVal = ((HWREG(COMMON_REG_BASE +
COMMON_REG_O_SEMAPHORE_PREV_OWNER1) >> ui32BitPos ) & 0x3);
}
else
{
ui32SemVal = ((HWREG(COMMON_REG_BASE +
COMMON_REG_O_SEMAPHORE_PREV_OWNER2) >> ui32BitPos ) & 0x3);
}
//
// return the owner
//
return ui32SemVal;
}
}
//*****************************************************************************
//
// Close the Doxygen group.
//! @}
//
//*****************************************************************************

85
driverlib/hwspinlock.h Normal file
View File

@ -0,0 +1,85 @@
//*****************************************************************************
//
// hwspinlock.h
//
// Prototypes for the Apps-NWP spinlock.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#ifndef __HWSPINLOCK_H__
#define __HWSPINLOCK_H__
//*****************************************************************************
//
// If building with a C++ compiler, make all of the definitions in this header
// have a C binding.
//
//*****************************************************************************
#ifdef __cplusplus
extern "C"
{
#endif
//*****************************************************************************
// values that can be passed to API as ui32LockID parameter
//*****************************************************************************
#define HWSPINLOCK_SSPI 0x02000000
//*****************************************************************************
// Values that are returned from HwSpinLockTest()
//*****************************************************************************
#define HWSPINLOCK_OWNER_APPS 0x00000001
#define HWSPINLOCK_OWNER_NWP 0x00000002
#define HWSPINLOCK_OWNER_NONE 0x00000000
//*****************************************************************************
//
// API Function prototypes
//
//*****************************************************************************
extern void HwSpinLockAcquire(uint32_t ui32LockID);
extern int32_t HwSpinLockTryAcquire(uint32_t ui32LockID, uint32_t ui32Retry);
extern void HwSpinLockRelease(uint32_t ui32LockID);
extern uint32_t HwSpinLockTest(uint32_t ui32LockID, bool bCurrentStatus);
//*****************************************************************************
//
// Mark the end of the C bindings section for C++ compilers.
//
//*****************************************************************************
#ifdef __cplusplus
}
#endif
#endif // __HWSPINLOCK_H__

2055
driverlib/i2c.c Normal file

File diff suppressed because it is too large Load Diff

361
driverlib/i2c.h Normal file
View File

@ -0,0 +1,361 @@
//*****************************************************************************
//
// i2c.h
//
// Prototypes for the I2C Driver.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#ifndef __DRIVERLIB_I2C_H__
#define __DRIVERLIB_I2C_H__
//*****************************************************************************
//
// If building with a C++ compiler, make all of the definitions in this header
// have a C binding.
//
//*****************************************************************************
#ifdef __cplusplus
extern "C"
{
#endif
//*****************************************************************************
//
// Defines for the API.
//
//*****************************************************************************
//*****************************************************************************
//
// Interrupt defines.
//
//*****************************************************************************
#define I2C_INT_MASTER 0x00000001
#define I2C_INT_SLAVE 0x00000002
//*****************************************************************************
//
// I2C Master commands.
//
//*****************************************************************************
#define I2C_MASTER_CMD_SINGLE_SEND \
0x00000007
#define I2C_MASTER_CMD_SINGLE_RECEIVE \
0x00000007
#define I2C_MASTER_CMD_BURST_SEND_START \
0x00000003
#define I2C_MASTER_CMD_BURST_SEND_CONT \
0x00000001
#define I2C_MASTER_CMD_BURST_SEND_FINISH \
0x00000005
#define I2C_MASTER_CMD_BURST_SEND_STOP \
0x00000004
#define I2C_MASTER_CMD_BURST_SEND_ERROR_STOP \
0x00000004
#define I2C_MASTER_CMD_BURST_RECEIVE_START \
0x0000000b
#define I2C_MASTER_CMD_BURST_RECEIVE_CONT \
0x00000009
#define I2C_MASTER_CMD_BURST_RECEIVE_FINISH \
0x00000005
#define I2C_MASTER_CMD_BURST_RECEIVE_ERROR_STOP \
0x00000004
#define I2C_MASTER_CMD_QUICK_COMMAND \
0x00000027
#define I2C_MASTER_CMD_HS_MASTER_CODE_SEND \
0x00000013
#define I2C_MASTER_CMD_FIFO_SINGLE_SEND \
0x00000046
#define I2C_MASTER_CMD_FIFO_SINGLE_RECEIVE \
0x00000046
#define I2C_MASTER_CMD_FIFO_BURST_SEND_START \
0x00000042
#define I2C_MASTER_CMD_FIFO_BURST_SEND_CONT \
0x00000040
#define I2C_MASTER_CMD_FIFO_BURST_SEND_FINISH \
0x00000044
#define I2C_MASTER_CMD_FIFO_BURST_SEND_ERROR_STOP \
0x00000004
#define I2C_MASTER_CMD_FIFO_BURST_RECEIVE_START \
0x0000004a
#define I2C_MASTER_CMD_FIFO_BURST_RECEIVE_CONT \
0x00000048
#define I2C_MASTER_CMD_FIFO_BURST_RECEIVE_FINISH \
0x00000044
#define I2C_MASTER_CMD_FIFO_BURST_RECEIVE_ERROR_STOP \
0x00000004
//*****************************************************************************
//
// I2C Master glitch filter configuration.
//
//*****************************************************************************
#define I2C_MASTER_GLITCH_FILTER_DISABLED \
0
#define I2C_MASTER_GLITCH_FILTER_1 \
0x00010000
#define I2C_MASTER_GLITCH_FILTER_2 \
0x00020000
#define I2C_MASTER_GLITCH_FILTER_3 \
0x00030000
#define I2C_MASTER_GLITCH_FILTER_4 \
0x00040000
#define I2C_MASTER_GLITCH_FILTER_8 \
0x00050000
#define I2C_MASTER_GLITCH_FILTER_16 \
0x00060000
#define I2C_MASTER_GLITCH_FILTER_32 \
0x00070000
//*****************************************************************************
//
// I2C Master error status.
//
//*****************************************************************************
#define I2C_MASTER_ERR_NONE 0
#define I2C_MASTER_ERR_ADDR_ACK 0x00000004
#define I2C_MASTER_ERR_DATA_ACK 0x00000008
#define I2C_MASTER_ERR_ARB_LOST 0x00000010
#define I2C_MASTER_ERR_CLK_TOUT 0x00000080
//*****************************************************************************
//
// I2C Slave action requests
//
//*****************************************************************************
#define I2C_SLAVE_ACT_NONE 0
#define I2C_SLAVE_ACT_RREQ 0x00000001 // Master has sent data
#define I2C_SLAVE_ACT_TREQ 0x00000002 // Master has requested data
#define I2C_SLAVE_ACT_RREQ_FBR 0x00000005 // Master has sent first byte
#define I2C_SLAVE_ACT_OWN2SEL 0x00000008 // Master requested secondary slave
#define I2C_SLAVE_ACT_QCMD 0x00000010 // Master has sent a Quick Command
#define I2C_SLAVE_ACT_QCMD_DATA 0x00000020 // Master Quick Command value
//*****************************************************************************
//
// Miscellaneous I2C driver definitions.
//
//*****************************************************************************
#define I2C_MASTER_MAX_RETRIES 1000 // Number of retries
//*****************************************************************************
//
// I2C Master interrupts.
//
//*****************************************************************************
#define I2C_MASTER_INT_RX_FIFO_FULL \
0x00000800 // RX FIFO Full Interrupt
#define I2C_MASTER_INT_TX_FIFO_EMPTY \
0x00000400 // TX FIFO Empty Interrupt
#define I2C_MASTER_INT_RX_FIFO_REQ \
0x00000200 // RX FIFO Request Interrupt
#define I2C_MASTER_INT_TX_FIFO_REQ \
0x00000100 // TX FIFO Request Interrupt
#define I2C_MASTER_INT_ARB_LOST \
0x00000080 // Arb Lost Interrupt
#define I2C_MASTER_INT_STOP 0x00000040 // Stop Condition Interrupt
#define I2C_MASTER_INT_START 0x00000020 // Start Condition Interrupt
#define I2C_MASTER_INT_NACK 0x00000010 // Addr/Data NACK Interrupt
#define I2C_MASTER_INT_TX_DMA_DONE \
0x00000008 // TX DMA Complete Interrupt
#define I2C_MASTER_INT_RX_DMA_DONE \
0x00000004 // RX DMA Complete Interrupt
#define I2C_MASTER_INT_TIMEOUT 0x00000002 // Clock Timeout Interrupt
#define I2C_MASTER_INT_DATA 0x00000001 // Data Interrupt
//*****************************************************************************
//
// I2C Slave interrupts.
//
//*****************************************************************************
#define I2C_SLAVE_INT_RX_FIFO_FULL \
0x00000100 // RX FIFO Full Interrupt
#define I2C_SLAVE_INT_TX_FIFO_EMPTY \
0x00000080 // TX FIFO Empty Interrupt
#define I2C_SLAVE_INT_RX_FIFO_REQ \
0x00000040 // RX FIFO Request Interrupt
#define I2C_SLAVE_INT_TX_FIFO_REQ \
0x00000020 // TX FIFO Request Interrupt
#define I2C_SLAVE_INT_TX_DMA_DONE \
0x00000010 // TX DMA Complete Interrupt
#define I2C_SLAVE_INT_RX_DMA_DONE \
0x00000008 // RX DMA Complete Interrupt
#define I2C_SLAVE_INT_STOP 0x00000004 // Stop Condition Interrupt
#define I2C_SLAVE_INT_START 0x00000002 // Start Condition Interrupt
#define I2C_SLAVE_INT_DATA 0x00000001 // Data Interrupt
//*****************************************************************************
//
// I2C Slave FIFO configuration macros.
//
//*****************************************************************************
#define I2C_SLAVE_TX_FIFO_ENABLE \
0x00000002
#define I2C_SLAVE_RX_FIFO_ENABLE \
0x00000004
//*****************************************************************************
//
// I2C FIFO configuration macros.
//
//*****************************************************************************
#define I2C_FIFO_CFG_TX_MASTER 0x00000000
#define I2C_FIFO_CFG_TX_SLAVE 0x00008000
#define I2C_FIFO_CFG_RX_MASTER 0x00000000
#define I2C_FIFO_CFG_RX_SLAVE 0x80000000
#define I2C_FIFO_CFG_TX_MASTER_DMA \
0x00002000
#define I2C_FIFO_CFG_TX_SLAVE_DMA \
0x0000a000
#define I2C_FIFO_CFG_RX_MASTER_DMA \
0x20000000
#define I2C_FIFO_CFG_RX_SLAVE_DMA \
0xa0000000
#define I2C_FIFO_CFG_TX_NO_TRIG 0x00000000
#define I2C_FIFO_CFG_TX_TRIG_1 0x00000001
#define I2C_FIFO_CFG_TX_TRIG_2 0x00000002
#define I2C_FIFO_CFG_TX_TRIG_3 0x00000003
#define I2C_FIFO_CFG_TX_TRIG_4 0x00000004
#define I2C_FIFO_CFG_TX_TRIG_5 0x00000005
#define I2C_FIFO_CFG_TX_TRIG_6 0x00000006
#define I2C_FIFO_CFG_TX_TRIG_7 0x00000007
#define I2C_FIFO_CFG_TX_TRIG_8 0x00000008
#define I2C_FIFO_CFG_RX_NO_TRIG 0x00000000
#define I2C_FIFO_CFG_RX_TRIG_1 0x00010000
#define I2C_FIFO_CFG_RX_TRIG_2 0x00020000
#define I2C_FIFO_CFG_RX_TRIG_3 0x00030000
#define I2C_FIFO_CFG_RX_TRIG_4 0x00040000
#define I2C_FIFO_CFG_RX_TRIG_5 0x00050000
#define I2C_FIFO_CFG_RX_TRIG_6 0x00060000
#define I2C_FIFO_CFG_RX_TRIG_7 0x00070000
#define I2C_FIFO_CFG_RX_TRIG_8 0x00080000
//*****************************************************************************
//
// I2C FIFO status.
//
//*****************************************************************************
#define I2C_FIFO_RX_BELOW_TRIG_LEVEL \
0x00040000
#define I2C_FIFO_RX_FULL 0x00020000
#define I2C_FIFO_RX_EMPTY 0x00010000
#define I2C_FIFO_TX_BELOW_TRIG_LEVEL \
0x00000004
#define I2C_FIFO_TX_FULL 0x00000002
#define I2C_FIFO_TX_EMPTY 0x00000001
//*****************************************************************************
//
// Prototypes for the APIs.
//
//*****************************************************************************
extern void I2CIntRegister(uint32_t ui32Base, void(pfnHandler)(void));
extern void I2CIntUnregister(uint32_t ui32Base);
extern void I2CTxFIFOConfigSet(uint32_t ui32Base, uint32_t ui32Config);
extern void I2CTxFIFOFlush(uint32_t ui32Base);
extern void I2CRxFIFOConfigSet(uint32_t ui32Base, uint32_t ui32Config);
extern void I2CRxFIFOFlush(uint32_t ui32Base);
extern uint32_t I2CFIFOStatus(uint32_t ui32Base);
extern void I2CFIFODataPut(uint32_t ui32Base, uint8_t ui8Data);
extern uint32_t I2CFIFODataPutNonBlocking(uint32_t ui32Base,
uint8_t ui8Data);
extern uint32_t I2CFIFODataGet(uint32_t ui32Base);
extern uint32_t I2CFIFODataGetNonBlocking(uint32_t ui32Base,
uint8_t *pui8Data);
extern void I2CMasterBurstLengthSet(uint32_t ui32Base,
uint8_t ui8Length);
extern uint32_t I2CMasterBurstCountGet(uint32_t ui32Base);
extern void I2CMasterGlitchFilterConfigSet(uint32_t ui32Base,
uint32_t ui32Config);
extern void I2CSlaveFIFOEnable(uint32_t ui32Base, uint32_t ui32Config);
extern void I2CSlaveFIFODisable(uint32_t ui32Base);
extern bool I2CMasterBusBusy(uint32_t ui32Base);
extern bool I2CMasterBusy(uint32_t ui32Base);
extern void I2CMasterControl(uint32_t ui32Base, uint32_t ui32Cmd);
extern uint32_t I2CMasterDataGet(uint32_t ui32Base);
extern void I2CMasterDataPut(uint32_t ui32Base, uint8_t ui8Data);
extern void I2CMasterDisable(uint32_t ui32Base);
extern void I2CMasterEnable(uint32_t ui32Base);
extern uint32_t I2CMasterErr(uint32_t ui32Base);
extern void I2CMasterInitExpClk(uint32_t ui32Base, uint32_t ui32I2CClk,
bool bFast);
extern void I2CMasterIntClear(uint32_t ui32Base);
extern void I2CMasterIntDisable(uint32_t ui32Base);
extern void I2CMasterIntEnable(uint32_t ui32Base);
extern bool I2CMasterIntStatus(uint32_t ui32Base, bool bMasked);
extern void I2CMasterIntEnableEx(uint32_t ui32Base,
uint32_t ui32IntFlags);
extern void I2CMasterIntDisableEx(uint32_t ui32Base,
uint32_t ui32IntFlags);
extern uint32_t I2CMasterIntStatusEx(uint32_t ui32Base,
bool bMasked);
extern void I2CMasterIntClearEx(uint32_t ui32Base,
uint32_t ui32IntFlags);
extern void I2CMasterTimeoutSet(uint32_t ui32Base, uint32_t ui32Value);
extern void I2CSlaveACKOverride(uint32_t ui32Base, bool bEnable);
extern void I2CSlaveACKValueSet(uint32_t ui32Base, bool bACK);
extern uint32_t I2CMasterLineStateGet(uint32_t ui32Base);
extern void I2CMasterSlaveAddrSet(uint32_t ui32Base,
uint8_t ui8SlaveAddr,
bool bReceive);
extern uint32_t I2CSlaveDataGet(uint32_t ui32Base);
extern void I2CSlaveDataPut(uint32_t ui32Base, uint8_t ui8Data);
extern void I2CSlaveDisable(uint32_t ui32Base);
extern void I2CSlaveEnable(uint32_t ui32Base);
extern void I2CSlaveInit(uint32_t ui32Base, uint8_t ui8SlaveAddr);
extern void I2CSlaveAddressSet(uint32_t ui32Base, uint8_t ui8AddrNum,
uint8_t ui8SlaveAddr);
extern void I2CSlaveIntClear(uint32_t ui32Base);
extern void I2CSlaveIntDisable(uint32_t ui32Base);
extern void I2CSlaveIntEnable(uint32_t ui32Base);
extern void I2CSlaveIntClearEx(uint32_t ui32Base, uint32_t ui32IntFlags);
extern void I2CSlaveIntDisableEx(uint32_t ui32Base,
uint32_t ui32IntFlags);
extern void I2CSlaveIntEnableEx(uint32_t ui32Base, uint32_t ui32IntFlags);
extern bool I2CSlaveIntStatus(uint32_t ui32Base, bool bMasked);
extern uint32_t I2CSlaveIntStatusEx(uint32_t ui32Base,
bool bMasked);
extern uint32_t I2CSlaveStatus(uint32_t ui32Base);
//*****************************************************************************
//
// Mark the end of the C bindings section for C++ compilers.
//
//*****************************************************************************
#ifdef __cplusplus
}
#endif
#endif // __DRIVERLIB_I2C_H__

1012
driverlib/i2s.c Normal file

File diff suppressed because it is too large Load Diff

218
driverlib/i2s.h Normal file
View File

@ -0,0 +1,218 @@
//*****************************************************************************
//
// i2s.h
//
// Defines and Macros for the I2S.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#ifndef __I2S_H__
#define __I2S_H__
//*****************************************************************************
//
// If building with a C++ compiler, make all of the definitions in this header
// have a C binding.
//
//*****************************************************************************
#ifdef __cplusplus
extern "C"
{
#endif
//*****************************************************************************
//
// I2S DMA ports.
//
//*****************************************************************************
#define I2S_TX_DMA_PORT 0x4401E200
#define I2S_RX_DMA_PORT 0x4401E280
//*****************************************************************************
//
// Values that can be passed to I2SConfigSetExpClk() as the ulConfig parameter.
//
//*****************************************************************************
#define I2S_SLOT_SIZE_8 0x00300032
#define I2S_SLOT_SIZE_16 0x00700074
#define I2S_SLOT_SIZE_24 0x00B000B6
#define I2S_PORT_CPU 0x00080008
#define I2S_PORT_DMA 0x00000000
#define I2S_MODE_MASTER 0x00000000
#define I2S_MODE_SLAVE 0x00008000
//*****************************************************************************
//
// Values that can be passed as ulDataLine parameter.
//
//*****************************************************************************
#define I2S_DATA_LINE_0 0x00000001
#define I2S_DATA_LINE_1 0x00000002
//*****************************************************************************
//
// Values that can be passed to I2SSerializerConfig() as the ulSerMode
// parameter.
//
//*****************************************************************************
#define I2S_SER_MODE_TX 0x00000001
#define I2S_SER_MODE_RX 0x00000002
#define I2S_SER_MODE_DISABLE 0x00000000
//*****************************************************************************
//
// Values that can be passed to I2SSerializerConfig() as the ulInActState
// parameter.
//
//*****************************************************************************
#define I2S_INACT_TRI_STATE 0x00000000
#define I2S_INACT_LOW_LEVEL 0x00000008
#define I2S_INACT_HIGH_LEVEL 0x0000000C
//*****************************************************************************
//
// Values that can be passed to I2SIntEnable() and I2SIntDisable() as the
// ulIntFlags parameter.
//
//*****************************************************************************
#define I2S_INT_XUNDRN 0x00000001
#define I2S_INT_XSYNCERR 0x00000002
#define I2S_INT_XLAST 0x00000010
#define I2S_INT_XDATA 0x00000020
#define I2S_INT_XSTAFRM 0x00000080
#define I2S_INT_XDMA 0x80000000
#define I2S_INT_ROVRN 0x00010000
#define I2S_INT_RSYNCERR 0x00020000
#define I2S_INT_RLAST 0x00100000
#define I2S_INT_RDATA 0x00200000
#define I2S_INT_RSTAFRM 0x00800000
#define I2S_INT_RDMA 0x40000000
//*****************************************************************************
//
// Values that can be passed to I2SRxActiveSlotSet() and I2STxActiveSlotSet
//
//*****************************************************************************
#define I2S_ACT_SLOT_EVEN 0x00000001
#define I2S_ACT_SLOT_ODD 0x00000002
//*****************************************************************************
//
// Values that can be passed to I2SIntClear() as the
// ulIntFlags parameter and returned from I2SIntStatus().
//
//*****************************************************************************
#define I2S_STS_XERR 0x00000100
#define I2S_STS_XDMAERR 0x00000080
#define I2S_STS_XSTAFRM 0x00000040
#define I2S_STS_XDATA 0x00000020
#define I2S_STS_XLAST 0x00000010
#define I2S_STS_XSYNCERR 0x00000002
#define I2S_STS_XUNDRN 0x00000001
#define I2S_STS_XDMA 0x80000000
#define I2S_STS_RERR 0x01000000
#define I2S_STS_RDMAERR 0x00800000
#define I2S_STS_RSTAFRM 0x00400000
#define I2S_STS_RDATA 0x00200000
#define I2S_STS_RLAST 0x00100000
#define I2S_STS_RSYNCERR 0x00020000
#define I2S_STS_ROVERN 0x00010000
#define I2S_STS_RDMA 0x40000000
//*****************************************************************************
//
// Values that can be passed to I2SEnable() as the ulMode parameter.
//
//*****************************************************************************
#define I2S_MODE_TX_ONLY 0x00000001
#define I2S_MODE_TX_RX_SYNC 0x00000003
//*****************************************************************************
//
// API Function prototypes
//
//*****************************************************************************
extern void I2SEnable(unsigned long ulBase, unsigned long ulMode);
extern void I2SDisable(unsigned long ulBase);
extern void I2SDataPut(unsigned long ulBase, unsigned long ulDataLine,
unsigned long ulData);
extern long I2SDataPutNonBlocking(unsigned long ulBase,
unsigned long ulDataLine, unsigned long ulData);
extern void I2SDataGet(unsigned long ulBase, unsigned long ulDataLine,
unsigned long *pulData);
extern long I2SDataGetNonBlocking(unsigned long ulBase,
unsigned long ulDataLine, unsigned long *pulData);
extern void I2SConfigSetExpClk(unsigned long ulBase, unsigned long ulI2SClk,
unsigned long ulBitClk, unsigned long ulConfig);
extern void I2STxFIFOEnable(unsigned long ulBase, unsigned long ulTxLevel,
unsigned long ulWordsPerTransfer);
extern void I2STxFIFODisable(unsigned long ulBase);
extern void I2SRxFIFOEnable(unsigned long ulBase, unsigned long ulRxLevel,
unsigned long ulWordsPerTransfer);
extern void I2SRxFIFODisable(unsigned long ulBase);
extern unsigned long I2STxFIFOStatusGet(unsigned long ulBase);
extern unsigned long I2SRxFIFOStatusGet(unsigned long ulBase);
extern void I2SSerializerConfig(unsigned long ulBase, unsigned long ulDataLine,
unsigned long ulSerMode, unsigned long ulInActState);
extern void I2SIntEnable(unsigned long ulBase, unsigned long ulIntFlags);
extern void I2SIntDisable(unsigned long ulBase, unsigned long ulIntFlags);
extern unsigned long I2SIntStatus(unsigned long ulBase);
extern void I2SIntClear(unsigned long ulBase, unsigned long ulIntFlags);
extern void I2SIntRegister(unsigned long ulBase, void (*pfnHandler)(void));
extern void I2SIntUnregister(unsigned long ulBase);
extern void I2STxActiveSlotSet(unsigned long ulBase, unsigned long ulActSlot);
extern void I2SRxActiveSlotSet(unsigned long ulBase, unsigned long ulActSlot);
//*****************************************************************************
//
// Mark the end of the C bindings section for C++ compilers.
//
//*****************************************************************************
#ifdef __cplusplus
}
#endif
#endif //__I2S_H__

769
driverlib/interrupt.c Normal file
View File

@ -0,0 +1,769 @@
//*****************************************************************************
//
// interrupt.c
//
// Driver for the NVIC Interrupt Controller.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
//*****************************************************************************
//
//! \addtogroup interrupt_api
//! @{
//
//*****************************************************************************
#include "inc/hw_ints.h"
#include "inc/hw_nvic.h"
#include "inc/hw_types.h"
#include "cpu.h"
#include "debug.h"
#include "interrupt.h"
//*****************************************************************************
//
// This is a mapping between priority grouping encodings and the number of
// preemption priority bits.
//
//*****************************************************************************
static const unsigned long g_pulPriority[] =
{
NVIC_APINT_PRIGROUP_0_8, NVIC_APINT_PRIGROUP_1_7, NVIC_APINT_PRIGROUP_2_6,
NVIC_APINT_PRIGROUP_3_5, NVIC_APINT_PRIGROUP_4_4, NVIC_APINT_PRIGROUP_5_3,
NVIC_APINT_PRIGROUP_6_2, NVIC_APINT_PRIGROUP_7_1
};
//*****************************************************************************
//
// This is a mapping between interrupt number and the register that contains
// the priority encoding for that interrupt.
//
//*****************************************************************************
static const unsigned long g_pulRegs[] =
{
0, NVIC_SYS_PRI1, NVIC_SYS_PRI2, NVIC_SYS_PRI3, NVIC_PRI0, NVIC_PRI1,
NVIC_PRI2, NVIC_PRI3, NVIC_PRI4, NVIC_PRI5, NVIC_PRI6, NVIC_PRI7,
NVIC_PRI8, NVIC_PRI9, NVIC_PRI10, NVIC_PRI11, NVIC_PRI12, NVIC_PRI13,
NVIC_PRI14, NVIC_PRI15, NVIC_PRI16, NVIC_PRI17, NVIC_PRI18, NVIC_PRI19,
NVIC_PRI20, NVIC_PRI21, NVIC_PRI22, NVIC_PRI23, NVIC_PRI24, NVIC_PRI25,
NVIC_PRI26, NVIC_PRI27, NVIC_PRI28, NVIC_PRI29, NVIC_PRI30, NVIC_PRI31,
NVIC_PRI32, NVIC_PRI33, NVIC_PRI34, NVIC_PRI35, NVIC_PRI36, NVIC_PRI37,
NVIC_PRI38, NVIC_PRI39, NVIC_PRI40, NVIC_PRI41, NVIC_PRI42, NVIC_PRI43,
NVIC_PRI44, NVIC_PRI45, NVIC_PRI46, NVIC_PRI47, NVIC_PRI48
};
//*****************************************************************************
//
// This is a mapping between interrupt number (for the peripheral interrupts
// only) and the register that contains the interrupt enable for that
// interrupt.
//
//*****************************************************************************
static const unsigned long g_pulEnRegs[] =
{
NVIC_EN0, NVIC_EN1, NVIC_EN2, NVIC_EN3, NVIC_EN4, NVIC_EN5
};
//*****************************************************************************
//
// This is a mapping between interrupt number (for the peripheral interrupts
// only) and the register that contains the interrupt disable for that
// interrupt.
//
//*****************************************************************************
static const unsigned long g_pulDisRegs[] =
{
NVIC_DIS0, NVIC_DIS1, NVIC_DIS2, NVIC_DIS3, NVIC_DIS4, NVIC_DIS5
};
//*****************************************************************************
//
// This is a mapping between interrupt number (for the peripheral interrupts
// only) and the register that contains the interrupt pend for that interrupt.
//
//*****************************************************************************
static const unsigned long g_pulPendRegs[] =
{
NVIC_PEND0, NVIC_PEND1, NVIC_PEND2, NVIC_PEND3, NVIC_PEND4, NVIC_PEND5
};
//*****************************************************************************
//
// This is a mapping between interrupt number (for the peripheral interrupts
// only) and the register that contains the interrupt unpend for that
// interrupt.
//
//*****************************************************************************
static const unsigned long g_pulUnpendRegs[] =
{
NVIC_UNPEND0, NVIC_UNPEND1, NVIC_UNPEND2, NVIC_UNPEND3, NVIC_UNPEND4,
NVIC_UNPEND5
};
//*****************************************************************************
//
//! \internal
//! The default interrupt handler.
//!
//! This is the default interrupt handler for all interrupts. It simply loops
//! forever so that the system state is preserved for observation by a
//! debugger. Since interrupts should be disabled before unregistering the
//! corresponding handler, this should never be called.
//!
//! \return None.
//
//*****************************************************************************
static void
IntDefaultHandler(void)
{
//
// Go into an infinite loop.
//
while(1)
{
}
}
//*****************************************************************************
//
//! Enables the processor interrupt.
//!
//! Allows the processor to respond to interrupts. This does not affect the
//! set of interrupts enabled in the interrupt controller; it just gates the
//! single interrupt from the controller to the processor.
//!
//! \note Previously, this function had no return value. As such, it was
//! possible to include <tt>interrupt.h</tt> and call this function without
//! having included <tt>hw_types.h</tt>. Now that the return is a
//! <tt>tBoolean</tt>, a compiler error will occur in this case. The solution
//! is to include <tt>hw_types.h</tt> before including <tt>interrupt.h</tt>.
//!
//! \return Returns \b true if interrupts were disabled when the function was
//! called or \b false if they were initially enabled.
//
//*****************************************************************************
tBoolean
IntMasterEnable(void)
{
//
// Enable processor interrupts.
//
return(CPUcpsie());
}
//*****************************************************************************
//
//! Disables the processor interrupt.
//!
//! Prevents the processor from receiving interrupts. This does not affect the
//! set of interrupts enabled in the interrupt controller; it just gates the
//! single interrupt from the controller to the processor.
//!
//! \note Previously, this function had no return value. As such, it was
//! possible to include <tt>interrupt.h</tt> and call this function without
//! having included <tt>hw_types.h</tt>. Now that the return is a
//! <tt>tBoolean</tt>, a compiler error will occur in this case. The solution
//! is to include <tt>hw_types.h</tt> before including <tt>interrupt.h</tt>.
//!
//! \return Returns \b true if interrupts were already disabled when the
//! function was called or \b false if they were initially enabled.
//
//*****************************************************************************
tBoolean
IntMasterDisable(void)
{
//
// Disable processor interrupts.
//
return(CPUcpsid());
}
//*****************************************************************************
//
//! Sets the NVIC VTable base.
//!
//! \param ulVtableBase specifies the new base address of VTable
//!
//! This function is used to specify a new base address for the VTable.
//! This function must be called before using IntRegister() for registering
//! any interrupt handler.
//!
//!
//! \return None.
//
//*****************************************************************************
void
IntVTableBaseSet(unsigned long ulVtableBase)
{
HWREG(NVIC_VTABLE) = ulVtableBase;
}
//*****************************************************************************
//
//! Registers a function to be called when an interrupt occurs.
//!
//! \param ulInterrupt specifies the interrupt in question.
//! \param pfnHandler is a pointer to the function to be called.
//!
//! This function is used to specify the handler function to be called when the
//! given interrupt is asserted to the processor. When the interrupt occurs,
//! if it is enabled (via IntEnable()), the handler function will be called in
//! interrupt context. Since the handler function can preempt other code, care
//! must be taken to protect memory or peripherals that are accessed by the
//! handler and other non-handler code.
//!
//!
//! \return None.
//
//*****************************************************************************
void
IntRegister(unsigned long ulInterrupt, void (*pfnHandler)(void))
{
unsigned long *ulNvicTbl;
//
// Check the arguments.
//
ASSERT(ulInterrupt < NUM_INTERRUPTS);
ulNvicTbl = (unsigned long *)HWREG(NVIC_VTABLE);
ulNvicTbl[ulInterrupt]= (unsigned long)pfnHandler;
}
//*****************************************************************************
//
//! Unregisters the function to be called when an interrupt occurs.
//!
//! \param ulInterrupt specifies the interrupt in question.
//!
//! This function is used to indicate that no handler should be called when the
//! given interrupt is asserted to the processor. The interrupt source will be
//! automatically disabled (via IntDisable()) if necessary.
//!
//! \sa IntRegister() for important information about registering interrupt
//! handlers.
//!
//! \return None.
//
//*****************************************************************************
void
IntUnregister(unsigned long ulInterrupt)
{
unsigned long *ulNvicTbl;
//
// Check the arguments.
//
ASSERT(ulInterrupt < NUM_INTERRUPTS);
ulNvicTbl = (unsigned long *)HWREG(NVIC_VTABLE);
ulNvicTbl[ulInterrupt]= (unsigned long)IntDefaultHandler;
}
//*****************************************************************************
//
//! Sets the priority grouping of the interrupt controller.
//!
//! \param ulBits specifies the number of bits of preemptable priority.
//!
//! This function specifies the split between preemptable priority levels and
//! subpriority levels in the interrupt priority specification. The range of
//! the grouping values are dependent upon the hardware implementation; on
//! the CC3200 , three bits are available for hardware interrupt
//! prioritization and therefore priority grouping values of three through
//! seven have the same effect.
//!
//! \return None.
//
//*****************************************************************************
void
IntPriorityGroupingSet(unsigned long ulBits)
{
//
// Check the arguments.
//
ASSERT(ulBits < NUM_PRIORITY);
//
// Set the priority grouping.
//
HWREG(NVIC_APINT) = NVIC_APINT_VECTKEY | g_pulPriority[ulBits];
}
//*****************************************************************************
//
//! Gets the priority grouping of the interrupt controller.
//!
//! This function returns the split between preemptable priority levels and
//! subpriority levels in the interrupt priority specification.
//!
//! \return The number of bits of preemptable priority.
//
//*****************************************************************************
unsigned long
IntPriorityGroupingGet(void)
{
unsigned long ulLoop, ulValue;
//
// Read the priority grouping.
//
ulValue = HWREG(NVIC_APINT) & NVIC_APINT_PRIGROUP_M;
//
// Loop through the priority grouping values.
//
for(ulLoop = 0; ulLoop < NUM_PRIORITY; ulLoop++)
{
//
// Stop looping if this value matches.
//
if(ulValue == g_pulPriority[ulLoop])
{
break;
}
}
//
// Return the number of priority bits.
//
return(ulLoop);
}
//*****************************************************************************
//
//! Sets the priority of an interrupt.
//!
//! \param ulInterrupt specifies the interrupt in question.
//! \param ucPriority specifies the priority of the interrupt.
//!
//! This function is used to set the priority of an interrupt. When multiple
//! interrupts are asserted simultaneously, the ones with the highest priority
//! are processed before the lower priority interrupts. Smaller numbers
//! correspond to higher interrupt priorities; priority 0 is the highest
//! interrupt priority.
//!
//! The hardware priority mechanism will only look at the upper N bits of the
//! priority level (where N is 3), so any prioritization must be performed in
//! those bits. The remaining bits can be used to sub-prioritize the interrupt
//! sources, and may be used by the hardware priority mechanism on a future
//! part. This arrangement allows priorities to migrate to different NVIC
//! implementations without changing the gross prioritization of the
//! interrupts.
//!
//! The parameter \e ucPriority can be any one of the following
//! -\b INT_PRIORITY_LVL_0
//! -\b INT_PRIORITY_LVL_1
//! -\b INT_PRIORITY_LVL_2
//! -\b INT_PRIORITY_LVL_3
//! -\b INT_PRIORITY_LVL_4
//! -\b INT_PRIORITY_LVL_5
//! -\b INT_PRIORITY_LVL_6
//! -\b INT_PRIORITY_LVL_7
//!
//! \return None.
//
//*****************************************************************************
void
IntPrioritySet(unsigned long ulInterrupt, unsigned char ucPriority)
{
unsigned long ulTemp;
//
// Check the arguments.
//
ASSERT((ulInterrupt >= 4) && (ulInterrupt < NUM_INTERRUPTS));
//
// Set the interrupt priority.
//
ulTemp = HWREG(g_pulRegs[ulInterrupt >> 2]);
ulTemp &= ~(0xFF << (8 * (ulInterrupt & 3)));
ulTemp |= ucPriority << (8 * (ulInterrupt & 3));
HWREG(g_pulRegs[ulInterrupt >> 2]) = ulTemp;
}
//*****************************************************************************
//
//! Gets the priority of an interrupt.
//!
//! \param ulInterrupt specifies the interrupt in question.
//!
//! This function gets the priority of an interrupt. See IntPrioritySet() for
//! a definition of the priority value.
//!
//! \return Returns the interrupt priority, or -1 if an invalid interrupt was
//! specified.
//
//*****************************************************************************
long
IntPriorityGet(unsigned long ulInterrupt)
{
//
// Check the arguments.
//
ASSERT((ulInterrupt >= 4) && (ulInterrupt < NUM_INTERRUPTS));
//
// Return the interrupt priority.
//
return((HWREG(g_pulRegs[ulInterrupt >> 2]) >> (8 * (ulInterrupt & 3))) &
0xFF);
}
//*****************************************************************************
//
//! Enables an interrupt.
//!
//! \param ulInterrupt specifies the interrupt to be enabled.
//!
//! The specified interrupt is enabled in the interrupt controller. Other
//! enables for the interrupt (such as at the peripheral level) are unaffected
//! by this function.
//!
//! \return None.
//
//*****************************************************************************
void
IntEnable(unsigned long ulInterrupt)
{
//
// Check the arguments.
//
ASSERT(ulInterrupt < NUM_INTERRUPTS);
//
// Determine the interrupt to enable.
//
if(ulInterrupt == FAULT_MPU)
{
//
// Enable the MemManage interrupt.
//
HWREG(NVIC_SYS_HND_CTRL) |= NVIC_SYS_HND_CTRL_MEM;
__asm(" dsb ");
__asm(" isb ");
}
else if(ulInterrupt == FAULT_BUS)
{
//
// Enable the bus fault interrupt.
//
HWREG(NVIC_SYS_HND_CTRL) |= NVIC_SYS_HND_CTRL_BUS;
__asm(" dsb ");
__asm(" isb ");
}
else if(ulInterrupt == FAULT_USAGE)
{
//
// Enable the usage fault interrupt.
//
HWREG(NVIC_SYS_HND_CTRL) |= NVIC_SYS_HND_CTRL_USAGE;
__asm(" dsb ");
__asm(" isb ");
}
else if(ulInterrupt == FAULT_SYSTICK)
{
//
// Enable the System Tick interrupt.
//
HWREG(NVIC_ST_CTRL) |= NVIC_ST_CTRL_INTEN;
__asm(" dsb ");
__asm(" isb ");
}
else if(ulInterrupt >= 16)
{
//
// Enable the general interrupt.
//
HWREG(g_pulEnRegs[(ulInterrupt - 16) / 32]) =
1 << ((ulInterrupt - 16) & 31);
__asm(" dsb ");
__asm(" isb ");
}
}
//*****************************************************************************
//
//! Disables an interrupt.
//!
//! \param ulInterrupt specifies the interrupt to be disabled.
//!
//! The specified interrupt is disabled in the interrupt controller. Other
//! enables for the interrupt (such as at the peripheral level) are unaffected
//! by this function.
//!
//! \return None.
//
//*****************************************************************************
void
IntDisable(unsigned long ulInterrupt)
{
//
// Check the arguments.
//
ASSERT(ulInterrupt < NUM_INTERRUPTS);
//
// Determine the interrupt to disable.
//
if(ulInterrupt == FAULT_MPU)
{
//
// Disable the MemManage interrupt.
//
HWREG(NVIC_SYS_HND_CTRL) &= ~(NVIC_SYS_HND_CTRL_MEM);
__asm(" dsb ");
__asm(" isb ");
}
else if(ulInterrupt == FAULT_BUS)
{
//
// Disable the bus fault interrupt.
//
HWREG(NVIC_SYS_HND_CTRL) &= ~(NVIC_SYS_HND_CTRL_BUS);
__asm(" dsb ");
__asm(" isb ");
}
else if(ulInterrupt == FAULT_USAGE)
{
//
// Disable the usage fault interrupt.
//
HWREG(NVIC_SYS_HND_CTRL) &= ~(NVIC_SYS_HND_CTRL_USAGE);
__asm(" dsb ");
__asm(" isb ");
}
else if(ulInterrupt == FAULT_SYSTICK)
{
//
// Disable the System Tick interrupt.
//
HWREG(NVIC_ST_CTRL) &= ~(NVIC_ST_CTRL_INTEN);
__asm(" dsb ");
__asm(" isb ");
}
else if(ulInterrupt >= 16)
{
//
// Disable the general interrupt.
//
HWREG(g_pulDisRegs[(ulInterrupt - 16) / 32]) =
1 << ((ulInterrupt - 16) & 31);
__asm(" dsb ");
__asm(" isb ");
}
}
//*****************************************************************************
//
//! Pends an interrupt.
//!
//! \param ulInterrupt specifies the interrupt to be pended.
//!
//! The specified interrupt is pended in the interrupt controller. This will
//! cause the interrupt controller to execute the corresponding interrupt
//! handler at the next available time, based on the current interrupt state
//! priorities. For example, if called by a higher priority interrupt handler,
//! the specified interrupt handler will not be called until after the current
//! interrupt handler has completed execution. The interrupt must have been
//! enabled for it to be called.
//!
//! \return None.
//
//*****************************************************************************
void
IntPendSet(unsigned long ulInterrupt)
{
//
// Check the arguments.
//
ASSERT(ulInterrupt < NUM_INTERRUPTS);
//
// Determine the interrupt to pend.
//
if(ulInterrupt == FAULT_NMI)
{
//
// Pend the NMI interrupt.
//
HWREG(NVIC_INT_CTRL) |= NVIC_INT_CTRL_NMI_SET;
__asm(" dsb ");
__asm(" isb ");
}
else if(ulInterrupt == FAULT_PENDSV)
{
//
// Pend the PendSV interrupt.
//
HWREG(NVIC_INT_CTRL) |= NVIC_INT_CTRL_PEND_SV;
__asm(" dsb ");
__asm(" isb ");
}
else if(ulInterrupt == FAULT_SYSTICK)
{
//
// Pend the SysTick interrupt.
//
HWREG(NVIC_INT_CTRL) |= NVIC_INT_CTRL_PENDSTSET;
__asm(" dsb ");
__asm(" isb ");
}
else if(ulInterrupt >= 16)
{
//
// Pend the general interrupt.
//
HWREG(g_pulPendRegs[(ulInterrupt - 16) / 32]) =
1 << ((ulInterrupt - 16) & 31);
__asm(" dsb ");
__asm(" isb ");
}
}
//*****************************************************************************
//
//! Unpends an interrupt.
//!
//! \param ulInterrupt specifies the interrupt to be unpended.
//!
//! The specified interrupt is unpended in the interrupt controller. This will
//! cause any previously generated interrupts that have not been handled yet
//! (due to higher priority interrupts or the interrupt no having been enabled
//! yet) to be discarded.
//!
//! \return None.
//
//*****************************************************************************
void
IntPendClear(unsigned long ulInterrupt)
{
//
// Check the arguments.
//
ASSERT(ulInterrupt < NUM_INTERRUPTS);
//
// Determine the interrupt to unpend.
//
if(ulInterrupt == FAULT_PENDSV)
{
//
// Unpend the PendSV interrupt.
//
HWREG(NVIC_INT_CTRL) |= NVIC_INT_CTRL_UNPEND_SV;
}
else if(ulInterrupt == FAULT_SYSTICK)
{
//
// Unpend the SysTick interrupt.
//
HWREG(NVIC_INT_CTRL) |= NVIC_INT_CTRL_PENDSTCLR;
}
else if(ulInterrupt >= 16)
{
//
// Unpend the general interrupt.
//
HWREG(g_pulUnpendRegs[(ulInterrupt - 16) / 32]) =
1 << ((ulInterrupt - 16) & 31);
}
}
//*****************************************************************************
//
//! Sets the priority masking level
//!
//! \param ulPriorityMask is the priority level that will be masked.
//!
//! This function sets the interrupt priority masking level so that all
//! interrupts at the specified or lesser priority level is masked. This
//! can be used to globally disable a set of interrupts with priority below
//! a predetermined threshold. A value of 0 disables priority
//! masking.
//!
//! Smaller numbers correspond to higher interrupt priorities. So for example
//! a priority level mask of 4 will allow interrupts of priority level 0-3,
//! and interrupts with a numerical priority of 4 and greater will be blocked.
//!
//! The hardware priority mechanism will only look at the upper N bits of the
//! priority level (where N is 3), so any
//! prioritization must be performed in those bits.
//!
//! \return None.
//
//*****************************************************************************
void
IntPriorityMaskSet(unsigned long ulPriorityMask)
{
CPUbasepriSet(ulPriorityMask);
}
//*****************************************************************************
//
//! Gets the priority masking level
//!
//! This function gets the current setting of the interrupt priority masking
//! level. The value returned is the priority level such that all interrupts
//! of that and lesser priority are masked. A value of 0 means that priority
//! masking is disabled.
//!
//! Smaller numbers correspond to higher interrupt priorities. So for example
//! a priority level mask of 4 will allow interrupts of priority level 0-3,
//! and interrupts with a numerical priority of 4 and greater will be blocked.
//!
//! The hardware priority mechanism will only look at the upper N bits of the
//! priority level (where N is 3), so any
//! prioritization must be performed in those bits.
//!
//! \return Returns the value of the interrupt priority level mask.
//
//*****************************************************************************
unsigned long
IntPriorityMaskGet(void)
{
return(CPUbasepriGet());
}
//*****************************************************************************
//
// Close the Doxygen group.
//! @}
//
//*****************************************************************************

120
driverlib/interrupt.h Normal file
View File

@ -0,0 +1,120 @@
//*****************************************************************************
//
// interrupt.h
//
// Prototypes for the NVIC Interrupt Controller Driver.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#ifndef __INTERRUPT_H__
#define __INTERRUPT_H__
//*****************************************************************************
//
// If building with a C++ compiler, make all of the definitions in this header
// have a C binding.
//
//*****************************************************************************
#ifdef __cplusplus
extern "C"
{
#endif
//*****************************************************************************
//
// A union that describes the entries of the vector table. The union is needed
// since the first entry is the stack pointer and the remainder are function
// pointers.
//
//*****************************************************************************
typedef union
{
void (*pfnHandler)(void);
unsigned long ulPtr;
}
uVectorEntry;
//*****************************************************************************
//
// Macro to generate an interrupt priority mask based on the number of bits
// of priority supported by the hardware.
//
//*****************************************************************************
#define INT_PRIORITY_MASK ((0xFF << (8 - NUM_PRIORITY_BITS)) & 0xFF)
//*****************************************************************************
// Interrupt priority levels
//*****************************************************************************
#define INT_PRIORITY_LVL_0 0x00
#define INT_PRIORITY_LVL_1 0x20
#define INT_PRIORITY_LVL_2 0x40
#define INT_PRIORITY_LVL_3 0x60
#define INT_PRIORITY_LVL_4 0x80
#define INT_PRIORITY_LVL_5 0xA0
#define INT_PRIORITY_LVL_6 0xC0
#define INT_PRIORITY_LVL_7 0xE0
//*****************************************************************************
//
// Prototypes for the APIs.
//
//*****************************************************************************
extern tBoolean IntMasterEnable(void);
extern tBoolean IntMasterDisable(void);
extern void IntVTableBaseSet(unsigned long ulVtableBase);
extern void IntRegister(unsigned long ulInterrupt, void (*pfnHandler)(void));
extern void IntUnregister(unsigned long ulInterrupt);
extern void IntPriorityGroupingSet(unsigned long ulBits);
extern unsigned long IntPriorityGroupingGet(void);
extern void IntPrioritySet(unsigned long ulInterrupt,
unsigned char ucPriority);
extern long IntPriorityGet(unsigned long ulInterrupt);
extern void IntEnable(unsigned long ulInterrupt);
extern void IntDisable(unsigned long ulInterrupt);
extern void IntPendSet(unsigned long ulInterrupt);
extern void IntPendClear(unsigned long ulInterrupt);
extern void IntPriorityMaskSet(unsigned long ulPriorityMask);
extern unsigned long IntPriorityMaskGet(void);
//*****************************************************************************
//
// Mark the end of the C bindings section for C++ compilers.
//
//*****************************************************************************
#ifdef __cplusplus
}
#endif
#endif // __INTERRUPT_H__

667
driverlib/pin.c Normal file
View File

@ -0,0 +1,667 @@
//*****************************************************************************
//
// pin.c
//
// Mapping of peripherals to pins.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
//*****************************************************************************
//
//! \addtogroup pin_api
//! @{
//
//*****************************************************************************
#include "inc/hw_types.h"
#include "inc/hw_memmap.h"
#include "inc/hw_ocp_shared.h"
#include "pin.h"
//*****************************************************************************
// Macros
//*****************************************************************************
#define PAD_MODE_MASK 0x0000000F
#define PAD_STRENGTH_MASK 0x000000E0
#define PAD_TYPE_MASK 0x00000310
#define PAD_CONFIG_BASE ((OCP_SHARED_BASE + \
OCP_SHARED_O_GPIO_PAD_CONFIG_0))
//*****************************************************************************
// PIN to PAD matrix
//*****************************************************************************
static const unsigned long g_ulPinToPadMap[64] =
{
10,11,12,13,14,15,16,17,255,255,18,
19,20,21,22,23,24,40,28,29,25,255,
255,255,255,255,255,255,255,255,255,255,255,
255,255,255,255,255,255,255,255,255,255,255,
31,255,255,255,255,0,255,32,30,255,1,
255,2,3,4,5,6,7,8,9
};
//*****************************************************************************
//
//! Configures pin mux for the specified pin.
//!
//! \param ulPin is a valid pin.
//! \param ulPinMode is one of the valid mode
//!
//! This function configures the pin mux that selects the peripheral function
//! associated with a particular SOC pin. Only one peripheral function at a
//! time can be associated with a pin, and each peripheral function should
//! only be associated with a single pin at a time.
//!
//! \return none
//
//*****************************************************************************
void PinModeSet(unsigned long ulPin,unsigned long ulPinMode)
{
unsigned long ulPad;
//
// Get the corresponding Pad
//
ulPad = g_ulPinToPadMap[ulPin & 0x3F];
//
// Calculate the register address
//
ulPad = ((ulPad << 2) + PAD_CONFIG_BASE);
//
// Set the mode.
//
HWREG(ulPad) = (((HWREG(ulPad) & ~PAD_MODE_MASK) | ulPinMode) & ~(3<<10));
}
//*****************************************************************************
//
//! Gets current pin mux configuration of specified pin.
//!
//! \param ulPin is a valid pin.
//!
//! This function get the current configuration of the pin mux.
//!
//! \return Returns current pin mode if \e ulPin is valid, 0xFF otherwise.
//
//*****************************************************************************
unsigned long PinModeGet(unsigned long ulPin)
{
unsigned long ulPad;
//
// Get the corresponding Pad
//
ulPad = g_ulPinToPadMap[ulPin & 0x3F];
//
// Calculate the register address
//
ulPad = ((ulPad << 2) + PAD_CONFIG_BASE) ;
//
// return the mode.
//
return (HWREG(ulPad) & PAD_MODE_MASK);
}
//*****************************************************************************
//
//! Sets the direction of the specified pin(s).
//!
//! \param ulPin is one of the valid pin.
//! \param ulPinIO is the pin direction and/or mode.
//!
//! This function configures the specified pin(s) as either input only or
//! output only or it configures the pin to be under hardware control.
//!
//! The parameter \e ulPinIO is an enumerated data type that can be one of
//! the following values:
//!
//! - \b PIN_DIR_MODE_IN
//! - \b PIN_DIR_MODE_OUT
//! - \b PIN_DIR_MODE_HW
//!
//! where \b PIN_DIR_MODE_IN specifies that the pin is programmed as a
//! input only, \b PIN_DIR_MODE_OUT specifies that the pin is
//! programmed output only, and \b PIN_DIR_MODE_HW specifies that the pin is
//! placed under hardware control.
//!
//!
//! \return None.
//
//*****************************************************************************
void PinDirModeSet(unsigned long ulPin, unsigned long ulPinIO)
{
unsigned long ulPad;
//
// Get the corresponding Pad
//
ulPad = g_ulPinToPadMap[ulPin & 0x3F];
//
// Calculate the register address
//
ulPad = ((ulPad << 2) + PAD_CONFIG_BASE);
//
// Set the direction
//
HWREG(ulPad) = ((HWREG(ulPad) & ~0xC00) | ulPinIO);
}
//*****************************************************************************
//
//! Gets the direction of a pin.
//!
//! \param ulPin is one of the valid pin.
//!
//! This function gets the direction and control mode for a specified pin on
//! the selected GPIO port. The pin can be configured as either an input only
//! or output only, or it can be under hardware control. The type of control
//! and direction are returned as an enumerated data type.
//!
//! \return Returns one of the enumerated data types described for
//! GPIODirModeSet().
//
//*****************************************************************************
unsigned long PinDirModeGet(unsigned long ulPin)
{
unsigned long ulPad;
//
// Get the corresponding Pad
//
ulPad = g_ulPinToPadMap[ulPin & 0x3F];
//
// Calculate the register address
//
ulPad = ((ulPad << 2) + PAD_CONFIG_BASE);
//
// Return the direction
//
return ((HWREG(ulPad) & 0xC00));
}
//*****************************************************************************
//
//! Gets Pin output drive strength and Type
//!
//! \param ulPin is one of the valid pin
//! \param pulPinStrength is pointer to storage for output drive strength
//! \param pulPinType is pinter to storage for pin type
//!
//! This function gets the pin type and output drive strength for the pin
//! specified by \e ulPin parameter. Parameters \e pulPinStrength and
//! \e pulPinType corresponds to the values used in PinConfigSet().
//!
//!
//! \return None.
//
//*****************************************************************************
void PinConfigGet(unsigned long ulPin,unsigned long *pulPinStrength,
unsigned long *pulPinType)
{
unsigned long ulPad;
//
// Get the corresponding Pad
//
ulPad = g_ulPinToPadMap[ulPin & 0x3F];
//
// Calculate the register address
//
ulPad = ((ulPad << 2) + PAD_CONFIG_BASE);
//
// Get the type
//
*pulPinType = (HWREG(ulPad) & PAD_TYPE_MASK);
//
// Get the output drive strength
//
*pulPinStrength = (HWREG(ulPad) & PAD_STRENGTH_MASK);
}
//*****************************************************************************
//
//! Configure Pin output drive strength and Type
//!
//! \param ulPin is one of the valid pin
//! \param ulPinStrength is logical OR of valid output drive strengths.
//! \param ulPinType is one of the valid pin type.
//!
//! This function sets the pin type and strength for the pin specified by
//! \e ulPin parameter.
//!
//! The parameter \e ulPinStrength should be one of the following
//! - \b PIN_STRENGTH_2MA
//! - \b PIN_STRENGTH_4MA
//! - \b PIN_STRENGTH_6MA
//!
//!
//! The parameter \e ulPinType should be one of the following
//! For standard type
//!
//! - \b PIN_TYPE_STD
//! - \b PIN_TYPE_STD_PU
//! - \b PIN_TYPE_STD_PD
//!
//! And for Open drain type
//!
//! - \b PIN_TYPE_OD
//! - \b PIN_TYPE_OD_PU
//! - \b PIN_TYPE_OD_PD
//!
//! \return None.
//
//*****************************************************************************
void PinConfigSet(unsigned long ulPin,unsigned long ulPinStrength,
unsigned long ulPinType)
{
unsigned long ulPad;
//
// Get the corresponding Pad
//
ulPad = g_ulPinToPadMap[ulPin & 0x3F];
//
// Write the register
//
if(ulPinType == PIN_TYPE_ANALOG)
{
//
// Isolate the input
//
HWREG(0x4402E144) |= ((0x80 << ulPad) & (0x1E << 8));
//
// Calculate the register address
//
ulPad = ((ulPad << 2) + PAD_CONFIG_BASE);
//
// Isolate the output
//
HWREG(ulPad) = 0xC00;
}
else
{
//
// Enable the input
//
HWREG(0x4402E144) &= ~((0x80 << ulPad) & (0x1E << 8));
//
// Calculate the register address
//
ulPad = ((ulPad << 2) + PAD_CONFIG_BASE);
//
// Write the configuration
//
HWREG(ulPad) = ((HWREG(ulPad) & ~(PAD_STRENGTH_MASK | PAD_TYPE_MASK)) |
(ulPinStrength | ulPinType ));
}
}
//*****************************************************************************
//
//! Sets the pin mode and configures the pin for use by UART peripheral
//!
//! \param ulPin is one of the valid pin.
//! \param ulPinMode is one of the valid pin mode.
//!
//! The UART pins must be properly configured for the peripheral to
//! function correctly. This function provides a typical configuration for
//! those pin(s); other configurations may work as well depending upon the
//! board setup (for example, using the on-chip pull-ups).
//!
//!
//! \note This function cannot be used to turn any pin into a UART pin; it
//! only sets the pin mode and configures it for proper UART operation.
//!
//!
//! \return None.
//
//*****************************************************************************
void PinTypeUART(unsigned long ulPin,unsigned long ulPinMode)
{
//
// Set the pin to specified mode
//
PinModeSet(ulPin,ulPinMode);
//
// Set the pin for standard operation
//
PinConfigSet(ulPin,PIN_STRENGTH_2MA,PIN_TYPE_STD);
}
//*****************************************************************************
//
//! Sets the pin mode and configures the pin for use by I2C peripheral
//!
//! \param ulPin is one of the valid pin.
//! \param ulPinMode is one of the valid pin mode.
//!
//! The I2C pins must be properly configured for the peripheral to
//! function correctly. This function provides a typical configuration for
//! the pin.
//!
//!
//! \note This function cannot be used to turn any pin into a I2C pin; it
//! only sets the pin mode and configures it for proper I2C operation.
//!
//!
//! \return None.
//
//*****************************************************************************
void PinTypeI2C(unsigned long ulPin,unsigned long ulPinMode)
{
//
// Set the pin to specified mode
//
PinModeSet(ulPin,ulPinMode);
//
// Set the pin for open-drain operation with a weak pull-up.
//
PinConfigSet(ulPin,PIN_STRENGTH_2MA,PIN_TYPE_OD_PU);
}
//*****************************************************************************
//
//! Sets the pin mode and configures the pin for use by SPI peripheral
//!
//! \param ulPin is one of the valid pin.
//! \param ulPinMode is one of the valid pin mode.
//!
//! The SPI pins must be properly configured for the peripheral to
//! function correctly. This function provides a typical configuration for
//! those pin.
//!
//!
//! \note This function cannot be used to turn any pin into a SPI pin; it
//! only sets the pin mode and configures it for proper SPI operation.
//!
//!
//! \return None.
//
//*****************************************************************************
void PinTypeSPI(unsigned long ulPin,unsigned long ulPinMode)
{
//
// Set the pin to specified mode
//
PinModeSet(ulPin,ulPinMode);
//
// Set the pin for standard operation
//
PinConfigSet(ulPin,PIN_STRENGTH_2MA|PIN_STRENGTH_4MA,PIN_TYPE_STD);
}
//*****************************************************************************
//
//! Sets the pin mode and configures the pin for use by I2S peripheral
//!
//! \param ulPin is one of the valid pin.
//! \param ulPinMode is one of the valid pin mode.
//!
//! The I2S pins must be properly configured for the peripheral to
//! function correctly. This function provides a typical configuration for
//! those pin.
//!
//!
//! \note This function cannot be used to turn any pin into a I2S pin; it
//! only sets the pin mode and configures it for proper I2S operation.
//!
//! \return None.
//
//*****************************************************************************
void PinTypeI2S(unsigned long ulPin,unsigned long ulPinMode)
{
//
// Set the pin to specified mode
//
PinModeSet(ulPin,ulPinMode);
//
// Set the pin for standard operation
//
PinConfigSet(ulPin,PIN_STRENGTH_2MA|PIN_STRENGTH_4MA,PIN_TYPE_STD);
}
//*****************************************************************************
//
//! Sets the pin mode and configures the pin for use by Timer peripheral
//!
//! \param ulPin is one of the valid pin.
//! \param ulPinMode is one of the valid pin mode.
//!
//! The timer PWM pins must be properly configured for the Timer peripheral to
//! function correctly. This function provides a typical configuration for
//! those pin; other configurations may work as well depending upon the
//! board setup (for example, using the on-chip pull-ups).
//!
//!
//! \note This function cannot be used to turn any pin into a timer PWM pin; it
//! only sets the pin mode and configures it for proper timer PWM operation.
//!
//! \return None.
//
//*****************************************************************************
void PinTypeTimer(unsigned long ulPin,unsigned long ulPinMode)
{
//
// Set the pin to specified mode
//
PinModeSet(ulPin,ulPinMode);
//
// Set the pin for standard operation
//
PinConfigSet(ulPin,PIN_STRENGTH_2MA|PIN_STRENGTH_4MA,PIN_TYPE_STD);
}
//*****************************************************************************
//
//! Sets the pin mode and configures the pin for use by Camera peripheral
//!
//! \param ulPin is one of the valid pin.
//! \param ulPinMode is one of the valid pin mode.
//!
//! The Camera pins must be properly configured for the peripheral to
//! function correctly. This function provides a typical configuration for
//! those pin.
//!
//!
//! \note This function cannot be used to turn any pin into a Camera pin; it
//! only sets the pin mode and configures it for proper Camera operation.
//!
//! \return None.
//
//*****************************************************************************
void PinTypeCamera(unsigned long ulPin,unsigned long ulPinMode)
{
//
// Set the pin to specified mode
//
PinModeSet(ulPin,ulPinMode);
//
// Set the pin for standard operation
//
PinConfigSet(ulPin,PIN_STRENGTH_2MA|PIN_STRENGTH_4MA,PIN_TYPE_STD);
}
//*****************************************************************************
//
//! Sets the pin mode and configures the pin for use by GPIO peripheral
//!
//! \param ulPin is one of the valid pin.
//! \param ulPinMode is one of the valid pin mode.
//! \param bOpenDrain is one to decide either OpenDrain or STD
//!
//! The GPIO pins must be properly configured for the peripheral to
//! function correctly. This function provides a typical configuration for
//! those pin.
//!
//!
//! \return None.
//
//*****************************************************************************
void PinTypeGPIO(unsigned long ulPin,unsigned long ulPinMode,tBoolean bOpenDrain)
{
//
// Set the pin for standard push-pull operation.
//
if(bOpenDrain)
{
PinConfigSet(ulPin, PIN_STRENGTH_2MA, PIN_TYPE_OD);
}
else
{
PinConfigSet(ulPin, PIN_STRENGTH_2MA, PIN_TYPE_STD);
}
//
// Set the pin to specified mode
//
PinModeSet(ulPin, ulPinMode);
}
//*****************************************************************************
//
//! Sets the pin mode and configures the pin for use by ADC
//!
//! \param ulPin is one of the valid pin.
//! \param ulPinMode is one of the valid pin mode.
//!
//! The ADC pins must be properly configured for the peripheral to
//! function correctly. This function provides a typical configuration for
//! those pin.
//!
//!
//! \note This function cannot be used to turn any pin into a ADC pin; it
//! only sets the pin mode and configures it for proper ADC operation.
//!
//! \return None.
//
//*****************************************************************************
void PinTypeADC(unsigned long ulPin,unsigned long ulPinMode)
{
//
// Configure the Pin
//
PinConfigSet(ulPin,PIN_STRENGTH_2MA,PIN_TYPE_ANALOG);
}
//*****************************************************************************
//
//! Sets the pin mode and configures the pin for use by SD Host peripheral
//!
//! \param ulPin is one of the valid pin.
//! \param ulPinMode is one of the valid pin mode.
//!
//! The MMC pins must be properly configured for the peripheral to
//! function correctly. This function provides a typical configuration for
//! those pin.
//!
//!
//! \note This function cannot be used to turn any pin into a SD Host pin; it
//! only sets the pin mode and configures it for proper SD Host operation.
//!
//! \return None.
//
//*****************************************************************************
void PinTypeSDHost(unsigned long ulPin,unsigned long ulPinMode)
{
//
// Set pin mode
//
PinModeSet(ulPin,ulPinMode);
//
// Configure the Pin
//
PinConfigSet(ulPin,PIN_STRENGTH_2MA,PIN_TYPE_STD);
}
//*****************************************************************************
//
// Close the Doxygen group.
//! @}
//
//*****************************************************************************

176
driverlib/pin.h Normal file
View File

@ -0,0 +1,176 @@
//*****************************************************************************
//
// pin.h
//
// Defines and Macros for the pin mux module
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#ifndef __PIN_H__
#define __PIN_H__
//*****************************************************************************
//
// If building with a C++ compiler, make all of the definitions in this header
// have a C binding.
//
//*****************************************************************************
#ifdef __cplusplus
extern "C"
{
#endif
//*****************************************************************************
// Macros Defining Pins
//*****************************************************************************
#define PIN_01 0x00000000
#define PIN_02 0x00000001
#define PIN_03 0x00000002
#define PIN_04 0x00000003
#define PIN_05 0x00000004
#define PIN_06 0x00000005
#define PIN_07 0x00000006
#define PIN_08 0x00000007
#define PIN_11 0x0000000A
#define PIN_12 0x0000000B
#define PIN_13 0x0000000C
#define PIN_14 0x0000000D
#define PIN_15 0x0000000E
#define PIN_16 0x0000000F
#define PIN_17 0x00000010
#define PIN_18 0x00000011
#define PIN_19 0x00000012
#define PIN_20 0x00000013
#define PIN_21 0x00000014
#define PIN_45 0x0000002C
#define PIN_46 0x0000002D
#define PIN_47 0x0000002E
#define PIN_48 0x0000002F
#define PIN_49 0x00000030
#define PIN_50 0x00000031
#define PIN_52 0x00000033
#define PIN_53 0x00000034
#define PIN_55 0x00000036
#define PIN_56 0x00000037
#define PIN_57 0x00000038
#define PIN_58 0x00000039
#define PIN_59 0x0000003A
#define PIN_60 0x0000003B
#define PIN_61 0x0000003C
#define PIN_62 0x0000003D
#define PIN_63 0x0000003E
#define PIN_64 0x0000003F
//*****************************************************************************
// Macros that can be used with PinConfigSet(), PinTypeGet(), PinStrengthGet()
//*****************************************************************************
#define PIN_MODE_0 0x00000000
#define PIN_MODE_1 0x00000001
#define PIN_MODE_2 0x00000002
#define PIN_MODE_3 0x00000003
#define PIN_MODE_4 0x00000004
#define PIN_MODE_5 0x00000005
#define PIN_MODE_6 0x00000006
#define PIN_MODE_7 0x00000007
#define PIN_MODE_8 0x00000008
#define PIN_MODE_9 0x00000009
#define PIN_MODE_10 0x0000000A
#define PIN_MODE_11 0x0000000B
#define PIN_MODE_12 0x0000000C
#define PIN_MODE_13 0x0000000D
#define PIN_MODE_14 0x0000000E
#define PIN_MODE_15 0x0000000F
// Note : PIN_MODE_255 is a dummy define for pinmux utility code generation
// PIN_MODE_255 should never be used in any user code.
#define PIN_MODE_255 0x000000FF
//*****************************************************************************
// Macros that can be used with PinDirModeSet() and returned from
// PinDirModeGet().
//*****************************************************************************
#define PIN_DIR_MODE_IN 0x00000C00 // Pin is input
#define PIN_DIR_MODE_OUT 0x00000800 // Pin is output
#define PIN_DIR_MODE_HW 0x00000000 // Pin is peripheral function
//*****************************************************************************
// Macros that can be used with PinConfigSet()
//*****************************************************************************
#define PIN_STRENGTH_2MA 0x00000020
#define PIN_STRENGTH_4MA 0x00000040
#define PIN_STRENGTH_6MA 0x00000060
#define PIN_TYPE_STD 0x00000000
#define PIN_TYPE_STD_PU 0x00000100
#define PIN_TYPE_STD_PD 0x00000200
#define PIN_TYPE_OD 0x00000010
#define PIN_TYPE_OD_PU 0x00000110
#define PIN_TYPE_OD_PD 0x00000210
#define PIN_TYPE_ANALOG 0x10000000
//*****************************************************************************
//
// API Function prototypes
//
//*****************************************************************************
extern void PinModeSet(unsigned long ulPin, unsigned long ulPinMode);
extern void PinDirModeSet(unsigned long ulPin, unsigned long ulPinIO);
extern unsigned long PinDirModeGet(unsigned long ulPin);
extern unsigned long PinModeGet(unsigned long ulPin);
extern void PinConfigGet(unsigned long ulPin,unsigned long *pulPinStrength,
unsigned long *pulPinType);
extern void PinConfigSet(unsigned long ulPin,unsigned long ulPinStrength,
unsigned long ulPinType);
extern void PinTypeUART(unsigned long ulPin,unsigned long ulPinMode);
extern void PinTypeI2C(unsigned long ulPin,unsigned long ulPinMode);
extern void PinTypeSPI(unsigned long ulPin,unsigned long ulPinMode);
extern void PinTypeI2S(unsigned long ulPin,unsigned long ulPinMode);
extern void PinTypeTimer(unsigned long ulPin,unsigned long ulPinMode);
extern void PinTypeCamera(unsigned long ulPin,unsigned long ulPinMode);
extern void PinTypeGPIO(unsigned long ulPin,unsigned long ulPinMode,
tBoolean bOpenDrain);
extern void PinTypeADC(unsigned long ulPin,unsigned long ulPinMode);
extern void PinTypeSDHost(unsigned long ulPin,unsigned long ulPinMode);
#ifdef __cplusplus
}
#endif
#endif //__PIN_H__

2033
driverlib/prcm.c Normal file

File diff suppressed because it is too large Load Diff

272
driverlib/prcm.h Normal file
View File

@ -0,0 +1,272 @@
//*****************************************************************************
//
// prcm.h
//
// Prototypes for the PRCM control driver.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#ifndef __PRCM_H__
#define __PRCM_H__
//*****************************************************************************
//
// If building with a C++ compiler, make all of the definitions in this header
// have a C binding.
//
//*****************************************************************************
#ifdef __cplusplus
extern "C"
{
#endif
//*****************************************************************************
//
// Peripheral clock and reset control registers
//
//*****************************************************************************
typedef struct _PRCM_PeripheralRegs_
{
unsigned long ulClkReg;
unsigned long ulRstReg;
}PRCM_PeriphRegs_t;
//*****************************************************************************
// Values that can be passed to PRCMPeripheralEnable() and
// PRCMPeripheralDisable()
//*****************************************************************************
#define PRCM_RUN_MODE_CLK 0x00000001
#define PRCM_SLP_MODE_CLK 0x00000100
//*****************************************************************************
// Values that can be passed to PRCMSRAMRetentionEnable() and
// PRCMSRAMRetentionDisable() as ulSramColSel.
//*****************************************************************************
#define PRCM_SRAM_COL_1 0x00000001
#define PRCM_SRAM_COL_2 0x00000002
#define PRCM_SRAM_COL_3 0x00000004
#define PRCM_SRAM_COL_4 0x00000008
//*****************************************************************************
// Values that can be passed to PRCMSRAMRetentionEnable() and
// PRCMSRAMRetentionDisable() as ulModeFlags.
//*****************************************************************************
#define PRCM_SRAM_LPDS_RET 0x00000002
//*****************************************************************************
// Values that can be passed to PRCMLPDSWakeupSourceEnable(),
// PRCMLPDSWakeupCauseGet() and PRCMLPDSWakeupSourceDisable().
//*****************************************************************************
#define PRCM_LPDS_HOST_IRQ 0x00000080
#define PRCM_LPDS_GPIO 0x00000010
#define PRCM_LPDS_TIMER 0x00000001
//*****************************************************************************
// Values that can be passed to PRCMLPDSWakeUpGPIOSelect() as Type
//*****************************************************************************
#define PRCM_LPDS_LOW_LEVEL 0x00000002
#define PRCM_LPDS_HIGH_LEVEL 0x00000000
#define PRCM_LPDS_FALL_EDGE 0x00000001
#define PRCM_LPDS_RISE_EDGE 0x00000003
//*****************************************************************************
// Values that can be passed to PRCMLPDSWakeUpGPIOSelect()
//*****************************************************************************
#define PRCM_LPDS_GPIO2 0x00000000
#define PRCM_LPDS_GPIO4 0x00000001
#define PRCM_LPDS_GPIO13 0x00000002
#define PRCM_LPDS_GPIO17 0x00000003
#define PRCM_LPDS_GPIO11 0x00000004
#define PRCM_LPDS_GPIO24 0x00000005
#define PRCM_LPDS_GPIO26 0x00000006
//*****************************************************************************
// Values that can be passed to PRCMHibernateWakeupSourceEnable(),
// PRCMHibernateWakeupSourceDisable().
//*****************************************************************************
#define PRCM_HIB_SLOW_CLK_CTR 0x00000001
//*****************************************************************************
// Values that can be passed to PRCMHibernateWakeUpGPIOSelect() as ulType
//*****************************************************************************
#define PRCM_HIB_LOW_LEVEL 0x00000000
#define PRCM_HIB_HIGH_LEVEL 0x00000001
#define PRCM_HIB_FALL_EDGE 0x00000002
#define PRCM_HIB_RISE_EDGE 0x00000003
//*****************************************************************************
// Values that can be passed to PRCMHibernateWakeupSourceEnable(),
// PRCMHibernateWakeupSourceDisable(), PRCMHibernateWakeUpGPIOSelect()
//*****************************************************************************
#define PRCM_HIB_GPIO2 0x00010000
#define PRCM_HIB_GPIO4 0x00020000
#define PRCM_HIB_GPIO13 0x00040000
#define PRCM_HIB_GPIO17 0x00080000
#define PRCM_HIB_GPIO11 0x00100000
#define PRCM_HIB_GPIO24 0x00200000
#define PRCM_HIB_GPIO26 0x00400000
//*****************************************************************************
// Values that will be returned from PRCMSysResetCauseGet().
//*****************************************************************************
#define PRCM_POWER_ON 0x00000000
#define PRCM_LPDS_EXIT 0x00000001
#define PRCM_CORE_RESET 0x00000003
#define PRCM_MCU_RESET 0x00000004
#define PRCM_WDT_RESET 0x00000005
#define PRCM_SOC_RESET 0x00000006
#define PRCM_HIB_EXIT 0x00000007
//*****************************************************************************
// Values that can be passed to PRCMHibernateWakeupCauseGet().
//*****************************************************************************
#define PRCM_HIB_WAKEUP_CAUSE_SLOW_CLOCK 0x00000002
#define PRCM_HIB_WAKEUP_CAUSE_GPIO 0x00000004
//*****************************************************************************
// Values that can be passed to PRCMSEnableInterrupt
//*****************************************************************************
#define PRCM_INT_SLOW_CLK_CTR 0x00004000
//*****************************************************************************
// Values that can be passed to PRCMPeripheralClkEnable(),
// PRCMPeripheralClkDisable(), PRCMPeripheralReset()
//*****************************************************************************
#define PRCM_CAMERA 0x00000000
#define PRCM_I2S 0x00000001
#define PRCM_SDHOST 0x00000002
#define PRCM_GSPI 0x00000003
#define PRCM_LSPI 0x00000004
#define PRCM_UDMA 0x00000005
#define PRCM_GPIOA0 0x00000006
#define PRCM_GPIOA1 0x00000007
#define PRCM_GPIOA2 0x00000008
#define PRCM_GPIOA3 0x00000009
#define PRCM_GPIOA4 0x0000000A
#define PRCM_WDT 0x0000000B
#define PRCM_UARTA0 0x0000000C
#define PRCM_UARTA1 0x0000000D
#define PRCM_TIMERA0 0x0000000E
#define PRCM_TIMERA1 0x0000000F
#define PRCM_TIMERA2 0x00000010
#define PRCM_TIMERA3 0x00000011
#define PRCM_DTHE 0x00000012
#define PRCM_SSPI 0x00000013
#define PRCM_I2CA0 0x00000014
// Note : PRCM_ADC is a dummy define for pinmux utility code generation
// PRCM_ADC should never be used in any user code.
#define PRCM_ADC 0x000000FF
//*****************************************************************************
//
// API Function prototypes
//
//*****************************************************************************
extern void PRCMMCUReset(tBoolean bIncludeSubsystem);
extern unsigned long PRCMSysResetCauseGet(void);
extern void PRCMPeripheralClkEnable(unsigned long ulPeripheral,
unsigned long ulClkFlags);
extern void PRCMPeripheralClkDisable(unsigned long ulPeripheral,
unsigned long ulClkFlags);
extern void PRCMPeripheralReset(unsigned long ulPeripheral);
extern tBoolean PRCMPeripheralStatusGet(unsigned long ulPeripheral);
extern void PRCMI2SClockFreqSet(unsigned long ulI2CClkFreq);
extern unsigned long PRCMPeripheralClockGet(unsigned long ulPeripheral);
extern void PRCMSleepEnter(void);
extern void PRCMSRAMRetentionEnable(unsigned long ulSramColSel,
unsigned long ulFlags);
extern void PRCMSRAMRetentionDisable(unsigned long ulSramColSel,
unsigned long ulFlags);
extern void PRCMLPDSRestoreInfoSet(unsigned long ulRestoreSP,
unsigned long ulRestorePC);
extern void PRCMLPDSEnter(void);
extern void PRCMLPDSIntervalSet(unsigned long ulTicks);
extern void PRCMLPDSWakeupSourceEnable(unsigned long ulLpdsWakeupSrc);
extern unsigned long PRCMLPDSWakeupCauseGet(void);
extern void PRCMLPDSWakeUpGPIOSelect(unsigned long ulGPIOPin,
unsigned long ulType);
extern void PRCMLPDSWakeupSourceDisable(unsigned long ulLpdsWakeupSrc);
extern void PRCMHibernateEnter(void);
extern void PRCMHibernateWakeupSourceEnable(unsigned long ulHIBWakupSrc);
extern unsigned long PRCMHibernateWakeupCauseGet(void);
extern void PRCMHibernateWakeUpGPIOSelect(unsigned long ulMultiGPIOBitMap,
unsigned long ulType);
extern void PRCMHibernateWakeupSourceDisable(unsigned long ulHIBWakupSrc);
extern void PRCMHibernateIntervalSet(unsigned long long ullTicks);
extern unsigned long long PRCMSlowClkCtrGet(void);
extern unsigned long long PRCMSlowClkCtrFastGet(void);
extern void PRCMSlowClkCtrMatchSet(unsigned long long ullTicks);
extern unsigned long long PRCMSlowClkCtrMatchGet(void);
extern void PRCMOCRRegisterWrite(unsigned char ucIndex,
unsigned long ulRegValue);
extern unsigned long PRCMOCRRegisterRead(unsigned char ucIndex);
extern void PRCMIntRegister(void (*pfnHandler)(void));
extern void PRCMIntUnregister(void);
extern void PRCMIntEnable(unsigned long ulIntFlags);
extern void PRCMIntDisable(unsigned long ulIntFlags);
extern unsigned long PRCMIntStatus(void);
extern void PRCMRTCInUseSet(void);
extern tBoolean PRCMRTCInUseGet(void);
extern void PRCMRTCSet(unsigned long ulSecs, unsigned short usMsec);
extern void PRCMRTCGet(unsigned long *ulSecs, unsigned short *usMsec);
extern void PRCMRTCMatchSet(unsigned long ulSecs, unsigned short usMsec);
extern void PRCMRTCMatchGet(unsigned long *ulSecs, unsigned short *usMsec);
extern void PRCMCC3200MCUInit(void);
extern unsigned long PRCMHIBRegRead(unsigned long ulRegAddr);
extern void PRCMHIBRegWrite(unsigned long ulRegAddr, unsigned long ulValue);
extern unsigned long PRCMCameraFreqSet(unsigned char ulDivider,
unsigned char ulWidth);
extern void PRCMLPDSEnterKeepDebugIf(void);
//*****************************************************************************
//
// Mark the end of the C bindings section for C++ compilers.
//
//*****************************************************************************
#ifdef __cplusplus
}
#endif
#endif // __PRCM_H__

2237
driverlib/rom.h Normal file

File diff suppressed because it is too large Load Diff

3174
driverlib/rom_map.h Normal file

File diff suppressed because it is too large Load Diff

101
driverlib/rom_patch.h Normal file
View File

@ -0,0 +1,101 @@
//*****************************************************************************
//
// rom_patch.h
//
// Macros to facilitate patching driverlib API's in the ROM.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
//*****************************************************************************
//
// List of API's in the ROM that need to be patched.
// For e.g. to patch ROM_UARTCharPut add the line #undef ROM_UARTCharPut
//*****************************************************************************
#undef ROM_ADCIntClear
#undef ROM_IntEnable
#undef ROM_IntDisable
#undef ROM_IntPendSet
#undef ROM_PRCMHibernateWakeUpGPIOSelect
#undef ROM_SDHostCardErrorMaskSet
#undef ROM_SDHostCardErrorMaskGet
#undef ROM_TimerConfigure
#undef ROM_TimerDMAEventSet
#undef ROM_TimerDMAEventGet
#undef ROM_SDHostDataNonBlockingWrite
#undef ROM_SDHostDataWrite
#undef ROM_SDHostDataRead
#undef ROM_SDHostDataNonBlockingRead
#undef ROM_PRCMSysResetCauseGet
#undef ROM_PRCMPeripheralClkEnable
#undef ROM_PRCMLPDSWakeUpGPIOSelect
#undef ROM_PRCMHibernateWakeupSourceEnable
#undef ROM_PRCMHibernateWakeupSourceDisable
#undef ROM_PRCMHibernateWakeupCauseGet
#undef ROM_PRCMHibernateIntervalSet
#undef ROM_PRCMHibernateWakeUpGPIOSelect
#undef ROM_PRCMHibernateEnter
#undef ROM_PRCMSlowClkCtrGet
#undef ROM_PRCMSlowClkCtrMatchSet
#undef ROM_PRCMSlowClkCtrMatchGet
#undef ROM_PRCMOCRRegisterWrite
#undef ROM_PRCMOCRRegisterRead
#undef ROM_PRCMIntEnable
#undef ROM_PRCMIntDisable
#undef ROM_PRCMRTCInUseSet
#undef ROM_PRCMRTCInUseGet
#undef ROM_PRCMRTCSet
#undef ROM_PRCMRTCGet
#undef ROM_PRCMRTCMatchSet
#undef ROM_PRCMRTCMatchGet
#undef ROM_PRCMPeripheralClkDisable
#undef ROM_PRCMPeripheralReset
#undef ROM_PRCMPeripheralStatusGet
#undef ROM_SPIConfigSetExpClk
#undef ROM_AESDataProcess
#undef ROM_DESDataProcess
#undef ROM_I2SEnable
#undef ROM_I2SConfigSetExpClk
#undef ROM_PinConfigSet
#undef ROM_PRCMLPDSEnter
#undef ROM_PRCMCC3200MCUInit
#undef ROM_SDHostIntStatus
#undef ROM_SDHostBlockCountSet
#undef ROM_UARTModemControlSet
#undef ROM_UARTModemControlClear
#undef ROM_CameraXClkSet
#undef ROM_PRCMMCUReset
#undef ROM_SPIDmaDisable
#undef ROM_PRCMSRAMRetentionEnable
#undef ROM_PRCMSRAMRetentionDisable
#undef ROM_PRCMDeepSleepEnter

744
driverlib/sdhost.c Normal file
View File

@ -0,0 +1,744 @@
//*****************************************************************************
//
// sdhost.c
//
// Driver for the SD Host (SDHost) Interface
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
//*****************************************************************************
//
//! \addtogroup Secure_Digital_Host_api
//! @{
//
//*****************************************************************************
#include "inc/hw_types.h"
#include "inc/hw_memmap.h"
#include "inc/hw_mmchs.h"
#include "inc/hw_ints.h"
#include "inc/hw_apps_config.h"
#include "interrupt.h"
#include "sdhost.h"
//*****************************************************************************
//
//! Configures SDHost module.
//!
//! \param ulBase is the base address of SDHost module.
//!
//! This function configures the SDHost module, enabling internal sub-modules.
//!
//! \return None.
//
//*****************************************************************************
void
SDHostInit(unsigned long ulBase)
{
//
// Assert module reset
//
HWREG(ulBase + MMCHS_O_SYSCONFIG) = 0x2;
//
// Wait for soft reset to complete
//
while( !(HWREG(ulBase + MMCHS_O_SYSCONFIG) & 0x1) )
{
}
//
// Assert internal reset
//
HWREG(ulBase + MMCHS_O_SYSCTL) |= (1 << 24);
//
// Wait for Reset to complete
//
while( (HWREG(ulBase + MMCHS_O_SYSCTL) & (0x1 << 24)) )
{
}
//
// Set capability register, 1.8 and 3.0 V
//
HWREG(ulBase + MMCHS_O_CAPA) = (0x7 <<24);
//
// Select bus voltage, 3.0 V
//
HWREG(ulBase + MMCHS_O_HCTL) |= 0x7 << 9;
//
// Power up the bus
//
HWREG(ulBase + MMCHS_O_HCTL) |= 1 << 8;
//
// Wait for power on
//
while( !(HWREG(ulBase + MMCHS_O_HCTL) & (1<<8)) )
{
}
HWREG(ulBase + MMCHS_O_CON) |= 1 << 21;
//
// Un-mask all events
//
HWREG(ulBase + MMCHS_O_IE) = 0xFFFFFFFF;
}
//*****************************************************************************
//
//! Resets SDHost command line
//!
//! \param ulBase is the base address of SDHost module.
//!
//! This function assers a soft reset for the command line
//!
//! \return None.
//
//*****************************************************************************
void
SDHostCmdReset(unsigned long ulBase)
{
HWREG(ulBase + MMCHS_O_SYSCTL) |= 1 << 25;
while( (HWREG(ulBase + MMCHS_O_SYSCTL) & (1 << 25)) )
{
}
}
//*****************************************************************************
//
//! Sends command over SDHost interface
//!
//! \param ulBase is the base address of SDHost module.
//! \param ulCmd is the command to send.
//! \param ulArg is the argument for the command.
//!
//! This function send command to the attached card over the SDHost interface.
//!
//! The \e ulCmd parameter can be one of \b SDHOST_CMD_0 to \b SDHOST_CMD_63.
//! It can be logically ORed with one or more of the following:
//! - \b SDHOST_MULTI_BLK for multi-block transfer
//! - \b SDHOST_WR_CMD if command is followed by write data
//! - \b SDHOST_RD_CMD if command is followed by read data
//! - \b SDHOST_DMA_EN if SDHost need to generate DMA request.
//! - \b SDHOST_RESP_LEN_136 if 136 bit response is expected
//! - \b SDHOST_RESP_LEN_48 if 48 bit response is expected
//! - \b SDHOST_RESP_LEN_48B if 48 bit response with busy bit is expected
//!
//! The parameter \e ulArg is the argument for the command
//!
//! \return Returns 0 on success, -1 otherwise.
//
//*****************************************************************************
long
SDHostCmdSend(unsigned long ulBase, unsigned long ulCmd, unsigned ulArg)
{
//
// Set Data Timeout
//
HWREG(ulBase + MMCHS_O_SYSCTL) |= 0x000E0000;
//
// Check for cmd inhabit
//
if( (HWREG(ulBase + MMCHS_O_PSTATE) & 0x1))
{
return -1;
}
//
// Set the argument
//
HWREG(ulBase + MMCHS_O_ARG) = ulArg;
//
// Send the command
//
HWREG(ulBase + MMCHS_O_CMD) = ulCmd;
return 0;
}
//*****************************************************************************
//
//! Writes a data word into the SDHost write buffer.
//!
//! \param ulBase is the base address of SDHost module.
//! \param ulData is data word to be transfered.
//!
//! This function writes a single data word into the SDHost write buffer. The
//! function returns \b true if there was a space available in the buffer else
//! returns \b false.
//!
//! \return Return \b true on success, \b false otherwise.
//
//*****************************************************************************
tBoolean
SDHostDataNonBlockingWrite(unsigned long ulBase, unsigned long ulData)
{
//
// See if there is a space in the write buffer
//
if( (HWREG(ulBase + MMCHS_O_PSTATE) & (1<<10)) )
{
//
// Write the data into the buffer
//
HWREG(ulBase + MMCHS_O_DATA) = ulData;
//
// Success.
//
return(true);
}
else
{
//
// No free sapce, failure.
//
return(false);
}
}
//*****************************************************************************
//
//! Waits to write a data word into the SDHost write buffer.
//!
//! \param ulBase is the base address of SDHost module.
//! \param ulData is data word to be transfered.
//!
//! This function writes \e ulData into the SDHost write buffer. If there is no
//! space in the write buffer this function waits until there is a space
//! available before returning.
//!
//! \return None.
//
//*****************************************************************************
void
SDHostDataWrite(unsigned long ulBase, unsigned long ulData)
{
//
// Wait until space is available
//
while( !(HWREG(ulBase + MMCHS_O_PSTATE) & (1<<10)) )
{
}
//
// Write the data
//
HWREG(ulBase + MMCHS_O_DATA) = ulData;
}
//*****************************************************************************
//
//! Waits for a data word from the SDHost read buffer
//!
//! \param ulBase is the base address of SDHost module.
//! \param pulData is pointer to read data variable.
//!
//! This function reads a single data word from the SDHost read buffer. If there
//! is no data available in the buffer the function will wait until a data
//! word is received before returning.
//!
//! \return None.
//
//*****************************************************************************
void
SDHostDataRead(unsigned long ulBase, unsigned long *pulData)
{
//
// Wait until data is available
//
while( !(HWREG(ulBase + MMCHS_O_PSTATE) & (1<<11)) )
{
}
//
// Read the data
//
*pulData = HWREG(ulBase + MMCHS_O_DATA);
}
//*****************************************************************************
//
//! Reads single data word from the SDHost read buffer
//!
//! \param ulBase is the base address of SDHost module.
//! \param pulData is pointer to read data variable.
//!
//! This function reads a data word from the SDHost read buffer. The
//! function returns \b true if there was data available in to buffer else
//! returns \b false.
//!
//! \return Return \b true on success, \b false otherwise.
//
//*****************************************************************************
tBoolean
SDHostDataNonBlockingRead(unsigned long ulBase, unsigned long *pulData)
{
//
// See if there is any data in the read buffer.
//
if( (HWREG(ulBase + MMCHS_O_PSTATE) & (1<11)) )
{
//
// Read the data word.
//
*pulData = HWREG(ulBase + MMCHS_O_DATA);
//
// Success
//
return(true);
}
else
{
//
// No data available, failure.
//
return(false);
}
}
//*****************************************************************************
//
//! Registers the interrupt handler for SDHost interrupt
//!
//! \param ulBase is the base address of SDHost module
//! \param pfnHandler is a pointer to the function to be called when the
//! SDHost interrupt occurs.
//!
//! This function does the actual registering of the interrupt handler. This
//! function enables the global interrupt in the interrupt controller; specific
//! SDHost interrupts must be enabled via SDHostIntEnable(). It is the
//! interrupt handler's responsibility to clear the interrupt source.
//!
//! \sa IntRegister() for important information about registering interrupt
//! handlers.
//!
//! \return None.
//
//*****************************************************************************
void
SDHostIntRegister(unsigned long ulBase, void (*pfnHandler)(void))
{
//
// Register the interrupt handler.
//
IntRegister(INT_MMCHS, pfnHandler);
//
// Enable the SDHost interrupt.
//
IntEnable(INT_MMCHS);
}
//*****************************************************************************
//
//! Unregisters the interrupt handler for SDHost interrupt
//!
//! \param ulBase is the base address of SDHost module
//!
//! This function does the actual unregistering of the interrupt handler. It
//! clears the handler to be called when a SDHost interrupt occurs. This
//! function also masks off the interrupt in the interrupt controller so that
//! the interrupt handler no longer is called.
//!
//! \sa IntRegister() for important information about registering interrupt
//! handlers.
//!
//! \return None.
//
//*****************************************************************************
void
SDHostIntUnregister(unsigned long ulBase)
{
//
// Disable the SDHost interrupt.
//
IntDisable(INT_MMCHS);
//
// Unregister the interrupt handler.
//
IntUnregister(INT_MMCHS);
}
//*****************************************************************************
//
//! Enable individual interrupt source for the specified SDHost
//!
//! \param ulBase is the base address of SDHost module.
//! \param ulIntFlags is a bit mask of the interrupt sources to be enabled.
//!
//! This function enables the indicated SDHost interrupt sources. Only the
//! sources that are enabled can be reflected to the processor interrupt;
//! disabled sources have no effect on the processor.
//!
//! The \e ulIntFlags parameter is the logical OR of any of the following:
//! - \b SDHOST_INT_CC Command Complete interrupt
//! - \b SDHOST_INT_TC Transfer Complete interrupt
//! - \b SDHOST_INT_BWR Buffer Write Ready interrupt
//! - \b SDHOST_INT_BRR Buffer Read Ready interrupt
//! - \b SDHOST_INT_ERRI Error interrupt
//! - \b SDHOST_INT_CTO Command Timeout error interrupt
//! - \b SDHOST_INT_CEB Command End Bit error interrupt
//! - \b SDHOST_INT_DTO Data Timeout error interrupt
//! - \b SDHOST_INT_DCRC Data CRC error interrupt
//! - \b SDHOST_INT_DEB Data End Bit error
//! - \b SDHOST_INT_CERR Cart Status Error interrupt
//! - \b SDHOST_INT_BADA Bad Data error interrupt
//! - \b SDHOST_INT_DMARD Read DMA done interrupt
//! - \b SDHOST_INT_DMAWR Write DMA done interrupt
//!
//! Note that SDHOST_INT_ERRI can only be used with \sa SDHostIntStatus()
//! and is internally logical OR of all error status bits. Setting this bit
//! alone as \e ulIntFlags doesn't generates any interrupt.
//!
//! \return None.
//
//*****************************************************************************
void
SDHostIntEnable(unsigned long ulBase,unsigned long ulIntFlags)
{
//
// Enable DMA done interrupts
//
HWREG(APPS_CONFIG_BASE + APPS_CONFIG_O_DMA_DONE_INT_MASK_CLR) =
(ulIntFlags >> 30);
//
// Enable the individual interrupt sources
//
HWREG(ulBase + MMCHS_O_ISE) |= (ulIntFlags & 0x3FFFFFFF);
}
//*****************************************************************************
//
//! Enable individual interrupt source for the specified SDHost
//!
//! \param ulBase is the base address of SDHost module.
//! \param ulIntFlags is a bit mask of the interrupt sources to be enabled.
//!
//! This function disables the indicated SDHost interrupt sources. Only the
//! sources that are enabled can be reflected to the processor interrupt;
//! disabled sources have no effect on the processor.
//!
//! The \e ulIntFlags parameter has the same definition as the \e ulIntFlags
//! parameter to SDHostIntEnable().
//!
//! \return None.
//
//*****************************************************************************
void
SDHostIntDisable(unsigned long ulBase,unsigned long ulIntFlags)
{
//
// Disable DMA done interrupts
//
HWREG(APPS_CONFIG_BASE + APPS_CONFIG_O_DMA_DONE_INT_MASK_SET) =
(ulIntFlags >> 30);
//
// Disable the individual interrupt sources
//
HWREG(ulBase + MMCHS_O_ISE) &= ~(ulIntFlags & 0x3FFFFFFF);
}
//*****************************************************************************
//
//! Gets the current interrupt status.
//!
//! \param ulBase is the base address of SDHost module.
//!
//! This function returns the interrupt status for the specified SDHost.
//!
//! \return Returns the current interrupt status, enumerated as a bit field of
//! values described in SDHostIntEnable().
//
//*****************************************************************************
unsigned long
SDHostIntStatus(unsigned long ulBase)
{
unsigned long ulIntStatus;
//
// Get DMA done interrupt status
//
ulIntStatus = HWREG(APPS_CONFIG_BASE + APPS_CONFIG_O_DMA_DONE_INT_STS_RAW);
ulIntStatus = (ulIntStatus << 30);
//
// Return the status of individual interrupt sources
//
ulIntStatus |= (HWREG(ulBase + MMCHS_O_STAT) & 0x3FFFFFFF);
return(ulIntStatus);
}
//*****************************************************************************
//
//! Clears the individual interrupt sources.
//!
//! \param ulBase is the base address of SDHost module.
//! \param ulIntFlags is a bit mask of the interrupt sources to be cleared.
//!
//! The specified SDHost interrupt sources are cleared, so that they no longer
//! assert. This function must be called in the interrupt handler to keep the
//! interrupt from being recognized again immediately upon exit.
//!
//! The \e ulIntFlags parameter has the same definition as the \e ulIntFlags
//! parameter to SDHostIntEnable().
//!
//! \return None.
//
//*****************************************************************************
void
SDHostIntClear(unsigned long ulBase,unsigned long ulIntFlags)
{
//
// Clear DMA done interrupts
//
HWREG(APPS_CONFIG_BASE + APPS_CONFIG_O_DMA_DONE_INT_ACK) =
(ulIntFlags >> 30);
//
// Clear the individual interrupt sources
//
HWREG(ulBase + MMCHS_O_STAT) = (ulIntFlags & 0x3FFFFFFF);
}
//*****************************************************************************
//
//! Sets the card status error mask.
//!
//! \param ulBase is the base address of SDHost module
//! \param ulErrMask is the bit mask of card status errors to be enabled
//!
//! This function sets the card status error mask for response type R1, R1b,
//! R5, R5b and R6 response. The parameter \e ulErrMask is the bit mask of card
//! status errors to be enabled, if the corresponding bits in the 'card status'
//! field of a respose are set then the host controller indicates a card error
//! interrupt status. Only bits referenced as type E (error) in status field in
//! the response can set a card status error.
//!
//! \return None
//
//*****************************************************************************
void
SDHostCardErrorMaskSet(unsigned long ulBase, unsigned long ulErrMask)
{
//
// Set the card status error mask
//
HWREG(ulBase + MMCHS_O_CSRE) = ulErrMask;
}
//*****************************************************************************
//
//! Gets the card status error mask.
//!
//! \param ulBase is the base address of SDHost module
//!
//! This function gets the card status error mask for response type R1, R1b,
//! R5, R5b and R6 response.
//!
//! \return Returns the current card status error.
//
//*****************************************************************************
unsigned long
SDHostCardErrorMaskGet(unsigned long ulBase)
{
//
// Return the card status error mask
//
return(HWREG(ulBase + MMCHS_O_CSRE));
}
//*****************************************************************************
//
//! Sets the SD Card clock.
//!
//! \param ulBase is the base address of SDHost module
//! \param ulSDHostClk is the rate of clock supplied to SDHost module
//! \param ulCardClk is the required SD interface clock
//!
//! This function configures the SDHost interface to supply the specified clock
//! to the connected card.
//!
//! \return None.
//
//*****************************************************************************
void
SDHostSetExpClk(unsigned long ulBase, unsigned long ulSDHostClk,
unsigned long ulCardClk)
{
unsigned long ulDiv;
//
// Disable card clock
//
HWREG(ulBase + MMCHS_O_SYSCTL) &= ~0x4;
//
// Enable internal clock
//
HWREG(ulBase + MMCHS_O_SYSCTL) |= 0x1;
ulDiv = ((ulSDHostClk/ulCardClk) & 0x3FF);
//
// Set clock divider,
//
HWREG(ulBase + MMCHS_O_SYSCTL) = ((HWREG(ulBase + MMCHS_O_SYSCTL) &
~0x0000FFC0)| (ulDiv) << 6);
//
// Wait for clock to stablize
//
while( !(HWREG(ulBase + MMCHS_O_SYSCTL) & 0x2) )
{
}
//
// Enable card clock
//
HWREG(ulBase + MMCHS_O_SYSCTL) |= 0x4;
}
//*****************************************************************************
//
//! Get the response for the last command.
//!
//! \param ulBase is the base address of SDHost module
//! \param ulRespnse is 128-bit response.
//!
//! This function gets the response from the SD card for the last command
//! send.
//!
//! \return None.
//
//*****************************************************************************
void
SDHostRespGet(unsigned long ulBase, unsigned long ulRespnse[4])
{
//
// Read the responses.
//
ulRespnse[0] = HWREG(ulBase + MMCHS_O_RSP10);
ulRespnse[1] = HWREG(ulBase + MMCHS_O_RSP32);
ulRespnse[2] = HWREG(ulBase + MMCHS_O_RSP54);
ulRespnse[3] = HWREG(ulBase + MMCHS_O_RSP76);
}
//*****************************************************************************
//
//! Set the block size for data transfer
//!
//! \param ulBase is the base address of SDHost module
//! \param ulBlkSize is the transfer block size in bytes
//!
//! This function sets the block size the data transfer.
//!
//! The parameter \e ulBlkSize is size of each data block in bytes.
//! This should be in range 0 - 2^10.
//!
//! \return None.
//
//*****************************************************************************
void
SDHostBlockSizeSet(unsigned long ulBase, unsigned short ulBlkSize)
{
//
// Set the block size
//
HWREG(ulBase + MMCHS_O_BLK) = ((HWREG(ulBase + MMCHS_O_BLK) & 0x00000FFF)|
(ulBlkSize & 0xFFF));
}
//*****************************************************************************
//
//! Set the block size and count for data transfer
//!
//! \param ulBase is the base address of SDHost module
//! \param ulBlkCount is the number of blocks
//!
//! This function sets block count for the data transfer. This needs to be set
//! for each block transfer. \sa SDHostBlockSizeSet()
//!
//! \return None.
//
//*****************************************************************************
void
SDHostBlockCountSet(unsigned long ulBase, unsigned short ulBlkCount)
{
unsigned long ulRegVal;
//
// Read the current value
//
ulRegVal = HWREG(ulBase + MMCHS_O_BLK);
//
// Set the number of blocks
//
HWREG(ulBase + MMCHS_O_BLK) = ((ulRegVal & 0x0000FFFF)|
(ulBlkCount << 16));
}
//*****************************************************************************
//
// Close the Doxygen group.
//! @}
//
//*****************************************************************************

204
driverlib/sdhost.h Normal file
View File

@ -0,0 +1,204 @@
//*****************************************************************************
//
// sdhost.h
//
// Defines and Macros for the SDHost.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#ifndef __SDHOST_H__
#define __SDHOST_H__
//*****************************************************************************
//
// If building with a C++ compiler, make all of the definitions in this header
// have a C binding.
//
//*****************************************************************************
#ifdef __cplusplus
extern "C"
//{
#endif
//*****************************************************************************
// Values that can be passed to SDHostRespGet().
//*****************************************************************************
#define SDHOST_RESP_10 0x00000003
#define SDHOST_RESP_32 0x00000002
#define SDHOST_RESP_54 0x00000001
#define SDHOST_RESP_76 0x00000000
//*****************************************************************************
// Values that can be passed to SDHostIntEnable(), SDHostIntDisable(),
// SDHostIntClear() ,and returned from SDHostIntStatus().
//*****************************************************************************
#define SDHOST_INT_CC 0x00000001
#define SDHOST_INT_TC 0x00000002
#define SDHOST_INT_BWR 0x00000010
#define SDHOST_INT_BRR 0x00000020
#define SDHOST_INT_ERRI 0x00008000
#define SDHOST_INT_CTO 0x00010000
#define SDHOST_INT_CEB 0x00040000
#define SDHOST_INT_DTO 0x00100000
#define SDHOST_INT_DCRC 0x00200000
#define SDHOST_INT_DEB 0x00400000
#define SDHOST_INT_CERR 0x10000000
#define SDHOST_INT_BADA 0x20000000
#define SDHOST_INT_DMARD 0x40000000
#define SDHOST_INT_DMAWR 0x80000000
//*****************************************************************************
// Values that can be passed to SDHostCmdSend().
//*****************************************************************************
#define SDHOST_CMD_0 0x00000000
#define SDHOST_CMD_1 0x01000000
#define SDHOST_CMD_2 0x02000000
#define SDHOST_CMD_3 0x03000000
#define SDHOST_CMD_4 0x04000000
#define SDHOST_CMD_5 0x05000000
#define SDHOST_CMD_6 0x06000000
#define SDHOST_CMD_7 0x07000000
#define SDHOST_CMD_8 0x08000000
#define SDHOST_CMD_9 0x09000000
#define SDHOST_CMD_10 0x0A000000
#define SDHOST_CMD_11 0x0B000000
#define SDHOST_CMD_12 0x0C000000
#define SDHOST_CMD_13 0x0D000000
#define SDHOST_CMD_14 0x0E000000
#define SDHOST_CMD_15 0x0F000000
#define SDHOST_CMD_16 0x10000000
#define SDHOST_CMD_17 0x11000000
#define SDHOST_CMD_18 0x12000000
#define SDHOST_CMD_19 0x13000000
#define SDHOST_CMD_20 0x14000000
#define SDHOST_CMD_21 0x15000000
#define SDHOST_CMD_22 0x16000000
#define SDHOST_CMD_23 0x17000000
#define SDHOST_CMD_24 0x18000000
#define SDHOST_CMD_25 0x19000000
#define SDHOST_CMD_26 0x1A000000
#define SDHOST_CMD_27 0x1B000000
#define SDHOST_CMD_28 0x1C000000
#define SDHOST_CMD_29 0x1D000000
#define SDHOST_CMD_30 0x1E000000
#define SDHOST_CMD_31 0x1F000000
#define SDHOST_CMD_32 0x20000000
#define SDHOST_CMD_33 0x21000000
#define SDHOST_CMD_34 0x22000000
#define SDHOST_CMD_35 0x23000000
#define SDHOST_CMD_36 0x24000000
#define SDHOST_CMD_37 0x25000000
#define SDHOST_CMD_38 0x26000000
#define SDHOST_CMD_39 0x27000000
#define SDHOST_CMD_40 0x28000000
#define SDHOST_CMD_41 0x29000000
#define SDHOST_CMD_42 0x2A000000
#define SDHOST_CMD_43 0x2B000000
#define SDHOST_CMD_44 0x2C000000
#define SDHOST_CMD_45 0x2D000000
#define SDHOST_CMD_46 0x2E000000
#define SDHOST_CMD_47 0x2F000000
#define SDHOST_CMD_48 0x30000000
#define SDHOST_CMD_49 0x31000000
#define SDHOST_CMD_50 0x32000000
#define SDHOST_CMD_51 0x33000000
#define SDHOST_CMD_52 0x34000000
#define SDHOST_CMD_53 0x35000000
#define SDHOST_CMD_54 0x36000000
#define SDHOST_CMD_55 0x37000000
#define SDHOST_CMD_56 0x38000000
#define SDHOST_CMD_57 0x39000000
#define SDHOST_CMD_58 0x3A000000
#define SDHOST_CMD_59 0x3B000000
#define SDHOST_CMD_60 0x3C000000
#define SDHOST_CMD_61 0x3D000000
#define SDHOST_CMD_62 0x3E000000
#define SDHOST_CMD_63 0x3F000000
//*****************************************************************************
// Values that can be logically ORed with ulCmd parameter for SDHostCmdSend().
//*****************************************************************************
#define SDHOST_MULTI_BLK 0x00000022
#define SDHOST_DMA_EN 0x00000001
#define SDHOST_WR_CMD 0x00200000
#define SDHOST_RD_CMD 0x00200010
#define SDHOST_RESP_LEN_136 0x00010000
#define SDHOST_RESP_LEN_48 0x00020000
#define SDHOST_RESP_LEN_48B 0x00030000
//*****************************************************************************
//
// API Function prototypes
//
//*****************************************************************************
extern void SDHostCmdReset(unsigned long ulBase);
extern void SDHostInit(unsigned long ulBase);
extern long SDHostCmdSend(unsigned long ulBase,unsigned long ulCmd,
unsigned ulArg);
extern void SDHostIntRegister(unsigned long ulBase, void (*pfnHandler)(void));
extern void SDHostIntUnregister(unsigned long ulBase);
extern void SDHostIntEnable(unsigned long ulBase,unsigned long ulIntFlags);
extern void SDHostIntDisable(unsigned long ulBase,unsigned long ulIntFlags);
extern unsigned long SDHostIntStatus(unsigned long ulBase);
extern void SDHostIntClear(unsigned long ulBase,unsigned long ulIntFlags);
extern void SDHostCardErrorMaskSet(unsigned long ulBase,
unsigned long ulErrMask);
extern unsigned long SDHostCardErrorMaskGet(unsigned long ulBase);
extern void SDHostSetExpClk(unsigned long ulBase, unsigned long ulSDHostClk,
unsigned long ulCardClk);
extern void SDHostRespGet(unsigned long ulBase, unsigned long ulRespnse[4]);
extern void SDHostBlockSizeSet(unsigned long ulBase, unsigned short ulBlkSize);
extern void SDHostBlockCountSet(unsigned long ulBase,
unsigned short ulBlkCount);
extern tBoolean SDHostDataNonBlockingWrite(unsigned long ulBase,
unsigned long ulData);
extern tBoolean SDHostDataNonBlockingRead(unsigned long ulBase,
unsigned long *pulData);
extern void SDHostDataWrite(unsigned long ulBase, unsigned long ulData);
extern void SDHostDataRead(unsigned long ulBase, unsigned long *ulData);
//*****************************************************************************
//
// Mark the end of the C bindings section for C++ compilers.
//
//*****************************************************************************
#ifdef __cplusplus
//}
#endif
#endif // __SDHOST_H__

1095
driverlib/shamd5.c Normal file

File diff suppressed because it is too large Load Diff

120
driverlib/shamd5.h Normal file
View File

@ -0,0 +1,120 @@
//*****************************************************************************
//
// shamd5.h
//
// Defines and Macros for the SHA/MD5.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#ifndef __DRIVERLIB_SHAMD5_H__
#define __DRIVERLIB_SHAMD5_H__
//*****************************************************************************
//
// If building with a C++ compiler, make all of the definitions in this header
// have a C binding.
//
//*****************************************************************************
#ifdef __cplusplus
extern "C"
{
#endif
//*****************************************************************************
//
// The following defines are used to specify the algorithm in use in the
// SHA/MD5 module.
//
//*****************************************************************************
#define SHAMD5_ALGO_MD5 0x00000018 // MD5
#define SHAMD5_ALGO_SHA1 0x0000001a // SHA-1
#define SHAMD5_ALGO_SHA224 0x0000001c // SHA-224
#define SHAMD5_ALGO_SHA256 0x0000001e // SHA-256
#define SHAMD5_ALGO_HMAC_MD5 0x00000000 // HMAC-MD5
#define SHAMD5_ALGO_HMAC_SHA1 0x00000002 // HMAC-SHA-1
#define SHAMD5_ALGO_HMAC_SHA224 0x00000004 // HMAC-SHA-224
#define SHAMD5_ALGO_HMAC_SHA256 0x00000006 // HMAC-SHA-256
//*****************************************************************************
//
// The following defines are used to represent the different interrupt sources
// in SHAMD5IntEnable(), SHAMD5IntDisable(), SHAMD5GetIntStatus(), and
// SHAMD5BlockOnIntStatus() functions.
//
//*****************************************************************************
#define SHAMD5_INT_CONTEXT_READY 0x00000008
#define SHAMD5_INT_PARTHASH_READY 0x00000004
#define SHAMD5_INT_INPUT_READY 0x00000002
#define SHAMD5_INT_OUTPUT_READY 0x00000001
#define SHAMD5_INT_DMA_CONTEXT_IN 0x00010000
#define SHAMD5_INT_DMA_DATA_IN 0x00020000
#define SHAMD5_INT_DMA_CONTEXT_OUT 0x00040000
//*****************************************************************************
//
// Function prototypes
//
//*****************************************************************************
extern void SHAMD5ConfigSet(uint32_t ui32Base, uint32_t ui32Mode);
extern bool SHAMD5DataProcess(uint32_t ui32Base, uint8_t *pui8DataSrc,
uint32_t ui32DataLength, uint8_t *pui8HashResult);
extern void SHAMD5DataWrite(uint32_t ui32Base, uint8_t *pui8Src);
extern bool SHAMD5DataWriteNonBlocking(uint32_t ui32Base, uint8_t *pui8Src);
extern void SHAMD5DMADisable(uint32_t ui32Base);
extern void SHAMD5DMAEnable(uint32_t ui32Base);
extern void SHAMD5DataLengthSet(uint32_t ui32Base, uint32_t ui32Length);
extern void SHAMD5HMACKeySet(uint32_t ui32Base, uint8_t *pui8Src);
extern void SHAMD5HMACPPKeyGenerate(uint32_t ui32Base, uint8_t *pui8Key,
uint8_t *pui8PPKey);
extern void SHAMD5HMACPPKeySet(uint32_t ui32Base, uint8_t *pui8Src);
extern bool SHAMD5HMACProcess(uint32_t ui32Base, uint8_t *pui8DataSrc,
uint32_t ui32DataLength, uint8_t *pui8HashResult);
extern void SHAMD5IntClear(uint32_t ui32Base, uint32_t ui32IntFlags);
extern void SHAMD5IntDisable(uint32_t ui32Base, uint32_t ui32IntFlags);
extern void SHAMD5IntEnable(uint32_t ui32Base, uint32_t ui32IntFlags);
extern void SHAMD5IntRegister(uint32_t ui32Base, void(*pfnHandler)(void));
extern uint32_t SHAMD5IntStatus(uint32_t ui32Base, bool bMasked);
extern void SHAMD5IntUnregister(uint32_t ui32Base);
extern void SHAMD5ResultRead(uint32_t ui32Base, uint8_t *pui8Dest);
//*****************************************************************************
//
// Mark the end of the C bindings section for C++ compilers.
//
//*****************************************************************************
#ifdef __cplusplus
}
#endif
#endif // __DRIVERLIB_SHAMD5_H__

1527
driverlib/spi.c Normal file

File diff suppressed because it is too large Load Diff

163
driverlib/spi.h Normal file
View File

@ -0,0 +1,163 @@
//*****************************************************************************
//
// spi.h
//
// Defines and Macros for the SPI.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#ifndef __SPI_H__
#define __SPI_H__
//*****************************************************************************
//
// If building with a C++ compiler, make all of the definitions in this header
// have a C binding.
//
//*****************************************************************************
#ifdef __cplusplus
extern "C"
{
#endif
//*****************************************************************************
// Values that can be passed to SPIConfigSetExpClk() as ulMode parameter
//*****************************************************************************
#define SPI_MODE_MASTER 0x00000000
#define SPI_MODE_SLAVE 0x00000004
//*****************************************************************************
// Values that can be passed to SPIConfigSetExpClk() as ulSubMode parameter
//*****************************************************************************
#define SPI_SUB_MODE_0 0x00000000
#define SPI_SUB_MODE_1 0x00000001
#define SPI_SUB_MODE_2 0x00000002
#define SPI_SUB_MODE_3 0x00000003
//*****************************************************************************
// Values that can be passed to SPIConfigSetExpClk() as ulConfigFlags parameter
//*****************************************************************************
#define SPI_SW_CTRL_CS 0x01000000
#define SPI_HW_CTRL_CS 0x00000000
#define SPI_3PIN_MODE 0x02000000
#define SPI_4PIN_MODE 0x00000000
#define SPI_TURBO_ON 0x00080000
#define SPI_TURBO_OFF 0x00000000
#define SPI_CS_ACTIVEHIGH 0x00000000
#define SPI_CS_ACTIVELOW 0x00000040
#define SPI_WL_8 0x00000380
#define SPI_WL_16 0x00000780
#define SPI_WL_32 0x00000F80
//*****************************************************************************
// Values that can be passed to SPIFIFOEnable() and SPIFIFODisable()
//*****************************************************************************
#define SPI_TX_FIFO 0x08000000
#define SPI_RX_FIFO 0x10000000
//*****************************************************************************
// Values that can be passed to SPIDMAEnable() and SPIDMADisable()
//*****************************************************************************
#define SPI_RX_DMA 0x00008000
#define SPI_TX_DMA 0x00004000
//*****************************************************************************
// Values that can be passed to SPIIntEnable(), SPIIntDiasble(),
// SPIIntClear() or returned from SPIStatus()
//*****************************************************************************
#define SPI_INT_DMATX 0x20000000
#define SPI_INT_DMARX 0x10000000
#define SPI_INT_EOW 0x00020000
#define SPI_INT_WKS 0x00010000
#define SPI_INT_RX_OVRFLOW 0x00000008
#define SPI_INT_RX_FULL 0x00000004
#define SPI_INT_TX_UDRFLOW 0x00000002
#define SPI_INT_TX_EMPTY 0x00000001
//*****************************************************************************
// Values that can be passed to SPITransfer()
//*****************************************************************************
#define SPI_CS_ENABLE 0x00000001
#define SPI_CS_DISABLE 0x00000002
//*****************************************************************************
//
// API Function prototypes
//
//*****************************************************************************
extern void SPIEnable(unsigned long ulBase);
extern void SPIDisable(unsigned long ulBase);
extern void SPIReset(unsigned long ulBase);
extern void SPIConfigSetExpClk(unsigned long ulBase,unsigned long ulSPIClk,
unsigned long ulBitRate, unsigned long ulMode,
unsigned long ulSubMode, unsigned long ulConfig);
extern long SPIDataGetNonBlocking(unsigned long ulBase,
unsigned long * pulData);
extern void SPIDataGet(unsigned long ulBase, unsigned long *pulData);
extern long SPIDataPutNonBlocking(unsigned long ulBase,
unsigned long ulData);
extern void SPIDataPut(unsigned long ulBase, unsigned long ulData);
extern void SPIFIFOEnable(unsigned long ulBase, unsigned long ulFlags);
extern void SPIFIFODisable(unsigned long ulBase, unsigned long ulFlags);
extern void SPIFIFOLevelSet(unsigned long ulBase, unsigned long ulTxLevel,
unsigned long ulRxLevel);
extern void SPIFIFOLevelGet(unsigned long ulBase, unsigned long *pulTxLevel,
unsigned long *pulRxLevel);
extern void SPIWordCountSet(unsigned long ulBase, unsigned long ulWordCount);
extern void SPIIntRegister(unsigned long ulBase, void(*pfnHandler)(void));
extern void SPIIntUnregister(unsigned long ulBase);
extern void SPIIntEnable(unsigned long ulBase, unsigned long ulIntFlags);
extern void SPIIntDisable(unsigned long ulBase, unsigned long ulIntFlags);
extern unsigned long SPIIntStatus(unsigned long ulBase, tBoolean bMasked);
extern void SPIIntClear(unsigned long ulBase, unsigned long ulIntFlags);
extern void SPIDmaEnable(unsigned long ulBase, unsigned long ulFlags);
extern void SPIDmaDisable(unsigned long ulBase, unsigned long ulFlags);
extern void SPICSEnable(unsigned long ulBase);
extern void SPICSDisable(unsigned long ulBase);
extern long SPITransfer(unsigned long ulBase, unsigned char *ucDout,
unsigned char *ucDin, unsigned long ulSize,
unsigned long ulFlags);
//*****************************************************************************
//
// Mark the end of the C bindings section for C++ compilers.
//
//*****************************************************************************
#ifdef __cplusplus
}
#endif
#endif // __SPI_H__

275
driverlib/systick.c Normal file
View File

@ -0,0 +1,275 @@
//*****************************************************************************
//
// systick.c
//
// Driver for the SysTick timer in NVIC.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
//*****************************************************************************
//
//! \addtogroup systick_api
//! @{
//
//*****************************************************************************
#include "inc/hw_ints.h"
#include "inc/hw_nvic.h"
#include "inc/hw_types.h"
#include "debug.h"
#include "interrupt.h"
#include "systick.h"
//*****************************************************************************
//
//! Enables the SysTick counter.
//!
//! This function starts the SysTick counter. If an interrupt handler has been
//! registered, it is called when the SysTick counter rolls over.
//!
//! \note Calling this function causes the SysTick counter to (re)commence
//! counting from its current value. The counter is not automatically reloaded
//! with the period as specified in a previous call to SysTickPeriodSet(). If
//! an immediate reload is required, the \b NVIC_ST_CURRENT register must be
//! written to force the reload. Any write to this register clears the SysTick
//! counter to 0 and causes a reload with the supplied period on the next
//! clock.
//!
//! \return None.
//
//*****************************************************************************
void
SysTickEnable(void)
{
//
// Enable SysTick.
//
HWREG(NVIC_ST_CTRL) |= NVIC_ST_CTRL_CLK_SRC | NVIC_ST_CTRL_ENABLE;
}
//*****************************************************************************
//
//! Disables the SysTick counter.
//!
//! This function stops the SysTick counter. If an interrupt handler has been
//! registered, it is not called until SysTick is restarted.
//!
//! \return None.
//
//*****************************************************************************
void
SysTickDisable(void)
{
//
// Disable SysTick.
//
HWREG(NVIC_ST_CTRL) &= ~(NVIC_ST_CTRL_ENABLE);
}
//*****************************************************************************
//
//! Registers an interrupt handler for the SysTick interrupt.
//!
//! \param pfnHandler is a pointer to the function to be called when the
//! SysTick interrupt occurs.
//!
//! This function registers the handler to be called when a SysTick interrupt
//! occurs.
//!
//! \sa IntRegister() for important information about registering interrupt
//! handlers.
//!
//! \return None.
//
//*****************************************************************************
void
SysTickIntRegister(void (*pfnHandler)(void))
{
//
// Register the interrupt handler, returning an error if an error occurs.
//
IntRegister(FAULT_SYSTICK, pfnHandler);
//
// Enable the SysTick interrupt.
//
HWREG(NVIC_ST_CTRL) |= NVIC_ST_CTRL_INTEN;
}
//*****************************************************************************
//
//! Unregisters the interrupt handler for the SysTick interrupt.
//!
//! This function unregisters the handler to be called when a SysTick interrupt
//! occurs.
//!
//! \sa IntRegister() for important information about registering interrupt
//! handlers.
//!
//! \return None.
//
//*****************************************************************************
void
SysTickIntUnregister(void)
{
//
// Disable the SysTick interrupt.
//
HWREG(NVIC_ST_CTRL) &= ~(NVIC_ST_CTRL_INTEN);
//
// Unregister the interrupt handler.
//
IntUnregister(FAULT_SYSTICK);
}
//*****************************************************************************
//
//! Enables the SysTick interrupt.
//!
//! This function enables the SysTick interrupt, allowing it to be
//! reflected to the processor.
//!
//! \note The SysTick interrupt handler is not required to clear the SysTick
//! interrupt source because it is cleared automatically by the NVIC when the
//! interrupt handler is called.
//!
//! \return None.
//
//*****************************************************************************
void
SysTickIntEnable(void)
{
//
// Enable the SysTick interrupt.
//
HWREG(NVIC_ST_CTRL) |= NVIC_ST_CTRL_INTEN;
}
//*****************************************************************************
//
//! Disables the SysTick interrupt.
//!
//! This function disables the SysTick interrupt, preventing it from being
//! reflected to the processor.
//!
//! \return None.
//
//*****************************************************************************
void
SysTickIntDisable(void)
{
//
// Disable the SysTick interrupt.
//
HWREG(NVIC_ST_CTRL) &= ~(NVIC_ST_CTRL_INTEN);
}
//*****************************************************************************
//
//! Sets the period of the SysTick counter.
//!
//! \param ulPeriod is the number of clock ticks in each period of the SysTick
//! counter and must be between 1 and 16,777,216, inclusive.
//!
//! This function sets the rate at which the SysTick counter wraps, which
//! equates to the number of processor clocks between interrupts.
//!
//! \note Calling this function does not cause the SysTick counter to reload
//! immediately. If an immediate reload is required, the \b NVIC_ST_CURRENT
//! register must be written. Any write to this register clears the SysTick
//! counter to 0 and causes a reload with the \e ulPeriod supplied here on
//! the next clock after SysTick is enabled.
//!
//! \return None.
//
//*****************************************************************************
void
SysTickPeriodSet(unsigned long ulPeriod)
{
//
// Check the arguments.
//
ASSERT((ulPeriod > 0) && (ulPeriod <= 16777216));
//
// Set the period of the SysTick counter.
//
HWREG(NVIC_ST_RELOAD) = ulPeriod - 1;
}
//*****************************************************************************
//
//! Gets the period of the SysTick counter.
//!
//! This function returns the rate at which the SysTick counter wraps, which
//! equates to the number of processor clocks between interrupts.
//!
//! \return Returns the period of the SysTick counter.
//
//*****************************************************************************
unsigned long
SysTickPeriodGet(void)
{
//
// Return the period of the SysTick counter.
//
return(HWREG(NVIC_ST_RELOAD) + 1);
}
//*****************************************************************************
//
//! Gets the current value of the SysTick counter.
//!
//! This function returns the current value of the SysTick counter, which is
//! a value between the period - 1 and zero, inclusive.
//!
//! \return Returns the current value of the SysTick counter.
//
//*****************************************************************************
unsigned long
SysTickValueGet(void)
{
//
// Return the current value of the SysTick counter.
//
return(HWREG(NVIC_ST_CURRENT));
}
//*****************************************************************************
//
// Close the Doxygen group.
//! @}
//
//*****************************************************************************

78
driverlib/systick.h Normal file
View File

@ -0,0 +1,78 @@
//*****************************************************************************
//
// systick.h
//
// Prototypes for the SysTick driver.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#ifndef __SYSTICK_H__
#define __SYSTICK_H__
//*****************************************************************************
//
// If building with a C++ compiler, make all of the definitions in this header
// have a C binding.
//
//*****************************************************************************
#ifdef __cplusplus
extern "C"
{
#endif
//*****************************************************************************
//
// Prototypes for the APIs.
//
//*****************************************************************************
extern void SysTickEnable(void);
extern void SysTickDisable(void);
extern void SysTickIntRegister(void (*pfnHandler)(void));
extern void SysTickIntUnregister(void);
extern void SysTickIntEnable(void);
extern void SysTickIntDisable(void);
extern void SysTickPeriodSet(unsigned long ulPeriod);
extern unsigned long SysTickPeriodGet(void);
extern unsigned long SysTickValueGet(void);
//*****************************************************************************
//
// Mark the end of the C bindings section for C++ compilers.
//
//*****************************************************************************
#ifdef __cplusplus
}
#endif
#endif // __SYSTICK_H__

1103
driverlib/timer.c Normal file

File diff suppressed because it is too large Load Diff

210
driverlib/timer.h Normal file
View File

@ -0,0 +1,210 @@
//*****************************************************************************
//
// timer.h
//
// Prototypes for the timer module
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#ifndef __TIMER_H__
#define __TIMER_H__
//*****************************************************************************
//
// If building with a C++ compiler, make all of the definitions in this header
// have a C binding.
//
//*****************************************************************************
#ifdef __cplusplus
extern "C"
{
#endif
//*****************************************************************************
//
// Values that can be passed to TimerConfigure as the ulConfig parameter.
//
//*****************************************************************************
#define TIMER_CFG_ONE_SHOT 0x00000021 // Full-width one-shot timer
#define TIMER_CFG_ONE_SHOT_UP 0x00000031 // Full-width one-shot up-count
// timer
#define TIMER_CFG_PERIODIC 0x00000022 // Full-width periodic timer
#define TIMER_CFG_PERIODIC_UP 0x00000032 // Full-width periodic up-count
// timer
#define TIMER_CFG_SPLIT_PAIR 0x04000000 // Two half-width timers
#define TIMER_CFG_A_ONE_SHOT 0x00000021 // Timer A one-shot timer
#define TIMER_CFG_A_ONE_SHOT_UP 0x00000031 // Timer A one-shot up-count timer
#define TIMER_CFG_A_PERIODIC 0x00000022 // Timer A periodic timer
#define TIMER_CFG_A_PERIODIC_UP 0x00000032 // Timer A periodic up-count timer
#define TIMER_CFG_A_CAP_COUNT 0x00000003 // Timer A event counter
#define TIMER_CFG_A_CAP_COUNT_UP 0x00000013 // Timer A event up-counter
#define TIMER_CFG_A_CAP_TIME 0x00000007 // Timer A event timer
#define TIMER_CFG_A_CAP_TIME_UP 0x00000017 // Timer A event up-count timer
#define TIMER_CFG_A_PWM 0x0000000A // Timer A PWM output
#define TIMER_CFG_B_ONE_SHOT 0x00002100 // Timer B one-shot timer
#define TIMER_CFG_B_ONE_SHOT_UP 0x00003100 // Timer B one-shot up-count timer
#define TIMER_CFG_B_PERIODIC 0x00002200 // Timer B periodic timer
#define TIMER_CFG_B_PERIODIC_UP 0x00003200 // Timer B periodic up-count timer
#define TIMER_CFG_B_CAP_COUNT 0x00000300 // Timer B event counter
#define TIMER_CFG_B_CAP_COUNT_UP 0x00001300 // Timer B event up-counter
#define TIMER_CFG_B_CAP_TIME 0x00000700 // Timer B event timer
#define TIMER_CFG_B_CAP_TIME_UP 0x00001700 // Timer B event up-count timer
#define TIMER_CFG_B_PWM 0x00000A00 // Timer B PWM output
//*****************************************************************************
//
// Values that can be passed to TimerIntEnable, TimerIntDisable, and
// TimerIntClear as the ulIntFlags parameter, and returned from TimerIntStatus.
//
//*****************************************************************************
#define TIMER_TIMB_DMA 0x00002000 // TimerB DMA Done interrupt
#define TIMER_TIMB_MATCH 0x00000800 // TimerB match interrupt
#define TIMER_CAPB_EVENT 0x00000400 // CaptureB event interrupt
#define TIMER_CAPB_MATCH 0x00000200 // CaptureB match interrupt
#define TIMER_TIMB_TIMEOUT 0x00000100 // TimerB time out interrupt
#define TIMER_TIMA_DMA 0x00000020 // TimerA DMA Done interrupt
#define TIMER_TIMA_MATCH 0x00000010 // TimerA match interrupt
#define TIMER_CAPA_EVENT 0x00000004 // CaptureA event interrupt
#define TIMER_CAPA_MATCH 0x00000002 // CaptureA match interrupt
#define TIMER_TIMA_TIMEOUT 0x00000001 // TimerA time out interrupt
//*****************************************************************************
//
// Values that can be passed to TimerControlEvent as the ulEvent parameter.
//
//*****************************************************************************
#define TIMER_EVENT_POS_EDGE 0x00000000 // Count positive edges
#define TIMER_EVENT_NEG_EDGE 0x00000404 // Count negative edges
#define TIMER_EVENT_BOTH_EDGES 0x00000C0C // Count both edges
//*****************************************************************************
//
// Values that can be passed to most of the timer APIs as the ulTimer
// parameter.
//
//*****************************************************************************
#define TIMER_A 0x000000ff // Timer A
#define TIMER_B 0x0000ff00 // Timer B
#define TIMER_BOTH 0x0000ffff // Timer Both
//*****************************************************************************
//
// Values that can be passed to TimerSynchronize as the ulTimers parameter.
//
//*****************************************************************************
#define TIMER_0A_SYNC 0x00000001 // Synchronize Timer 0A
#define TIMER_0B_SYNC 0x00000002 // Synchronize Timer 0B
#define TIMER_1A_SYNC 0x00000004 // Synchronize Timer 1A
#define TIMER_1B_SYNC 0x00000008 // Synchronize Timer 1B
#define TIMER_2A_SYNC 0x00000010 // Synchronize Timer 2A
#define TIMER_2B_SYNC 0x00000020 // Synchronize Timer 2B
#define TIMER_3A_SYNC 0x00000040 // Synchronize Timer 3A
#define TIMER_3B_SYNC 0x00000080 // Synchronize Timer 3B
//*****************************************************************************
//
// Values that can be passed to TimerDMAEventSet() or returned from
// TimerDMAEventGet().
//
//*****************************************************************************
#define TIMER_DMA_MODEMATCH_B 0x00000800
#define TIMER_DMA_CAPEVENT_B 0x00000400
#define TIMER_DMA_CAPMATCH_B 0x00000200
#define TIMER_DMA_TIMEOUT_B 0x00000100
#define TIMER_DMA_MODEMATCH_A 0x00000010
#define TIMER_DMA_CAPEVENT_A 0x00000004
#define TIMER_DMA_CAPMATCH_A 0x00000002
#define TIMER_DMA_TIMEOUT_A 0x00000001
//*****************************************************************************
//
// Prototypes for the APIs.
//
//*****************************************************************************
extern void TimerEnable(unsigned long ulBase, unsigned long ulTimer);
extern void TimerDisable(unsigned long ulBase, unsigned long ulTimer);
extern void TimerConfigure(unsigned long ulBase, unsigned long ulConfig);
extern void TimerControlLevel(unsigned long ulBase, unsigned long ulTimer,
tBoolean bInvert);
extern void TimerControlEvent(unsigned long ulBase, unsigned long ulTimer,
unsigned long ulEvent);
extern void TimerControlStall(unsigned long ulBase, unsigned long ulTimer,
tBoolean bStall);
extern void TimerPrescaleSet(unsigned long ulBase, unsigned long ulTimer,
unsigned long ulValue);
extern unsigned long TimerPrescaleGet(unsigned long ulBase,
unsigned long ulTimer);
extern void TimerPrescaleMatchSet(unsigned long ulBase, unsigned long ulTimer,
unsigned long ulValue);
extern unsigned long TimerPrescaleMatchGet(unsigned long ulBase,
unsigned long ulTimer);
extern void TimerLoadSet(unsigned long ulBase, unsigned long ulTimer,
unsigned long ulValue);
extern unsigned long TimerLoadGet(unsigned long ulBase, unsigned long ulTimer);
extern unsigned long TimerValueGet(unsigned long ulBase,
unsigned long ulTimer);
extern void TimerValueSet(unsigned long ulBase, unsigned long ulTimer,
unsigned long ulValue);
extern void TimerMatchSet(unsigned long ulBase, unsigned long ulTimer,
unsigned long ulValue);
extern unsigned long TimerMatchGet(unsigned long ulBase,
unsigned long ulTimer);
extern void TimerIntRegister(unsigned long ulBase, unsigned long ulTimer,
void (*pfnHandler)(void));
extern void TimerIntUnregister(unsigned long ulBase, unsigned long ulTimer);
extern void TimerIntEnable(unsigned long ulBase, unsigned long ulIntFlags);
extern void TimerIntDisable(unsigned long ulBase, unsigned long ulIntFlags);
extern unsigned long TimerIntStatus(unsigned long ulBase, tBoolean bMasked);
extern void TimerIntClear(unsigned long ulBase, unsigned long ulIntFlags);
extern void TimerDMAEventSet(unsigned long ulBase, unsigned long ulDMAEvent);
extern unsigned long TimerDMAEventGet(unsigned long ulBase);
//*****************************************************************************
//
// Mark the end of the C bindings section for C++ compilers.
//
//*****************************************************************************
#ifdef __cplusplus
}
#endif
#endif // __TIMER_H__

1506
driverlib/uart.c Normal file

File diff suppressed because it is too large Load Diff

234
driverlib/uart.h Normal file
View File

@ -0,0 +1,234 @@
//*****************************************************************************
//
// uart.h
//
// Defines and Macros for the UART.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#ifndef __UART_H__
#define __UART_H__
//*****************************************************************************
//
// If building with a C++ compiler, make all of the definitions in this header
// have a C binding.
//
//*****************************************************************************
#ifdef __cplusplus
extern "C"
{
#endif
//*****************************************************************************
//
// Values that can be passed to UARTIntEnable, UARTIntDisable, and UARTIntClear
// as the ulIntFlags parameter, and returned from UARTIntStatus.
//
//*****************************************************************************
#define UART_INT_DMATX 0x20000 // DMA Tx Done interrupt Mask
#define UART_INT_DMARX 0x10000 // DMA Rx Done interrupt Mask
#define UART_INT_EOT 0x800 // End of transfer interrupt Mask
#define UART_INT_OE 0x400 // Overrun Error Interrupt Mask
#define UART_INT_BE 0x200 // Break Error Interrupt Mask
#define UART_INT_PE 0x100 // Parity Error Interrupt Mask
#define UART_INT_FE 0x080 // Framing Error Interrupt Mask
#define UART_INT_RT 0x040 // Receive Timeout Interrupt Mask
#define UART_INT_TX 0x020 // Transmit Interrupt Mask
#define UART_INT_RX 0x010 // Receive Interrupt Mask
#define UART_INT_CTS 0x002 // CTS Modem Interrupt Mask
//*****************************************************************************
//
// Values that can be passed to UARTConfigSetExpClk as the ulConfig parameter
// and returned by UARTConfigGetExpClk in the pulConfig parameter.
// Additionally, the UART_CONFIG_PAR_* subset can be passed to
// UARTParityModeSet as the ulParity parameter, and are returned by
// UARTParityModeGet.
//
//*****************************************************************************
#define UART_CONFIG_WLEN_MASK 0x00000060 // Mask for extracting word length
#define UART_CONFIG_WLEN_8 0x00000060 // 8 bit data
#define UART_CONFIG_WLEN_7 0x00000040 // 7 bit data
#define UART_CONFIG_WLEN_6 0x00000020 // 6 bit data
#define UART_CONFIG_WLEN_5 0x00000000 // 5 bit data
#define UART_CONFIG_STOP_MASK 0x00000008 // Mask for extracting stop bits
#define UART_CONFIG_STOP_ONE 0x00000000 // One stop bit
#define UART_CONFIG_STOP_TWO 0x00000008 // Two stop bits
#define UART_CONFIG_PAR_MASK 0x00000086 // Mask for extracting parity
#define UART_CONFIG_PAR_NONE 0x00000000 // No parity
#define UART_CONFIG_PAR_EVEN 0x00000006 // Even parity
#define UART_CONFIG_PAR_ODD 0x00000002 // Odd parity
#define UART_CONFIG_PAR_ONE 0x00000082 // Parity bit is one
#define UART_CONFIG_PAR_ZERO 0x00000086 // Parity bit is zero
//*****************************************************************************
//
// Values that can be passed to UARTFIFOLevelSet as the ulTxLevel parameter and
// returned by UARTFIFOLevelGet in the pulTxLevel.
//
//*****************************************************************************
#define UART_FIFO_TX1_8 0x00000000 // Transmit interrupt at 1/8 Full
#define UART_FIFO_TX2_8 0x00000001 // Transmit interrupt at 1/4 Full
#define UART_FIFO_TX4_8 0x00000002 // Transmit interrupt at 1/2 Full
#define UART_FIFO_TX6_8 0x00000003 // Transmit interrupt at 3/4 Full
#define UART_FIFO_TX7_8 0x00000004 // Transmit interrupt at 7/8 Full
//*****************************************************************************
//
// Values that can be passed to UARTFIFOLevelSet as the ulRxLevel parameter and
// returned by UARTFIFOLevelGet in the pulRxLevel.
//
//*****************************************************************************
#define UART_FIFO_RX1_8 0x00000000 // Receive interrupt at 1/8 Full
#define UART_FIFO_RX2_8 0x00000008 // Receive interrupt at 1/4 Full
#define UART_FIFO_RX4_8 0x00000010 // Receive interrupt at 1/2 Full
#define UART_FIFO_RX6_8 0x00000018 // Receive interrupt at 3/4 Full
#define UART_FIFO_RX7_8 0x00000020 // Receive interrupt at 7/8 Full
//*****************************************************************************
//
// Values that can be passed to UARTDMAEnable() and UARTDMADisable().
//
//*****************************************************************************
#define UART_DMA_ERR_RXSTOP 0x00000004 // Stop DMA receive if UART error
#define UART_DMA_TX 0x00000002 // Enable DMA for transmit
#define UART_DMA_RX 0x00000001 // Enable DMA for receive
//*****************************************************************************
//
// Values returned from UARTRxErrorGet().
//
//*****************************************************************************
#define UART_RXERROR_OVERRUN 0x00000008
#define UART_RXERROR_BREAK 0x00000004
#define UART_RXERROR_PARITY 0x00000002
#define UART_RXERROR_FRAMING 0x00000001
//*****************************************************************************
//
// Values that can be passed to UARTModemControlSet()and UARTModemControlClear()
// or returned from UARTModemControlGet().
//
//*****************************************************************************
#define UART_OUTPUT_RTS 0x00000800
//*****************************************************************************
//
// Values that can be returned from UARTModemStatusGet().
//
//*****************************************************************************
#define UART_INPUT_CTS 0x00000001
//*****************************************************************************
//
// Values that can be passed to UARTFlowControl() or returned from
// UARTFlowControlGet().
//
//*****************************************************************************
#define UART_FLOWCONTROL_TX 0x00008000
#define UART_FLOWCONTROL_RX 0x00004000
#define UART_FLOWCONTROL_NONE 0x00000000
//*****************************************************************************
//
// Values that can be passed to UARTTxIntModeSet() or returned from
// UARTTxIntModeGet().
//
//*****************************************************************************
#define UART_TXINT_MODE_FIFO 0x00000000
#define UART_TXINT_MODE_EOT 0x00000010
//*****************************************************************************
//
// API Function prototypes
//
//*****************************************************************************
extern void UARTParityModeSet(unsigned long ulBase, unsigned long ulParity);
extern unsigned long UARTParityModeGet(unsigned long ulBase);
extern void UARTFIFOLevelSet(unsigned long ulBase, unsigned long ulTxLevel,
unsigned long ulRxLevel);
extern void UARTFIFOLevelGet(unsigned long ulBase, unsigned long *pulTxLevel,
unsigned long *pulRxLevel);
extern void UARTConfigSetExpClk(unsigned long ulBase, unsigned long ulUARTClk,
unsigned long ulBaud, unsigned long ulConfig);
extern void UARTConfigGetExpClk(unsigned long ulBase, unsigned long ulUARTClk,
unsigned long *pulBaud,
unsigned long *pulConfig);
extern void UARTEnable(unsigned long ulBase);
extern void UARTDisable(unsigned long ulBase);
extern void UARTFIFOEnable(unsigned long ulBase);
extern void UARTFIFODisable(unsigned long ulBase);
extern tBoolean UARTCharsAvail(unsigned long ulBase);
extern tBoolean UARTSpaceAvail(unsigned long ulBase);
extern long UARTCharGetNonBlocking(unsigned long ulBase);
extern long UARTCharGet(unsigned long ulBase);
extern tBoolean UARTCharPutNonBlocking(unsigned long ulBase,
unsigned char ucData);
extern void UARTCharPut(unsigned long ulBase, unsigned char ucData);
extern void UARTBreakCtl(unsigned long ulBase, tBoolean bBreakState);
extern tBoolean UARTBusy(unsigned long ulBase);
extern void UARTIntRegister(unsigned long ulBase, void(*pfnHandler)(void));
extern void UARTIntUnregister(unsigned long ulBase);
extern void UARTIntEnable(unsigned long ulBase, unsigned long ulIntFlags);
extern void UARTIntDisable(unsigned long ulBase, unsigned long ulIntFlags);
extern unsigned long UARTIntStatus(unsigned long ulBase, tBoolean bMasked);
extern void UARTIntClear(unsigned long ulBase, unsigned long ulIntFlags);
extern void UARTDMAEnable(unsigned long ulBase, unsigned long ulDMAFlags);
extern void UARTDMADisable(unsigned long ulBase, unsigned long ulDMAFlags);
extern unsigned long UARTRxErrorGet(unsigned long ulBase);
extern void UARTRxErrorClear(unsigned long ulBase);
extern void UARTModemControlSet(unsigned long ulBase,
unsigned long ulControl);
extern void UARTModemControlClear(unsigned long ulBase,
unsigned long ulControl);
extern unsigned long UARTModemControlGet(unsigned long ulBase);
extern unsigned long UARTModemStatusGet(unsigned long ulBase);
extern void UARTFlowControlSet(unsigned long ulBase, unsigned long ulMode);
extern unsigned long UARTFlowControlGet(unsigned long ulBase);
extern void UARTTxIntModeSet(unsigned long ulBase, unsigned long ulMode);
extern unsigned long UARTTxIntModeGet(unsigned long ulBase);
//*****************************************************************************
//
// Mark the end of the C bindings section for C++ compilers.
//
//*****************************************************************************
#ifdef __cplusplus
}
#endif
#endif // __UART_H__

1254
driverlib/udma.c Normal file

File diff suppressed because it is too large Load Diff

663
driverlib/udma.h Normal file
View File

@ -0,0 +1,663 @@
//*****************************************************************************
//
// udma.h
//
// Prototypes and macros for the uDMA controller.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#ifndef __UDMA_H__
#define __UDMA_H__
//*****************************************************************************
//
// If building with a C++ compiler, make all of the definitions in this header
// have a C binding.
//
//*****************************************************************************
#ifdef __cplusplus
extern "C"
{
#endif
//*****************************************************************************
//
//! \addtogroup uDMA_Micro_Direct_Memory_Access_api
//! @{
//
//*****************************************************************************
//*****************************************************************************
//
// A structure that defines an entry in the channel control table. These
// fields are used by the uDMA controller and normally it is not necessary for
// software to directly read or write fields in the table.
//
//*****************************************************************************
typedef struct
{
//
// The ending source address of the data transfer.
//
volatile void *pvSrcEndAddr;
//
// The ending destination address of the data transfer.
//
volatile void *pvDstEndAddr;
//
// The channel control mode.
//
volatile unsigned long ulControl;
//
// An unused location.
//
volatile unsigned long ulSpare;
}
tDMAControlTable;
//*****************************************************************************
//
//! A helper macro for building scatter-gather task table entries.
//!
//! \param ulTransferCount is the count of items to transfer for this task.
//! \param ulItemSize is the bit size of the items to transfer for this task.
//! \param ulSrcIncrement is the bit size increment for source data.
//! \param pvSrcAddr is the starting address of the data to transfer.
//! \param ulDstIncrement is the bit size increment for destination data.
//! \param pvDstAddr is the starting address of the destination data.
//! \param ulArbSize is the arbitration size to use for the transfer task.
//! \param ulMode is the transfer mode for this task.
//!
//! This macro is intended to be used to help populate a table of uDMA tasks
//! for a scatter-gather transfer. This macro will calculate the values for
//! the fields of a task structure entry based on the input parameters.
//!
//! There are specific requirements for the values of each parameter. No
//! checking is done so it is up to the caller to ensure that correct values
//! are used for the parameters.
//!
//! The \e ulTransferCount parameter is the number of items that will be
//! transferred by this task. It must be in the range 1-1024.
//!
//! The \e ulItemSize parameter is the bit size of the transfer data. It must
//! be one of \b UDMA_SIZE_8, \b UDMA_SIZE_16, or \b UDMA_SIZE_32.
//!
//! The \e ulSrcIncrement parameter is the increment size for the source data.
//! It must be one of \b UDMA_SRC_INC_8, \b UDMA_SRC_INC_16,
//! \b UDMA_SRC_INC_32, or \b UDMA_SRC_INC_NONE.
//!
//! The \e pvSrcAddr parameter is a void pointer to the beginning of the source
//! data.
//!
//! The \e ulDstIncrement parameter is the increment size for the destination
//! data. It must be one of \b UDMA_DST_INC_8, \b UDMA_DST_INC_16,
//! \b UDMA_DST_INC_32, or \b UDMA_DST_INC_NONE.
//!
//! The \e pvDstAddr parameter is a void pointer to the beginning of the
//! location where the data will be transferred.
//!
//! The \e ulArbSize parameter is the arbitration size for the transfer, and
//! must be one of \b UDMA_ARB_1, \b UDMA_ARB_2, \b UDMA_ARB_4, and so on
//! up to \b UDMA_ARB_1024. This is used to select the arbitration size in
//! powers of 2, from 1 to 1024.
//!
//! The \e ulMode parameter is the mode to use for this transfer task. It
//! must be one of \b UDMA_MODE_BASIC, \b UDMA_MODE_AUTO,
//! \b UDMA_MODE_MEM_SCATTER_GATHER, or \b UDMA_MODE_PER_SCATTER_GATHER. Note
//! that normally all tasks will be one of the scatter-gather modes while the
//! last task is a task list will be AUTO or BASIC.
//!
//! This macro is intended to be used to initialize individual entries of
//! a structure of tDMAControlTable type, like this:
//!
//! \verbatim
//! tDMAControlTable MyTaskList[] =
//! {
//! uDMATaskStructEntry(Task1Count, UDMA_SIZE_8,
//! UDMA_SRC_INC_8, MySourceBuf,
//! UDMA_DST_INC_8, MyDestBuf,
//! UDMA_ARB_8, UDMA_MODE_MEM_SCATTER_GATHER),
//! uDMATaskStructEntry(Task2Count, ... ),
//! }
//! \endverbatim
//!
//! \return Nothing; this is not a function.
//
//*****************************************************************************
#define uDMATaskStructEntry(ulTransferCount, \
ulItemSize, \
ulSrcIncrement, \
pvSrcAddr, \
ulDstIncrement, \
pvDstAddr, \
ulArbSize, \
ulMode) \
{ \
(((ulSrcIncrement) == UDMA_SRC_INC_NONE) ? (void *)(pvSrcAddr) : \
((void *)(&((unsigned char *)(pvSrcAddr))[((ulTransferCount) << \
((ulSrcIncrement) >> 26)) - 1]))), \
(((ulDstIncrement) == UDMA_DST_INC_NONE) ? (void *)(pvDstAddr) : \
((void *)(&((unsigned char *)(pvDstAddr))[((ulTransferCount) << \
((ulDstIncrement) >> 30)) - 1]))), \
(ulSrcIncrement) | (ulDstIncrement) | (ulItemSize) | (ulArbSize) | \
(((ulTransferCount) - 1) << 4) | \
((((ulMode) == UDMA_MODE_MEM_SCATTER_GATHER) || \
((ulMode) == UDMA_MODE_PER_SCATTER_GATHER)) ? \
(ulMode) | UDMA_MODE_ALT_SELECT : (ulMode)), 0 \
}
//*****************************************************************************
//
// Close the Doxygen group.
//! @}
//
//*****************************************************************************
//*****************************************************************************
//
// Flags that can be passed to uDMAChannelAttributeEnable(),
// uDMAChannelAttributeDisable(), and returned from uDMAChannelAttributeGet().
//
//*****************************************************************************
#define UDMA_ATTR_USEBURST 0x00000001
#define UDMA_ATTR_ALTSELECT 0x00000002
#define UDMA_ATTR_HIGH_PRIORITY 0x00000004
#define UDMA_ATTR_REQMASK 0x00000008
#define UDMA_ATTR_ALL 0x0000000F
//*****************************************************************************
//
// DMA control modes that can be passed to uDMAModeSet() and returned
// uDMAModeGet().
//
//*****************************************************************************
#define UDMA_MODE_STOP 0x00000000
#define UDMA_MODE_BASIC 0x00000001
#define UDMA_MODE_AUTO 0x00000002
#define UDMA_MODE_PINGPONG 0x00000003
#define UDMA_MODE_MEM_SCATTER_GATHER \
0x00000004
#define UDMA_MODE_PER_SCATTER_GATHER \
0x00000006
#define UDMA_MODE_ALT_SELECT 0x00000001
//*****************************************************************************
//
// Flags to be OR'd with the channel ID to indicate if the primary or alternate
// control structure should be used.
//
//*****************************************************************************
#define UDMA_PRI_SELECT 0x00000000
#define UDMA_ALT_SELECT 0x00000020
//*****************************************************************************
//
// uDMA interrupt sources, to be passed to uDMAIntRegister() and
// uDMAIntUnregister().
//
//*****************************************************************************
#define UDMA_INT_SW INT_UDMA
#define UDMA_INT_ERR INT_UDMAERR
//*****************************************************************************
//*****************************************************************************
//
// Channel configuration values that can be passed to uDMAControlSet().
//
//*****************************************************************************
#define UDMA_DST_INC_8 0x00000000
#define UDMA_DST_INC_16 0x40000000
#define UDMA_DST_INC_32 0x80000000
#define UDMA_DST_INC_NONE 0xc0000000
#define UDMA_SRC_INC_8 0x00000000
#define UDMA_SRC_INC_16 0x04000000
#define UDMA_SRC_INC_32 0x08000000
#define UDMA_SRC_INC_NONE 0x0c000000
#define UDMA_SIZE_8 0x00000000
#define UDMA_SIZE_16 0x11000000
#define UDMA_SIZE_32 0x22000000
#define UDMA_ARB_1 0x00000000
#define UDMA_ARB_2 0x00004000
#define UDMA_ARB_4 0x00008000
#define UDMA_ARB_8 0x0000c000
#define UDMA_ARB_16 0x00010000
#define UDMA_ARB_32 0x00014000
#define UDMA_ARB_64 0x00018000
#define UDMA_ARB_128 0x0001c000
#define UDMA_ARB_256 0x00020000
#define UDMA_ARB_512 0x00024000
#define UDMA_ARB_1024 0x00028000
#define UDMA_NEXT_USEBURST 0x00000008
//*****************************************************************************
//
// Values that can be passed to uDMAChannelAssign() to select peripheral
// mapping for each channel. The channels named RESERVED may be assigned
// to a peripheral in future parts.
//
//*****************************************************************************
//
// Channel 0
//
#define UDMA_CH0_TIMERA0_A 0x00000000
#define UDMA_CH0_SHAMD5_CIN 0x00010000
#define UDMA_CH0_SW 0x00030000
//
// Channel 1
//
#define UDMA_CH1_TIMERA0_B 0x00000001
#define UDMA_CH1_SHAMD5_DIN 0x00010001
#define UDMA_CH1_SW 0x00030001
//
// Channel 2
//
#define UDMA_CH2_TIMERA1_A 0x00000002
#define UDMA_CH2_SHAMD5_COUT 0x00010002
#define UDMA_CH2_SW 0x00030002
//
// Channel 3
//
#define UDMA_CH3_TIMERA1_B 0x00000003
#define UDMA_CH3_DES_CIN 0x00010003
#define UDMA_CH3_SW 0x00030003
//
// Channel 4
//
#define UDMA_CH4_TIMERA2_A 0x00000004
#define UDMA_CH4_DES_DIN 0x00010004
#define UDMA_CH4_I2S_RX 0x00020004
#define UDMA_CH4_SW 0x00030004
//
// Channel 5
//
#define UDMA_CH5_TIMERA2_B 0x00000005
#define UDMA_CH5_DES_DOUT 0x00010005
#define UDMA_CH5_I2S_TX 0x00020005
#define UDMA_CH5_SW 0x00030005
//
// Channel 6
//
#define UDMA_CH6_TIMERA3_A 0x00000006
#define UDMA_CH6_GSPI_RX 0x00010006
#define UDMA_CH6_GPIOA2 0x00020006
#define UDMA_CH6_SW 0x00030006
//
// Channel 7
//
#define UDMA_CH7_TIMERA3_B 0x00000007
#define UDMA_CH7_GSPI_TX 0x00010007
#define UDMA_CH7_GPIOA3 0x00020007
#define UDMA_CH7_SW 0x00030007
//
// Channel 8
//
#define UDMA_CH8_UARTA0_RX 0x00000008
#define UDMA_CH8_TIMERA0_A 0x00010008
#define UDMA_CH8_TIMERA2_A 0x00020008
#define UDMA_CH8_SW 0x00030008
//
// Channel 9
//
#define UDMA_CH9_UARTA0_TX 0x00000009
#define UDMA_CH9_TIMERA0_B 0x00010009
#define UDMA_CH9_TIMERA2_B 0x00020009
#define UDMA_CH9_SW 0x00030009
//
// Channel 10
//
#define UDMA_CH10_UARTA1_RX 0x0000000A
#define UDMA_CH10_TIMERA1_A 0x0001000A
#define UDMA_CH10_TIMERA3_A 0x0002000A
#define UDMA_CH10_SW 0x0003000A
//
// Channel 11
//
#define UDMA_CH11_UARTA1_TX 0x0000000B
#define UDMA_CH11_TIMERA1_B 0x0001000B
#define UDMA_CH11_TIMERA3_B 0x0002000B
#define UDMA_CH11_SW 0x0003000B
//
// Channel 12
//
#define UDMA_CH12_LSPI_RX 0x0000000C
#define UDMA_CH12_SW 0x0003000C
//
// Channel 13
//
#define UDMA_CH13_LSPI_TX 0x0000000D
#define UDMA_CH13_SW 0x0003000D
//
// Channel 14
//
#define UDMA_CH14_ADC_CH0 0x0000000E
#define UDMA_CH14_SDHOST_RX 0x0002000E
#define UDMA_CH14_SW 0x0003000E
//
// Channel 15
//
#define UDMA_CH15_ADC_CH1 0x0000000F
#define UDMA_CH15_SDHOST_TX 0x0002000F
#define UDMA_CH15_SW 0x0003000F
//
// Channel 16
//
#define UDMA_CH16_ADC_CH2 0x00000010
#define UDMA_CH16_TIMERA2_A 0x00010010
#define UDMA_CH16_SW 0x00030010
//
// Channel 17
//
#define UDMA_CH17_ADC_CH3 0x00000011
#define UDMA_CH17_TIMERA2_B 0x00010011
#define UDMA_CH17_SW 0x00030011
//
// Channel 18
//
#define UDMA_CH18_GPIOA0 0x00000012
#define UDMA_CH18_AES_CIN 0x00010012
#define UDMA_CH18_I2S_RX 0x00020012
#define UDMA_CH18_SW 0x00030012
//
// Channel 19
//
#define UDMA_CH19_GPOIA1 0x00000013
#define UDMA_CH19_AES_COUT 0x00010013
#define UDMA_CH19_I2S_TX 0x00020013
#define UDMA_CH19_SW 0x00030013
//
// Channel 20
//
#define UDMA_CH20_GPIOA2 0x00000014
#define UDMA_CH20_AES_DIN 0x00010014
#define UDMA_CH20_SW 0x00030014
//
// Channel 21
//
#define UDMA_CH21_GPIOA3 0x00000015
#define UDMA_CH21_AES_DOUT 0x00010015
#define UDMA_CH21_SW 0x00030015
//
// Channel 22
//
#define UDMA_CH22_CAMERA 0x00000016
#define UDMA_CH22_GPIOA4 0x00010016
#define UDMA_CH22_SW 0x00030016
//
// Channel 23
//
#define UDMA_CH23_SDHOST_RX 0x00000017
#define UDMA_CH23_TIMERA3_A 0x00010017
#define UDMA_CH23_TIMERA2_A 0x00020017
#define UDMA_CH23_SW 0x00030017
//
// Channel 24
//
#define UDMA_CH24_SDHOST_TX 0x00000018
#define UDMA_CH24_TIMERA3_B 0x00010018
#define UDMA_CH24_TIMERA2_B 0x00020018
#define UDMA_CH24_SW 0x00030018
//
// Channel 25
//
#define UDMA_CH25_SSPI_RX 0x00000019
#define UDMA_CH25_I2CA0_RX 0x00010019
#define UDMA_CH25_SW 0x00030019
//
// Channel 26
//
#define UDMA_CH26_SSPI_TX 0x0000001A
#define UDMA_CH26_I2CA0_TX 0x0001001A
#define UDMA_CH26_SW 0x0003001A
//
// Channel 27
//
#define UDMA_CH27_GPIOA0 0x0001001B
#define UDMA_CH27_SW 0x0003001B
//
// Channel 28
//
#define UDMA_CH28_GPIOA1 0x0001001C
#define UDMA_CH28_SW 0x0003001C
//
// Channel 29
//
#define UDMA_CH29_GPIOA4 0x0000001D
#define UDMA_CH29_SW 0x0003001D
//
// Channel 30
//
#define UDMA_CH30_GSPI_RX 0x0000001E
#define UDMA_CH30_SDHOST_RX 0x0001001E
#define UDMA_CH30_I2CA0_RX 0x0002001E
#define UDMA_CH30_SW 0x0003001E
//
// Channel 31
//
#define UDMA_CH31_GSPI_TX 0x0000001F
#define UDMA_CH31_SDHOST_TX 0x0001001F
#define UDMA_CH31_I2CA0_RX 0x0002001F
#define UDMA_CH31_SW 0x0003001F
//*****************************************************************************
//
// The following are defines for the Micro Direct Memory Access (uDMA) offsets.
//
//*****************************************************************************
#define UDMA_O_SRCENDP 0x00000000 // DMA Channel Source Address End
// Pointer
#define UDMA_O_DSTENDP 0x00000004 // DMA Channel Destination Address
// End Pointer
#define UDMA_O_CHCTL 0x00000008 // DMA Channel Control Word
//*****************************************************************************
//
// The following are defines for the bit fields in the UDMA_O_SRCENDP register.
//
//*****************************************************************************
#define UDMA_SRCENDP_ADDR_M 0xFFFFFFFF // Source Address End Pointer
#define UDMA_SRCENDP_ADDR_S 0
//*****************************************************************************
//
// The following are defines for the bit fields in the UDMA_O_DSTENDP register.
//
//*****************************************************************************
#define UDMA_DSTENDP_ADDR_M 0xFFFFFFFF // Destination Address End Pointer
#define UDMA_DSTENDP_ADDR_S 0
//*****************************************************************************
//
// The following are defines for the bit fields in the UDMA_O_CHCTL register.
//
//*****************************************************************************
#define UDMA_CHCTL_DSTINC_M 0xC0000000 // Destination Address Increment
#define UDMA_CHCTL_DSTINC_8 0x00000000 // Byte
#define UDMA_CHCTL_DSTINC_16 0x40000000 // Half-word
#define UDMA_CHCTL_DSTINC_32 0x80000000 // Word
#define UDMA_CHCTL_DSTINC_NONE 0xC0000000 // No increment
#define UDMA_CHCTL_DSTSIZE_M 0x30000000 // Destination Data Size
#define UDMA_CHCTL_DSTSIZE_8 0x00000000 // Byte
#define UDMA_CHCTL_DSTSIZE_16 0x10000000 // Half-word
#define UDMA_CHCTL_DSTSIZE_32 0x20000000 // Word
#define UDMA_CHCTL_SRCINC_M 0x0C000000 // Source Address Increment
#define UDMA_CHCTL_SRCINC_8 0x00000000 // Byte
#define UDMA_CHCTL_SRCINC_16 0x04000000 // Half-word
#define UDMA_CHCTL_SRCINC_32 0x08000000 // Word
#define UDMA_CHCTL_SRCINC_NONE 0x0C000000 // No increment
#define UDMA_CHCTL_SRCSIZE_M 0x03000000 // Source Data Size
#define UDMA_CHCTL_SRCSIZE_8 0x00000000 // Byte
#define UDMA_CHCTL_SRCSIZE_16 0x01000000 // Half-word
#define UDMA_CHCTL_SRCSIZE_32 0x02000000 // Word
#define UDMA_CHCTL_ARBSIZE_M 0x0003C000 // Arbitration Size
#define UDMA_CHCTL_ARBSIZE_1 0x00000000 // 1 Transfer
#define UDMA_CHCTL_ARBSIZE_2 0x00004000 // 2 Transfers
#define UDMA_CHCTL_ARBSIZE_4 0x00008000 // 4 Transfers
#define UDMA_CHCTL_ARBSIZE_8 0x0000C000 // 8 Transfers
#define UDMA_CHCTL_ARBSIZE_16 0x00010000 // 16 Transfers
#define UDMA_CHCTL_ARBSIZE_32 0x00014000 // 32 Transfers
#define UDMA_CHCTL_ARBSIZE_64 0x00018000 // 64 Transfers
#define UDMA_CHCTL_ARBSIZE_128 0x0001C000 // 128 Transfers
#define UDMA_CHCTL_ARBSIZE_256 0x00020000 // 256 Transfers
#define UDMA_CHCTL_ARBSIZE_512 0x00024000 // 512 Transfers
#define UDMA_CHCTL_ARBSIZE_1024 0x00028000 // 1024 Transfers
#define UDMA_CHCTL_XFERSIZE_M 0x00003FF0 // Transfer Size (minus 1)
#define UDMA_CHCTL_NXTUSEBURST 0x00000008 // Next Useburst
#define UDMA_CHCTL_XFERMODE_M 0x00000007 // uDMA Transfer Mode
#define UDMA_CHCTL_XFERMODE_STOP \
0x00000000 // Stop
#define UDMA_CHCTL_XFERMODE_BASIC \
0x00000001 // Basic
#define UDMA_CHCTL_XFERMODE_AUTO \
0x00000002 // Auto-Request
#define UDMA_CHCTL_XFERMODE_PINGPONG \
0x00000003 // Ping-Pong
#define UDMA_CHCTL_XFERMODE_MEM_SG \
0x00000004 // Memory Scatter-Gather
#define UDMA_CHCTL_XFERMODE_MEM_SGA \
0x00000005 // Alternate Memory Scatter-Gather
#define UDMA_CHCTL_XFERMODE_PER_SG \
0x00000006 // Peripheral Scatter-Gather
#define UDMA_CHCTL_XFERMODE_PER_SGA \
0x00000007 // Alternate Peripheral
// Scatter-Gather
#define UDMA_CHCTL_XFERSIZE_S 4
//*****************************************************************************
//
// API Function prototypes
//
//*****************************************************************************
extern void uDMAEnable(void);
extern void uDMADisable(void);
extern unsigned long uDMAErrorStatusGet(void);
extern void uDMAErrorStatusClear(void);
extern void uDMAChannelEnable(unsigned long ulChannelNum);
extern void uDMAChannelDisable(unsigned long ulChannelNum);
extern tBoolean uDMAChannelIsEnabled(unsigned long ulChannelNum);
extern void uDMAControlBaseSet(void *pControlTable);
extern void *uDMAControlBaseGet(void);
extern void *uDMAControlAlternateBaseGet(void);
extern void uDMAChannelRequest(unsigned long ulChannelNum);
extern void uDMAChannelAttributeEnable(unsigned long ulChannelNum,
unsigned long ulAttr);
extern void uDMAChannelAttributeDisable(unsigned long ulChannelNum,
unsigned long ulAttr);
extern unsigned long uDMAChannelAttributeGet(unsigned long ulChannelNum);
extern void uDMAChannelControlSet(unsigned long ulChannelStructIndex,
unsigned long ulControl);
extern void uDMAChannelTransferSet(unsigned long ulChannelStructIndex,
unsigned long ulMode, void *pvSrcAddr,
void *pvDstAddr,
unsigned long ulTransferSize);
extern void uDMAChannelScatterGatherSet(unsigned long ulChannelNum,
unsigned ulTaskCount, void *pvTaskList,
unsigned long ulIsPeriphSG);
extern unsigned long uDMAChannelSizeGet(unsigned long ulChannelStructIndex);
extern unsigned long uDMAChannelModeGet(unsigned long ulChannelStructIndex);
extern void uDMAIntRegister(unsigned long ulIntChannel,
void (*pfnHandler)(void));
extern void uDMAIntUnregister(unsigned long ulIntChannel);
extern unsigned long uDMAIntStatus(void);
extern void uDMAIntClear(unsigned long ulChanMask);
extern void uDMAChannelAssign(unsigned long ulMapping);
//*****************************************************************************
//
// Mark the end of the C bindings section for C++ compilers.
//
//*****************************************************************************
#ifdef __cplusplus
}
#endif
#endif // __UDMA_H__

104
driverlib/utils.c Normal file
View File

@ -0,0 +1,104 @@
//*****************************************************************************
//
// utils.c
//
// Utility APIs
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
//*****************************************************************************
//
//! \addtogroup Utils_api
//! @{
//
//*****************************************************************************
#include "utils.h"
//*****************************************************************************
//
//! Provides a small delay.
//!
//! \param ulCount is the number of delay loop iterations to perform.
//!
//! This function provides a means of generating a constant length delay. It
//! is written in assembly to keep the delay consistent across tool chains,
//! avoiding the need to tune the delay based on the tool chain in use.
//!
//! The loop takes 3 cycles/loop.
//!
//! \return None.
//
//*****************************************************************************
#if defined(ewarm) || defined(DOXYGEN)
void
UtilsDelay(unsigned long ulCount)
{
__asm(" subs r0, #1\n"
" bne.n UtilsDelay\n");
}
#endif
#if defined(gcc)
void __attribute__((naked))
UtilsDelay(unsigned long ulCount)
{
__asm(" subs r0, #1\n"
" bne UtilsDelay\n"
" bx lr");
}
#endif
//
// For CCS implement this function in pure assembly. This prevents the TI
// compiler from doing funny things with the optimizer.
//
#if defined(ccs)
__asm(" .sect \".text:UtilsDelay\"\n"
" .clink\n"
" .thumbfunc UtilsDelay\n"
" .thumb\n"
" .global UtilsDelay\n"
"UtilsDelay:\n"
" subs r0, #1\n"
" bne.n UtilsDelay\n"
" bx lr\n");
#endif
//*****************************************************************************
//
// Close the Doxygen group.
//! @}
//
//*****************************************************************************

71
driverlib/utils.h Normal file
View File

@ -0,0 +1,71 @@
//*****************************************************************************
//
// utils.h
//
// Prototypes and macros for utility APIs
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#ifndef __UTILS_H__
#define __UTILS_H__
//*****************************************************************************
//
// If building with a C++ compiler, make all of the definitions in this header
// have a C binding.
//
//*****************************************************************************
#ifdef __cplusplus
extern "C"
{
#endif
//*****************************************************************************
//
// API Function prototypes
//
//*****************************************************************************
extern void UtilsDelay(unsigned long ulCount);
//*****************************************************************************
//
// Mark the end of the C bindings section for C++ compilers.
//
//*****************************************************************************
#ifdef __cplusplus
}
#endif
#endif //__UTILS_H__

71
driverlib/version.h Normal file
View File

@ -0,0 +1,71 @@
//*****************************************************************************
//
// version.h
//
// Contains Driverlib version details
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#ifndef __DRIVERLIB_VERSION_H__
#define __DRIVERLIB_VERSION_H__
//*****************************************************************************
//
// If building with a C++ compiler, make all of the definitions in this header
// have a C binding.
//
//*****************************************************************************
#ifdef __cplusplus
extern "C"
{
#endif
#define DRIVERLIB_MAJOR_VERSION_NUM 1
#define DRIVERLIB_MINOR_VERSION_NUM 2
#define DRIVERLIB_SUBMINOR_VERSION_NUM 0
#define DRIVERLIB_RELEASE_DAY 17
#define DRIVERLIB_RELEASE_MONTH 2
#define DRIVERLIB_RELEASE_YEAR 2016
//*****************************************************************************
//
// Mark the end of the C bindings section for C++ compilers.
//
//*****************************************************************************
#ifdef __cplusplus
}
#endif
#endif // __DRIVERLIB_VERSION_H__

491
driverlib/wdt.c Normal file
View File

@ -0,0 +1,491 @@
//*****************************************************************************
//
// wdt.c
//
// Driver for the Watchdog Timer Module.
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
//*****************************************************************************
//
//! \addtogroup WDT_Watchdog_Timer_api
//! @{
//
//*****************************************************************************
#include "inc/hw_ints.h"
#include "inc/hw_memmap.h"
#include "inc/hw_types.h"
#include "inc/hw_wdt.h"
#include "debug.h"
#include "interrupt.h"
#include "wdt.h"
//*****************************************************************************
//
//! Determines if the watchdog timer is enabled.
//!
//! \param ulBase is the base address of the watchdog timer module.
//!
//! This will check to see if the watchdog timer is enabled.
//!
//! \return Returns \b true if the watchdog timer is enabled, and \b false
//! if it is not.
//
//*****************************************************************************
tBoolean
WatchdogRunning(unsigned long ulBase)
{
//
// Check the arguments.
//
ASSERT((ulBase == WDT_BASE));
//
// See if the watchdog timer module is enabled, and return.
//
return(HWREG(ulBase + WDT_O_CTL) & WDT_CTL_INTEN);
}
//*****************************************************************************
//
//! Enables the watchdog timer.
//!
//! \param ulBase is the base address of the watchdog timer module.
//!
//! This will enable the watchdog timer counter and interrupt.
//!
//! \note This function will have no effect if the watchdog timer has
//! been locked.
//!
//! \sa WatchdogLock(), WatchdogUnlock()
//!
//! \return None.
//
//*****************************************************************************
void
WatchdogEnable(unsigned long ulBase)
{
//
// Check the arguments.
//
ASSERT((ulBase == WDT_BASE));
//
// Enable the watchdog timer module.
//
HWREG(ulBase + WDT_O_CTL) |= WDT_CTL_INTEN;
}
//*****************************************************************************
//
//! Enables the watchdog timer lock mechanism.
//!
//! \param ulBase is the base address of the watchdog timer module.
//!
//! Locks out write access to the watchdog timer configuration registers.
//!
//! \return None.
//
//*****************************************************************************
void
WatchdogLock(unsigned long ulBase)
{
//
// Check the arguments.
//
ASSERT((ulBase == WDT_BASE));
//
// Lock out watchdog register writes. Writing anything to the WDT_O_LOCK
// register causes the lock to go into effect.
//
HWREG(ulBase + WDT_O_LOCK) = WDT_LOCK_LOCKED;
}
//*****************************************************************************
//
//! Disables the watchdog timer lock mechanism.
//!
//! \param ulBase is the base address of the watchdog timer module.
//!
//! Enables write access to the watchdog timer configuration registers.
//!
//! \return None.
//
//*****************************************************************************
void
WatchdogUnlock(unsigned long ulBase)
{
//
// Check the arguments.
//
ASSERT((ulBase == WDT_BASE));
//
// Unlock watchdog register writes.
//
HWREG(ulBase + WDT_O_LOCK) = WDT_LOCK_UNLOCK;
}
//*****************************************************************************
//
//! Gets the state of the watchdog timer lock mechanism.
//!
//! \param ulBase is the base address of the watchdog timer module.
//!
//! Returns the lock state of the watchdog timer registers.
//!
//! \return Returns \b true if the watchdog timer registers are locked, and
//! \b false if they are not locked.
//
//*****************************************************************************
tBoolean
WatchdogLockState(unsigned long ulBase)
{
//
// Check the arguments.
//
ASSERT((ulBase == WDT_BASE));
//
// Get the lock state.
//
return((HWREG(ulBase + WDT_O_LOCK) == WDT_LOCK_LOCKED) ? true : false);
}
//*****************************************************************************
//
//! Sets the watchdog timer reload value.
//!
//! \param ulBase is the base address of the watchdog timer module.
//! \param ulLoadVal is the load value for the watchdog timer.
//!
//! This function sets the value to load into the watchdog timer when the count
//! reaches zero for the first time; if the watchdog timer is running when this
//! function is called, then the value will be immediately loaded into the
//! watchdog timer counter. If the \e ulLoadVal parameter is 0, then an
//! interrupt is immediately generated.
//!
//! \note This function will have no effect if the watchdog timer has
//! been locked.
//!
//! \sa WatchdogLock(), WatchdogUnlock(), WatchdogReloadGet()
//!
//! \return None.
//
//*****************************************************************************
void
WatchdogReloadSet(unsigned long ulBase, unsigned long ulLoadVal)
{
//
// Check the arguments.
//
ASSERT((ulBase == WDT_BASE));
//
// Set the load register.
//
HWREG(ulBase + WDT_O_LOAD) = ulLoadVal;
}
//*****************************************************************************
//
//! Gets the watchdog timer reload value.
//!
//! \param ulBase is the base address of the watchdog timer module.
//!
//! This function gets the value that is loaded into the watchdog timer when
//! the count reaches zero for the first time.
//!
//! \sa WatchdogReloadSet()
//!
//! \return None.
//
//*****************************************************************************
unsigned long
WatchdogReloadGet(unsigned long ulBase)
{
//
// Check the arguments.
//
ASSERT((ulBase == WDT_BASE));
//
// Get the load register.
//
return(HWREG(ulBase + WDT_O_LOAD));
}
//*****************************************************************************
//
//! Gets the current watchdog timer value.
//!
//! \param ulBase is the base address of the watchdog timer module.
//!
//! This function reads the current value of the watchdog timer.
//!
//! \return Returns the current value of the watchdog timer.
//
//*****************************************************************************
unsigned long
WatchdogValueGet(unsigned long ulBase)
{
//
// Check the arguments.
//
ASSERT((ulBase == WDT_BASE));
//
// Get the current watchdog timer register value.
//
return(HWREG(ulBase + WDT_O_VALUE));
}
//*****************************************************************************
//
//! Registers an interrupt handler for watchdog timer interrupt.
//!
//! \param ulBase is the base address of the watchdog timer module.
//! \param pfnHandler is a pointer to the function to be called when the
//! watchdog timer interrupt occurs.
//!
//! This function does the actual registering of the interrupt handler. This
//! will enable the global interrupt in the interrupt controller; the watchdog
//! timer interrupt must be enabled via WatchdogEnable(). It is the interrupt
//! handler's responsibility to clear the interrupt source via
//! WatchdogIntClear().
//!
//! \sa IntRegister() for important information about registering interrupt
//! handlers.
//!
//! \note This function will only register the standard watchdog interrupt
//! handler. To register the NMI watchdog handler, use IntRegister()
//! to register the handler for the \b FAULT_NMI interrupt.
//!
//! \return None.
//
//*****************************************************************************
void
WatchdogIntRegister(unsigned long ulBase, void (*pfnHandler)(void))
{
//
// Check the arguments.
//
ASSERT((ulBase == WDT_BASE));
//
// Register the interrupt handler and
// Enable the watchdog timer interrupt.
//
IntRegister(INT_WDT, pfnHandler);
IntEnable(INT_WDT);
}
//*****************************************************************************
//
//! Unregisters an interrupt handler for the watchdog timer interrupt.
//!
//! \param ulBase is the base address of the watchdog timer module.
//!
//! This function does the actual unregistering of the interrupt handler. This
//! function will clear the handler to be called when a watchdog timer
//! interrupt occurs. This will also mask off the interrupt in the interrupt
//! controller so that the interrupt handler no longer is called.
//!
//! \sa IntRegister() for important information about registering interrupt
//! handlers.
//!
//! \note This function will only unregister the standard watchdog interrupt
//! handler. To unregister the NMI watchdog handler, use IntUnregister()
//! to unregister the handler for the \b FAULT_NMI interrupt.
//!
//! \return None.
//
//*****************************************************************************
void
WatchdogIntUnregister(unsigned long ulBase)
{
//
// Check the arguments.
//
ASSERT((ulBase == WDT_BASE));
//
// Disable the interrupt
IntDisable(INT_WDT);
//
// Unregister the interrupt handler.
//
IntUnregister(INT_WDT);
}
//*****************************************************************************
//
//! Gets the current watchdog timer interrupt status.
//!
//! \param ulBase is the base address of the watchdog timer module.
//! \param bMasked is \b false if the raw interrupt status is required and
//! \b true if the masked interrupt status is required.
//!
//! This returns the interrupt status for the watchdog timer module. Either
//! the raw interrupt status or the status of interrupt that is allowed to
//! reflect to the processor can be returned.
//!
//! \return Returns the current interrupt status, where a 1 indicates that the
//! watchdog interrupt is active, and a 0 indicates that it is not active.
//
//*****************************************************************************
unsigned long
WatchdogIntStatus(unsigned long ulBase, tBoolean bMasked)
{
//
// Check the arguments.
//
ASSERT((ulBase == WDT_BASE));
//
// Return either the interrupt status or the raw interrupt status as
// requested.
//
if(bMasked)
{
return(HWREG(ulBase + WDT_O_MIS));
}
else
{
return(HWREG(ulBase + WDT_O_RIS));
}
}
//*****************************************************************************
//
//! Clears the watchdog timer interrupt.
//!
//! \param ulBase is the base address of the watchdog timer module.
//!
//! The watchdog timer interrupt source is cleared, so that it no longer
//! asserts.
//!
//! \note Because there is a write buffer in the Cortex-M3 processor, it may
//! take several clock cycles before the interrupt source is actually cleared.
//! Therefore, it is recommended that the interrupt source be cleared early in
//! the interrupt handler (as opposed to the very last action) to avoid
//! returning from the interrupt handler before the interrupt source is
//! actually cleared. Failure to do so may result in the interrupt handler
//! being immediately reentered (because the interrupt controller still sees
//! the interrupt source asserted).
//!
//! \return None.
//
//*****************************************************************************
void
WatchdogIntClear(unsigned long ulBase)
{
//
// Check the arguments.
//
ASSERT((ulBase == WDT_BASE));
//
// Clear the interrupt source.
//
HWREG(ulBase + WDT_O_ICR) = WDT_INT_TIMEOUT;
}
//*****************************************************************************
//
//! Enables stalling of the watchdog timer during debug events.
//!
//! \param ulBase is the base address of the watchdog timer module.
//!
//! This function allows the watchdog timer to stop counting when the processor
//! is stopped by the debugger. By doing so, the watchdog is prevented from
//! expiring (typically almost immediately from a human time perspective) and
//! resetting the system (if reset is enabled). The watchdog will instead
//! expired after the appropriate number of processor cycles have been executed
//! while debugging (or at the appropriate time after the processor has been
//! restarted).
//!
//! \return None.
//
//*****************************************************************************
void
WatchdogStallEnable(unsigned long ulBase)
{
//
// Check the arguments.
//
ASSERT((ulBase == WDT_BASE));
//
// Enable timer stalling.
//
HWREG(ulBase + WDT_O_TEST) |= WDT_TEST_STALL;
}
//*****************************************************************************
//
//! Disables stalling of the watchdog timer during debug events.
//!
//! \param ulBase is the base address of the watchdog timer module.
//!
//! This function disables the debug mode stall of the watchdog timer. By
//! doing so, the watchdog timer continues to count regardless of the processor
//! debug state.
//!
//! \return None.
//
//*****************************************************************************
void
WatchdogStallDisable(unsigned long ulBase)
{
//
// Check the arguments.
//
ASSERT((ulBase == WDT_BASE));
//
// Disable timer stalling.
//
HWREG(ulBase + WDT_O_TEST) &= ~(WDT_TEST_STALL);
}
//*****************************************************************************
//
// Close the Doxygen group.
//! @}
//
//*****************************************************************************

82
driverlib/wdt.h Normal file
View File

@ -0,0 +1,82 @@
//*****************************************************************************
//
// wdt.h - Prototypes for the Watchdog Timer API
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#ifndef __WATCHDOG_H__
#define __WATCHDOG_H__
//*****************************************************************************
//
// If building with a C++ compiler, make all of the definitions in this header
// have a C binding.
//
//*****************************************************************************
#ifdef __cplusplus
extern "C"
{
#endif
//*****************************************************************************
//
// Prototypes for the APIs.
//
//*****************************************************************************
extern tBoolean WatchdogRunning(unsigned long ulBase);
extern void WatchdogEnable(unsigned long ulBase);
extern void WatchdogLock(unsigned long ulBase);
extern void WatchdogUnlock(unsigned long ulBase);
extern tBoolean WatchdogLockState(unsigned long ulBase);
extern void WatchdogReloadSet(unsigned long ulBase, unsigned long ulLoadVal);
extern unsigned long WatchdogReloadGet(unsigned long ulBase);
extern unsigned long WatchdogValueGet(unsigned long ulBase);
extern void WatchdogIntRegister(unsigned long ulBase, void(*pfnHandler)(void));
extern void WatchdogIntUnregister(unsigned long ulBase);
extern unsigned long WatchdogIntStatus(unsigned long ulBase, tBoolean bMasked);
extern void WatchdogIntClear(unsigned long ulBase);
extern void WatchdogStallEnable(unsigned long ulBase);
extern void WatchdogStallDisable(unsigned long ulBase);
//*****************************************************************************
//
// Mark the end of the C bindings section for C++ compilers.
//
//*****************************************************************************
#ifdef __cplusplus
}
#endif
#endif // __WATCHDOG_H__

9
gdbinit Normal file
View File

@ -0,0 +1,9 @@
target remote | openocd -c "gdb_port pipe; log_output openocd.log" -f board/ti_cc3200_launchxl.cfg
load
set $sp = g_pfnVectors[0]
set $pc = g_pfnVectors[1]
break main
continue

53
gnu.ld Normal file
View File

@ -0,0 +1,53 @@
HEAP_SIZE = 0x00010000;
MEMORY
{
/* SRAM size of 240KB for cc3200 ES 1.33 device onward */
SRAM (rwx) : ORIGIN = 0x20004000, LENGTH = 0x3C000
}
SECTIONS
{
.text :
{
_text = .;
KEEP(*(.intvecs))
*(.text*)
*(.rodata*)
*(.ARM.extab* .gnu.linkonce.armextab.*)
. = ALIGN(8);
_etext = .;
} > SRAM
.ARM : {
__exidx_start = .;
*(.ARM.exidx*)
__exidx_end = .;
} > SRAM
__init_data = .;
.data : AT(__init_data)
{
_data = .;
*(.data*)
. = ALIGN (8);
_edata = .;
} > SRAM
.bss :
{
_bss = .;
*(.bss*)
*(COMMON)
_ebss = .;
} > SRAM
.heap :
{
_heap = .;
. = . + HEAP_SIZE;
. = ALIGN(8);
_eheap = .;
}
}

229
inc/asmdefs.h Normal file
View File

@ -0,0 +1,229 @@
//*****************************************************************************
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
//*****************************************************************************
//
// asmdefs.h - Macros to allow assembly code be portable among toolchains.
//
//*****************************************************************************
#ifndef __ASMDEFS_H__
#define __ASMDEFS_H__
//*****************************************************************************
//
// The defines required for code_red.
//
//*****************************************************************************
#ifdef codered
//
// The assembly code preamble required to put the assembler into the correct
// configuration.
//
.syntax unified
.thumb
//
// Section headers.
//
#define __LIBRARY__ @
#define __TEXT__ .text
#define __DATA__ .data
#define __BSS__ .bss
#define __TEXT_NOROOT__ .text
//
// Assembler nmenonics.
//
#define __ALIGN__ .balign 4
#define __END__ .end
#define __EXPORT__ .globl
#define __IMPORT__ .extern
#define __LABEL__ :
#define __STR__ .ascii
#define __THUMB_LABEL__ .thumb_func
#define __WORD__ .word
#define __INLINE_DATA__
#endif // codered
//*****************************************************************************
//
// The defines required for EW-ARM.
//
//*****************************************************************************
#ifdef ewarm
//
// Section headers.
//
#define __LIBRARY__ module
#define __TEXT__ rseg CODE:CODE(2)
#define __DATA__ rseg DATA:DATA(2)
#define __BSS__ rseg DATA:DATA(2)
#define __TEXT_NOROOT__ rseg CODE:CODE:NOROOT(2)
//
// Assembler nmenonics.
//
#define __ALIGN__ alignrom 2
#define __END__ end
#define __EXPORT__ export
#define __IMPORT__ import
#define __LABEL__
#define __STR__ dcb
#define __THUMB_LABEL__ thumb
#define __WORD__ dcd
#define __INLINE_DATA__ data
#endif // ewarm
//*****************************************************************************
//
// The defines required for GCC.
//
//*****************************************************************************
#if defined(gcc)
//
// The assembly code preamble required to put the assembler into the correct
// configuration.
//
.syntax unified
.thumb
//
// Section headers.
//
#define __LIBRARY__ @
#define __TEXT__ .text
#define __DATA__ .data
#define __BSS__ .bss
#define __TEXT_NOROOT__ .text
//
// Assembler nmenonics.
//
#define __ALIGN__ .balign 4
#define __END__ .end
#define __EXPORT__ .globl
#define __IMPORT__ .extern
#define __LABEL__ :
#define __STR__ .ascii
#define __THUMB_LABEL__ .thumb_func
#define __WORD__ .word
#define __INLINE_DATA__
#endif // gcc
//*****************************************************************************
//
// The defines required for RV-MDK.
//
//*****************************************************************************
#ifdef rvmdk
//
// The assembly code preamble required to put the assembler into the correct
// configuration.
//
thumb
require8
preserve8
//
// Section headers.
//
#define __LIBRARY__ ;
#define __TEXT__ area ||.text||, code, readonly, align=2
#define __DATA__ area ||.data||, data, align=2
#define __BSS__ area ||.bss||, noinit, align=2
#define __TEXT_NOROOT__ area ||.text||, code, readonly, align=2
//
// Assembler nmenonics.
//
#define __ALIGN__ align 4
#define __END__ end
#define __EXPORT__ export
#define __IMPORT__ import
#define __LABEL__
#define __STR__ dcb
#define __THUMB_LABEL__
#define __WORD__ dcd
#define __INLINE_DATA__
#endif // rvmdk
//*****************************************************************************
//
// The defines required for Sourcery G++.
//
//*****************************************************************************
#if defined(sourcerygxx)
//
// The assembly code preamble required to put the assembler into the correct
// configuration.
//
.syntax unified
.thumb
//
// Section headers.
//
#define __LIBRARY__ @
#define __TEXT__ .text
#define __DATA__ .data
#define __BSS__ .bss
#define __TEXT_NOROOT__ .text
//
// Assembler nmenonics.
//
#define __ALIGN__ .balign 4
#define __END__ .end
#define __EXPORT__ .globl
#define __IMPORT__ .extern
#define __LABEL__ :
#define __STR__ .ascii
#define __THUMB_LABEL__ .thumb_func
#define __WORD__ .word
#define __INLINE_DATA__
#endif // sourcerygxx
#endif // __ASMDEF_H__

888
inc/hw_adc.h Normal file
View File

@ -0,0 +1,888 @@
//*****************************************************************************
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#ifndef __HW_ADC_H__
#define __HW_ADC_H__
//*****************************************************************************
//
// The following are defines for the ADC register offsets.
//
//*****************************************************************************
#define ADC_O_ADC_CTRL 0x00000000 // ADC control register.
#define ADC_O_adc_ch0_gain 0x00000004 // Channel 0 gain setting
#define ADC_O_adc_ch1_gain 0x00000008 // Channel 1 gain setting
#define ADC_O_adc_ch2_gain 0x0000000C // Channel 2 gain setting
#define ADC_O_adc_ch3_gain 0x00000010 // Channel 3 gain setting
#define ADC_O_adc_ch4_gain 0x00000014 // Channel 4 gain setting
#define ADC_O_adc_ch5_gain 0x00000018 // Channel 5 gain setting
#define ADC_O_adc_ch6_gain 0x0000001C // Channel 6 gain setting
#define ADC_O_adc_ch7_gain 0x00000020 // Channel 7 gain setting
#define ADC_O_adc_ch0_irq_en 0x00000024 // Channel 0 interrupt enable
// register
#define ADC_O_adc_ch1_irq_en 0x00000028 // Channel 1 interrupt enable
// register
#define ADC_O_adc_ch2_irq_en 0x0000002C // Channel 2 interrupt enable
// register
#define ADC_O_adc_ch3_irq_en 0x00000030 // Channel 3 interrupt enable
// register
#define ADC_O_adc_ch4_irq_en 0x00000034 // Channel 4 interrupt enable
// register
#define ADC_O_adc_ch5_irq_en 0x00000038 // Channel 5 interrupt enable
// register
#define ADC_O_adc_ch6_irq_en 0x0000003C // Channel 6 interrupt enable
// register
#define ADC_O_adc_ch7_irq_en 0x00000040 // Channel 7 interrupt enable
// register
#define ADC_O_adc_ch0_irq_status \
0x00000044 // Channel 0 interrupt status
// register
#define ADC_O_adc_ch1_irq_status \
0x00000048 // Channel 1 interrupt status
// register
#define ADC_O_adc_ch2_irq_status \
0x0000004C
#define ADC_O_adc_ch3_irq_status \
0x00000050 // Channel 3 interrupt status
// register
#define ADC_O_adc_ch4_irq_status \
0x00000054 // Channel 4 interrupt status
// register
#define ADC_O_adc_ch5_irq_status \
0x00000058
#define ADC_O_adc_ch6_irq_status \
0x0000005C // Channel 6 interrupt status
// register
#define ADC_O_adc_ch7_irq_status \
0x00000060 // Channel 7 interrupt status
// register
#define ADC_O_adc_dma_mode_en 0x00000064 // DMA mode enable register
#define ADC_O_adc_timer_configuration \
0x00000068 // ADC timer configuration register
#define ADC_O_adc_timer_current_count \
0x00000070 // ADC timer current count register
#define ADC_O_channel0FIFODATA 0x00000074 // CH0 FIFO DATA register
#define ADC_O_channel1FIFODATA 0x00000078 // CH1 FIFO DATA register
#define ADC_O_channel2FIFODATA 0x0000007C // CH2 FIFO DATA register
#define ADC_O_channel3FIFODATA 0x00000080 // CH3 FIFO DATA register
#define ADC_O_channel4FIFODATA 0x00000084 // CH4 FIFO DATA register
#define ADC_O_channel5FIFODATA 0x00000088 // CH5 FIFO DATA register
#define ADC_O_channel6FIFODATA 0x0000008C // CH6 FIFO DATA register
#define ADC_O_channel7FIFODATA 0x00000090 // CH7 FIFO DATA register
#define ADC_O_adc_ch0_fifo_lvl 0x00000094 // channel 0 FIFO Level register
#define ADC_O_adc_ch1_fifo_lvl 0x00000098 // Channel 1 interrupt status
// register
#define ADC_O_adc_ch2_fifo_lvl 0x0000009C
#define ADC_O_adc_ch3_fifo_lvl 0x000000A0 // Channel 3 interrupt status
// register
#define ADC_O_adc_ch4_fifo_lvl 0x000000A4 // Channel 4 interrupt status
// register
#define ADC_O_adc_ch5_fifo_lvl 0x000000A8
#define ADC_O_adc_ch6_fifo_lvl 0x000000AC // Channel 6 interrupt status
// register
#define ADC_O_adc_ch7_fifo_lvl 0x000000B0 // Channel 7 interrupt status
// register
#define ADC_O_ADC_CH_ENABLE 0x000000B8
//******************************************************************************
//
// The following are defines for the bit fields in the ADC_O_ADC_CTRL register.
//
//******************************************************************************
#define ADC_ADC_CTRL_adc_cap_scale \
0x00000020 // ADC CAP SCALE.
#define ADC_ADC_CTRL_adc_buf_bypass \
0x00000010 // ADC ANA CIO buffer bypass.
// Signal is modelled in ANA TOP.
// When '1': ADC buffer is bypassed.
#define ADC_ADC_CTRL_adc_buf_en 0x00000008 // ADC ANA buffer enable. When 1:
// ADC buffer is enabled.
#define ADC_ADC_CTRL_adc_core_en \
0x00000004 // ANA ADC core en. This signal act
// as glbal enable to ADC CIO. When
// 1: ADC core is enabled.
#define ADC_ADC_CTRL_adc_soft_reset \
0x00000002 // ADC soft reset. When '1' : reset
// ADC internal logic.
#define ADC_ADC_CTRL_adc_en 0x00000001 // ADC global enable. When set ADC
// module is enabled
//******************************************************************************
//
// The following are defines for the bit fields in the
// ADC_O_adc_ch0_gain register.
//
//******************************************************************************
#define ADC_adc_ch0_gain_adc_channel0_gain_M \
0x00000003 // gain setting for ADC channel 0.
// when "00": 1x when "01: 2x when
// "10":3x when "11" 4x
#define ADC_adc_ch0_gain_adc_channel0_gain_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// ADC_O_adc_ch1_gain register.
//
//******************************************************************************
#define ADC_adc_ch1_gain_adc_channel1_gain_M \
0x00000003 // gain setting for ADC channel 1.
// when "00": 1x when "01: 2x when
// "10":3x when "11" 4x
#define ADC_adc_ch1_gain_adc_channel1_gain_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// ADC_O_adc_ch2_gain register.
//
//******************************************************************************
#define ADC_adc_ch2_gain_adc_channel2_gain_M \
0x00000003 // gain setting for ADC channel 2.
// when "00": 1x when "01: 2x when
// "10":3x when "11" 4x
#define ADC_adc_ch2_gain_adc_channel2_gain_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// ADC_O_adc_ch3_gain register.
//
//******************************************************************************
#define ADC_adc_ch3_gain_adc_channel3_gain_M \
0x00000003 // gain setting for ADC channel 3.
// when "00": 1x when "01: 2x when
// "10":3x when "11" 4x
#define ADC_adc_ch3_gain_adc_channel3_gain_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// ADC_O_adc_ch4_gain register.
//
//******************************************************************************
#define ADC_adc_ch4_gain_adc_channel4_gain_M \
0x00000003 // gain setting for ADC channel 4
// when "00": 1x when "01: 2x when
// "10":3x when "11" 4x
#define ADC_adc_ch4_gain_adc_channel4_gain_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// ADC_O_adc_ch5_gain register.
//
//******************************************************************************
#define ADC_adc_ch5_gain_adc_channel5_gain_M \
0x00000003 // gain setting for ADC channel 5.
// when "00": 1x when "01: 2x when
// "10":3x when "11" 4x
#define ADC_adc_ch5_gain_adc_channel5_gain_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// ADC_O_adc_ch6_gain register.
//
//******************************************************************************
#define ADC_adc_ch6_gain_adc_channel6_gain_M \
0x00000003 // gain setting for ADC channel 6
// when "00": 1x when "01: 2x when
// "10":3x when "11" 4x
#define ADC_adc_ch6_gain_adc_channel6_gain_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// ADC_O_adc_ch7_gain register.
//
//******************************************************************************
#define ADC_adc_ch7_gain_adc_channel7_gain_M \
0x00000003 // gain setting for ADC channel 7.
// when "00": 1x when "01: 2x when
// "10":3x when "11" 4x
#define ADC_adc_ch7_gain_adc_channel7_gain_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// ADC_O_adc_ch0_irq_en register.
//
//******************************************************************************
#define ADC_adc_ch0_irq_en_adc_channel0_irq_en_M \
0x0000000F // interrupt enable register for
// per ADC channel bit 3: when '1'
// -> enable FIFO overflow interrupt
// bit 2: when '1' -> enable FIFO
// underflow interrupt bit 1: when
// "1' -> enable FIFO empty
// interrupt bit 0: when "1" ->
// enable FIFO full interrupt
#define ADC_adc_ch0_irq_en_adc_channel0_irq_en_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// ADC_O_adc_ch1_irq_en register.
//
//******************************************************************************
#define ADC_adc_ch1_irq_en_adc_channel1_irq_en_M \
0x0000000F // interrupt enable register for
// per ADC channel bit 3: when '1'
// -> enable FIFO overflow interrupt
// bit 2: when '1' -> enable FIFO
// underflow interrupt bit 1: when
// "1' -> enable FIFO empty
// interrupt bit 0: when "1" ->
// enable FIFO full interrupt
#define ADC_adc_ch1_irq_en_adc_channel1_irq_en_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// ADC_O_adc_ch2_irq_en register.
//
//******************************************************************************
#define ADC_adc_ch2_irq_en_adc_channel2_irq_en_M \
0x0000000F // interrupt enable register for
// per ADC channel bit 3: when '1'
// -> enable FIFO overflow interrupt
// bit 2: when '1' -> enable FIFO
// underflow interrupt bit 1: when
// "1' -> enable FIFO empty
// interrupt bit 0: when "1" ->
// enable FIFO full interrupt
#define ADC_adc_ch2_irq_en_adc_channel2_irq_en_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// ADC_O_adc_ch3_irq_en register.
//
//******************************************************************************
#define ADC_adc_ch3_irq_en_adc_channel3_irq_en_M \
0x0000000F // interrupt enable register for
// per ADC channel bit 3: when '1'
// -> enable FIFO overflow interrupt
// bit 2: when '1' -> enable FIFO
// underflow interrupt bit 1: when
// "1' -> enable FIFO empty
// interrupt bit 0: when "1" ->
// enable FIFO full interrupt
#define ADC_adc_ch3_irq_en_adc_channel3_irq_en_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// ADC_O_adc_ch4_irq_en register.
//
//******************************************************************************
#define ADC_adc_ch4_irq_en_adc_channel4_irq_en_M \
0x0000000F // interrupt enable register for
// per ADC channel bit 3: when '1'
// -> enable FIFO overflow interrupt
// bit 2: when '1' -> enable FIFO
// underflow interrupt bit 1: when
// "1' -> enable FIFO empty
// interrupt bit 0: when "1" ->
// enable FIFO full interrupt
#define ADC_adc_ch4_irq_en_adc_channel4_irq_en_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// ADC_O_adc_ch5_irq_en register.
//
//******************************************************************************
#define ADC_adc_ch5_irq_en_adc_channel5_irq_en_M \
0x0000000F // interrupt enable register for
// per ADC channel bit 3: when '1'
// -> enable FIFO overflow interrupt
// bit 2: when '1' -> enable FIFO
// underflow interrupt bit 1: when
// "1' -> enable FIFO empty
// interrupt bit 0: when "1" ->
// enable FIFO full interrupt
#define ADC_adc_ch5_irq_en_adc_channel5_irq_en_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// ADC_O_adc_ch6_irq_en register.
//
//******************************************************************************
#define ADC_adc_ch6_irq_en_adc_channel6_irq_en_M \
0x0000000F // interrupt enable register for
// per ADC channel bit 3: when '1'
// -> enable FIFO overflow interrupt
// bit 2: when '1' -> enable FIFO
// underflow interrupt bit 1: when
// "1' -> enable FIFO empty
// interrupt bit 0: when "1" ->
// enable FIFO full interrupt
#define ADC_adc_ch6_irq_en_adc_channel6_irq_en_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// ADC_O_adc_ch7_irq_en register.
//
//******************************************************************************
#define ADC_adc_ch7_irq_en_adc_channel7_irq_en_M \
0x0000000F // interrupt enable register for
// per ADC channel bit 3: when '1'
// -> enable FIFO overflow interrupt
// bit 2: when '1' -> enable FIFO
// underflow interrupt bit 1: when
// "1' -> enable FIFO empty
// interrupt bit 0: when "1" ->
// enable FIFO full interrupt
#define ADC_adc_ch7_irq_en_adc_channel7_irq_en_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// ADC_O_adc_ch0_irq_status register.
//
//******************************************************************************
#define ADC_adc_ch0_irq_status_adc_channel0_irq_status_M \
0x0000000F // interrupt status register for
// per ADC channel. Interrupt status
// can be cleared on write. bit 3:
// when value '1' is written ->
// would clear FIFO overflow
// interrupt status in the next
// cycle. if same interrupt is set
// in the same cycle then interurpt
// would be set and clear command
// will be ignored. bit 2: when
// value '1' is written -> would
// clear FIFO underflow interrupt
// status in the next cycle. bit 1:
// when value '1' is written ->
// would clear FIFO empty interrupt
// status in the next cycle. bit 0:
// when value '1' is written ->
// would clear FIFO full interrupt
// status in the next cycle.
#define ADC_adc_ch0_irq_status_adc_channel0_irq_status_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// ADC_O_adc_ch1_irq_status register.
//
//******************************************************************************
#define ADC_adc_ch1_irq_status_adc_channel1_irq_status_M \
0x0000000F // interrupt status register for
// per ADC channel. Interrupt status
// can be cleared on write. bit 3:
// when value '1' is written ->
// would clear FIFO overflow
// interrupt status in the next
// cycle. if same interrupt is set
// in the same cycle then interurpt
// would be set and clear command
// will be ignored. bit 2: when
// value '1' is written -> would
// clear FIFO underflow interrupt
// status in the next cycle. bit 1:
// when value '1' is written ->
// would clear FIFO empty interrupt
// status in the next cycle. bit 0:
// when value '1' is written ->
// would clear FIFO full interrupt
// status in the next cycle.
#define ADC_adc_ch1_irq_status_adc_channel1_irq_status_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// ADC_O_adc_ch2_irq_status register.
//
//******************************************************************************
#define ADC_adc_ch2_irq_status_adc_channel2_irq_status_M \
0x0000000F // interrupt status register for
// per ADC channel. Interrupt status
// can be cleared on write. bit 3:
// when value '1' is written ->
// would clear FIFO overflow
// interrupt status in the next
// cycle. if same interrupt is set
// in the same cycle then interurpt
// would be set and clear command
// will be ignored. bit 2: when
// value '1' is written -> would
// clear FIFO underflow interrupt
// status in the next cycle. bit 1:
// when value '1' is written ->
// would clear FIFO empty interrupt
// status in the next cycle. bit 0:
// when value '1' is written ->
// would clear FIFO full interrupt
// status in the next cycle.
#define ADC_adc_ch2_irq_status_adc_channel2_irq_status_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// ADC_O_adc_ch3_irq_status register.
//
//******************************************************************************
#define ADC_adc_ch3_irq_status_adc_channel3_irq_status_M \
0x0000000F // interrupt status register for
// per ADC channel. Interrupt status
// can be cleared on write. bit 3:
// when value '1' is written ->
// would clear FIFO overflow
// interrupt status in the next
// cycle. if same interrupt is set
// in the same cycle then interurpt
// would be set and clear command
// will be ignored. bit 2: when
// value '1' is written -> would
// clear FIFO underflow interrupt
// status in the next cycle. bit 1:
// when value '1' is written ->
// would clear FIFO empty interrupt
// status in the next cycle. bit 0:
// when value '1' is written ->
// would clear FIFO full interrupt
// status in the next cycle.
#define ADC_adc_ch3_irq_status_adc_channel3_irq_status_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// ADC_O_adc_ch4_irq_status register.
//
//******************************************************************************
#define ADC_adc_ch4_irq_status_adc_channel4_irq_status_M \
0x0000000F // interrupt status register for
// per ADC channel. Interrupt status
// can be cleared on write. bit 3:
// when value '1' is written ->
// would clear FIFO overflow
// interrupt status in the next
// cycle. if same interrupt is set
// in the same cycle then interurpt
// would be set and clear command
// will be ignored. bit 2: when
// value '1' is written -> would
// clear FIFO underflow interrupt
// status in the next cycle. bit 1:
// when value '1' is written ->
// would clear FIFO empty interrupt
// status in the next cycle. bit 0:
// when value '1' is written ->
// would clear FIFO full interrupt
// status in the next cycle.
#define ADC_adc_ch4_irq_status_adc_channel4_irq_status_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// ADC_O_adc_ch5_irq_status register.
//
//******************************************************************************
#define ADC_adc_ch5_irq_status_adc_channel5_irq_status_M \
0x0000000F // interrupt status register for
// per ADC channel. Interrupt status
// can be cleared on write. bit 3:
// when value '1' is written ->
// would clear FIFO overflow
// interrupt status in the next
// cycle. if same interrupt is set
// in the same cycle then interurpt
// would be set and clear command
// will be ignored. bit 2: when
// value '1' is written -> would
// clear FIFO underflow interrupt
// status in the next cycle. bit 1:
// when value '1' is written ->
// would clear FIFO empty interrupt
// status in the next cycle. bit 0:
// when value '1' is written ->
// would clear FIFO full interrupt
// status in the next cycle.
#define ADC_adc_ch5_irq_status_adc_channel5_irq_status_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// ADC_O_adc_ch6_irq_status register.
//
//******************************************************************************
#define ADC_adc_ch6_irq_status_adc_channel6_irq_status_M \
0x0000000F // interrupt status register for
// per ADC channel. Interrupt status
// can be cleared on write. bit 3:
// when value '1' is written ->
// would clear FIFO overflow
// interrupt status in the next
// cycle. if same interrupt is set
// in the same cycle then interurpt
// would be set and clear command
// will be ignored. bit 2: when
// value '1' is written -> would
// clear FIFO underflow interrupt
// status in the next cycle. bit 1:
// when value '1' is written ->
// would clear FIFO empty interrupt
// status in the next cycle. bit 0:
// when value '1' is written ->
// would clear FIFO full interrupt
// status in the next cycle.
#define ADC_adc_ch6_irq_status_adc_channel6_irq_status_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// ADC_O_adc_ch7_irq_status register.
//
//******************************************************************************
#define ADC_adc_ch7_irq_status_adc_channel7_irq_status_M \
0x0000000F // interrupt status register for
// per ADC channel. Interrupt status
// can be cleared on write. bit 3:
// when value '1' is written ->
// would clear FIFO overflow
// interrupt status in the next
// cycle. if same interrupt is set
// in the same cycle then interurpt
// would be set and clear command
// will be ignored. bit 2: when
// value '1' is written -> would
// clear FIFO underflow interrupt
// status in the next cycle. bit 1:
// when value '1' is written ->
// would clear FIFO empty interrupt
// status in the next cycle. bit 0:
// when value '1' is written ->
// would clear FIFO full interrupt
// status in the next cycle.
#define ADC_adc_ch7_irq_status_adc_channel7_irq_status_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// ADC_O_adc_dma_mode_en register.
//
//******************************************************************************
#define ADC_adc_dma_mode_en_DMA_MODEenable_M \
0x000000FF // this register enable DMA mode.
// when '1' respective ADC channel
// is enabled for DMA. When '0' only
// interrupt mode is enabled. Bit 0:
// channel 0 DMA mode enable. Bit 1:
// channel 1 DMA mode enable. Bit 2:
// channel 2 DMA mode enable. Bit 3:
// channel 3 DMA mode enable. bit 4:
// channel 4 DMA mode enable. bit 5:
// channel 5 DMA mode enable. bit 6:
// channel 6 DMA mode enable. bit 7:
// channel 7 DMA mode enable.
#define ADC_adc_dma_mode_en_DMA_MODEenable_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// ADC_O_adc_timer_configuration register.
//
//******************************************************************************
#define ADC_adc_timer_configuration_timeren \
0x02000000 // when '1' timer is enabled.
#define ADC_adc_timer_configuration_timerreset \
0x01000000 // when '1' reset timer.
#define ADC_adc_timer_configuration_timercount_M \
0x00FFFFFF // Timer count configuration. 17
// bit counter is supported. Other
// MSB's are redundent.
#define ADC_adc_timer_configuration_timercount_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// ADC_O_adc_timer_current_count register.
//
//******************************************************************************
#define ADC_adc_timer_current_count_timercurrentcount_M \
0x0001FFFF // Timer count configuration
#define ADC_adc_timer_current_count_timercurrentcount_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// ADC_O_channel0FIFODATA register.
//
//******************************************************************************
#define ADC_channel0FIFODATA_FIFO_RD_DATA_M \
0xFFFFFFFF // read to this register would
// return ADC data along with time
// stamp information in following
// format: bits [13:0] : ADC sample
// bits [31:14]: : time stamp per
// ADC sample
#define ADC_channel0FIFODATA_FIFO_RD_DATA_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// ADC_O_channel1FIFODATA register.
//
//******************************************************************************
#define ADC_channel1FIFODATA_FIFO_RD_DATA_M \
0xFFFFFFFF // read to this register would
// return ADC data along with time
// stamp information in following
// format: bits [13:0] : ADC sample
// bits [31:14]: : time stamp per
// ADC sample
#define ADC_channel1FIFODATA_FIFO_RD_DATA_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// ADC_O_channel2FIFODATA register.
//
//******************************************************************************
#define ADC_channel2FIFODATA_FIFO_RD_DATA_M \
0xFFFFFFFF // read to this register would
// return ADC data along with time
// stamp information in following
// format: bits [13:0] : ADC sample
// bits [31:14]: : time stamp per
// ADC sample
#define ADC_channel2FIFODATA_FIFO_RD_DATA_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// ADC_O_channel3FIFODATA register.
//
//******************************************************************************
#define ADC_channel3FIFODATA_FIFO_RD_DATA_M \
0xFFFFFFFF // read to this register would
// return ADC data along with time
// stamp information in following
// format: bits [13:0] : ADC sample
// bits [31:14]: : time stamp per
// ADC sample
#define ADC_channel3FIFODATA_FIFO_RD_DATA_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// ADC_O_channel4FIFODATA register.
//
//******************************************************************************
#define ADC_channel4FIFODATA_FIFO_RD_DATA_M \
0xFFFFFFFF // read to this register would
// return ADC data along with time
// stamp information in following
// format: bits [13:0] : ADC sample
// bits [31:14]: : time stamp per
// ADC sample
#define ADC_channel4FIFODATA_FIFO_RD_DATA_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// ADC_O_channel5FIFODATA register.
//
//******************************************************************************
#define ADC_channel5FIFODATA_FIFO_RD_DATA_M \
0xFFFFFFFF // read to this register would
// return ADC data along with time
// stamp information in following
// format: bits [13:0] : ADC sample
// bits [31:14]: : time stamp per
// ADC sample
#define ADC_channel5FIFODATA_FIFO_RD_DATA_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// ADC_O_channel6FIFODATA register.
//
//******************************************************************************
#define ADC_channel6FIFODATA_FIFO_RD_DATA_M \
0xFFFFFFFF // read to this register would
// return ADC data along with time
// stamp information in following
// format: bits [13:0] : ADC sample
// bits [31:14]: : time stamp per
// ADC sample
#define ADC_channel6FIFODATA_FIFO_RD_DATA_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// ADC_O_channel7FIFODATA register.
//
//******************************************************************************
#define ADC_channel7FIFODATA_FIFO_RD_DATA_M \
0xFFFFFFFF // read to this register would
// return ADC data along with time
// stamp information in following
// format: bits [13:0] : ADC sample
// bits [31:14]: : time stamp per
// ADC sample
#define ADC_channel7FIFODATA_FIFO_RD_DATA_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// ADC_O_adc_ch0_fifo_lvl register.
//
//******************************************************************************
#define ADC_adc_ch0_fifo_lvl_adc_channel0_fifo_lvl_M \
0x00000007 // This register shows current FIFO
// level. FIFO is 4 word wide.
// Possible supported levels are :
// 0x0 to 0x3
#define ADC_adc_ch0_fifo_lvl_adc_channel0_fifo_lvl_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// ADC_O_adc_ch1_fifo_lvl register.
//
//******************************************************************************
#define ADC_adc_ch1_fifo_lvl_adc_channel1_fifo_lvl_M \
0x00000007 // This register shows current FIFO
// level. FIFO is 4 word wide.
// Possible supported levels are :
// 0x0 to 0x3
#define ADC_adc_ch1_fifo_lvl_adc_channel1_fifo_lvl_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// ADC_O_adc_ch2_fifo_lvl register.
//
//******************************************************************************
#define ADC_adc_ch2_fifo_lvl_adc_channel2_fifo_lvl_M \
0x00000007 // This register shows current FIFO
// level. FIFO is 4 word wide.
// Possible supported levels are :
// 0x0 to 0x3
#define ADC_adc_ch2_fifo_lvl_adc_channel2_fifo_lvl_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// ADC_O_adc_ch3_fifo_lvl register.
//
//******************************************************************************
#define ADC_adc_ch3_fifo_lvl_adc_channel3_fifo_lvl_M \
0x00000007 // This register shows current FIFO
// level. FIFO is 4 word wide.
// Possible supported levels are :
// 0x0 to 0x3
#define ADC_adc_ch3_fifo_lvl_adc_channel3_fifo_lvl_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// ADC_O_adc_ch4_fifo_lvl register.
//
//******************************************************************************
#define ADC_adc_ch4_fifo_lvl_adc_channel4_fifo_lvl_M \
0x00000007 // This register shows current FIFO
// level. FIFO is 4 word wide.
// Possible supported levels are :
// 0x0 to 0x3
#define ADC_adc_ch4_fifo_lvl_adc_channel4_fifo_lvl_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// ADC_O_adc_ch5_fifo_lvl register.
//
//******************************************************************************
#define ADC_adc_ch5_fifo_lvl_adc_channel5_fifo_lvl_M \
0x00000007 // This register shows current FIFO
// level. FIFO is 4 word wide.
// Possible supported levels are :
// 0x0 to 0x3
#define ADC_adc_ch5_fifo_lvl_adc_channel5_fifo_lvl_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// ADC_O_adc_ch6_fifo_lvl register.
//
//******************************************************************************
#define ADC_adc_ch6_fifo_lvl_adc_channel6_fifo_lvl_M \
0x00000007 // This register shows current FIFO
// level. FIFO is 4 word wide.
// Possible supported levels are :
// 0x0 to 0x3
#define ADC_adc_ch6_fifo_lvl_adc_channel6_fifo_lvl_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// ADC_O_adc_ch7_fifo_lvl register.
//
//******************************************************************************
#define ADC_adc_ch7_fifo_lvl_adc_channel7_fifo_lvl_M \
0x00000007 // This register shows current FIFO
// level. FIFO is 4 word wide.
// Possible supported levels are :
// 0x0 to 0x3
#define ADC_adc_ch7_fifo_lvl_adc_channel7_fifo_lvl_S 0
#endif // __HW_ADC_H__

802
inc/hw_aes.h Normal file
View File

@ -0,0 +1,802 @@
//*****************************************************************************
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#ifndef __HW_AES_H__
#define __HW_AES_H__
//*****************************************************************************
//
// The following are defines for the AES_P register offsets.
//
//*****************************************************************************
#define AES_O_KEY2_6 0x00000000 // XTS second key / CBC-MAC third
// key
#define AES_O_KEY2_7 0x00000004 // XTS second key (MSW for 256-bit
// key) / CBC-MAC third key (MSW)
#define AES_O_KEY2_4 0x00000008 // XTS / CCM second key / CBC-MAC
// third key (LSW)
#define AES_O_KEY2_5 0x0000000C // XTS second key (MSW for 192-bit
// key) / CBC-MAC third key
#define AES_O_KEY2_2 0x00000010 // XTS / CCM / CBC-MAC second key /
// Hash Key input
#define AES_O_KEY2_3 0x00000014 // XTS second key (MSW for 128-bit
// key) + CCM/CBC-MAC second key
// (MSW) / Hash Key input (MSW)
#define AES_O_KEY2_0 0x00000018 // XTS / CCM / CBC-MAC second key
// (LSW) / Hash Key input (LSW)
#define AES_O_KEY2_1 0x0000001C // XTS / CCM / CBC-MAC second key /
// Hash Key input
#define AES_O_KEY1_6 0x00000020 // Key (LSW for 256-bit key)
#define AES_O_KEY1_7 0x00000024 // Key (MSW for 256-bit key)
#define AES_O_KEY1_4 0x00000028 // Key (LSW for 192-bit key)
#define AES_O_KEY1_5 0x0000002C // Key (MSW for 192-bit key)
#define AES_O_KEY1_2 0x00000030 // Key
#define AES_O_KEY1_3 0x00000034 // Key (MSW for 128-bit key)
#define AES_O_KEY1_0 0x00000038 // Key (LSW for 128-bit key)
#define AES_O_KEY1_1 0x0000003C // Key
#define AES_O_IV_IN_0 0x00000040 // Initialization Vector input
// (LSW)
#define AES_O_IV_IN_1 0x00000044 // Initialization vector input
#define AES_O_IV_IN_2 0x00000048 // Initialization vector input
#define AES_O_IV_IN_3 0x0000004C // Initialization Vector input
// (MSW)
#define AES_O_CTRL 0x00000050 // register determines the mode of
// operation of the AES Engine
#define AES_O_C_LENGTH_0 0x00000054 // Crypto data length registers
// (LSW and MSW) store the
// cryptographic data length in
// bytes for all modes. Once
// processing with this context is
// started@@ this length decrements
// to zero. Data lengths up to (2^61
// 1) bytes are allowed. For GCM@@
// any value up to 2^36 - 32 bytes
// can be used. This is because a
// 32-bit counter mode is used; the
// maximum number of 128-bit blocks
// is 2^32 2@@ resulting in a
// maximum number of bytes of 2^36 -
// 32. A write to this register
// triggers the engine to start
// using this context. This is valid
// for all modes except GCM and CCM.
// Note that for the combined
// modes@@ this length does not
// include the authentication only
// data; the authentication length
// is specified in the
// AES_AUTH_LENGTH register below.
// All modes must have a length > 0.
// For the combined modes@@ it is
// allowed to have one of the
// lengths equal to zero. For the
// basic encryption modes
// (ECB/CBC/CTR/ICM/CFB128) it is
// allowed to program zero to the
// length field; in that case the
// length is assumed infinite. All
// data must be byte (8-bit)
// aligned; bit aligned data streams
// are not supported by the AES
// Engine. For a Host read
// operation@@ these registers
// return all-zeroes.
#define AES_O_C_LENGTH_1 0x00000058 // Crypto data length registers
// (LSW and MSW) store the
// cryptographic data length in
// bytes for all modes. Once
// processing with this context is
// started@@ this length decrements
// to zero. Data lengths up to (2^61
// 1) bytes are allowed. For GCM@@
// any value up to 2^36 - 32 bytes
// can be used. This is because a
// 32-bit counter mode is used; the
// maximum number of 128-bit blocks
// is 2^32 2@@ resulting in a
// maximum number of bytes of 2^36 -
// 32. A write to this register
// triggers the engine to start
// using this context. This is valid
// for all modes except GCM and CCM.
// Note that for the combined
// modes@@ this length does not
// include the authentication only
// data; the authentication length
// is specified in the
// AES_AUTH_LENGTH register below.
// All modes must have a length > 0.
// For the combined modes@@ it is
// allowed to have one of the
// lengths equal to zero. For the
// basic encryption modes
// (ECB/CBC/CTR/ICM/CFB128) it is
// allowed to program zero to the
// length field; in that case the
// length is assumed infinite. All
// data must be byte (8-bit)
// aligned; bit aligned data streams
// are not supported by the AES
// Engine. For a Host read
// operation@@ these registers
// return all-zeroes.
#define AES_O_AUTH_LENGTH 0x0000005C // AAD data length. The
// authentication length register
// store the authentication data
// length in bytes for combined
// modes only (GCM or CCM) Supported
// AAD-lengths for CCM are from 0 to
// (2^16 - 2^8) bytes. For GCM any
// value up to (2^32 - 1) bytes can
// be used. Once processing with
// this context is started@@ this
// length decrements to zero. A
// write to this register triggers
// the engine to start using this
// context for GCM and CCM. For XTS
// this register is optionally used
// to load j. Loading of j is
// only required if j != 0. j is
// a 28-bit value and must be
// written to bits [31-4] of this
// register. j represents the
// sequential number of the 128-bit
// block inside the data unit. For
// the first block in a unit@@ this
// value is zero. It is not required
// to provide a j for each new
// data block within a unit. Note
// that it is possible to start with
// a j unequal to zero; refer to
// Table 4 for more details. For a
// Host read operation@@ these
// registers return all-zeroes.
#define AES_O_DATA_IN_0 0x00000060 // Data register to read and write
// plaintext/ciphertext (MSW)
#define AES_O_DATA_IN_1 0x00000064 // Data register to read and write
// plaintext/ciphertext
#define AES_O_DATA_IN_2 0x00000068 // Data register to read and write
// plaintext/ciphertext
#define AES_O_DATA_IN_3 0x0000006C // Data register to read and write
// plaintext/ciphertext (LSW)
#define AES_O_TAG_OUT_0 0x00000070
#define AES_O_TAG_OUT_1 0x00000074
#define AES_O_TAG_OUT_2 0x00000078
#define AES_O_TAG_OUT_3 0x0000007C
#define AES_O_REVISION 0x00000080 // Register AES_REVISION
#define AES_O_SYSCONFIG 0x00000084 // Register AES_SYSCONFIG.This
// register configures the DMA
// signals and controls the IDLE and
// reset logic
#define AES_O_SYSSTATUS 0x00000088
#define AES_O_IRQSTATUS 0x0000008C // This register indicates the
// interrupt status. If one of the
// interrupt bits is set the
// interrupt output will be asserted
#define AES_O_IRQENABLE 0x00000090 // This register contains an enable
// bit for each unique interrupt
// generated by the module. It
// matches the layout of
// AES_IRQSTATUS register. An
// interrupt is enabled when the bit
// in this register is set to 1.
// An interrupt that is enabled is
// propagated to the SINTREQUEST_x
// output. All interrupts need to be
// enabled explicitly by writing
// this register.
//******************************************************************************
//
// The following are defines for the bit fields in the AES_O_KEY2_6 register.
//
//******************************************************************************
#define AES_KEY2_6_KEY_M 0xFFFFFFFF // key data
#define AES_KEY2_6_KEY_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the AES_O_KEY2_7 register.
//
//******************************************************************************
#define AES_KEY2_7_KEY_M 0xFFFFFFFF // key data
#define AES_KEY2_7_KEY_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the AES_O_KEY2_4 register.
//
//******************************************************************************
#define AES_KEY2_4_KEY_M 0xFFFFFFFF // key data
#define AES_KEY2_4_KEY_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the AES_O_KEY2_5 register.
//
//******************************************************************************
#define AES_KEY2_5_KEY_M 0xFFFFFFFF // key data
#define AES_KEY2_5_KEY_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the AES_O_KEY2_2 register.
//
//******************************************************************************
#define AES_KEY2_2_KEY_M 0xFFFFFFFF // key data
#define AES_KEY2_2_KEY_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the AES_O_KEY2_3 register.
//
//******************************************************************************
#define AES_KEY2_3_KEY_M 0xFFFFFFFF // key data
#define AES_KEY2_3_KEY_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the AES_O_KEY2_0 register.
//
//******************************************************************************
#define AES_KEY2_0_KEY_M 0xFFFFFFFF // key data
#define AES_KEY2_0_KEY_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the AES_O_KEY2_1 register.
//
//******************************************************************************
#define AES_KEY2_1_KEY_M 0xFFFFFFFF // key data
#define AES_KEY2_1_KEY_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the AES_O_KEY1_6 register.
//
//******************************************************************************
#define AES_KEY1_6_KEY_M 0xFFFFFFFF // key data
#define AES_KEY1_6_KEY_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the AES_O_KEY1_7 register.
//
//******************************************************************************
#define AES_KEY1_7_KEY_M 0xFFFFFFFF // key data
#define AES_KEY1_7_KEY_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the AES_O_KEY1_4 register.
//
//******************************************************************************
#define AES_KEY1_4_KEY_M 0xFFFFFFFF // key data
#define AES_KEY1_4_KEY_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the AES_O_KEY1_5 register.
//
//******************************************************************************
#define AES_KEY1_5_KEY_M 0xFFFFFFFF // key data
#define AES_KEY1_5_KEY_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the AES_O_KEY1_2 register.
//
//******************************************************************************
#define AES_KEY1_2_KEY_M 0xFFFFFFFF // key data
#define AES_KEY1_2_KEY_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the AES_O_KEY1_3 register.
//
//******************************************************************************
#define AES_KEY1_3_KEY_M 0xFFFFFFFF // key data
#define AES_KEY1_3_KEY_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the AES_O_KEY1_0 register.
//
//******************************************************************************
#define AES_KEY1_0_KEY_M 0xFFFFFFFF // key data
#define AES_KEY1_0_KEY_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the AES_O_KEY1_1 register.
//
//******************************************************************************
#define AES_KEY1_1_KEY_M 0xFFFFFFFF // key data
#define AES_KEY1_1_KEY_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the AES_O_IV_IN_0 register.
//
//******************************************************************************
#define AES_IV_IN_0_DATA_M 0xFFFFFFFF // IV data
#define AES_IV_IN_0_DATA_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the AES_O_IV_IN_1 register.
//
//******************************************************************************
#define AES_IV_IN_1_DATA_M 0xFFFFFFFF // IV data
#define AES_IV_IN_1_DATA_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the AES_O_IV_IN_2 register.
//
//******************************************************************************
#define AES_IV_IN_2_DATA_M 0xFFFFFFFF // IV data
#define AES_IV_IN_2_DATA_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the AES_O_IV_IN_3 register.
//
//******************************************************************************
#define AES_IV_IN_3_DATA_M 0xFFFFFFFF // IV data
#define AES_IV_IN_3_DATA_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the AES_O_CTRL register.
//
//******************************************************************************
#define AES_CTRL_CONTEXT_READY \
0x80000000 // If 1@@ this read-only status
// bit indicates that the context
// data registers can be overwritten
// and the host is permitted to
// write the next context.
#define AES_CTRL_SVCTXTRDY \
0x40000000 // If 1@@ this read-only status
// bit indicates that an AES
// authentication TAG and/or IV
// block(s) is/are available for the
// host to retrieve. This bit is
// only asserted if the
// save_context bit is set to 1.
// The bit is mutual exclusive with
// the context_ready bit.
#define AES_CTRL_SAVE_CONTEXT 0x20000000 // This bit is used to indicate
// that an authentication TAG or
// result IV needs to be stored as a
// result context. If this bit is
// set@@ context output DMA and/or
// interrupt will be asserted if the
// operation is finished and related
// signals are enabled.
#define AES_CTRL_CCM_M 0x01C00000 // Defines “M” that indicated the
// length of the authentication
// field for CCM operations; the
// authentication field length
// equals two times (the value of
// CCM-M plus one). Note that the
// AES Engine always returns a
// 128-bit authentication field@@ of
// which the M least significant
// bytes are valid. All values are
// supported.
#define AES_CTRL_CCM_S 22
#define AES_CTRL_CCM_L_M 0x00380000 // Defines “L” that indicated the
// width of the length field for CCM
// operations; the length field in
// bytes equals the value of CMM-L
// plus one. Supported values for L
// are (programmed value): 2 (1)@@ 4
// (3) and 8 (7).
#define AES_CTRL_CCM_L_S 19
#define AES_CTRL_CCM 0x00040000 // AES-CCM is selected@@ this is a
// combined mode@@ using AES for
// both authentication and
// encryption. No additional mode
// selection is required. 0 Other
// mode selected 1 ccm mode selected
#define AES_CTRL_GCM_M 0x00030000 // AES-GCM mode is selected.this is
// a combined mode@@ using the
// Galois field multiplier GF(2^128)
// for authentication and AES-CTR
// mode for encryption@@ the bits
// specify the GCM mode. 0x0 No
// operation 0x1 GHASH with H loaded
// and Y0-encrypted forced to zero
// 0x2 GHASH with H loaded and
// Y0-encrypted calculated
// internally 0x3 Autonomous GHASH
// (both H and Y0-encrypted
// calculated internally)
#define AES_CTRL_GCM_S 16
#define AES_CTRL_CBCMAC 0x00008000 // AES-CBC MAC is selected@@ the
// Direction bit must be set to 1
// for this mode. 0 Other mode
// selected 1 cbcmac mode selected
#define AES_CTRL_F9 0x00004000 // AES f9 mode is selected@@ the
// AES key size must be set to
// 128-bit for this mode. 0 Other
// mode selected 1 f9 selected
#define AES_CTRL_F8 0x00002000 // AES f8 mode is selected@@ the
// AES key size must be set to
// 128-bit for this mode. 0 Other
// mode selected 1 f8 selected
#define AES_CTRL_XTS_M 0x00001800 // AES-XTS operation is selected;
// the bits specify the XTS mode.01
// = Previous/intermediate tweak
// value and j loaded (value is
// loaded via IV@@ j is loaded via
// the AAD length register) 0x0 No
// operation 0x1
// Previous/intermediate tweak value
// and j loaded (value is loaded
// via IV@@ j is loaded via the AAD
// length register) 0x2 Key2@@ i and
// j loaded (i is loaded via IV@@ j
// is loaded via the AAD length
// register) 0x3 Key2 and i loaded@@
// j=0 (i is loaded via IV)
#define AES_CTRL_XTS_S 11
#define AES_CTRL_CFB 0x00000400 // full block AES cipher feedback
// mode (CFB128) is selected. 0
// other mode selected 1 cfb
// selected
#define AES_CTRL_ICM 0x00000200 // AES integer counter mode (ICM)
// is selected@@ this is a counter
// mode with a 16-bit wide counter.
// 0 Other mode selected. 1 ICM mode
// selected
#define AES_CTRL_CTR_WIDTH_M 0x00000180 // Specifies the counter width for
// AES-CTR mode 0x0 Counter is 32
// bits 0x1 Counter is 64 bits 0x2
// Counter is 128 bits 0x3 Counter
// is 192 bits
#define AES_CTRL_CTR_WIDTH_S 7
#define AES_CTRL_CTR 0x00000040 // Tthis bit must also be set for
// GCM and CCM@@ when
// encryption/decryption is
// required. 0 Other mode selected 1
// Counter mode
#define AES_CTRL_MODE 0x00000020 // ecb/cbc mode 0 ecb mode 1 cbc
// mode
#define AES_CTRL_KEY_SIZE_M 0x00000018 // key size 0x0 reserved 0x1 Key is
// 128 bits. 0x2 Key is 192 bits 0x3
// Key is 256
#define AES_CTRL_KEY_SIZE_S 3
#define AES_CTRL_DIRECTION 0x00000004 // If set to 1 an encrypt
// operation is performed. If set to
// 0 a decrypt operation is
// performed. Read 0 decryption is
// selected Read 1 Encryption is
// selected
#define AES_CTRL_INPUT_READY 0x00000002 // If 1@@ this read-only status
// bit indicates that the 16-byte
// input buffer is empty@@ and the
// host is permitted to write the
// next block of data.
#define AES_CTRL_OUTPUT_READY 0x00000001 // If 1@@ this read-only status
// bit indicates that an AES output
// block is available for the host
// to retrieve.
//******************************************************************************
//
// The following are defines for the bit fields in the
// AES_O_C_LENGTH_0 register.
//
//******************************************************************************
//******************************************************************************
//
// The following are defines for the bit fields in the
// AES_O_C_LENGTH_1 register.
//
//******************************************************************************
#define AES_C_LENGTH_1_LENGTH_M \
0x1FFFFFFF // Data length (MSW) length
// registers (LSW and MSW) store the
// cryptographic data length in
// bytes for all modes. Once
// processing with this context is
// started@@ this length decrements
// to zero. Data lengths up to (2^61
// 1) bytes are allowed. For GCM@@
// any value up to 2^36 - 32 bytes
// can be used. This is because a
// 32-bit counter mode is used; the
// maximum number of 128-bit blocks
// is 2^32 2@@ resulting in a
// maximum number of bytes of 2^36 -
// 32. A write to this register
// triggers the engine to start
// using this context. This is valid
// for all modes except GCM and CCM.
// Note that for the combined
// modes@@ this length does not
// include the authentication only
// data; the authentication length
// is specified in the
// AES_AUTH_LENGTH register below.
// All modes must have a length > 0.
// For the combined modes@@ it is
// allowed to have one of the
// lengths equal to zero. For the
// basic encryption modes
// (ECB/CBC/CTR/ICM/CFB128) it is
// allowed to program zero to the
// length field; in that case the
// length is assumed infinite. All
// data must be byte (8-bit)
// aligned; bit aligned data streams
// are not supported by the AES
// Engine. For a Host read
// operation@@ these registers
// return all-zeroes.
#define AES_C_LENGTH_1_LENGTH_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// AES_O_AUTH_LENGTH register.
//
//******************************************************************************
#define AES_AUTH_LENGTH_AUTH_M \
0xFFFFFFFF // data
#define AES_AUTH_LENGTH_AUTH_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the AES_O_DATA_IN_0 register.
//
//******************************************************************************
#define AES_DATA_IN_0_DATA_M 0xFFFFFFFF // Data to encrypt/decrypt
#define AES_DATA_IN_0_DATA_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the AES_O_DATA_IN_1 register.
//
//******************************************************************************
#define AES_DATA_IN_1_DATA_M 0xFFFFFFFF // Data to encrypt/decrypt
#define AES_DATA_IN_1_DATA_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the AES_O_DATA_IN_2 register.
//
//******************************************************************************
#define AES_DATA_IN_2_DATA_M 0xFFFFFFFF // Data to encrypt/decrypt
#define AES_DATA_IN_2_DATA_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the AES_O_DATA_IN_3 register.
//
//******************************************************************************
#define AES_DATA_IN_3_DATA_M 0xFFFFFFFF // Data to encrypt/decrypt
#define AES_DATA_IN_3_DATA_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the AES_O_TAG_OUT_0 register.
//
//******************************************************************************
#define AES_TAG_OUT_0_HASH_M 0xFFFFFFFF // Hash result (MSW)
#define AES_TAG_OUT_0_HASH_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the AES_O_TAG_OUT_1 register.
//
//******************************************************************************
#define AES_TAG_OUT_1_HASH_M 0xFFFFFFFF // Hash result (MSW)
#define AES_TAG_OUT_1_HASH_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the AES_O_TAG_OUT_2 register.
//
//******************************************************************************
#define AES_TAG_OUT_2_HASH_M 0xFFFFFFFF // Hash result (MSW)
#define AES_TAG_OUT_2_HASH_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the AES_O_TAG_OUT_3 register.
//
//******************************************************************************
#define AES_TAG_OUT_3_HASH_M 0xFFFFFFFF // Hash result (LSW)
#define AES_TAG_OUT_3_HASH_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the AES_O_REVISION register.
//
//******************************************************************************
#define AES_REVISION_SCHEME_M 0xC0000000
#define AES_REVISION_SCHEME_S 30
#define AES_REVISION_FUNC_M 0x0FFF0000 // Function indicates a software
// compatible module family. If
// there is no level of software
// compatibility a new Func number
// (and hence REVISION) should be
// assigned.
#define AES_REVISION_FUNC_S 16
#define AES_REVISION_R_RTL_M 0x0000F800 // RTL Version (R)@@ maintained by
// IP design owner. RTL follows a
// numbering such as X.Y.R.Z which
// are explained in this table. R
// changes ONLY when: (1) PDS
// uploads occur which may have been
// due to spec changes (2) Bug fixes
// occur (3) Resets to '0' when X or
// Y changes. Design team has an
// internal 'Z' (customer invisible)
// number which increments on every
// drop that happens due to DV and
// RTL updates. Z resets to 0 when R
// increments.
#define AES_REVISION_R_RTL_S 11
#define AES_REVISION_X_MAJOR_M \
0x00000700 // Major Revision (X)@@ maintained
// by IP specification owner. X
// changes ONLY when: (1) There is a
// major feature addition. An
// example would be adding Master
// Mode to Utopia Level2. The Func
// field (or Class/Type in old PID
// format) will remain the same. X
// does NOT change due to: (1) Bug
// fixes (2) Change in feature
// parameters.
#define AES_REVISION_X_MAJOR_S 8
#define AES_REVISION_CUSTOM_M 0x000000C0
#define AES_REVISION_CUSTOM_S 6
#define AES_REVISION_Y_MINOR_M \
0x0000003F // Minor Revision (Y)@@ maintained
// by IP specification owner. Y
// changes ONLY when: (1) Features
// are scaled (up or down).
// Flexibility exists in that this
// feature scalability may either be
// represented in the Y change or a
// specific register in the IP that
// indicates which features are
// exactly available. (2) When
// feature creeps from Is-Not list
// to Is list. But this may not be
// the case once it sees silicon; in
// which case X will change. Y does
// NOT change due to: (1) Bug fixes
// (2) Typos or clarifications (3)
// major functional/feature
// change/addition/deletion. Instead
// these changes may be reflected
// via R@@ S@@ X as applicable. Spec
// owner maintains a
// customer-invisible number 'S'
// which changes due to: (1)
// Typos/clarifications (2) Bug
// documentation. Note that this bug
// is not due to a spec change but
// due to implementation.
// Nevertheless@@ the spec tracks
// the IP bugs. An RTL release (say
// for silicon PG1.1) that occurs
// due to bug fix should document
// the corresponding spec number
// (X.Y.S) in its release notes.
#define AES_REVISION_Y_MINOR_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the AES_O_SYSCONFIG register.
//
//******************************************************************************
#define AES_SYSCONFIG_MACONTEXT_OUT_ON_DATA_OUT \
0x00000200 // If set to '1' the two context
// out requests
// (dma_req_context_out_en@@ Bit [8]
// above@@ and context_out interrupt
// enable@@ Bit [3] of AES_IRQENABLE
// register) are mapped on the
// corresponding data output request
// bit. In this case@@ the original
// context out bit values are
// ignored.
#define AES_SYSCONFIG_DMA_REQ_CONTEXT_OUT_EN \
0x00000100 // If set to 1@@ the DMA context
// output request is enabled (for
// context data out@@ e.g. TAG for
// authentication modes). 0 Dma
// disabled 1 Dma enabled
#define AES_SYSCONFIG_DMA_REQ_CONTEXT_IN_EN \
0x00000080 // If set to 1@@ the DMA context
// request is enabled. 0 Dma
// disabled 1 Dma enabled
#define AES_SYSCONFIG_DMA_REQ_DATA_OUT_EN \
0x00000040 // If set to 1@@ the DMA output
// request is enabled. 0 Dma
// disabled 1 Dma enabled
#define AES_SYSCONFIG_DMA_REQ_DATA_IN_EN \
0x00000020 // If set to 1@@ the DMA input
// request is enabled. 0 Dma
// disabled 1 Dma enabled
//******************************************************************************
//
// The following are defines for the bit fields in the AES_O_SYSSTATUS register.
//
//******************************************************************************
#define AES_SYSSTATUS_RESETDONE \
0x00000001
//******************************************************************************
//
// The following are defines for the bit fields in the AES_O_IRQSTATUS register.
//
//******************************************************************************
#define AES_IRQSTATUS_CONTEXT_OUT \
0x00000008 // This bit indicates
// authentication tag (and IV)
// interrupt(s) is/are active and
// triggers the interrupt output.
#define AES_IRQSTATUS_DATA_OUT \
0x00000004 // This bit indicates data output
// interrupt is active and triggers
// the interrupt output.
#define AES_IRQSTATUS_DATA_IN 0x00000002 // This bit indicates data input
// interrupt is active and triggers
// the interrupt output.
#define AES_IRQSTATUS_CONTEX_IN \
0x00000001 // This bit indicates context
// interrupt is active and triggers
// the interrupt output.
//******************************************************************************
//
// The following are defines for the bit fields in the AES_O_IRQENABLE register.
//
//******************************************************************************
#define AES_IRQENABLE_CONTEXT_OUT \
0x00000008 // This bit indicates
// authentication tag (and IV)
// interrupt(s) is/are active and
// triggers the interrupt output.
#define AES_IRQENABLE_DATA_OUT \
0x00000004 // This bit indicates data output
// interrupt is active and triggers
// the interrupt output.
#define AES_IRQENABLE_DATA_IN 0x00000002 // This bit indicates data input
// interrupt is active and triggers
// the interrupt output.
#define AES_IRQENABLE_CONTEX_IN \
0x00000001 // This bit indicates context
// interrupt is active and triggers
// the interrupt output.
#endif // __HW_AES_H__

747
inc/hw_apps_config.h Normal file
View File

@ -0,0 +1,747 @@
//*****************************************************************************
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#ifndef __HW_APPS_CONFIG_H__
#define __HW_APPS_CONFIG_H__
//*****************************************************************************
//
// The following are defines for the APPS_CONFIG register offsets.
//
//*****************************************************************************
#define APPS_CONFIG_O_PATCH_TRAP_ADDR_REG \
0x00000000 // Patch trap address Register
// array
#define APPS_CONFIG_O_PATCH_TRAP_EN_REG \
0x00000078
#define APPS_CONFIG_O_FAULT_STATUS_REG \
0x0000007C
#define APPS_CONFIG_O_MEMSS_WR_ERR_CLR_REG \
0x00000080
#define APPS_CONFIG_O_MEMSS_WR_ERR_ADDR_REG \
0x00000084
#define APPS_CONFIG_O_DMA_DONE_INT_MASK \
0x0000008C
#define APPS_CONFIG_O_DMA_DONE_INT_MASK_SET \
0x00000090
#define APPS_CONFIG_O_DMA_DONE_INT_MASK_CLR \
0x00000094
#define APPS_CONFIG_O_DMA_DONE_INT_STS_CLR \
0x00000098
#define APPS_CONFIG_O_DMA_DONE_INT_ACK \
0x0000009C
#define APPS_CONFIG_O_DMA_DONE_INT_STS_MASKED \
0x000000A0
#define APPS_CONFIG_O_DMA_DONE_INT_STS_RAW \
0x000000A4
#define APPS_CONFIG_O_FAULT_STATUS_CLR_REG \
0x000000A8
#define APPS_CONFIG_O_RESERVD_REG_0 \
0x000000AC
#define APPS_CONFIG_O_GPT_TRIG_SEL \
0x000000B0
#define APPS_CONFIG_O_TOP_DIE_SPARE_DIN_REG \
0x000000B4
#define APPS_CONFIG_O_TOP_DIE_SPARE_DOUT_REG \
0x000000B8
//******************************************************************************
//
// The following are defines for the bit fields in the
// APPS_CONFIG_O_PATCH_TRAP_ADDR_REG register.
//
//******************************************************************************
#define APPS_CONFIG_PATCH_TRAP_ADDR_REG_PATCH_TRAP_ADDR_M \
0xFFFFFFFF // When PATCH_TRAP_EN[n] is set bus
// fault is generated for the
// address
// PATCH_TRAP_ADDR_REG[n][31:0] from
// Idcode bus. The exception routine
// should take care to jump to the
// location where the patch
// correspond to this address is
// kept.
#define APPS_CONFIG_PATCH_TRAP_ADDR_REG_PATCH_TRAP_ADDR_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// APPS_CONFIG_O_PATCH_TRAP_EN_REG register.
//
//******************************************************************************
#define APPS_CONFIG_PATCH_TRAP_EN_REG_PATCH_TRAP_EN_M \
0x3FFFFFFF // When PATCH_TRAP_EN[n] is set bus
// fault is generated for the
// address PATCH_TRAP_ADD[n][31:0]
// from Idcode bus. The exception
// routine should take care to jump
// to the location where the patch
// correspond to this address is
// kept.
#define APPS_CONFIG_PATCH_TRAP_EN_REG_PATCH_TRAP_EN_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// APPS_CONFIG_O_FAULT_STATUS_REG register.
//
//******************************************************************************
#define APPS_CONFIG_FAULT_STATUS_REG_PATCH_ERR_INDEX_M \
0x0000003E // This field shows because of
// which patch trap address the
// bus_fault is generated. If the
// PATCH_ERR bit is set, then it
// means the bus fault is generated
// because of
// PATCH_TRAP_ADDR_REG[2^PATCH_ERR_INDEX]
#define APPS_CONFIG_FAULT_STATUS_REG_PATCH_ERR_INDEX_S 1
#define APPS_CONFIG_FAULT_STATUS_REG_PATCH_ERR \
0x00000001 // This bit is set when there is a
// bus fault because of patched
// address access to the Apps boot
// rom. Write 0 to clear this
// register.
//******************************************************************************
//
// The following are defines for the bit fields in the
// APPS_CONFIG_O_MEMSS_WR_ERR_CLR_REG register.
//
//******************************************************************************
#define APPS_CONFIG_MEMSS_WR_ERR_CLR_REG_MEMSS_WR_ERR_CLR \
0x00000001 // This bit is set when there is a
// an error in memss write access.
// And the address causing this
// error is captured in
// MEMSS_ERR_ADDR_REG. To capture
// the next error address one have
// to clear this bit.
//******************************************************************************
//
// The following are defines for the bit fields in the
// APPS_CONFIG_O_MEMSS_WR_ERR_ADDR_REG register.
//
//******************************************************************************
//******************************************************************************
//
// The following are defines for the bit fields in the
// APPS_CONFIG_O_DMA_DONE_INT_MASK register.
//
//******************************************************************************
#define APPS_CONFIG_DMA_DONE_INT_MASK_ADC_WR_DMA_DONE_INT_MASK_M \
0x0000F000 // 1= disable corresponding
// interrupt;0 = interrupt enabled
// bit 14: ADC channel 7 interrupt
// enable/disable bit 13: ADC
// channel 5 interrupt
// enable/disable bit 12: ADC
// channel 3 interrupt
// enable/disable bit 11: ADC
// channel 1 interrupt
// enable/disable
#define APPS_CONFIG_DMA_DONE_INT_MASK_ADC_WR_DMA_DONE_INT_MASK_S 12
#define APPS_CONFIG_DMA_DONE_INT_MASK_MCASP_WR_DMA_DONE_INT_MASK \
0x00000800 // 1= disable corresponding
// interrupt;0 = interrupt enabled
#define APPS_CONFIG_DMA_DONE_INT_MASK_MCASP_RD_DMA_DONE_INT_MASK \
0x00000400 // 1= disable corresponding
// interrupt;0 = interrupt enabled
#define APPS_CONFIG_DMA_DONE_INT_MASK_CAM_FIFO_EMPTY_DMA_DONE_INT_MASK \
0x00000200 // 1= disable corresponding
// interrupt;0 = interrupt enabled
#define APPS_CONFIG_DMA_DONE_INT_MASK_CAM_THRESHHOLD_DMA_DONE_INT_MASK \
0x00000100 // 1= disable corresponding
// interrupt;0 = interrupt enabled
#define APPS_CONFIG_DMA_DONE_INT_MASK_SHSPI_WR_DMA_DONE_INT_MASK \
0x00000080 // 1= disable corresponding
// interrupt;0 = interrupt enabled
#define APPS_CONFIG_DMA_DONE_INT_MASK_SHSPI_RD_DMA_DONE_INT_MASK \
0x00000040 // 1= disable corresponding
// interrupt;0 = interrupt enabled
#define APPS_CONFIG_DMA_DONE_INT_MASK_HOSTSPI_WR_DMA_DONE_INT_MASK \
0x00000020 // 1= disable corresponding
// interrupt;0 = interrupt enabled
#define APPS_CONFIG_DMA_DONE_INT_MASK_HOSTSPI_RD_DMA_DONE_INT_MASK \
0x00000010 // 1= disable corresponding
// interrupt;0 = interrupt enabled
#define APPS_CONFIG_DMA_DONE_INT_MASK_APPS_SPI_WR_DMA_DONE_INT_MASK \
0x00000008 // 1= disable corresponding
// interrupt;0 = interrupt enabled
#define APPS_CONFIG_DMA_DONE_INT_MASK_APPS_SPI_RD_DMA_DONE_INT_MASK \
0x00000004 // 1= disable corresponding
// interrupt;0 = interrupt enabled
#define APPS_CONFIG_DMA_DONE_INT_MASK_SDIOM_WR_DMA_DONE_INT_MASK \
0x00000002 // 1= disable corresponding
// interrupt;0 = interrupt enabled
#define APPS_CONFIG_DMA_DONE_INT_MASK_SDIOM_RD_DMA_DONE_INT_MASK \
0x00000001 // 1= disable corresponding
// interrupt;0 = interrupt enabled
//******************************************************************************
//
// The following are defines for the bit fields in the
// APPS_CONFIG_O_DMA_DONE_INT_MASK_SET register.
//
//******************************************************************************
#define APPS_CONFIG_DMA_DONE_INT_MASK_SET_ADC_WR_DMA_DONE_INT_MASK_SET_M \
0x0000F000 // write 1 to set mask of the
// corresponding DMA DONE IRQ;0 = no
// effect bit 14: ADC channel 7 DMA
// Done IRQ bit 13: ADC channel 5
// DMA Done IRQ bit 12: ADC channel
// 3 DMA Done IRQ bit 11: ADC
// channel 1 DMA Done IRQ
#define APPS_CONFIG_DMA_DONE_INT_MASK_SET_ADC_WR_DMA_DONE_INT_MASK_SET_S 12
#define APPS_CONFIG_DMA_DONE_INT_MASK_SET_MCASP_WR_DMA_DONE_INT_MASK_SET \
0x00000800 // write 1 to set mask of the
// corresponding DMA DONE IRQ;0 = no
// effect
#define APPS_CONFIG_DMA_DONE_INT_MASK_SET_MCASP_RD_DMA_DONE_INT_MASK_SET \
0x00000400 // write 1 to set mask of the
// corresponding DMA DONE IRQ;0 = no
// effect
#define APPS_CONFIG_DMA_DONE_INT_MASK_SET_CAM_FIFO_EMPTY_DMA_DONE_INT_MASK_SET \
0x00000200 // write 1 to set mask of the
// corresponding DMA DONE IRQ;0 = no
// effect
#define APPS_CONFIG_DMA_DONE_INT_MASK_SET_CAM_THRESHHOLD_DMA_DONE_INT_MASK_SET \
0x00000100 // write 1 to set mask of the
// corresponding DMA DONE IRQ;0 = no
// effect
#define APPS_CONFIG_DMA_DONE_INT_MASK_SET_SHSPI_WR_DMA_DONE_INT_MASK_SET \
0x00000080 // write 1 to set mask of the
// corresponding DMA DONE IRQ;0 = no
// effect
#define APPS_CONFIG_DMA_DONE_INT_MASK_SET_SHSPI_RD_DMA_DONE_INT_MASK_SET \
0x00000040 // write 1 to set mask of the
// corresponding DMA DONE IRQ;0 = no
// effect
#define APPS_CONFIG_DMA_DONE_INT_MASK_SET_HOSTSPI_WR_DMA_DONE_INT_MASK_SET \
0x00000020 // write 1 to set mask of the
// corresponding DMA DONE IRQ;0 = no
// effect
#define APPS_CONFIG_DMA_DONE_INT_MASK_SET_HOSTSPI_RD_DMA_DONE_INT_MASK_SET \
0x00000010 // write 1 to set mask of the
// corresponding DMA DONE IRQ;0 = no
// effect
#define APPS_CONFIG_DMA_DONE_INT_MASK_SET_APPS_SPI_WR_DMA_DONE_INT_MASK_SET \
0x00000008 // write 1 to set mask of the
// corresponding DMA DONE IRQ;0 = no
// effect
#define APPS_CONFIG_DMA_DONE_INT_MASK_SET_APPS_SPI_RD_DMA_DONE_INT_MASK_SET \
0x00000004 // write 1 to set mask of the
// corresponding DMA DONE IRQ;0 = no
// effect
#define APPS_CONFIG_DMA_DONE_INT_MASK_SET_SDIOM_WR_DMA_DONE_INT_MASK_SET \
0x00000002 // write 1 to set mask of the
// corresponding DMA DONE IRQ;0 = no
// effect
#define APPS_CONFIG_DMA_DONE_INT_MASK_SET_SDIOM_RD_DMA_DONE_INT_MASK_SET \
0x00000001 // write 1 to set mask of the
// corresponding DMA DONE IRQ;0 = no
// effect
//******************************************************************************
//
// The following are defines for the bit fields in the
// APPS_CONFIG_O_DMA_DONE_INT_MASK_CLR register.
//
//******************************************************************************
#define APPS_CONFIG_DMA_DONE_INT_MASK_CLR_ADC_WR_DMA_DONE_INT_MASK_CLR_M \
0x0000F000 // write 1 to clear mask of the
// corresponding DMA DONE IRQ;0 = no
// effect bit 14: ADC channel 7 DMA
// Done IRQ mask bit 13: ADC channel
// 5 DMA Done IRQ mask bit 12: ADC
// channel 3 DMA Done IRQ mask bit
// 11: ADC channel 1 DMA Done IRQ
// mask
#define APPS_CONFIG_DMA_DONE_INT_MASK_CLR_ADC_WR_DMA_DONE_INT_MASK_CLR_S 12
#define APPS_CONFIG_DMA_DONE_INT_MASK_CLR_MACASP_WR_DMA_DONE_INT_MASK_CLR \
0x00000800 // write 1 to clear mask of the
// corresponding DMA DONE IRQ;0 = no
// effect
#define APPS_CONFIG_DMA_DONE_INT_MASK_CLR_MCASP_RD_DMA_DONE_INT_MASK_CLR \
0x00000400 // write 1 to clear mask of the
// corresponding DMA DONE IRQ;0 = no
// effect
#define APPS_CONFIG_DMA_DONE_INT_MASK_CLR_CAM_FIFO_EMPTY_DMA_DONE_INT_MASK_CLR \
0x00000200 // write 1 to clear mask of the
// corresponding DMA DONE IRQ;0 = no
// effect
#define APPS_CONFIG_DMA_DONE_INT_MASK_CLR_CAM_THRESHHOLD_DMA_DONE_INT_MASK_CLR \
0x00000100 // write 1 to clear mask of the
// corresponding DMA DONE IRQ;0 = no
// effect
#define APPS_CONFIG_DMA_DONE_INT_MASK_CLR_SHSPI_WR_DMA_DONE_INT_MASK_CLR \
0x00000080 // write 1 to clear mask of the
// corresponding DMA DONE IRQ;0 = no
// effect
#define APPS_CONFIG_DMA_DONE_INT_MASK_CLR_SHSPI_RD_DMA_DONE_INT_MASK_CLR \
0x00000040 // write 1 to clear mask of the
// corresponding DMA DONE IRQ;0 = no
// effect
#define APPS_CONFIG_DMA_DONE_INT_MASK_CLR_HOSTSPI_WR_DMA_DONE_INT_MASK_CLR \
0x00000020 // write 1 to clear mask of the
// corresponding DMA DONE IRQ;0 = no
// effect
#define APPS_CONFIG_DMA_DONE_INT_MASK_CLR_HOSTSPI_RD_DMA_DONE_INT_MASK_CLR \
0x00000010 // write 1 to clear mask of the
// corresponding DMA DONE IRQ;0 = no
// effect
#define APPS_CONFIG_DMA_DONE_INT_MASK_CLR_APPS_SPI_WR_DMA_DONE_INT_MASK_CLR \
0x00000008 // write 1 to clear mask of the
// corresponding DMA DONE IRQ;0 = no
// effect
#define APPS_CONFIG_DMA_DONE_INT_MASK_CLR_APPS_SPI_RD_DMA_DONE_INT_MASK_CLR \
0x00000004 // write 1 to clear mask of the
// corresponding DMA DONE IRQ;0 = no
// effect
#define APPS_CONFIG_DMA_DONE_INT_MASK_CLR_SDIOM_WR_DMA_DONE_INT_MASK_CLR \
0x00000002 // write 1 to clear mask of the
// corresponding DMA DONE IRQ;0 = no
// effect
#define APPS_CONFIG_DMA_DONE_INT_MASK_CLR_SDIOM_RD_DMA_DONE_INT_MASK_CLR \
0x00000001 // write 1 to clear mask of the
// corresponding DMA DONE IRQ;0 = no
// effect
//******************************************************************************
//
// The following are defines for the bit fields in the
// APPS_CONFIG_O_DMA_DONE_INT_STS_CLR register.
//
//******************************************************************************
#define APPS_CONFIG_DMA_DONE_INT_STS_CLR_DMA_INT_STS_CLR_M \
0xFFFFFFFF // write 1 or 0 to clear all
// DMA_DONE interrupt;
#define APPS_CONFIG_DMA_DONE_INT_STS_CLR_DMA_INT_STS_CLR_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// APPS_CONFIG_O_DMA_DONE_INT_ACK register.
//
//******************************************************************************
#define APPS_CONFIG_DMA_DONE_INT_ACK_ADC_WR_DMA_DONE_INT_ACK_M \
0x0000F000 // write 1 to clear corresponding
// interrupt; 0 = no effect; bit 14:
// ADC channel 7 DMA Done IRQ bit
// 13: ADC channel 5 DMA Done IRQ
// bit 12: ADC channel 3 DMA Done
// IRQ bit 11: ADC channel 1 DMA
// Done IRQ
#define APPS_CONFIG_DMA_DONE_INT_ACK_ADC_WR_DMA_DONE_INT_ACK_S 12
#define APPS_CONFIG_DMA_DONE_INT_ACK_MCASP_WR_DMA_DONE_INT_ACK \
0x00000800 // write 1 to clear corresponding
// interrupt; 0 = no effect;
#define APPS_CONFIG_DMA_DONE_INT_ACK_MCASP_RD_DMA_DONE_INT_ACK \
0x00000400 // write 1 to clear corresponding
// interrupt; 0 = no effect;
#define APPS_CONFIG_DMA_DONE_INT_ACK_CAM_FIFO_EMPTY_DMA_DONE_INT_ACK \
0x00000200 // write 1 to clear corresponding
// interrupt; 0 = no effect;
#define APPS_CONFIG_DMA_DONE_INT_ACK_CAM_THRESHHOLD_DMA_DONE_INT_ACK \
0x00000100 // write 1 to clear corresponding
// interrupt; 0 = no effect;
#define APPS_CONFIG_DMA_DONE_INT_ACK_SHSPI_WR_DMA_DONE_INT_ACK \
0x00000080 // write 1 to clear corresponding
// interrupt; 0 = no effect;
#define APPS_CONFIG_DMA_DONE_INT_ACK_SHSPI_RD_DMA_DONE_INT_ACK \
0x00000040 // write 1 to clear corresponding
// interrupt; 0 = no effect;
#define APPS_CONFIG_DMA_DONE_INT_ACK_HOSTSPI_WR_DMA_DONE_INT_ACK \
0x00000020 // write 1 to clear corresponding
// interrupt; 0 = no effect;
#define APPS_CONFIG_DMA_DONE_INT_ACK_HOSTSPI_RD_DMA_DONE_INT_ACK \
0x00000010 // write 1 to clear corresponding
// interrupt; 0 = no effect;
#define APPS_CONFIG_DMA_DONE_INT_ACK_APPS_SPI_WR_DMA_DONE_INT_ACK \
0x00000008 // write 1 to clear corresponding
// interrupt; 0 = no effect;
#define APPS_CONFIG_DMA_DONE_INT_ACK_APPS_SPI_RD_DMA_DONE_INT_ACK \
0x00000004 // write 1 to clear corresponding
// interrupt; 0 = no effect;
#define APPS_CONFIG_DMA_DONE_INT_ACK_SDIOM_WR_DMA_DONE_INT_ACK \
0x00000002 // write 1 to clear corresponding
// interrupt; 0 = no effect;
#define APPS_CONFIG_DMA_DONE_INT_ACK_SDIOM_RD_DMA_DONE_INT_ACK \
0x00000001 // write 1 to clear corresponding
// interrupt; 0 = no effect;
//******************************************************************************
//
// The following are defines for the bit fields in the
// APPS_CONFIG_O_DMA_DONE_INT_STS_MASKED register.
//
//******************************************************************************
#define APPS_CONFIG_DMA_DONE_INT_STS_MASKED_ADC_WR_DMA_DONE_INT_STS_MASKED_M \
0x0000F000 // 1= corresponding interrupt is
// active and not masked. read is
// non-destructive;0 = corresponding
// interrupt is inactive or masked
// by DMA_DONE_INT mask bit 14: ADC
// channel 7 DMA Done IRQ bit 13:
// ADC channel 5 DMA Done IRQ bit
// 12: ADC channel 3 DMA Done IRQ
// bit 11: ADC channel 1 DMA Done
// IRQ
#define APPS_CONFIG_DMA_DONE_INT_STS_MASKED_ADC_WR_DMA_DONE_INT_STS_MASKED_S 12
#define APPS_CONFIG_DMA_DONE_INT_STS_MASKED_MCASP_WR_DMA_DONE_INT_STS_MASKED \
0x00000800 // 1= corresponding interrupt is
// active and not masked. read is
// non-destructive;0 = corresponding
// interrupt is inactive or masked
// by DMA_DONE_INT mask
#define APPS_CONFIG_DMA_DONE_INT_STS_MASKED_MCASP_RD_DMA_DONE_INT_STS_MASKED \
0x00000400 // 1= corresponding interrupt is
// active and not masked. read is
// non-destructive;0 = corresponding
// interrupt is inactive or masked
// by DMA_DONE_INT mask
#define APPS_CONFIG_DMA_DONE_INT_STS_MASKED_CAM_FIFO_EMPTY_DMA_DONE_INT_STS_MASKED \
0x00000200 // 1= corresponding interrupt is
// active and not masked. read is
// non-destructive;0 = corresponding
// interrupt is inactive or masked
// by DMA_DONE_INT mask
#define APPS_CONFIG_DMA_DONE_INT_STS_MASKED_CAM_THRESHHOLD_DMA_DONE_INT_STS_MASKED \
0x00000100 // 1= corresponding interrupt is
// active and not masked. read is
// non-destructive;0 = corresponding
// interrupt is inactive or masked
// by DMA_DONE_INT mask
#define APPS_CONFIG_DMA_DONE_INT_STS_MASKED_SHSPI_WR_DMA_DONE_INT_STS_MASKED \
0x00000080 // 1= corresponding interrupt is
// active and not masked. read is
// non-destructive;0 = corresponding
// interrupt is inactive or masked
// by DMA_DONE_INT mask
#define APPS_CONFIG_DMA_DONE_INT_STS_MASKED_SHSPI_RD_DMA_DONE_INT_STS_MASKED \
0x00000040 // 1= corresponding interrupt is
// active and not masked. read is
// non-destructive;0 = corresponding
// interrupt is inactive or masked
// by DMA_DONE_INT mask
#define APPS_CONFIG_DMA_DONE_INT_STS_MASKED_HOSTSPI_WR_DMA_DONE_INT_STS_MASKED \
0x00000020 // 1= corresponding interrupt is
// active and not masked. read is
// non-destructive;0 = corresponding
// interrupt is inactive or masked
// by DMA_DONE_INT mask
#define APPS_CONFIG_DMA_DONE_INT_STS_MASKED_HOSTSPI_RD_DMA_DONE_INT_STS_MASKED \
0x00000010 // 1= corresponding interrupt is
// active and not masked. read is
// non-destructive;0 = corresponding
// interrupt is inactive or masked
// by DMA_DONE_INT mask
#define APPS_CONFIG_DMA_DONE_INT_STS_MASKED_APPS_SPI_WR_DMA_DONE_INT_STS_MASKED \
0x00000008 // 1= corresponding interrupt is
// active and not masked. read is
// non-destructive;0 = corresponding
// interrupt is inactive or masked
// by DMA_DONE_INT mask
#define APPS_CONFIG_DMA_DONE_INT_STS_MASKED_APPS_SPI_RD_DMA_DONE_INT_STS_MASKED \
0x00000004 // 1= corresponding interrupt is
// active and not masked. read is
// non-destructive;0 = corresponding
// interrupt is inactive or masked
// by DMA_DONE_INT mask
#define APPS_CONFIG_DMA_DONE_INT_STS_MASKED_SDIOM_WR_DMA_DONE_INT_STS_MASKED \
0x00000002 // 1= corresponding interrupt is
// active and not masked. read is
// non-destructive;0 = corresponding
// interrupt is inactive or masked
// by DMA_DONE_INT mask
#define APPS_CONFIG_DMA_DONE_INT_STS_MASKED_SDIOM_RD_DMA_DONE_INT_STS_MASKED \
0x00000001 // 1= corresponding interrupt is
// active and not masked. read is
// non-destructive;0 = corresponding
// interrupt is inactive or masked
// by DMA_DONE_INT mask
//******************************************************************************
//
// The following are defines for the bit fields in the
// APPS_CONFIG_O_DMA_DONE_INT_STS_RAW register.
//
//******************************************************************************
#define APPS_CONFIG_DMA_DONE_INT_STS_RAW_ADC_WR_DMA_DONE_INT_STS_RAW_M \
0x0000F000 // 1= corresponding interrupt is
// active. read is non-destructive;0
// = corresponding interrupt is
// inactive bit 14: ADC channel 7
// DMA Done IRQ bit 13: ADC channel
// 5 DMA Done IRQ bit 12: ADC
// channel 3 DMA Done IRQ bit 11:
// ADC channel 1 DMA Done IRQ
#define APPS_CONFIG_DMA_DONE_INT_STS_RAW_ADC_WR_DMA_DONE_INT_STS_RAW_S 12
#define APPS_CONFIG_DMA_DONE_INT_STS_RAW_MCASP_WR_DMA_DONE_INT_STS_RAW \
0x00000800 // 1= corresponding interrupt is
// active. read is non-destructive;0
// = corresponding interrupt is
// inactive
#define APPS_CONFIG_DMA_DONE_INT_STS_RAW_MCASP_RD_DMA_DONE_INT_STS_RAW \
0x00000400 // 1= corresponding interrupt is
// active. read is non-destructive;0
// = corresponding interrupt is
// inactive
#define APPS_CONFIG_DMA_DONE_INT_STS_RAW_CAM_EPMTY_FIFO_DMA_DONE_INT_STS_RAW \
0x00000200 // 1= corresponding interrupt is
// active. read is non-destructive;0
// = corresponding interrupt is
// inactive
#define APPS_CONFIG_DMA_DONE_INT_STS_RAW_CAM_THRESHHOLD_DMA_DONE_INT_STS_RAW \
0x00000100 // 1= corresponding interrupt is
// active. read is non-destructive;0
// = corresponding interrupt is
// inactive
#define APPS_CONFIG_DMA_DONE_INT_STS_RAW_SHSPI_WR_DMA_DONE_INT_STS_RAW \
0x00000080 // 1= corresponding interrupt is
// active. read is non-destructive;0
// = corresponding interrupt is
// inactive
#define APPS_CONFIG_DMA_DONE_INT_STS_RAW_SHSPI_RD_DMA_DONE_INT_STS_RAW \
0x00000040 // 1= corresponding interrupt is
// active. read is non-destructive;0
// = corresponding interrupt is
// inactive
#define APPS_CONFIG_DMA_DONE_INT_STS_RAW_HOSTSPI_WR_DMA_DONE_INT_STS_RAW \
0x00000020 // 1= corresponding interrupt is
// active. read is non-destructive;0
// = corresponding interrupt is
// inactive
#define APPS_CONFIG_DMA_DONE_INT_STS_RAW_HOSTSPI_RD_DMA_DONE_INT_STS_RAW \
0x00000010 // 1= corresponding interrupt is
// active. read is non-destructive;0
// = corresponding interrupt is
// inactive
#define APPS_CONFIG_DMA_DONE_INT_STS_RAW_APPS_SPI_WR_DMA_DONE_INT_STS_RAW \
0x00000008 // 1= corresponding interrupt is
// active. read is non-destructive;0
// = corresponding interrupt is
// inactive
#define APPS_CONFIG_DMA_DONE_INT_STS_RAW_APPS_SPI_RD_DMA_DONE_INT_STS_RAW \
0x00000004 // 1= corresponding interrupt is
// active. read is non-destructive;0
// = corresponding interrupt is
// inactive
#define APPS_CONFIG_DMA_DONE_INT_STS_RAW_SDIOM_WR_DMA_DONE_INT_STS_RAW \
0x00000002 // 1= corresponding interrupt is
// active. read is non-destructive;0
// = corresponding interrupt is
// inactive
#define APPS_CONFIG_DMA_DONE_INT_STS_RAW_SDIOM_RD_DMA_DONE_INT_STS_RAW \
0x00000001 // 1= corresponding interrupt is
// active. read is non-destructive;0
// = corresponding interrupt is
// inactive
//******************************************************************************
//
// The following are defines for the bit fields in the
// APPS_CONFIG_O_FAULT_STATUS_CLR_REG register.
//
//******************************************************************************
#define APPS_CONFIG_FAULT_STATUS_CLR_REG_PATCH_ERR_CLR \
0x00000001 // Write 1 to clear the LSB of
// FAULT_STATUS_REG
//******************************************************************************
//
// The following are defines for the bit fields in the
// APPS_CONFIG_O_RESERVD_REG_0 register.
//
//******************************************************************************
//******************************************************************************
//
// The following are defines for the bit fields in the
// APPS_CONFIG_O_GPT_TRIG_SEL register.
//
//******************************************************************************
#define APPS_CONFIG_GPT_TRIG_SEL_GPT_TRIG_SEL_M \
0x000000FF // This bit is implemented for GPT
// trigger mode select. GPT IP
// support 2 modes: RTC mode and
// external trigger. When this bit
// is set to logic '1': enable
// external trigger mode for APPS
// GPT CP0 and CP1 pin. bit 0: when
// set '1' enable external GPT
// trigger 0 on GPIO0 CP0 pin else
// RTC mode is selected. bit 1: when
// set '1' enable external GPT
// trigger 1 on GPIO0 CP1 pin else
// RTC mode is selected. bit 2: when
// set '1' enable external GPT
// trigger 2 on GPIO1 CP0 pin else
// RTC mode is selected. bit 3: when
// set '1' enable external GPT
// trigger 3 on GPIO1 CP1 pin else
// RTC mode is selected. bit 4: when
// set '1' enable external GPT
// trigger 4 on GPIO2 CP0 pin else
// RTC mode is selected. bit 5: when
// set '1' enable external GPT
// trigger 5 on GPIO2 CP1 pin else
// RTC mode is selected. bit 6: when
// set '1' enable external GPT
// trigger 6 on GPIO3 CP0 pin else
// RTC mode is selected. bit 7: when
// set '1' enable external GPT
// trigger 7 on GPIO3 CP1 pin else
// RTC mode is selected.
#define APPS_CONFIG_GPT_TRIG_SEL_GPT_TRIG_SEL_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// APPS_CONFIG_O_TOP_DIE_SPARE_DIN_REG register.
//
//******************************************************************************
#define APPS_CONFIG_TOP_DIE_SPARE_DIN_REG_D2D_SPARE_DIN_M \
0x00000007 // Capture data from d2d_spare pads
#define APPS_CONFIG_TOP_DIE_SPARE_DIN_REG_D2D_SPARE_DIN_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// APPS_CONFIG_O_TOP_DIE_SPARE_DOUT_REG register.
//
//******************************************************************************
#define APPS_CONFIG_TOP_DIE_SPARE_DOUT_REG_D2D_SPARE_DOUT_M \
0x00000007 // Send data to d2d_spare pads -
// eventually this will get
// registered in top die
#define APPS_CONFIG_TOP_DIE_SPARE_DOUT_REG_D2D_SPARE_DOUT_S 0
#endif // __HW_APPS_CONFIG_H__

1506
inc/hw_apps_rcm.h Normal file

File diff suppressed because it is too large Load Diff

519
inc/hw_camera.h Normal file
View File

@ -0,0 +1,519 @@
//*****************************************************************************
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#ifndef __HW_CAMERA_H__
#define __HW_CAMERA_H__
//*****************************************************************************
//
// The following are defines for the CAMERA register offsets.
//
//*****************************************************************************
#define CAMERA_O_CC_REVISION 0x00000000 // This register contains the IP
// revision code ( Parallel Mode)
#define CAMERA_O_CC_SYSCONFIG 0x00000010 // This register controls the
// various parameters of the OCP
// interface (CCP and Parallel Mode)
#define CAMERA_O_CC_SYSSTATUS 0x00000014 // This register provides status
// information about the module
// excluding the interrupt status
// information (CCP and Parallel
// Mode)
#define CAMERA_O_CC_IRQSTATUS 0x00000018 // The interrupt status regroups
// all the status of the module
// internal events that can generate
// an interrupt (CCP & Parallel
// Mode)
#define CAMERA_O_CC_IRQENABLE 0x0000001C // The interrupt enable register
// allows to enable/disable the
// module internal sources of
// interrupt on an event-by-event
// basis (CCP & Parallel Mode)
#define CAMERA_O_CC_CTRL 0x00000040 // This register controls the
// various parameters of the Camera
// Core block (CCP & Parallel Mode)
#define CAMERA_O_CC_CTRL_DMA 0x00000044 // This register controls the DMA
// interface of the Camera Core
// block (CCP & Parallel Mode)
#define CAMERA_O_CC_CTRL_XCLK 0x00000048 // This register control the value
// of the clock divisor used to
// generate the external clock
// (Parallel Mode)
#define CAMERA_O_CC_FIFO_DATA 0x0000004C // This register allows to write to
// the FIFO and read from the FIFO
// (CCP & Parallel Mode)
#define CAMERA_O_CC_TEST 0x00000050 // This register shows the status
// of some important variables of
// the camera core module (CCP &
// Parallel Mode)
#define CAMERA_O_CC_GEN_PAR 0x00000054 // This register shows the values
// of the generic parameters of the
// module
//******************************************************************************
//
// The following are defines for the bit fields in the
// CAMERA_O_CC_REVISION register.
//
//******************************************************************************
#define CAMERA_CC_REVISION_REV_M \
0x000000FF // IP revision [7:4] Major revision
// [3:0] Minor revision Examples:
// 0x10 for 1.0 0x21 for 2.1
#define CAMERA_CC_REVISION_REV_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// CAMERA_O_CC_SYSCONFIG register.
//
//******************************************************************************
#define CAMERA_CC_SYSCONFIG_S_IDLE_MODE_M \
0x00000018 // Slave interface power management
// req/ack control """00""
// Force-idle. An idle request is
// acknoledged unconditionally"
// """01"" No-idle. An idle request
// is never acknowledged" """10""
// reserved (Smart-idle not
// implemented)"
#define CAMERA_CC_SYSCONFIG_S_IDLE_MODE_S 3
#define CAMERA_CC_SYSCONFIG_SOFT_RESET \
0x00000002 // Software reset. Set this bit to
// 1 to trigger a module reset. The
// bit is automatically reset by the
// hardware. During reset it always
// returns 0. 0 Normal mode 1 The
// module is reset
#define CAMERA_CC_SYSCONFIG_AUTO_IDLE \
0x00000001 // Internal OCP clock gating
// strategy 0 OCP clock is
// free-running 1 Automatic OCP
// clock gating strategy is applied
// based on the OCP interface
// activity
//******************************************************************************
//
// The following are defines for the bit fields in the
// CAMERA_O_CC_SYSSTATUS register.
//
//******************************************************************************
#define CAMERA_CC_SYSSTATUS_RESET_DONE2 \
0x00000001 // Internal Reset Monitoring 0
// Internal module reset is on-going
// 1 Reset completed
//******************************************************************************
//
// The following are defines for the bit fields in the
// CAMERA_O_CC_IRQSTATUS register.
//
//******************************************************************************
#define CAMERA_CC_IRQSTATUS_FS_IRQ \
0x00080000 // Frame Start has occurred 0 Event
// false "1 Event is true
// (""pending"")" 0 Event status bit
// unchanged 1 Event status bit is
// reset
#define CAMERA_CC_IRQSTATUS_LE_IRQ \
0x00040000 // Line End has occurred 0 Event
// false "1 Event is true
// (""pending"")" 0 Event status bit
// unchanged 1 Event status bit is
// reset
#define CAMERA_CC_IRQSTATUS_LS_IRQ \
0x00020000 // Line Start has occurred 0 Event
// false "1 Event is true
// (""pending"")" 0 Event status bit
// unchanged 1 Event status bit is
// reset
#define CAMERA_CC_IRQSTATUS_FE_IRQ \
0x00010000 // Frame End has occurred 0 Event
// false "1 Event is true
// (""pending"")" 0 Event status bit
// unchanged 1 Event status bit is
// reset
#define CAMERA_CC_IRQSTATUS_FSP_ERR_IRQ \
0x00000800 // FSP code error 0 Event false "1
// Event is true (""pending"")" 0
// Event status bit unchanged 1
// Event status bit is reset
#define CAMERA_CC_IRQSTATUS_FW_ERR_IRQ \
0x00000400 // Frame Height Error 0 Event false
// "1 Event is true (""pending"")" 0
// Event status bit unchanged 1
// Event status bit is reset
#define CAMERA_CC_IRQSTATUS_FSC_ERR_IRQ \
0x00000200 // False Synchronization Code 0
// Event false "1 Event is true
// (""pending"")" 0 Event status bit
// unchanged 1 Event status bit is
// reset
#define CAMERA_CC_IRQSTATUS_SSC_ERR_IRQ \
0x00000100 // Shifted Synchronization Code 0
// Event false "1 Event is true
// (""pending"")" 0 Event status bit
// unchanged 1 Event status bit is
// reset
#define CAMERA_CC_IRQSTATUS_FIFO_NONEMPTY_IRQ \
0x00000010 // FIFO is not empty 0 Event false
// "1 Event is true (""pending"")" 0
// Event status bit unchanged 1
// Event status bit is reset
#define CAMERA_CC_IRQSTATUS_FIFO_FULL_IRQ \
0x00000008 // FIFO is full 0 Event false "1
// Event is true (""pending"")" 0
// Event status bit unchanged 1
// Event status bit is reset
#define CAMERA_CC_IRQSTATUS_FIFO_THR_IRQ \
0x00000004 // FIFO threshold has been reached
// 0 Event false "1 Event is true
// (""pending"")" 0 Event status bit
// unchanged 1 Event status bit is
// reset
#define CAMERA_CC_IRQSTATUS_FIFO_OF_IRQ \
0x00000002 // FIFO overflow has occurred 0
// Event false "1 Event is true
// (""pending"")" 0 Event status bit
// unchanged 1 Event status bit is
// reset
#define CAMERA_CC_IRQSTATUS_FIFO_UF_IRQ \
0x00000001 // FIFO underflow has occurred 0
// Event false "1 Event is true
// (""pending"")" 0 Event status bit
// unchanged 1 Event status bit is
// reset
//******************************************************************************
//
// The following are defines for the bit fields in the
// CAMERA_O_CC_IRQENABLE register.
//
//******************************************************************************
#define CAMERA_CC_IRQENABLE_FS_IRQ_EN \
0x00080000 // Frame Start Interrupt Enable 0
// Event is masked 1 Event generates
// an interrupt when it occurs
#define CAMERA_CC_IRQENABLE_LE_IRQ_EN \
0x00040000 // Line End Interrupt Enable 0
// Event is masked 1 Event generates
// an interrupt when it occurs
#define CAMERA_CC_IRQENABLE_LS_IRQ_EN \
0x00020000 // Line Start Interrupt Enable 0
// Event is masked 1 Event generates
// an interrupt when it occurs
#define CAMERA_CC_IRQENABLE_FE_IRQ_EN \
0x00010000 // Frame End Interrupt Enable 0
// Event is masked 1 Event generates
// an interrupt when it occurs
#define CAMERA_CC_IRQENABLE_FSP_IRQ_EN \
0x00000800 // FSP code Interrupt Enable 0
// Event is masked 1 Event generates
// an interrupt when it occurs
#define CAMERA_CC_IRQENABLE_FW_ERR_IRQ_EN \
0x00000400 // Frame Height Error Interrupt
// Enable 0 Event is masked 1 Event
// generates an interrupt when it
// occurs
#define CAMERA_CC_IRQENABLE_FSC_ERR_IRQ_EN \
0x00000200 // False Synchronization Code
// Interrupt Enable 0 Event is
// masked 1 Event generates an
// interrupt when it occurs
#define CAMERA_CC_IRQENABLE_SSC_ERR_IRQ_EN \
0x00000100 // False Synchronization Code
// Interrupt Enable 0 Event is
// masked 1 Event generates an
// interrupt when it occurs
#define CAMERA_CC_IRQENABLE_FIFO_NONEMPTY_IRQ_EN \
0x00000010 // FIFO Threshold Interrupt Enable
// 0 Event is masked 1 Event
// generates an interrupt when it
// occurs
#define CAMERA_CC_IRQENABLE_FIFO_FULL_IRQ_EN \
0x00000008 // FIFO Threshold Interrupt Enable
// 0 Event is masked 1 Event
// generates an interrupt when it
// occurs
#define CAMERA_CC_IRQENABLE_FIFO_THR_IRQ_EN \
0x00000004 // FIFO Threshold Interrupt Enable
// 0 Event is masked 1 Event
// generates an interrupt when it
// occurs
#define CAMERA_CC_IRQENABLE_FIFO_OF_IRQ_EN \
0x00000002 // FIFO Overflow Interrupt Enable 0
// Event is masked 1 Event generates
// an interrupt when it occurs
#define CAMERA_CC_IRQENABLE_FIFO_UF_IRQ_EN \
0x00000001 // FIFO Underflow Interrupt Enable
// 0 Event is masked 1 Event
// generates an interrupt when it
// occurs
//******************************************************************************
//
// The following are defines for the bit fields in the CAMERA_O_CC_CTRL register.
//
//******************************************************************************
#define CAMERA_CC_CTRL_CC_IF_SYNCHRO \
0x00080000 // Synchronize all camera sensor
// inputs This must be set during
// the configuration phase before
// CC_EN set to '1'. This can be
// used in very high frequency to
// avoid dependancy to the IO
// timings. 0 No synchro (most of
// applications) 1 Synchro enabled
// (should never be required)
#define CAMERA_CC_CTRL_CC_RST 0x00040000 // Resets all the internal finite
// states machines of the camera
// core module - by writing a 1 to
// this bit. must be applied when
// CC_EN = 0 Reads returns 0
#define CAMERA_CC_CTRL_CC_FRAME_TRIG \
0x00020000 // Set the modality in which CC_EN
// works when a disabling of the
// sensor camera core is wanted "If
// CC_FRAME_TRIG = 1 by writing
// ""0"" to CC_EN" the module is
// disabled at the end of the frame
// "If CC_FRAME_TRIG = 0 by writing
// ""0"" to CC_EN" the module is
// disabled immediately
#define CAMERA_CC_CTRL_CC_EN 0x00010000 // Enables the sensor interface of
// the camera core module "By
// writing ""1"" to this field the
// module is enabled." "By writing
// ""0"" to this field the module is
// disabled at" the end of the frame
// if CC_FRAM_TRIG =1 and is
// disabled immediately if
// CC_FRAM_TRIG = 0
#define CAMERA_CC_CTRL_NOBT_SYNCHRO \
0x00002000 // Enables to start at the
// beginning of the frame or not in
// NoBT 0 Acquisition starts when
// Vertical synchro is high 1
// Acquisition starts when Vertical
// synchro goes from low to high
// (beginning of the frame) -
// Recommended.
#define CAMERA_CC_CTRL_BT_CORRECT \
0x00001000 // Enables the correction within
// the sync codes in BT mode 0
// correction is not enabled 1
// correction is enabled
#define CAMERA_CC_CTRL_PAR_ORDERCAM \
0x00000800 // Enables swap between image-data
// in parallel mode 0 swap is not
// enabled 1 swap is enabled
#define CAMERA_CC_CTRL_PAR_CLK_POL \
0x00000400 // Inverts the clock coming from
// the sensor in parallel mode 0
// clock not inverted - data sampled
// on rising edge 1 clock inverted -
// data sampled on falling edge
#define CAMERA_CC_CTRL_NOBT_HS_POL \
0x00000200 // Sets the polarity of the
// synchronization signals in NOBT
// parallel mode 0 CAM_P_HS is
// active high 1 CAM_P_HS is active
// low
#define CAMERA_CC_CTRL_NOBT_VS_POL \
0x00000100 // Sets the polarity of the
// synchronization signals in NOBT
// parallel mode 0 CAM_P_VS is
// active high 1 CAM_P_VS is active
// low
#define CAMERA_CC_CTRL_PAR_MODE_M \
0x0000000E // Sets the Protocol Mode of the
// Camera Core module in parallel
// mode (when CCP_MODE = 0) """000""
// Parallel NOBT 8-bit" """001""
// Parallel NOBT 10-bit" """010""
// Parallel NOBT 12-bit" """011""
// reserved" """100"" Parallet BT
// 8-bit" """101"" Parallel BT
// 10-bit" """110"" reserved"
// """111"" FIFO test mode. Refer to
// Table 12 - FIFO Write and Read
// access"
#define CAMERA_CC_CTRL_PAR_MODE_S 1
#define CAMERA_CC_CTRL_CCP_MODE 0x00000001 // Set the Camera Core in CCP mode
// 0 CCP mode disabled 1 CCP mode
// enabled
//******************************************************************************
//
// The following are defines for the bit fields in the
// CAMERA_O_CC_CTRL_DMA register.
//
//******************************************************************************
#define CAMERA_CC_CTRL_DMA_DMA_EN \
0x00000100 // Sets the number of dma request
// lines 0 DMA interface disabled
// The DMA request line stays
// inactive 1 DMA interface enabled
// The DMA request line is
// operational
#define CAMERA_CC_CTRL_DMA_FIFO_THRESHOLD_M \
0x0000007F // Sets the threshold of the FIFO
// the assertion of the dmarequest
// line takes place when the
// threshold is reached.
// """0000000"" threshold set to 1"
// """0000001"" threshold set to 2"
// … """1111111"" threshold set to
// 128"
#define CAMERA_CC_CTRL_DMA_FIFO_THRESHOLD_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// CAMERA_O_CC_CTRL_XCLK register.
//
//******************************************************************************
#define CAMERA_CC_CTRL_XCLK_XCLK_DIV_M \
0x0000001F // Sets the clock divisor value for
// CAM_XCLK generation. based on
// CAM_MCK (value of CAM_MCLK is
// 96MHz) """00000"" CAM_XCLK Stable
// Low Level" Divider not enabled
// """00001"" CAM_XCLK Stable High
// Level" Divider not enabled from 2
// to 30 CAM_XCLK = CAM_MCLK /
// XCLK_DIV """11111"" Bypass -
// CAM_XCLK = CAM_MCLK"
#define CAMERA_CC_CTRL_XCLK_XCLK_DIV_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// CAMERA_O_CC_FIFO_DATA register.
//
//******************************************************************************
#define CAMERA_CC_FIFO_DATA_FIFO_DATA_M \
0xFFFFFFFF // Writes the 32-bit word into the
// FIFO Reads the 32-bit word from
// the FIFO
#define CAMERA_CC_FIFO_DATA_FIFO_DATA_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the CAMERA_O_CC_TEST register.
//
//******************************************************************************
#define CAMERA_CC_TEST_FIFO_RD_POINTER_M \
0xFF000000 // FIFO READ Pointer This field
// shows the value of the FIFO read
// pointer Expected value ranges
// from 0 to 127
#define CAMERA_CC_TEST_FIFO_RD_POINTER_S 24
#define CAMERA_CC_TEST_FIFO_WR_POINTER_M \
0x00FF0000 // FIFO WRITE pointer This field
// shows the value of the FIFO write
// pointer Expected value ranges
// from 0 to 127
#define CAMERA_CC_TEST_FIFO_WR_POINTER_S 16
#define CAMERA_CC_TEST_FIFO_LEVEL_M \
0x0000FF00 // FIFO level (how many 32-bit
// words the FIFO contains) This
// field shows the value of the FIFO
// level and can assume values from
// 0 to 128
#define CAMERA_CC_TEST_FIFO_LEVEL_S 8
#define CAMERA_CC_TEST_FIFO_LEVEL_PEAK_M \
0x000000FF // FIFO level peak This field shows
// the max value of the FIFO level
// and can assume values from 0 to
// 128
#define CAMERA_CC_TEST_FIFO_LEVEL_PEAK_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// CAMERA_O_CC_GEN_PAR register.
//
//******************************************************************************
#define CAMERA_CC_GEN_PAR_CC_FIFO_DEPTH_M \
0x00000007 // Camera Core FIFO DEPTH generic
// parameter
#define CAMERA_CC_GEN_PAR_CC_FIFO_DEPTH_S 0
#endif // __HW_CAMERA_H__

1117
inc/hw_common_reg.h Normal file

File diff suppressed because it is too large Load Diff

339
inc/hw_des.h Normal file
View File

@ -0,0 +1,339 @@
//*****************************************************************************
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#ifndef __HW_DES_H__
#define __HW_DES_H__
//*****************************************************************************
//
// The following are defines for the DES_P register offsets.
//
//*****************************************************************************
#define DES_O_KEY3_L 0x00000000 // KEY3 (LSW) for 192-bit key
#define DES_O_KEY3_H 0x00000004 // KEY3 (MSW) for 192-bit key
#define DES_O_KEY2_L 0x00000008 // KEY2 (LSW) for 192-bit key
#define DES_O_KEY2_H 0x0000000C // KEY2 (MSW) for 192-bit key
#define DES_O_KEY1_L 0x00000010 // KEY1 (LSW) for 128-bit
// key/192-bit key
#define DES_O_KEY1_H 0x00000014 // KEY1 (LSW) for 128-bit
// key/192-bit key
#define DES_O_IV_L 0x00000018 // Initialization vector LSW
#define DES_O_IV_H 0x0000001C // Initialization vector MSW
#define DES_O_CTRL 0x00000020
#define DES_O_LENGTH 0x00000024 // Indicates the cryptographic data
// length in bytes for all modes.
// Once processing is started with
// this context this length
// decrements to zero. Data lengths
// up to (2^32 1) bytes are
// allowed. A write to this register
// triggers the engine to start
// using this context. For a Host
// read operation these registers
// return all-zeroes.
#define DES_O_DATA_L 0x00000028 // Data register(LSW) to read/write
// encrypted/decrypted data.
#define DES_O_DATA_H 0x0000002C // Data register(MSW) to read/write
// encrypted/decrypted data.
#define DES_O_REVISION 0x00000030
#define DES_O_SYSCONFIG 0x00000034
#define DES_O_SYSSTATUS 0x00000038
#define DES_O_IRQSTATUS 0x0000003C // This register indicates the
// interrupt status. If one of the
// interrupt bits is set the
// interrupt output will be asserted
#define DES_O_IRQENABLE 0x00000040 // This register contains an enable
// bit for each unique interrupt
// generated by the module. It
// matches the layout of
// DES_IRQSTATUS register. An
// interrupt is enabled when the bit
// in this register is set to 1
//******************************************************************************
//
// The following are defines for the bit fields in the DES_O_KEY3_L register.
//
//******************************************************************************
#define DES_KEY3_L_KEY3_L_M 0xFFFFFFFF // data for key3
#define DES_KEY3_L_KEY3_L_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the DES_O_KEY3_H register.
//
//******************************************************************************
#define DES_KEY3_H_KEY3_H_M 0xFFFFFFFF // data for key3
#define DES_KEY3_H_KEY3_H_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the DES_O_KEY2_L register.
//
//******************************************************************************
#define DES_KEY2_L_KEY2_L_M 0xFFFFFFFF // data for key2
#define DES_KEY2_L_KEY2_L_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the DES_O_KEY2_H register.
//
//******************************************************************************
#define DES_KEY2_H_KEY2_H_M 0xFFFFFFFF // data for key2
#define DES_KEY2_H_KEY2_H_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the DES_O_KEY1_L register.
//
//******************************************************************************
#define DES_KEY1_L_KEY1_L_M 0xFFFFFFFF // data for key1
#define DES_KEY1_L_KEY1_L_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the DES_O_KEY1_H register.
//
//******************************************************************************
#define DES_KEY1_H_KEY1_H_M 0xFFFFFFFF // data for key1
#define DES_KEY1_H_KEY1_H_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the DES_O_IV_L register.
//
//******************************************************************************
#define DES_IV_L_IV_L_M 0xFFFFFFFF // initialization vector for CBC
// CFB modes
#define DES_IV_L_IV_L_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the DES_O_IV_H register.
//
//******************************************************************************
#define DES_IV_H_IV_H_M 0xFFFFFFFF // initialization vector for CBC
// CFB modes
#define DES_IV_H_IV_H_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the DES_O_CTRL register.
//
//******************************************************************************
#define DES_CTRL_CONTEXT 0x80000000 // If 1 this read-only status bit
// indicates that the context data
// registers can be overwritten and
// the host is permitted to write
// the next context.
#define DES_CTRL_MODE_M 0x00000030 // Select CBC ECB or CFB mode 0x0
// ecb mode 0x1 cbc mode 0x2 cfb
// mode 0x3 reserved
#define DES_CTRL_MODE_S 4
#define DES_CTRL_TDES 0x00000008 // Select DES or triple DES
// encryption/decryption. 0 des mode
// 1 tdes mode
#define DES_CTRL_DIRECTION 0x00000004 // select encryption/decryption 0
// decryption is selected 1
// Encryption is selected
#define DES_CTRL_INPUT_READY 0x00000002 // When '1' ready to
// encrypt/decrypt data
#define DES_CTRL_OUTPUT_READY 0x00000001 // When '1' Data
// decrypted/encrypted ready
//******************************************************************************
//
// The following are defines for the bit fields in the DES_O_LENGTH register.
//
//******************************************************************************
#define DES_LENGTH_LENGTH_M 0xFFFFFFFF
#define DES_LENGTH_LENGTH_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the DES_O_DATA_L register.
//
//******************************************************************************
#define DES_DATA_L_DATA_L_M 0xFFFFFFFF // data for encryption/decryption
#define DES_DATA_L_DATA_L_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the DES_O_DATA_H register.
//
//******************************************************************************
#define DES_DATA_H_DATA_H_M 0xFFFFFFFF // data for encryption/decryption
#define DES_DATA_H_DATA_H_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the DES_O_REVISION register.
//
//******************************************************************************
#define DES_REVISION_SCHEME_M 0xC0000000
#define DES_REVISION_SCHEME_S 30
#define DES_REVISION_FUNC_M 0x0FFF0000 // Function indicates a software
// compatible module family. If
// there is no level of software
// compatibility a new Func number
// (and hence REVISION) should be
// assigned.
#define DES_REVISION_FUNC_S 16
#define DES_REVISION_R_RTL_M 0x0000F800 // RTL Version (R) maintained by IP
// design owner. RTL follows a
// numbering such as X.Y.R.Z which
// are explained in this table. R
// changes ONLY when: (1) PDS
// uploads occur which may have been
// due to spec changes (2) Bug fixes
// occur (3) Resets to '0' when X or
// Y changes. Design team has an
// internal 'Z' (customer invisible)
// number which increments on every
// drop that happens due to DV and
// RTL updates. Z resets to 0 when R
// increments.
#define DES_REVISION_R_RTL_S 11
#define DES_REVISION_X_MAJOR_M \
0x00000700 // Major Revision (X) maintained by
// IP specification owner. X changes
// ONLY when: (1) There is a major
// feature addition. An example
// would be adding Master Mode to
// Utopia Level2. The Func field (or
// Class/Type in old PID format)
// will remain the same. X does NOT
// change due to: (1) Bug fixes (2)
// Change in feature parameters.
#define DES_REVISION_X_MAJOR_S 8
#define DES_REVISION_CUSTOM_M 0x000000C0
#define DES_REVISION_CUSTOM_S 6
#define DES_REVISION_Y_MINOR_M \
0x0000003F // Minor Revision (Y) maintained by
// IP specification owner. Y changes
// ONLY when: (1) Features are
// scaled (up or down). Flexibility
// exists in that this feature
// scalability may either be
// represented in the Y change or a
// specific register in the IP that
// indicates which features are
// exactly available. (2) When
// feature creeps from Is-Not list
// to Is list. But this may not be
// the case once it sees silicon; in
// which case X will change. Y does
// NOT change due to: (1) Bug fixes
// (2) Typos or clarifications (3)
// major functional/feature
// change/addition/deletion. Instead
// these changes may be reflected
// via R S X as applicable. Spec
// owner maintains a
// customer-invisible number 'S'
// which changes due to: (1)
// Typos/clarifications (2) Bug
// documentation. Note that this bug
// is not due to a spec change but
// due to implementation.
// Nevertheless the spec tracks the
// IP bugs. An RTL release (say for
// silicon PG1.1) that occurs due to
// bug fix should document the
// corresponding spec number (X.Y.S)
// in its release notes.
#define DES_REVISION_Y_MINOR_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the DES_O_SYSCONFIG register.
//
//******************************************************************************
#define DES_SYSCONFIG_DMA_REQ_CONTEXT_IN_EN \
0x00000080 // If set to 1 the DMA context
// request is enabled. 0 Dma
// disabled 1 Dma enabled
#define DES_SYSCONFIG_DMA_REQ_DATA_OUT_EN \
0x00000040 // If set to 1 the DMA output
// request is enabled. 0 Dma
// disabled 1 Dma enabled
#define DES_SYSCONFIG_DMA_REQ_DATA_IN_EN \
0x00000020 // If set to 1 the DMA input
// request is enabled. 0 Dma
// disabled 1 Dma enabled
//******************************************************************************
//
// The following are defines for the bit fields in the DES_O_SYSSTATUS register.
//
//******************************************************************************
#define DES_SYSSTATUS_RESETDONE \
0x00000001
//******************************************************************************
//
// The following are defines for the bit fields in the DES_O_IRQSTATUS register.
//
//******************************************************************************
#define DES_IRQSTATUS_DATA_OUT \
0x00000004 // This bit indicates data output
// interrupt is active and triggers
// the interrupt output.
#define DES_IRQSTATUS_DATA_IN 0x00000002 // This bit indicates data input
// interrupt is active and triggers
// the interrupt output.
#define DES_IRQSTATUS_CONTEX_IN \
0x00000001 // This bit indicates context
// interrupt is active and triggers
// the interrupt output.
//******************************************************************************
//
// The following are defines for the bit fields in the DES_O_IRQENABLE register.
//
//******************************************************************************
#define DES_IRQENABLE_M_DATA_OUT \
0x00000004 // If this bit is set to 1 the
// secure data output interrupt is
// enabled.
#define DES_IRQENABLE_M_DATA_IN \
0x00000002 // If this bit is set to 1 the
// secure data input interrupt is
// enabled.
#define DES_IRQENABLE_M_CONTEX_IN \
0x00000001 // If this bit is set to 1 the
// secure context interrupt is
// enabled.
#endif // __HW_DES_H__

392
inc/hw_dthe.h Normal file
View File

@ -0,0 +1,392 @@
//*****************************************************************************
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
//*****************************************************************************
#ifndef __HW_DTHE_H__
#define __HW_DTHE_H__
//*****************************************************************************
//
// The following are defines for the DTHE register offsets.
//
//*****************************************************************************
#define DTHE_O_SHA_IM 0x00000810
#define DTHE_O_SHA_RIS 0x00000814
#define DTHE_O_SHA_MIS 0x00000818
#define DTHE_O_SHA_IC 0x0000081C
#define DTHE_O_AES_IM 0x00000820
#define DTHE_O_AES_RIS 0x00000824
#define DTHE_O_AES_MIS 0x00000828
#define DTHE_O_AES_IC 0x0000082C
#define DTHE_O_DES_IM 0x00000830
#define DTHE_O_DES_RIS 0x00000834
#define DTHE_O_DES_MIS 0x00000838
#define DTHE_O_DES_IC 0x0000083C
#define DTHE_O_EIP_CGCFG 0x00000A00
#define DTHE_O_EIP_CGREQ 0x00000A04
#define DTHE_O_CRC_CTRL 0x00000C00
#define DTHE_O_CRC_SEED 0x00000C10
#define DTHE_O_CRC_DIN 0x00000C14
#define DTHE_O_CRC_RSLT_PP 0x00000C18
#define DTHE_O_RAND_KEY0 0x00000F00
#define DTHE_O_RAND_KEY1 0x00000F04
#define DTHE_O_RAND_KEY2 0x00000F08
#define DTHE_O_RAND_KEY3 0x00000F0C
//******************************************************************************
//
// The following are defines for the bit fields in the
// DTHE_O_SHAMD5_IMST register.
//
//******************************************************************************
#define DTHE_SHAMD5_IMST_DIN 0x00000004 // Data in: this interrupt is
// raised when DMA writes last word
// of input data to internal FIFO of
// the engine
#define DTHE_SHAMD5_IMST_COUT 0x00000002 // Context out: this interrupt is
// raised when DMA complets the
// output context movement from
// internal register
#define DTHE_SHAMD5_IMST_CIN 0x00000001 // context in: this interrupt is
// raised when DMA complets Context
// write to internal register
//******************************************************************************
//
// The following are defines for the bit fields in the
// DTHE_O_SHAMD5_IRIS register.
//
//******************************************************************************
#define DTHE_SHAMD5_IRIS_DIN 0x00000004 // input Data movement is done
#define DTHE_SHAMD5_IRIS_COUT 0x00000002 // Context output is done
#define DTHE_SHAMD5_IRIS_CIN 0x00000001 // context input is done
//******************************************************************************
//
// The following are defines for the bit fields in the
// DTHE_O_SHAMD5_IMIS register.
//
//******************************************************************************
#define DTHE_SHAMD5_IMIS_DIN 0x00000004 // input Data movement is done
#define DTHE_SHAMD5_IMIS_COUT 0x00000002 // Context output is done
#define DTHE_SHAMD5_IMIS_CIN 0x00000001 // context input is done
//******************************************************************************
//
// The following are defines for the bit fields in the
// DTHE_O_SHAMD5_ICIS register.
//
//******************************************************************************
#define DTHE_SHAMD5_ICIS_DIN 0x00000004 // Clear “input Data movement done”
// flag
#define DTHE_SHAMD5_ICIS_COUT 0x00000002 // Clear “Context output done” flag
#define DTHE_SHAMD5_ICIS_CIN 0x00000001 // Clear “context input done” flag
//******************************************************************************
//
// The following are defines for the bit fields in the
// DTHE_O_AES_IMST register.
//
//******************************************************************************
#define DTHE_AES_IMST_DOUT 0x00000008 // Data out: this interrupt is
// raised when DMA finishes writing
// last word of the process result
#define DTHE_AES_IMST_DIN 0x00000004 // Data in: this interrupt is
// raised when DMA writes last word
// of input data to internal FIFO of
// the engine
#define DTHE_AES_IMST_COUT 0x00000002 // Context out: this interrupt is
// raised when DMA complets the
// output context movement from
// internal register
#define DTHE_AES_IMST_CIN 0x00000001 // context in: this interrupt is
// raised when DMA complets Context
// write to internal register
//******************************************************************************
//
// The following are defines for the bit fields in the
// DTHE_O_AES_IRIS register.
//
//******************************************************************************
#define DTHE_AES_IRIS_DOUT 0x00000008 // Output Data movement is done
#define DTHE_AES_IRIS_DIN 0x00000004 // input Data movement is done
#define DTHE_AES_IRIS_COUT 0x00000002 // Context output is done
#define DTHE_AES_IRIS_CIN 0x00000001 // context input is done
//******************************************************************************
//
// The following are defines for the bit fields in the
// DTHE_O_AES_IMIS register.
//
//******************************************************************************
#define DTHE_AES_IMIS_DOUT 0x00000008 // Output Data movement is done
#define DTHE_AES_IMIS_DIN 0x00000004 // input Data movement is done
#define DTHE_AES_IMIS_COUT 0x00000002 // Context output is done
#define DTHE_AES_IMIS_CIN 0x00000001 // context input is done
//******************************************************************************
//
// The following are defines for the bit fields in the
// DTHE_O_AES_ICIS register.
//
//******************************************************************************
#define DTHE_AES_ICIS_DOUT 0x00000008 // Clear “output Data movement
// done” flag
#define DTHE_AES_ICIS_DIN 0x00000004 // Clear “input Data movement done”
// flag
#define DTHE_AES_ICIS_COUT 0x00000002 // Clear “Context output done” flag
#define DTHE_AES_ICIS_CIN 0x00000001 // Clear “context input done” flag
//******************************************************************************
//
// The following are defines for the bit fields in the
// DTHE_O_DES_IMST register.
//
//******************************************************************************
#define DTHE_DES_IMST_DOUT 0x00000008 // Data out: this interrupt is
// raised when DMA finishes writing
// last word of the process result
#define DTHE_DES_IMST_DIN 0x00000004 // Data in: this interrupt is
// raised when DMA writes last word
// of input data to internal FIFO of
// the engine
#define DTHE_DES_IMST_CIN 0x00000001 // context in: this interrupt is
// raised when DMA complets Context
// write to internal register
//******************************************************************************
//
// The following are defines for the bit fields in the
// DTHE_O_DES_IRIS register.
//
//******************************************************************************
#define DTHE_DES_IRIS_DOUT 0x00000008 // Output Data movement is done
#define DTHE_DES_IRIS_DIN 0x00000004 // input Data movement is done
#define DTHE_DES_IRIS_CIN 0x00000001 // context input is done
//******************************************************************************
//
// The following are defines for the bit fields in the
// DTHE_O_DES_IMIS register.
//
//******************************************************************************
#define DTHE_DES_IMIS_DOUT 0x00000008 // Output Data movement is done
#define DTHE_DES_IMIS_DIN 0x00000004 // input Data movement is done
#define DTHE_DES_IMIS_CIN 0x00000001 // context input is done
//******************************************************************************
//
// The following are defines for the bit fields in the
// DTHE_O_DES_ICIS register.
//
//******************************************************************************
#define DTHE_DES_ICIS_DOUT 0x00000008 // Clear “output Data movement
// done” flag
#define DTHE_DES_ICIS_DIN 0x00000004 // Clear “input Data movement done”
// flag
#define DTHE_DES_ICIS_CIN 0x00000001 // Clear "context input done” flag
//******************************************************************************
//
// The following are defines for the bit fields in the
// DTHE_O_EIP_CGCFG register.
//
//******************************************************************************
#define DTHE_EIP_CGCFG_EIP29_CFG \
0x00000010 // Clock gating protocol setting
// for EIP29T. 0 Follow direct
// protocol 1 Follow idle_req/ack
// protocol.
#define DTHE_EIP_CGCFG_EIP75_CFG \
0x00000008 // Clock gating protocol setting
// for EIP75T. 0 Follow direct
// protocol 1 Follow idle_req/ack
// protocol.
#define DTHE_EIP_CGCFG_EIP16_CFG \
0x00000004 // Clock gating protocol setting
// for DES. 0 Follow direct
// protocol 1 Follow idle_req/ack
// protocol.
#define DTHE_EIP_CGCFG_EIP36_CFG \
0x00000002 // Clock gating protocol setting
// for AES. 0 Follow direct
// protocol 1 Follow idle_req/ack
// protocol.
#define DTHE_EIP_CGCFG_EIP57_CFG \
0x00000001 // Clock gating protocol setting
// for SHAMD5. 0 Follow direct
// protocol 1 Follow idle_req/ack
// protocol.
//******************************************************************************
//
// The following are defines for the bit fields in the
// DTHE_O_EIP_CGREQ register.
//
//******************************************************************************
#define DTHE_EIP_CGREQ_Key_M 0xF0000000 // When “0x5” write “1” to lower
// bits [4:0] will set the bit.
// Write “0” will be ignored When
// “0x2” write “1” to lower bit
// [4:0] will clear the bit. Write
// “0” will be ignored for other key
// value, regular read write
// operation
#define DTHE_EIP_CGREQ_Key_S 28
#define DTHE_EIP_CGREQ_EIP29_REQ \
0x00000010 // 0 request clock gating 1
// request to un-gate the clock.
#define DTHE_EIP_CGREQ_EIP75_REQ \
0x00000008 // 0 request clock gating 1
// request to un-gate the clock.
#define DTHE_EIP_CGREQ_EIP16_REQ \
0x00000004 // 0 request clock gating 1
// request to un-gate the clock.
#define DTHE_EIP_CGREQ_EIP36_REQ \
0x00000002 // 0 request clock gating 1
// request to un-gate the clock.
#define DTHE_EIP_CGREQ_EIP57_REQ \
0x00000001 // 0 request clock gating 1
// request to un-gate the clock.
//******************************************************************************
//
// The following are defines for the bit fields in the DTHE_O_CRC_CTRL register.
//
//******************************************************************************
#define DTHE_CRC_CTRL_INIT_M 0x00006000 // Initialize the CRC 00 use SEED
// register context as starting
// value 10 all “zero” 11 all
// “one” This is self clearing. With
// first write to data register this
// value clears to zero and remain
// zero for rest of the operation
// unless written again
#define DTHE_CRC_CTRL_INIT_S 13
#define DTHE_CRC_CTRL_SIZE 0x00001000 // Input data size 0 32 bit 1 8
// bit
#define DTHE_CRC_CTRL_OINV 0x00000200 // Inverse the bits of result
// before storing to CRC_RSLT_PP0
#define DTHE_CRC_CTRL_OBR 0x00000100 // Bit reverse the output result
// byte before storing to
// CRC_RSLT_PP0. applicable for all
// bytes in word
#define DTHE_CRC_CTRL_IBR 0x00000080 // Bit reverse the input byte. For
// all bytes in word
#define DTHE_CRC_CTRL_ENDIAN_M \
0x00000030 // Endian control [0] swap byte
// in half-word [1] swap half word
#define DTHE_CRC_CTRL_ENDIAN_S 4
#define DTHE_CRC_CTRL_TYPE_M 0x0000000F // Type of operation 0000
// polynomial 0x8005 0001
// polynomial 0x1021 0010
// polynomial 0x4C11DB7 0011
// polynomial 0x1EDC6F41 1000 TCP
// checksum TYPE in DTHE_S_CRC_CTRL
// & DTHE_S_CRC_CTRL should be
// exclusive
#define DTHE_CRC_CTRL_TYPE_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the DTHE_O_CRC_SEED register.
//
//******************************************************************************
#define DTHE_CRC_SEED_SEED_M 0xFFFFFFFF // Starting seed of CRC and
// checksum operation. Please see
// CTRL register for more detail.
// This resister also holds the
// latest result of CRC or checksum
// operation
#define DTHE_CRC_SEED_SEED_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the DTHE_O_CRC_DIN register.
//
//******************************************************************************
#define DTHE_CRC_DIN_DATA_IN_M \
0xFFFFFFFF // Input data for CRC or checksum
// operation
#define DTHE_CRC_DIN_DATA_IN_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// DTHE_O_CRC_RSLT_PP register.
//
//******************************************************************************
#define DTHE_CRC_RSLT_PP_RSLT_PP_M \
0xFFFFFFFF // Input data for CRC or checksum
// operation
#define DTHE_CRC_RSLT_PP_RSLT_PP_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// DTHE_O_RAND_KEY0 register.
//
//******************************************************************************
#define DTHE_RAND_KEY0_KEY_M 0xFFFFFFFF // Device Specific Randon key
// [31:0]
#define DTHE_RAND_KEY0_KEY_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// DTHE_O_RAND_KEY1 register.
//
//******************************************************************************
#define DTHE_RAND_KEY1_KEY_M 0xFFFFFFFF // Device Specific Randon key
// [63:32]
#define DTHE_RAND_KEY1_KEY_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// DTHE_O_RAND_KEY2 register.
//
//******************************************************************************
#define DTHE_RAND_KEY2_KEY_M 0xFFFFFFFF // Device Specific Randon key
// [95:34]
#define DTHE_RAND_KEY2_KEY_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the
// DTHE_O_RAND_KEY3 register.
//
//******************************************************************************
#define DTHE_RAND_KEY3_KEY_M 0xFFFFFFFF // Device Specific Randon key
// [127:96]
#define DTHE_RAND_KEY3_KEY_S 0
#endif // __HW_DTHE_H__

1862
inc/hw_flash_ctrl.h Normal file

File diff suppressed because it is too large Load Diff

1349
inc/hw_gpio.h Normal file

File diff suppressed because it is too large Load Diff

3322
inc/hw_gprcm.h Normal file

File diff suppressed because it is too large Load Diff

1750
inc/hw_hib1p2.h Normal file

File diff suppressed because it is too large Load Diff

1138
inc/hw_hib3p3.h Normal file

File diff suppressed because it is too large Load Diff

503
inc/hw_i2c.h Normal file
View File

@ -0,0 +1,503 @@
//*****************************************************************************
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
#ifndef __HW_I2C_H__
#define __HW_I2C_H__
//*****************************************************************************
//
// The following are defines for the I2C register offsets.
//
//*****************************************************************************
#define I2C_O_MSA 0x00000000
#define I2C_O_MCS 0x00000004
#define I2C_O_MDR 0x00000008
#define I2C_O_MTPR 0x0000000C
#define I2C_O_MIMR 0x00000010
#define I2C_O_MRIS 0x00000014
#define I2C_O_MMIS 0x00000018
#define I2C_O_MICR 0x0000001C
#define I2C_O_MCR 0x00000020
#define I2C_O_MCLKOCNT 0x00000024
#define I2C_O_MBMON 0x0000002C
#define I2C_O_MBLEN 0x00000030
#define I2C_O_MBCNT 0x00000034
#define I2C_O_SOAR 0x00000800
#define I2C_O_SCSR 0x00000804
#define I2C_O_SDR 0x00000808
#define I2C_O_SIMR 0x0000080C
#define I2C_O_SRIS 0x00000810
#define I2C_O_SMIS 0x00000814
#define I2C_O_SICR 0x00000818
#define I2C_O_SOAR2 0x0000081C
#define I2C_O_SACKCTL 0x00000820
#define I2C_O_FIFODATA 0x00000F00
#define I2C_O_FIFOCTL 0x00000F04
#define I2C_O_FIFOSTATUS 0x00000F08
#define I2C_O_OBSMUXSEL0 0x00000F80
#define I2C_O_OBSMUXSEL1 0x00000F84
#define I2C_O_MUXROUTE 0x00000F88
#define I2C_O_PV 0x00000FB0
#define I2C_O_PP 0x00000FC0
#define I2C_O_PC 0x00000FC4
#define I2C_O_CC 0x00000FC8
//******************************************************************************
//
// The following are defines for the bit fields in the I2C_O_MSA register.
//
//******************************************************************************
#define I2C_MSA_SA_M 0x000000FE // I2C Slave Address
#define I2C_MSA_SA_S 1
#define I2C_MSA_RS 0x00000001 // Receive not send
//******************************************************************************
//
// The following are defines for the bit fields in the I2C_O_MCS register.
//
//******************************************************************************
#define I2C_MCS_ACTDMARX 0x80000000 // DMA RX Active Status
#define I2C_MCS_ACTDMATX 0x40000000 // DMA TX Active Status
#define I2C_MCS_CLKTO 0x00000080 // Clock Timeout Error
#define I2C_MCS_BUSBSY 0x00000040 // Bus Busy
#define I2C_MCS_IDLE 0x00000020 // I2C Idle
#define I2C_MCS_ARBLST 0x00000010 // Arbitration Lost
#define I2C_MCS_ACK 0x00000008 // Data Acknowledge Enable
#define I2C_MCS_ADRACK 0x00000004 // Acknowledge Address
#define I2C_MCS_ERROR 0x00000002 // Error
#define I2C_MCS_BUSY 0x00000001 // I2C Busy
//******************************************************************************
//
// The following are defines for the bit fields in the I2C_O_MDR register.
//
//******************************************************************************
#define I2C_MDR_DATA_M 0x000000FF // Data Transferred
#define I2C_MDR_DATA_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the I2C_O_MTPR register.
//
//******************************************************************************
#define I2C_MTPR_HS 0x00000080 // High-Speed Enable
#define I2C_MTPR_TPR_M 0x0000007F // SCL Clock Period
#define I2C_MTPR_TPR_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the I2C_O_MIMR register.
//
//******************************************************************************
#define I2C_MIMR_RXFFIM 0x00000800 // Receive FIFO Full Interrupt Mask
#define I2C_MIMR_TXFEIM 0x00000400 // Transmit FIFO Empty Interrupt
// Mask
#define I2C_MIMR_RXIM 0x00000200 // Receive FIFO Request Interrupt
// Mask
#define I2C_MIMR_TXIM 0x00000100 // Transmit FIFO Request Interrupt
// Mask
#define I2C_MIMR_ARBLOSTIM 0x00000080 // Arbitration Lost Interrupt Mask
#define I2C_MIMR_STOPIM 0x00000040 // STOP Detection Interrupt Mask
#define I2C_MIMR_STARTIM 0x00000020 // START Detection Interrupt Mask
#define I2C_MIMR_NACKIM 0x00000010 // Address/Data NACK Interrupt Mask
#define I2C_MIMR_DMATXIM 0x00000008 // Transmit DMA Interrupt Mask
#define I2C_MIMR_DMARXIM 0x00000004 // Receive DMA Interrupt Mask
#define I2C_MIMR_CLKIM 0x00000002 // Clock Timeout Interrupt Mask
#define I2C_MIMR_IM 0x00000001 // Master Interrupt Mask
//******************************************************************************
//
// The following are defines for the bit fields in the I2C_O_MRIS register.
//
//******************************************************************************
#define I2C_MRIS_RXFFRIS 0x00000800 // Receive FIFO Full Raw Interrupt
// Status
#define I2C_MRIS_TXFERIS 0x00000400 // Transmit FIFO Empty Raw
// Interrupt Status
#define I2C_MRIS_RXRIS 0x00000200 // Receive FIFO Request Raw
// Interrupt Status
#define I2C_MRIS_TXRIS 0x00000100 // Transmit Request Raw Interrupt
// Status
#define I2C_MRIS_ARBLOSTRIS 0x00000080 // Arbitration Lost Raw Interrupt
// Status
#define I2C_MRIS_STOPRIS 0x00000040 // STOP Detection Raw Interrupt
// Status
#define I2C_MRIS_STARTRIS 0x00000020 // START Detection Raw Interrupt
// Status
#define I2C_MRIS_NACKRIS 0x00000010 // Address/Data NACK Raw Interrupt
// Status
#define I2C_MRIS_DMATXRIS 0x00000008 // Transmit DMA Raw Interrupt
// Status
#define I2C_MRIS_DMARXRIS 0x00000004 // Receive DMA Raw Interrupt Status
#define I2C_MRIS_CLKRIS 0x00000002 // Clock Timeout Raw Interrupt
// Status
#define I2C_MRIS_RIS 0x00000001 // Master Raw Interrupt Status
//******************************************************************************
//
// The following are defines for the bit fields in the I2C_O_MMIS register.
//
//******************************************************************************
#define I2C_MMIS_RXFFMIS 0x00000800 // Receive FIFO Full Interrupt Mask
#define I2C_MMIS_TXFEMIS 0x00000400 // Transmit FIFO Empty Interrupt
// Mask
#define I2C_MMIS_RXMIS 0x00000200 // Receive FIFO Request Interrupt
// Mask
#define I2C_MMIS_TXMIS 0x00000100 // Transmit Request Interrupt Mask
#define I2C_MMIS_ARBLOSTMIS 0x00000080 // Arbitration Lost Interrupt Mask
#define I2C_MMIS_STOPMIS 0x00000040 // STOP Detection Interrupt Mask
#define I2C_MMIS_STARTMIS 0x00000020 // START Detection Interrupt Mask
#define I2C_MMIS_NACKMIS 0x00000010 // Address/Data NACK Interrupt Mask
#define I2C_MMIS_DMATXMIS 0x00000008 // Transmit DMA Interrupt Status
#define I2C_MMIS_DMARXMIS 0x00000004 // Receive DMA Interrupt Status
#define I2C_MMIS_CLKMIS 0x00000002 // Clock Timeout Masked Interrupt
// Status
#define I2C_MMIS_MIS 0x00000001 // Masked Interrupt Status
//******************************************************************************
//
// The following are defines for the bit fields in the I2C_O_MICR register.
//
//******************************************************************************
#define I2C_MICR_RXFFIC 0x00000800 // Receive FIFO Full Interrupt
// Clear
#define I2C_MICR_TXFEIC 0x00000400 // Transmit FIFO Empty Interrupt
// Clear
#define I2C_MICR_RXIC 0x00000200 // Receive FIFO Request Interrupt
// Clear
#define I2C_MICR_TXIC 0x00000100 // Transmit FIFO Request Interrupt
// Clear
#define I2C_MICR_ARBLOSTIC 0x00000080 // Arbitration Lost Interrupt Clear
#define I2C_MICR_STOPIC 0x00000040 // STOP Detection Interrupt Clear
#define I2C_MICR_STARTIC 0x00000020 // START Detection Interrupt Clear
#define I2C_MICR_NACKIC 0x00000010 // Address/Data NACK Interrupt
// Clear
#define I2C_MICR_DMATXIC 0x00000008 // Transmit DMA Interrupt Clear
#define I2C_MICR_DMARXIC 0x00000004 // Receive DMA Interrupt Clear
#define I2C_MICR_CLKIC 0x00000002 // Clock Timeout Interrupt Clear
#define I2C_MICR_IC 0x00000001 // Master Interrupt Clear
//******************************************************************************
//
// The following are defines for the bit fields in the I2C_O_MCR register.
//
//******************************************************************************
#define I2C_MCR_MMD 0x00000040 // Multi-master Disable
#define I2C_MCR_SFE 0x00000020 // I2C Slave Function Enable
#define I2C_MCR_MFE 0x00000010 // I2C Master Function Enable
#define I2C_MCR_LPBK 0x00000001 // I2C Loopback
//******************************************************************************
//
// The following are defines for the bit fields in the I2C_O_MCLKOCNT register.
//
//******************************************************************************
#define I2C_MCLKOCNT_CNTL_M 0x000000FF // I2C Master Count
#define I2C_MCLKOCNT_CNTL_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the I2C_O_MBMON register.
//
//******************************************************************************
#define I2C_MBMON_SDA 0x00000002 // I2C SDA Status
#define I2C_MBMON_SCL 0x00000001 // I2C SCL Status
//******************************************************************************
//
// The following are defines for the bit fields in the I2C_O_MBLEN register.
//
//******************************************************************************
#define I2C_MBLEN_CNTL_M 0x000000FF // I2C Burst Length
#define I2C_MBLEN_CNTL_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the I2C_O_MBCNT register.
//
//******************************************************************************
#define I2C_MBCNT_CNTL_M 0x000000FF // I2C Master Burst Count
#define I2C_MBCNT_CNTL_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the I2C_O_SOAR register.
//
//******************************************************************************
#define I2C_SOAR_OAR_M 0x0000007F // I2C Slave Own Address
#define I2C_SOAR_OAR_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the I2C_O_SCSR register.
//
//******************************************************************************
#define I2C_SCSR_ACTDMARX 0x80000000 // DMA RX Active Status
#define I2C_SCSR_ACTDMATX 0x40000000 // DMA TX Active Status
#define I2C_SCSR_QCMDRW 0x00000020 // Quick Command Read / Write
#define I2C_SCSR_QCMDST 0x00000010 // Quick Command Status
#define I2C_SCSR_OAR2SEL 0x00000008 // OAR2 Address Matched
#define I2C_SCSR_FBR 0x00000004 // First Byte Received
#define I2C_SCSR_TREQ 0x00000002 // Transmit Request
#define I2C_SCSR_DA 0x00000001 // Device Active
//******************************************************************************
//
// The following are defines for the bit fields in the I2C_O_SDR register.
//
//******************************************************************************
#define I2C_SDR_DATA_M 0x000000FF // Data for Transfer
#define I2C_SDR_DATA_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the I2C_O_SIMR register.
//
//******************************************************************************
#define I2C_SIMR_IM 0x00000100 // Interrupt Mask
#define I2C_SIMR_TXFEIM 0x00000080 // Transmit FIFO Empty Interrupt
// Mask
#define I2C_SIMR_RXIM 0x00000040 // Receive FIFO Request Interrupt
// Mask
#define I2C_SIMR_TXIM 0x00000020 // Transmit FIFO Request Interrupt
// Mask
#define I2C_SIMR_DMATXIM 0x00000010 // Transmit DMA Interrupt Mask
#define I2C_SIMR_DMARXIM 0x00000008 // Receive DMA Interrupt Mask
#define I2C_SIMR_STOPIM 0x00000004 // Stop Condition Interrupt Mask
#define I2C_SIMR_STARTIM 0x00000002 // Start Condition Interrupt Mask
#define I2C_SIMR_DATAIM 0x00000001 // Data Interrupt Mask
//******************************************************************************
//
// The following are defines for the bit fields in the I2C_O_SRIS register.
//
//******************************************************************************
#define I2C_SRIS_RIS 0x00000100 // Raw Interrupt Status
#define I2C_SRIS_TXFERIS 0x00000080 // Transmit FIFO Empty Raw
// Interrupt Status
#define I2C_SRIS_RXRIS 0x00000040 // Receive FIFO Request Raw
// Interrupt Status
#define I2C_SRIS_TXRIS 0x00000020 // Transmit Request Raw Interrupt
// Status
#define I2C_SRIS_DMATXRIS 0x00000010 // Transmit DMA Raw Interrupt
// Status
#define I2C_SRIS_DMARXRIS 0x00000008 // Receive DMA Raw Interrupt Status
#define I2C_SRIS_STOPRIS 0x00000004 // Stop Condition Raw Interrupt
// Status
#define I2C_SRIS_STARTRIS 0x00000002 // Start Condition Raw Interrupt
// Status
#define I2C_SRIS_DATARIS 0x00000001 // Data Raw Interrupt Status
//******************************************************************************
//
// The following are defines for the bit fields in the I2C_O_SMIS register.
//
//******************************************************************************
#define I2C_SMIS_RXFFMIS 0x00000100 // Receive FIFO Full Interrupt Mask
#define I2C_SMIS_TXFEMIS 0x00000080 // Transmit FIFO Empty Interrupt
// Mask
#define I2C_SMIS_RXMIS 0x00000040 // Receive FIFO Request Interrupt
// Mask
#define I2C_SMIS_TXMIS 0x00000020 // Transmit FIFO Request Interrupt
// Mask
#define I2C_SMIS_DMATXMIS 0x00000010 // Transmit DMA Masked Interrupt
// Status
#define I2C_SMIS_DMARXMIS 0x00000008 // Receive DMA Masked Interrupt
// Status
#define I2C_SMIS_STOPMIS 0x00000004 // Stop Condition Masked Interrupt
// Status
#define I2C_SMIS_STARTMIS 0x00000002 // Start Condition Masked Interrupt
// Status
#define I2C_SMIS_DATAMIS 0x00000001 // Data Masked Interrupt Status
//******************************************************************************
//
// The following are defines for the bit fields in the I2C_O_SICR register.
//
//******************************************************************************
#define I2C_SICR_RXFFIC 0x00000100 // Receive FIFO Full Interrupt Mask
#define I2C_SICR_TXFEIC 0x00000080 // Transmit FIFO Empty Interrupt
// Mask
#define I2C_SICR_RXIC 0x00000040 // Receive Request Interrupt Mask
#define I2C_SICR_TXIC 0x00000020 // Transmit Request Interrupt Mask
#define I2C_SICR_DMATXIC 0x00000010 // Transmit DMA Interrupt Clear
#define I2C_SICR_DMARXIC 0x00000008 // Receive DMA Interrupt Clear
#define I2C_SICR_STOPIC 0x00000004 // Stop Condition Interrupt Clear
#define I2C_SICR_STARTIC 0x00000002 // Start Condition Interrupt Clear
#define I2C_SICR_DATAIC 0x00000001 // Data Interrupt Clear
//******************************************************************************
//
// The following are defines for the bit fields in the I2C_O_SOAR2 register.
//
//******************************************************************************
#define I2C_SOAR2_OAR2EN 0x00000080 // I2C Slave Own Address 2 Enable
#define I2C_SOAR2_OAR2_M 0x0000007F // I2C Slave Own Address 2
#define I2C_SOAR2_OAR2_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the I2C_O_SACKCTL register.
//
//******************************************************************************
#define I2C_SACKCTL_ACKOVAL 0x00000002 // I2C Slave ACK Override Value
#define I2C_SACKCTL_ACKOEN 0x00000001 // I2C Slave ACK Override Enable
//******************************************************************************
//
// The following are defines for the bit fields in the I2C_O_FIFODATA register.
//
//******************************************************************************
#define I2C_FIFODATA_DATA_M 0x000000FF // I2C FIFO Data Byte
#define I2C_FIFODATA_DATA_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the I2C_O_FIFOCTL register.
//
//******************************************************************************
#define I2C_FIFOCTL_RXASGNMT 0x80000000 // RX Control Assignment
#define I2C_FIFOCTL_RXFLUSH 0x40000000 // RX FIFO Flush
#define I2C_FIFOCTL_DMARXENA 0x20000000 // DMA RX Channel Enable
#define I2C_FIFOCTL_RXTRIG_M 0x00070000 // RX FIFO Trigger
#define I2C_FIFOCTL_RXTRIG_S 16
#define I2C_FIFOCTL_TXASGNMT 0x00008000 // TX Control Assignment
#define I2C_FIFOCTL_TXFLUSH 0x00004000 // TX FIFO Flush
#define I2C_FIFOCTL_DMATXENA 0x00002000 // DMA TX Channel Enable
#define I2C_FIFOCTL_TXTRIG_M 0x00000007 // TX FIFO Trigger
#define I2C_FIFOCTL_TXTRIG_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the I2C_O_FIFOSTATUS register.
//
//******************************************************************************
#define I2C_FIFOSTATUS_RXABVTRIG \
0x00040000 // RX FIFO Above Trigger Level
#define I2C_FIFOSTATUS_RXFF 0x00020000 // RX FIFO Full
#define I2C_FIFOSTATUS_RXFE 0x00010000 // RX FIFO Empty
#define I2C_FIFOSTATUS_TXBLWTRIG \
0x00000004 // TX FIFO Below Trigger Level
#define I2C_FIFOSTATUS_TXFF 0x00000002 // TX FIFO Full
#define I2C_FIFOSTATUS_TXFE 0x00000001 // TX FIFO Empty
//******************************************************************************
//
// The following are defines for the bit fields in the I2C_O_OBSMUXSEL0 register.
//
//******************************************************************************
#define I2C_OBSMUXSEL0_LN3_M 0x07000000 // Observation Mux Lane 3
#define I2C_OBSMUXSEL0_LN3_S 24
#define I2C_OBSMUXSEL0_LN2_M 0x00070000 // Observation Mux Lane 2
#define I2C_OBSMUXSEL0_LN2_S 16
#define I2C_OBSMUXSEL0_LN1_M 0x00000700 // Observation Mux Lane 1
#define I2C_OBSMUXSEL0_LN1_S 8
#define I2C_OBSMUXSEL0_LN0_M 0x00000007 // Observation Mux Lane 0
#define I2C_OBSMUXSEL0_LN0_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the I2C_O_OBSMUXSEL1 register.
//
//******************************************************************************
#define I2C_OBSMUXSEL1_LN7_M 0x07000000 // Observation Mux Lane 7
#define I2C_OBSMUXSEL1_LN7_S 24
#define I2C_OBSMUXSEL1_LN6_M 0x00070000 // Observation Mux Lane 6
#define I2C_OBSMUXSEL1_LN6_S 16
#define I2C_OBSMUXSEL1_LN5_M 0x00000700 // Observation Mux Lane 5
#define I2C_OBSMUXSEL1_LN5_S 8
#define I2C_OBSMUXSEL1_LN4_M 0x00000007 // Observation Mux Lane 4
#define I2C_OBSMUXSEL1_LN4_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the I2C_O_MUXROUTE register.
//
//******************************************************************************
#define I2C_MUXROUTE_LN7ROUTE_M \
0x70000000 // Lane 7 output is routed to the
// lane pointed to by the offset in
// this bit field
#define I2C_MUXROUTE_LN7ROUTE_S 28
#define I2C_MUXROUTE_LN6ROUTE_M \
0x07000000 // Lane 6 output is routed to the
// lane pointed to by the offset in
// this bit field
#define I2C_MUXROUTE_LN6ROUTE_S 24
#define I2C_MUXROUTE_LN5ROUTE_M \
0x00700000 // Lane 5 output is routed to the
// lane pointed to by the offset in
// this bit field
#define I2C_MUXROUTE_LN5ROUTE_S 20
#define I2C_MUXROUTE_LN4ROUTE_M \
0x00070000 // Lane 4 output is routed to the
// lane pointed to by the offset in
// this bit field
#define I2C_MUXROUTE_LN4ROUTE_S 16
#define I2C_MUXROUTE_LN3ROUTE_M \
0x00007000 // Lane 3 output is routed to the
// lane pointed to by the offset in
// this bit field
#define I2C_MUXROUTE_LN3ROUTE_S 12
#define I2C_MUXROUTE_LN2ROUTE_M \
0x00000700 // Lane 2 output is routed to the
// lane pointed to by the offset in
// this bit field
#define I2C_MUXROUTE_LN2ROUTE_S 8
#define I2C_MUXROUTE_LN1ROUTE_M \
0x00000070 // Lane 1 output is routed to the
// lane pointed to by the offset in
// this bit field
#define I2C_MUXROUTE_LN1ROUTE_S 4
#define I2C_MUXROUTE_LN0ROUTE_M \
0x00000007 // Lane 0 output is routed to the
// lane pointed to by the offset in
// this bit field
#define I2C_MUXROUTE_LN0ROUTE_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the I2C_O_PV register.
//
//******************************************************************************
#define I2C_PV_MAJOR_M 0x0000FF00 // Major Revision
#define I2C_PV_MAJOR_S 8
#define I2C_PV_MINOR_M 0x000000FF // Minor Revision
#define I2C_PV_MINOR_S 0
//******************************************************************************
//
// The following are defines for the bit fields in the I2C_O_PP register.
//
//******************************************************************************
#define I2C_PP_HS 0x00000001 // High-Speed Capable
//******************************************************************************
//
// The following are defines for the bit fields in the I2C_O_PC register.
//
//******************************************************************************
#define I2C_PC_HS 0x00000001 // High-Speed Capable
//******************************************************************************
//
// The following are defines for the bit fields in the I2C_O_CC register.
//
//******************************************************************************
#endif // __HW_I2C_H__

117
inc/hw_ints.h Normal file
View File

@ -0,0 +1,117 @@
//*****************************************************************************
//
// Copyright (C) 2014 Texas Instruments Incorporated - http://www.ti.com/
//
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
// Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// 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.
//
// Neither the name of Texas Instruments Incorporated nor the names of
// its contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
//*****************************************************************************
//*****************************************************************************
//
// hw_ints.h - Macros that define the interrupt assignment on CC3200.
//
//*****************************************************************************
#ifndef __HW_INTS_H__
#define __HW_INTS_H__
//*****************************************************************************
//
// The following are defines for the fault assignments.
//
//*****************************************************************************
#define FAULT_NMI 2 // NMI fault
#define FAULT_HARD 3 // Hard fault
#define FAULT_MPU 4 // MPU fault
#define FAULT_BUS 5 // Bus fault
#define FAULT_USAGE 6 // Usage fault
#define FAULT_SVCALL 11 // SVCall
#define FAULT_DEBUG 12 // Debug monitor
#define FAULT_PENDSV 14 // PendSV
#define FAULT_SYSTICK 15 // System Tick
//*****************************************************************************
//
// The following are defines for the interrupt assignments.
//
//*****************************************************************************
#define INT_GPIOA0 16 // GPIO Port S0
#define INT_GPIOA1 17 // GPIO Port S1
#define INT_GPIOA2 18 // GPIO Port S2
#define INT_GPIOA3 19 // GPIO Port S3
#define INT_UARTA0 21 // UART0 Rx and Tx
#define INT_UARTA1 22 // UART1 Rx and Tx
#define INT_I2CA0 24 // I2C controller
#define INT_ADCCH0 30 // ADC Sequence 0
#define INT_ADCCH1 31 // ADC Sequence 1
#define INT_ADCCH2 32 // ADC Sequence 2
#define INT_ADCCH3 33 // ADC Sequence 3
#define INT_WDT 34 // Watchdog Timer0
#define INT_TIMERA0A 35 // Timer 0 subtimer A
#define INT_TIMERA0B 36 // Timer 0 subtimer B
#define INT_TIMERA1A 37 // Timer 1 subtimer A
#define INT_TIMERA1B 38 // Timer 1 subtimer B
#define INT_TIMERA2A 39 // Timer 2 subtimer A
#define INT_TIMERA2B 40 // Timer 2 subtimer B
#define INT_FLASH 45 // FLASH Control
#define INT_TIMERA3A 51 // Timer 3 subtimer A
#define INT_TIMERA3B 52 // Timer 3 subtimer B
#define INT_UDMA 62 // uDMA controller
#define INT_UDMAERR 63 // uDMA Error
#define INT_SHA 164 // SHA
#define INT_AES 167 // AES
#define INT_DES 169 // DES
#define INT_MMCHS 175 // SDIO
#define INT_I2S 177 // McAPS
#define INT_CAMERA 179 // Camera
#define INT_NWPIC 187 // Interprocessor communication
#define INT_PRCM 188 // Power, Reset and Clock Module
#define INT_SSPI 191 // Shared SPI
#define INT_GSPI 192 // Generic SPI
#define INT_LSPI 193 // Link SPI
//*****************************************************************************
//
// The following are defines for the total number of interrupts.
//
//*****************************************************************************
#define NUM_INTERRUPTS 195 //The above number plus 2?
//*****************************************************************************
//
// The following are defines for the total number of priority levels.
//
//*****************************************************************************
#define NUM_PRIORITY 8
#define NUM_PRIORITY_BITS 3
#endif // __HW_INTS_H__

Some files were not shown because too many files have changed in this diff Show More