forked from springcute/rt-thread
[bsp] Add BSP for TM4C1294XL (TI Tiva C Series Connected LaunchPad)
This commit is contained in:
parent
fc6747ef6c
commit
3a1c1c4500
|
@ -0,0 +1,14 @@
|
|||
# for module compiling
|
||||
import os
|
||||
Import('RTT_ROOT')
|
||||
|
||||
cwd = str(Dir('#'))
|
||||
objs = []
|
||||
list = os.listdir(cwd)
|
||||
|
||||
for d in list:
|
||||
path = os.path.join(cwd, d)
|
||||
if os.path.isfile(os.path.join(path, 'SConscript')):
|
||||
objs = objs + SConscript(os.path.join(d, 'SConscript'))
|
||||
|
||||
Return('objs')
|
|
@ -0,0 +1,29 @@
|
|||
import os
|
||||
import sys
|
||||
import rtconfig
|
||||
|
||||
if os.getenv('RTT_ROOT'):
|
||||
RTT_ROOT = os.getenv('RTT_ROOT')
|
||||
else:
|
||||
RTT_ROOT = os.path.normpath(os.getcwd() + '/../..')
|
||||
|
||||
sys.path = sys.path + [os.path.join(RTT_ROOT, 'tools')]
|
||||
from building import *
|
||||
|
||||
TARGET = 'rtthread.' + rtconfig.TARGET_EXT
|
||||
|
||||
env = Environment(tools = ['mingw'],
|
||||
AS = rtconfig.AS, ASFLAGS = rtconfig.AFLAGS,
|
||||
CC = rtconfig.CC, CCFLAGS = rtconfig.CFLAGS,
|
||||
AR = rtconfig.AR, ARFLAGS = '-rc',
|
||||
LINK = rtconfig.LINK, LINKFLAGS = rtconfig.LFLAGS)
|
||||
env.PrependENVPath('PATH', rtconfig.EXEC_PATH)
|
||||
|
||||
Export('RTT_ROOT')
|
||||
Export('rtconfig')
|
||||
|
||||
# prepare building environment
|
||||
objs = PrepareBuilding(env, RTT_ROOT, has_libcpu=False)
|
||||
|
||||
# make a building
|
||||
DoBuilding(TARGET, objs)
|
|
@ -0,0 +1,11 @@
|
|||
Import('RTT_ROOT')
|
||||
Import('rtconfig')
|
||||
from building import *
|
||||
|
||||
cwd = os.path.join(str(Dir('#')), 'applications')
|
||||
src = Glob('*.c')
|
||||
CPPPATH = [cwd, str(Dir('#'))]
|
||||
|
||||
group = DefineGroup('Applications', src, depend = [''], CPPPATH = CPPPATH)
|
||||
|
||||
Return('group')
|
|
@ -0,0 +1,37 @@
|
|||
/*
|
||||
* File : application.c
|
||||
* This file is part of RT-Thread RTOS
|
||||
* COPYRIGHT (C) 2014, RT-Thread Development Team
|
||||
*
|
||||
* The license and distribution terms for this file may be
|
||||
* found in the file LICENSE in this distribution or at
|
||||
* http://www.rt-thread.org/license/LICENSE
|
||||
*
|
||||
* Change Logs:
|
||||
* Date Author Notes
|
||||
* 2014-07-18 ArdaFu the first version for TM4C129X
|
||||
*/
|
||||
|
||||
#include <rtthread.h>
|
||||
#include <board.h>
|
||||
#include <components.h>
|
||||
|
||||
/* thread phase init */
|
||||
void rt_init_thread_entry(void *parameter)
|
||||
{
|
||||
/* Initialization RT-Thread Components */
|
||||
#ifdef RT_USING_COMPONENTS_INIT
|
||||
rt_components_init();
|
||||
#endif
|
||||
}
|
||||
|
||||
int rt_application_init(void)
|
||||
{
|
||||
rt_thread_t tid;
|
||||
tid = rt_thread_create("init",
|
||||
rt_init_thread_entry, RT_NULL,
|
||||
2048, RT_THREAD_PRIORITY_MAX / 3, 20);
|
||||
if (tid != RT_NULL) rt_thread_startup(tid);
|
||||
|
||||
return 0;
|
||||
}
|
|
@ -0,0 +1,100 @@
|
|||
/*
|
||||
* File : board.c
|
||||
* This file is part of RT-Thread RTOS
|
||||
* COPYRIGHT (C) 2013 RT-Thread Develop Team
|
||||
*
|
||||
* The license and distribution terms for this file may be
|
||||
* found in the file LICENSE in this distribution or at
|
||||
* http://www.rt-thread.org/license/LICENSE
|
||||
*
|
||||
* Change Logs:
|
||||
* Date Author Notes
|
||||
* 2009-01-05 Bernard first implementation
|
||||
* 2014-07-18 ArdaFu Port to TM4C129X
|
||||
*/
|
||||
|
||||
#include <rthw.h>
|
||||
#include <rtthread.h>
|
||||
#include <components.h>
|
||||
|
||||
#include "board.h"
|
||||
#include "drv_uart.h"
|
||||
#include "interrupt.h"
|
||||
#include "sysctl.h"
|
||||
#include "systick.h"
|
||||
#include "fpu.h"
|
||||
#include "driverlib/rom_map.h"
|
||||
|
||||
#define SYS_CLOCK_DEFAULT 120000000
|
||||
uint32_t SysClock;
|
||||
|
||||
#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
|
||||
|
||||
/**
|
||||
* This is the timer interrupt service routine.
|
||||
*
|
||||
*/
|
||||
void SysTick_Handler(void)
|
||||
{
|
||||
/* enter interrupt */
|
||||
rt_interrupt_enter();
|
||||
|
||||
rt_tick_increase();
|
||||
|
||||
/* leave interrupt */
|
||||
rt_interrupt_leave();
|
||||
}
|
||||
|
||||
extern void PendSV_Handler(void);
|
||||
extern void HardFault_Handler(void);
|
||||
|
||||
|
||||
/**
|
||||
* This function will initial LPC40xx board.
|
||||
*/
|
||||
void rt_hw_board_init()
|
||||
{
|
||||
IntRegister(FAULT_HARD, HardFault_Handler);
|
||||
IntRegister(FAULT_PENDSV, PendSV_Handler);
|
||||
IntRegister(FAULT_SYSTICK, SysTick_Handler);
|
||||
|
||||
//
|
||||
// Enable lazy stacking for interrupt handlers. This allows floating-point
|
||||
// instructions to be used within interrupt handlers, but at the expense of
|
||||
// extra stack usage.
|
||||
//
|
||||
MAP_FPULazyStackingEnable();
|
||||
|
||||
//
|
||||
// Set the clocking to run directly from the external crystal/oscillator.
|
||||
// TODO: The SYSCTL_XTAL_ value must be changed to match the value of the
|
||||
// crystal on your board.
|
||||
//
|
||||
SysClock = MAP_SysCtlClockFreqSet((SYSCTL_XTAL_25MHZ | SYSCTL_OSC_MAIN | SYSCTL_USE_PLL | SYSCTL_CFG_VCO_480),
|
||||
SYS_CLOCK_DEFAULT);
|
||||
|
||||
MAP_SysTickDisable();
|
||||
MAP_SysTickPeriodSet(SysClock/ RT_TICK_PER_SECOND - 1);
|
||||
MAP_SysTickIntEnable();
|
||||
MAP_SysTickEnable();
|
||||
|
||||
|
||||
/* set pend exception priority */
|
||||
//IntPrioritySet(FAULT_PENDSV, (1 << __NVIC_PRIO_BITS) - 1);
|
||||
/*init uart device*/
|
||||
|
||||
rt_hw_uart_init();
|
||||
rt_console_set_device(RT_CONSOLE_DEVICE_NAME);
|
||||
//
|
||||
// Enable interrupts to the processor.
|
||||
//
|
||||
MAP_IntMasterEnable();
|
||||
}
|
|
@ -0,0 +1,52 @@
|
|||
/*
|
||||
* File : board.h
|
||||
* This file is part of RT-Thread RTOS
|
||||
* COPYRIGHT (C) 2009, RT-Thread Development Team
|
||||
*
|
||||
* The license and distribution terms for this file may be
|
||||
* found in the file LICENSE in this distribution or at
|
||||
* http://www.rt-thread.org/license/LICENSE
|
||||
*
|
||||
* Change Logs:
|
||||
* Date Author Notes
|
||||
* 2009-09-22 Bernard add board.h to this bsp
|
||||
* 2010-02-04 Magicoe add board.h to LPC176x bsp
|
||||
* 2014-07-18 ArdaFu port it to TM4C129X bsp
|
||||
*/
|
||||
|
||||
#ifndef __BOARD_H__
|
||||
#define __BOARD_H__
|
||||
|
||||
#include "tm4c129xnczad.h"
|
||||
#include <rtthread.h>
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
extern uint32_t SysClock;
|
||||
// <RDTConfigurator URL="http://www.rt-thread.com/eclipse">
|
||||
|
||||
// <bool name="RT_USING_UART0" description="Using UART0" default="true" />
|
||||
#define RT_USING_UART0
|
||||
// <bool name="RT_USING_UART1" description="Using UART1" default="true" />
|
||||
//#define RT_USING_UART1
|
||||
// <bool name="RT_USING_UART2" description="Using UART2" default="true" />
|
||||
//#define RT_USING_UART2
|
||||
|
||||
// </RDTConfigurator>
|
||||
|
||||
#ifdef __CC_ARM
|
||||
extern int Image$$RW_IRAM1$$ZI$$Limit;
|
||||
#define HEAP_BEGIN ((void *)&Image$$RW_IRAM1$$ZI$$Limit)
|
||||
#elif __ICCARM__
|
||||
#pragma section="HEAP"
|
||||
#define HEAP_BEGIN (__segment_end("HEAP"))
|
||||
#else
|
||||
extern int __bss_end;
|
||||
#define HEAP_BEGIN ((void *)&__bss_end)
|
||||
#endif
|
||||
#define HEAP_END (0x20000000 + 256*1024)
|
||||
|
||||
#define FINSH_DEVICE_NAME RT_CONSOLE_DEVICE_NAME
|
||||
void rt_hw_board_init(void);
|
||||
|
||||
#endif
|
|
@ -0,0 +1,68 @@
|
|||
/*
|
||||
* File : startup.c
|
||||
* This file is part of RT-Thread RTOS
|
||||
* COPYRIGHT (C) 2009, RT-Thread Development Team
|
||||
*
|
||||
* The license and distribution terms for this file may be
|
||||
* found in the file LICENSE in this distribution or at
|
||||
* http://www.rt-thread.org/license/LICENSE
|
||||
*
|
||||
* Change Logs:
|
||||
* Date Author Notes
|
||||
* 2009-01-05 Bernard first implementation
|
||||
* 2010-03-04 Magicoe for LPC17xx
|
||||
* 2014-07-18 ArdaFu Port to TM4C129X
|
||||
*/
|
||||
|
||||
#include <rthw.h>
|
||||
#include <rtthread.h>
|
||||
|
||||
#include "board.h"
|
||||
|
||||
extern int rt_application_init(void);
|
||||
|
||||
/**
|
||||
* This function will startup RT-Thread RTOS.
|
||||
*/
|
||||
void rtthread_startup(void)
|
||||
{
|
||||
/* initialize board */
|
||||
rt_hw_board_init();
|
||||
|
||||
/* show version */
|
||||
rt_show_version();
|
||||
|
||||
#ifdef RT_USING_HEAP
|
||||
rt_system_heap_init((void *)HEAP_BEGIN, (void *)HEAP_END);
|
||||
#endif
|
||||
|
||||
/* initialize scheduler system */
|
||||
rt_system_scheduler_init();
|
||||
/* initialize system timer*/
|
||||
rt_system_timer_init();
|
||||
/* initialize application */
|
||||
rt_application_init();
|
||||
|
||||
/* initialize timer thread */
|
||||
rt_system_timer_thread_init();
|
||||
|
||||
/* initialize idle thread */
|
||||
rt_thread_idle_init();
|
||||
|
||||
/* start scheduler */
|
||||
rt_system_scheduler_start();
|
||||
|
||||
/* never reach here */
|
||||
return ;
|
||||
}
|
||||
|
||||
int main(void)
|
||||
{
|
||||
/* disable interrupt first */
|
||||
rt_hw_interrupt_disable();
|
||||
|
||||
/* startup RT-Thread RTOS */
|
||||
rtthread_startup();
|
||||
|
||||
return 0;
|
||||
}
|
|
@ -0,0 +1,14 @@
|
|||
from building import *
|
||||
|
||||
cwd = GetCurrentDir()
|
||||
src = Glob('*.c')
|
||||
|
||||
# remove no need file.
|
||||
if GetDepend('RT_USING_LWIP') == False:
|
||||
SrcRemove(src, 'drv_emac.c')
|
||||
|
||||
CPPPATH = [cwd]
|
||||
|
||||
group = DefineGroup('Drivers', src, depend = [''], CPPPATH = CPPPATH)
|
||||
|
||||
Return('group')
|
|
@ -0,0 +1,202 @@
|
|||
/*
|
||||
* File : drv_uart.c
|
||||
* This file is part of RT-Thread RTOS
|
||||
* COPYRIGHT (C) 2009-2013 RT-Thread Develop Team
|
||||
*
|
||||
* The license and distribution terms for this file may be
|
||||
* found in the file LICENSE in this distribution or at
|
||||
* http://www.rt-thread.org/license/LICENSE
|
||||
*
|
||||
* Change Logs:
|
||||
* Date Author Notes
|
||||
* 2013-05-18 Bernard The first version for LPC40xx
|
||||
* 2014-07-18 ArdaFu Port to TM4C129X
|
||||
*/
|
||||
|
||||
#include <rthw.h>
|
||||
#include <rtthread.h>
|
||||
#include <rtdevice.h>
|
||||
|
||||
#include "board.h"
|
||||
//#include <components.h>
|
||||
|
||||
#include "sysctl.h"
|
||||
#include "gpio.h"
|
||||
#include "uart.h"
|
||||
#include "hw_memmap.h"
|
||||
#include "pin_map.h"
|
||||
#include "interrupt.h"
|
||||
#include "rom.h"
|
||||
#include "rom_map.h"
|
||||
typedef struct hw_uart_device
|
||||
{
|
||||
uint32_t hw_base; // base address
|
||||
}hw_uart_t;
|
||||
|
||||
#define GetHwUartPtr(serial) ((hw_uart_t*)(serial->parent.user_data))
|
||||
|
||||
static rt_err_t hw_configure(struct rt_serial_device *serial, struct serial_configure *cfg)
|
||||
{
|
||||
hw_uart_t* uart;
|
||||
RT_ASSERT(serial != RT_NULL);
|
||||
uart = GetHwUartPtr(serial);
|
||||
MAP_UARTDisable(uart->hw_base);
|
||||
/* Initialize UART Configuration parameter structure to default state:
|
||||
* Baudrate = 115200 bps
|
||||
* 8 data bit
|
||||
* 1 Stop bit
|
||||
* None parity
|
||||
*/
|
||||
// Initialize UART0 peripheral with given to corresponding parameter
|
||||
MAP_UARTConfigSetExpClk(uart->hw_base, SysClock, cfg->baud_rate,
|
||||
(UART_CONFIG_WLEN_8 | UART_CONFIG_STOP_ONE | UART_CONFIG_PAR_NONE));
|
||||
MAP_UARTFIFOEnable(uart->hw_base);
|
||||
|
||||
//
|
||||
// Enable the UART.
|
||||
//
|
||||
MAP_UARTEnable(uart->hw_base);
|
||||
return RT_EOK;
|
||||
}
|
||||
|
||||
static rt_err_t hw_control(struct rt_serial_device *serial, int cmd, void *arg)
|
||||
{
|
||||
hw_uart_t* uart;
|
||||
RT_ASSERT(serial != RT_NULL);
|
||||
uart = GetHwUartPtr(serial);
|
||||
|
||||
switch (cmd)
|
||||
{
|
||||
case RT_DEVICE_CTRL_CLR_INT:
|
||||
/* disable rx irq */
|
||||
MAP_UARTIntDisable(uart->hw_base, UART_INT_RX | UART_INT_RT);
|
||||
break;
|
||||
case RT_DEVICE_CTRL_SET_INT:
|
||||
/* enable rx irq */
|
||||
MAP_UARTIntEnable(uart->hw_base, UART_INT_RX | UART_INT_RT);
|
||||
break;
|
||||
}
|
||||
|
||||
return RT_EOK;
|
||||
}
|
||||
|
||||
static int hw_putc(struct rt_serial_device *serial, char c)
|
||||
{
|
||||
hw_uart_t* uart;
|
||||
RT_ASSERT(serial != RT_NULL);
|
||||
uart = GetHwUartPtr(serial);
|
||||
|
||||
MAP_UARTCharPut(uart->hw_base, *((uint8_t *)&c));
|
||||
return 1;
|
||||
}
|
||||
|
||||
static int hw_getc(struct rt_serial_device *serial)
|
||||
{
|
||||
hw_uart_t* uart;
|
||||
RT_ASSERT(serial != RT_NULL);
|
||||
uart = GetHwUartPtr(serial);
|
||||
|
||||
return MAP_UARTCharGetNonBlocking(uart->hw_base);
|
||||
}
|
||||
|
||||
static const struct rt_uart_ops hw_uart_ops =
|
||||
{
|
||||
hw_configure,
|
||||
hw_control,
|
||||
hw_putc,
|
||||
hw_getc,
|
||||
};
|
||||
|
||||
#if defined(RT_USING_UART0)
|
||||
/* UART0 device driver structure */
|
||||
struct rt_serial_device serial0;
|
||||
struct serial_ringbuffer uart0_int_rx_buf;
|
||||
hw_uart_t uart0 =
|
||||
{
|
||||
UART0_BASE,
|
||||
};
|
||||
|
||||
void UART0_IRQHandler(void)
|
||||
{
|
||||
uint32_t intsrc;
|
||||
hw_uart_t *uart = &uart0;
|
||||
|
||||
/* enter interrupt */
|
||||
rt_interrupt_enter();
|
||||
|
||||
/* Determine the interrupt source */
|
||||
intsrc = UARTIntStatus(uart->hw_base, true);
|
||||
|
||||
// Receive Data Available or Character time-out
|
||||
if (intsrc & (UART_INT_RX | UART_INT_RT))
|
||||
{
|
||||
UARTIntClear(UART0_BASE, intsrc);
|
||||
rt_hw_serial_isr(&serial0);
|
||||
|
||||
}
|
||||
|
||||
/* leave interrupt */
|
||||
rt_interrupt_leave();
|
||||
}
|
||||
#endif
|
||||
|
||||
int rt_hw_uart_init(void)
|
||||
{
|
||||
hw_uart_t* uart;
|
||||
struct serial_configure config;
|
||||
|
||||
#ifdef RT_USING_UART0
|
||||
uart = &uart0;
|
||||
config.baud_rate = BAUD_RATE_115200;
|
||||
config.bit_order = BIT_ORDER_LSB;
|
||||
config.data_bits = DATA_BITS_8;
|
||||
config.parity = PARITY_NONE;
|
||||
config.stop_bits = STOP_BITS_1;
|
||||
config.invert = NRZ_NORMAL;
|
||||
|
||||
serial0.ops = &hw_uart_ops;
|
||||
serial0.int_rx = &uart0_int_rx_buf;
|
||||
serial0.config = config;
|
||||
|
||||
//
|
||||
// Enable the peripherals used by this example.
|
||||
// The UART itself needs to be enabled, as well as the GPIO port
|
||||
// containing the pins that will be used.
|
||||
//
|
||||
|
||||
MAP_SysCtlPeripheralEnable(SYSCTL_PERIPH_GPIOA);
|
||||
|
||||
//
|
||||
// Configure the GPIO pin muxing for the UART function.
|
||||
// This is only necessary if your part supports GPIO pin function muxing.
|
||||
// Study the data sheet to see which functions are allocated per pin.
|
||||
// TODO: change this to select the port/pin you are using
|
||||
//
|
||||
MAP_GPIOPinConfigure(GPIO_PA0_U0RX);
|
||||
MAP_GPIOPinConfigure(GPIO_PA1_U0TX);
|
||||
|
||||
//
|
||||
// Since GPIO A0 and A1 are used for the UART function, they must be
|
||||
// configured for use as a peripheral function (instead of GPIO).
|
||||
// TODO: change this to match the port/pin you are using
|
||||
//
|
||||
MAP_GPIOPinTypeUART(GPIO_PORTA_BASE, GPIO_PIN_0 | GPIO_PIN_1);
|
||||
|
||||
MAP_SysCtlPeripheralEnable(SYSCTL_PERIPH_UART0);
|
||||
|
||||
/* preemption = 1, sub-priority = 1 */
|
||||
//IntPrioritySet(INT_UART0, ((0x01 << 3) | 0x01));
|
||||
|
||||
/* Enable Interrupt for UART channel */
|
||||
UARTIntRegister(uart->hw_base, UART0_IRQHandler);
|
||||
MAP_IntEnable(INT_UART0);
|
||||
MAP_UARTEnable(uart->hw_base);
|
||||
|
||||
/* register UART0 device */
|
||||
rt_hw_serial_register(&serial0, "uart0",
|
||||
RT_DEVICE_FLAG_RDWR | RT_DEVICE_FLAG_INT_RX | RT_DEVICE_FLAG_STREAM,
|
||||
uart);
|
||||
#endif
|
||||
return 0;
|
||||
}
|
||||
//INIT_BOARD_EXPORT(rt_hw_uart_init);
|
|
@ -0,0 +1,20 @@
|
|||
/*
|
||||
* File : drv_uart.h
|
||||
* This file is part of RT-Thread RTOS
|
||||
* COPYRIGHT (C) 2009-2013 RT-Thread Develop Team
|
||||
*
|
||||
* The license and distribution terms for this file may be
|
||||
* found in the file LICENSE in this distribution or at
|
||||
* http://www.rt-thread.org/license/LICENSE
|
||||
*
|
||||
* Change Logs:
|
||||
* Date Author Notes
|
||||
* 2013-05-18 Bernard The first version for LPC40xx
|
||||
* 2014-07-18 ArdaFu Port to TM4C129X
|
||||
*/
|
||||
#ifndef __UART_H__
|
||||
#define __UART_H__
|
||||
|
||||
void rt_hw_uart_init(void);
|
||||
|
||||
#endif
|
|
@ -0,0 +1,31 @@
|
|||
Import('RTT_ROOT')
|
||||
Import('rtconfig')
|
||||
from building import *
|
||||
|
||||
# The set of source files associated with this SConscript file.
|
||||
cwd = GetCurrentDir()
|
||||
src = Glob('driverlib/*.c')
|
||||
SrcRemove(src, 'onewire.c')
|
||||
|
||||
# add for startup script
|
||||
if rtconfig.CROSS_TOOL == 'gcc':
|
||||
src += ['startup/startup_gcc.c']
|
||||
elif rtconfig.CROSS_TOOL == 'keil':
|
||||
src += ['startup/startup_rvmdk.S']
|
||||
elif rtconfig.CROSS_TOOL == 'iar':
|
||||
src += ['startup/startup_ewarm.c']
|
||||
elif rtconfig.CROSS_TOOL == 'ccs':
|
||||
src += ['startup/startup_ccs.c']
|
||||
|
||||
CPPPATH = [cwd, cwd + '/inc', cwd + '/driverlib']
|
||||
|
||||
CPPDEFINES = [rtconfig.PART_TYPE]
|
||||
if rtconfig.CROSS_TOOL == 'gcc':
|
||||
CPPDEFINES += ['gcc'];
|
||||
CPPDEFINES += ['uint_fast8_t=uint32_t'];
|
||||
CPPDEFINES += ['uint_fast32_t=uint32_t'];
|
||||
CPPDEFINES += ['int_fast8_t=int32_t'];
|
||||
CPPDEFINES += ['uint_fast16_t=uint32_t'];
|
||||
group = DefineGroup('Libraries', src, depend = [''], CPPPATH = CPPPATH, CPPDEFINES = CPPDEFINES)
|
||||
|
||||
Return('group')
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,328 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// adc.h - ADC headers for using the ADC driver functions.
|
||||
//
|
||||
// Copyright (c) 2005-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __DRIVERLIB_ADC_H__
|
||||
#define __DRIVERLIB_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 ADCSequenceConfigure as the ui32Trigger
|
||||
// parameter.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define ADC_TRIGGER_PROCESSOR 0x00000000 // Processor event
|
||||
#define ADC_TRIGGER_COMP0 0x00000001 // Analog comparator 0 event
|
||||
#define ADC_TRIGGER_COMP1 0x00000002 // Analog comparator 1 event
|
||||
#define ADC_TRIGGER_COMP2 0x00000003 // Analog comparator 2 event
|
||||
#define ADC_TRIGGER_EXTERNAL 0x00000004 // External event
|
||||
#define ADC_TRIGGER_TIMER 0x00000005 // Timer event
|
||||
#define ADC_TRIGGER_PWM0 0x00000006 // PWM0 event
|
||||
#define ADC_TRIGGER_PWM1 0x00000007 // PWM1 event
|
||||
#define ADC_TRIGGER_PWM2 0x00000008 // PWM2 event
|
||||
#define ADC_TRIGGER_PWM3 0x00000009 // PWM3 event
|
||||
#define ADC_TRIGGER_NEVER 0x0000000E // Never Trigger
|
||||
#define ADC_TRIGGER_ALWAYS 0x0000000F // Always event
|
||||
#define ADC_TRIGGER_PWM_MOD0 0x00000000 // PWM triggers from PWM0
|
||||
#define ADC_TRIGGER_PWM_MOD1 0x00000010 // PWM triggers from PWM1
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to ADCSequenceStepConfigure as the ui32Config
|
||||
// parameter.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define ADC_CTL_TS 0x00000080 // Temperature sensor select
|
||||
#define ADC_CTL_IE 0x00000040 // Interrupt enable
|
||||
#define ADC_CTL_END 0x00000020 // Sequence end select
|
||||
#define ADC_CTL_D 0x00000010 // Differential select
|
||||
#define ADC_CTL_CH0 0x00000000 // Input channel 0
|
||||
#define ADC_CTL_CH1 0x00000001 // Input channel 1
|
||||
#define ADC_CTL_CH2 0x00000002 // Input channel 2
|
||||
#define ADC_CTL_CH3 0x00000003 // Input channel 3
|
||||
#define ADC_CTL_CH4 0x00000004 // Input channel 4
|
||||
#define ADC_CTL_CH5 0x00000005 // Input channel 5
|
||||
#define ADC_CTL_CH6 0x00000006 // Input channel 6
|
||||
#define ADC_CTL_CH7 0x00000007 // Input channel 7
|
||||
#define ADC_CTL_CH8 0x00000008 // Input channel 8
|
||||
#define ADC_CTL_CH9 0x00000009 // Input channel 9
|
||||
#define ADC_CTL_CH10 0x0000000A // Input channel 10
|
||||
#define ADC_CTL_CH11 0x0000000B // Input channel 11
|
||||
#define ADC_CTL_CH12 0x0000000C // Input channel 12
|
||||
#define ADC_CTL_CH13 0x0000000D // Input channel 13
|
||||
#define ADC_CTL_CH14 0x0000000E // Input channel 14
|
||||
#define ADC_CTL_CH15 0x0000000F // Input channel 15
|
||||
#define ADC_CTL_CH16 0x00000100 // Input channel 16
|
||||
#define ADC_CTL_CH17 0x00000101 // Input channel 17
|
||||
#define ADC_CTL_CH18 0x00000102 // Input channel 18
|
||||
#define ADC_CTL_CH19 0x00000103 // Input channel 19
|
||||
#define ADC_CTL_CH20 0x00000104 // Input channel 20
|
||||
#define ADC_CTL_CH21 0x00000105 // Input channel 21
|
||||
#define ADC_CTL_CH22 0x00000106 // Input channel 22
|
||||
#define ADC_CTL_CH23 0x00000107 // Input channel 23
|
||||
#define ADC_CTL_CMP0 0x00080000 // Select Comparator 0
|
||||
#define ADC_CTL_CMP1 0x00090000 // Select Comparator 1
|
||||
#define ADC_CTL_CMP2 0x000A0000 // Select Comparator 2
|
||||
#define ADC_CTL_CMP3 0x000B0000 // Select Comparator 3
|
||||
#define ADC_CTL_CMP4 0x000C0000 // Select Comparator 4
|
||||
#define ADC_CTL_CMP5 0x000D0000 // Select Comparator 5
|
||||
#define ADC_CTL_CMP6 0x000E0000 // Select Comparator 6
|
||||
#define ADC_CTL_CMP7 0x000F0000 // Select Comparator 7
|
||||
#define ADC_CTL_SHOLD_4 0x00000000 // Sample and hold 4 ADC clocks
|
||||
#define ADC_CTL_SHOLD_8 0x00200000 // Sample and hold 8 ADC clocks
|
||||
#define ADC_CTL_SHOLD_16 0x00400000 // Sample and hold 16 ADC clocks
|
||||
#define ADC_CTL_SHOLD_32 0x00600000 // Sample and hold 32 ADC clocks
|
||||
#define ADC_CTL_SHOLD_64 0x00800000 // Sample and hold 64 ADC clocks
|
||||
#define ADC_CTL_SHOLD_128 0x00A00000 // Sample and hold 128 ADC clocks
|
||||
#define ADC_CTL_SHOLD_256 0x00C00000 // Sample and hold 256 ADC clocks
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to ADCComparatorConfigure as part of the
|
||||
// ui32Config parameter.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define ADC_COMP_TRIG_NONE 0x00000000 // Trigger Disabled
|
||||
#define ADC_COMP_TRIG_LOW_ALWAYS \
|
||||
0x00001000 // Trigger Low Always
|
||||
#define ADC_COMP_TRIG_LOW_ONCE 0x00001100 // Trigger Low Once
|
||||
#define ADC_COMP_TRIG_LOW_HALWAYS \
|
||||
0x00001200 // Trigger Low Always (Hysteresis)
|
||||
#define ADC_COMP_TRIG_LOW_HONCE 0x00001300 // Trigger Low Once (Hysteresis)
|
||||
#define ADC_COMP_TRIG_MID_ALWAYS \
|
||||
0x00001400 // Trigger Mid Always
|
||||
#define ADC_COMP_TRIG_MID_ONCE 0x00001500 // Trigger Mid Once
|
||||
#define ADC_COMP_TRIG_HIGH_ALWAYS \
|
||||
0x00001C00 // Trigger High Always
|
||||
#define ADC_COMP_TRIG_HIGH_ONCE 0x00001D00 // Trigger High Once
|
||||
#define ADC_COMP_TRIG_HIGH_HALWAYS \
|
||||
0x00001E00 // Trigger High Always (Hysteresis)
|
||||
#define ADC_COMP_TRIG_HIGH_HONCE \
|
||||
0x00001F00 // Trigger High Once (Hysteresis)
|
||||
|
||||
#define ADC_COMP_INT_NONE 0x00000000 // Interrupt Disabled
|
||||
#define ADC_COMP_INT_LOW_ALWAYS \
|
||||
0x00000010 // Interrupt Low Always
|
||||
#define ADC_COMP_INT_LOW_ONCE 0x00000011 // Interrupt Low Once
|
||||
#define ADC_COMP_INT_LOW_HALWAYS \
|
||||
0x00000012 // Interrupt Low Always
|
||||
// (Hysteresis)
|
||||
#define ADC_COMP_INT_LOW_HONCE 0x00000013 // Interrupt Low Once (Hysteresis)
|
||||
#define ADC_COMP_INT_MID_ALWAYS \
|
||||
0x00000014 // Interrupt Mid Always
|
||||
#define ADC_COMP_INT_MID_ONCE 0x00000015 // Interrupt Mid Once
|
||||
#define ADC_COMP_INT_HIGH_ALWAYS \
|
||||
0x0000001C // Interrupt High Always
|
||||
#define ADC_COMP_INT_HIGH_ONCE 0x0000001D // Interrupt High Once
|
||||
#define ADC_COMP_INT_HIGH_HALWAYS \
|
||||
0x0000001E // Interrupt High Always
|
||||
// (Hysteresis)
|
||||
#define ADC_COMP_INT_HIGH_HONCE \
|
||||
0x0000001F // Interrupt High Once (Hysteresis)
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be used to modify the sequence number passed to
|
||||
// ADCProcessorTrigger in order to get cross-module synchronous processor
|
||||
// triggers.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define ADC_TRIGGER_WAIT 0x08000000 // Wait for the synchronous trigger
|
||||
#define ADC_TRIGGER_SIGNAL 0x80000000 // Signal the synchronous trigger
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to ADCPhaseDelaySet as the ui32Phase parameter and
|
||||
// returned from ADCPhaseDelayGet.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define ADC_PHASE_0 0x00000000 // 0 degrees
|
||||
#define ADC_PHASE_22_5 0x00000001 // 22.5 degrees
|
||||
#define ADC_PHASE_45 0x00000002 // 45 degrees
|
||||
#define ADC_PHASE_67_5 0x00000003 // 67.5 degrees
|
||||
#define ADC_PHASE_90 0x00000004 // 90 degrees
|
||||
#define ADC_PHASE_112_5 0x00000005 // 112.5 degrees
|
||||
#define ADC_PHASE_135 0x00000006 // 135 degrees
|
||||
#define ADC_PHASE_157_5 0x00000007 // 157.5 degrees
|
||||
#define ADC_PHASE_180 0x00000008 // 180 degrees
|
||||
#define ADC_PHASE_202_5 0x00000009 // 202.5 degrees
|
||||
#define ADC_PHASE_225 0x0000000A // 225 degrees
|
||||
#define ADC_PHASE_247_5 0x0000000B // 247.5 degrees
|
||||
#define ADC_PHASE_270 0x0000000C // 270 degrees
|
||||
#define ADC_PHASE_292_5 0x0000000D // 292.5 degrees
|
||||
#define ADC_PHASE_315 0x0000000E // 315 degrees
|
||||
#define ADC_PHASE_337_5 0x0000000F // 337.5 degrees
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to ADCReferenceSet as the ui32Ref parameter.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define ADC_REF_INT 0x00000000 // Internal reference
|
||||
#define ADC_REF_EXT_3V 0x00000001 // External 3V reference
|
||||
#define ADC_REF_EXT_1V 0x00000003 // External 1V reference
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to ADCIntDisableEx(), ADCIntEnableEx(),
|
||||
// ADCIntClearEx() and ADCIntStatusEx().
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define ADC_INT_SS0 0x00000001
|
||||
#define ADC_INT_SS1 0x00000002
|
||||
#define ADC_INT_SS2 0x00000004
|
||||
#define ADC_INT_SS3 0x00000008
|
||||
#define ADC_INT_DMA_SS0 0x00000100
|
||||
#define ADC_INT_DMA_SS1 0x00000200
|
||||
#define ADC_INT_DMA_SS2 0x00000400
|
||||
#define ADC_INT_DMA_SS3 0x00000800
|
||||
#define ADC_INT_DCON_SS0 0x00010000
|
||||
#define ADC_INT_DCON_SS1 0x00020000
|
||||
#define ADC_INT_DCON_SS2 0x00040000
|
||||
#define ADC_INT_DCON_SS3 0x00080000
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to ADCClockConfigSet() and ADCClockConfigGet().
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define ADC_CLOCK_RATE_FULL 0x00000070
|
||||
#define ADC_CLOCK_RATE_HALF 0x00000050
|
||||
#define ADC_CLOCK_RATE_FOURTH 0x00000030
|
||||
#define ADC_CLOCK_RATE_EIGHTH 0x00000010
|
||||
#define ADC_CLOCK_SRC_PLL 0x00000000
|
||||
#define ADC_CLOCK_SRC_PIOSC 0x00000001
|
||||
#define ADC_CLOCK_SRC_ALTCLK 0x00000001
|
||||
#define ADC_CLOCK_SRC_MOSC 0x00000002
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Prototypes for the APIs.
|
||||
//
|
||||
//*****************************************************************************
|
||||
extern void ADCIntRegister(uint32_t ui32Base, uint32_t ui32SequenceNum,
|
||||
void (*pfnHandler)(void));
|
||||
extern void ADCIntUnregister(uint32_t ui32Base, uint32_t ui32SequenceNum);
|
||||
extern void ADCIntDisable(uint32_t ui32Base, uint32_t ui32SequenceNum);
|
||||
extern void ADCIntEnable(uint32_t ui32Base, uint32_t ui32SequenceNum);
|
||||
extern uint32_t ADCIntStatus(uint32_t ui32Base, uint32_t ui32SequenceNum,
|
||||
bool bMasked);
|
||||
extern void ADCIntClear(uint32_t ui32Base, uint32_t ui32SequenceNum);
|
||||
extern void ADCSequenceEnable(uint32_t ui32Base, uint32_t ui32SequenceNum);
|
||||
extern void ADCSequenceDisable(uint32_t ui32Base, uint32_t ui32SequenceNum);
|
||||
extern void ADCSequenceConfigure(uint32_t ui32Base, uint32_t ui32SequenceNum,
|
||||
uint32_t ui32Trigger, uint32_t ui32Priority);
|
||||
extern void ADCSequenceStepConfigure(uint32_t ui32Base,
|
||||
uint32_t ui32SequenceNum,
|
||||
uint32_t ui32Step, uint32_t ui32Config);
|
||||
extern int32_t ADCSequenceOverflow(uint32_t ui32Base,
|
||||
uint32_t ui32SequenceNum);
|
||||
extern void ADCSequenceOverflowClear(uint32_t ui32Base,
|
||||
uint32_t ui32SequenceNum);
|
||||
extern int32_t ADCSequenceUnderflow(uint32_t ui32Base,
|
||||
uint32_t ui32SequenceNum);
|
||||
extern void ADCSequenceUnderflowClear(uint32_t ui32Base,
|
||||
uint32_t ui32SequenceNum);
|
||||
extern int32_t ADCSequenceDataGet(uint32_t ui32Base, uint32_t ui32SequenceNum,
|
||||
uint32_t *pui32Buffer);
|
||||
extern void ADCProcessorTrigger(uint32_t ui32Base, uint32_t ui32SequenceNum);
|
||||
extern void ADCSoftwareOversampleConfigure(uint32_t ui32Base,
|
||||
uint32_t ui32SequenceNum,
|
||||
uint32_t ui32Factor);
|
||||
extern void ADCSoftwareOversampleStepConfigure(uint32_t ui32Base,
|
||||
uint32_t ui32SequenceNum,
|
||||
uint32_t ui32Step,
|
||||
uint32_t ui32Config);
|
||||
extern void ADCSoftwareOversampleDataGet(uint32_t ui32Base,
|
||||
uint32_t ui32SequenceNum,
|
||||
uint32_t *pui32Buffer,
|
||||
uint32_t ui32Count);
|
||||
extern void ADCHardwareOversampleConfigure(uint32_t ui32Base,
|
||||
uint32_t ui32Factor);
|
||||
extern void ADCClockConfigSet(uint32_t ui32Base, uint32_t ui32Config,
|
||||
uint32_t ui32ClockDiv);
|
||||
extern uint32_t ADCClockConfigGet(uint32_t ui32Base, uint32_t *pui32ClockDiv);
|
||||
|
||||
extern void ADCComparatorConfigure(uint32_t ui32Base, uint32_t ui32Comp,
|
||||
uint32_t ui32Config);
|
||||
extern void ADCComparatorRegionSet(uint32_t ui32Base, uint32_t ui32Comp,
|
||||
uint32_t ui32LowRef, uint32_t ui32HighRef);
|
||||
extern void ADCComparatorReset(uint32_t ui32Base, uint32_t ui32Comp,
|
||||
bool bTrigger, bool bInterrupt);
|
||||
extern void ADCComparatorIntDisable(uint32_t ui32Base,
|
||||
uint32_t ui32SequenceNum);
|
||||
extern void ADCComparatorIntEnable(uint32_t ui32Base,
|
||||
uint32_t ui32SequenceNum);
|
||||
extern uint32_t ADCComparatorIntStatus(uint32_t ui32Base);
|
||||
extern void ADCComparatorIntClear(uint32_t ui32Base, uint32_t ui32Status);
|
||||
extern void ADCIntDisableEx(uint32_t ui32Base, uint32_t ui32IntFlags);
|
||||
extern void ADCIntEnableEx(uint32_t ui32Base, uint32_t ui32IntFlags);
|
||||
extern uint32_t ADCIntStatusEx(uint32_t ui32Base, bool bMasked);
|
||||
extern void ADCIntClearEx(uint32_t ui32Base, uint32_t ui32IntFlags);
|
||||
extern void ADCSequenceDMAEnable(uint32_t ui32Base, uint32_t ui32SequenceNum);
|
||||
extern void ADCSequenceDMADisable(uint32_t ui32Base, uint32_t ui32SequenceNum);
|
||||
extern bool ADCBusy(uint32_t ui32Base);
|
||||
extern void ADCReferenceSet(uint32_t ui32Base, uint32_t ui32Ref);
|
||||
extern uint32_t ADCReferenceGet(uint32_t ui32Base);
|
||||
extern void ADCPhaseDelaySet(uint32_t ui32Base, uint32_t ui32Phase);
|
||||
extern uint32_t ADCPhaseDelayGet(uint32_t ui32Base);
|
||||
extern void ADCSampleRateSet(uint32_t ui32Base, uint32_t ui32ADCClock,
|
||||
uint32_t ui32Rate);
|
||||
extern uint32_t ADCSampleRateGet(uint32_t ui32Base);
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Mark the end of the C bindings section for C++ compilers.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // __DRIVERLIB_ADC_H__
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,218 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// aes.h - Defines and Macros for the AES module.
|
||||
//
|
||||
// Copyright (c) 2012-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#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 \
|
||||
0x20010000
|
||||
#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_1 0x00000000
|
||||
#define AES_CFG_CCM_L_2 0x00080000
|
||||
#define AES_CFG_CCM_L_3 0x00100000
|
||||
#define AES_CFG_CCM_L_4 0x00180000
|
||||
#define AES_CFG_CCM_L_5 0x00200000
|
||||
#define AES_CFG_CCM_L_6 0x00280000
|
||||
#define AES_CFG_CCM_L_7 0x00300000
|
||||
#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 0x00080000
|
||||
#define AES_INT_DMA_DATA_IN 0x00020000
|
||||
#define AES_INT_DMA_DATA_OUT 0x00040000
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Defines used when enabling and disabling DMA requests in the
|
||||
// AESEnableDMA and AESDisableDMA functions.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define AES_DMA_DATA_IN 0x00000020
|
||||
#define AES_DMA_DATA_OUT 0x00000040
|
||||
#define AES_DMA_CONTEXT_IN 0x00000080
|
||||
#define AES_DMA_CONTEXT_OUT 0x00000100
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Function prototypes.
|
||||
//
|
||||
//*****************************************************************************
|
||||
extern void AESAuthLengthSet(uint32_t ui32Base, uint32_t ui32Length);
|
||||
extern void AESConfigSet(uint32_t ui32Base, uint32_t ui32Config);
|
||||
extern void AESDataRead(uint32_t ui32Base, uint32_t *pui32Dest);
|
||||
extern bool AESDataReadNonBlocking(uint32_t ui32Base, uint32_t *pui32Dest);
|
||||
extern bool AESDataProcess(uint32_t ui32Base, uint32_t *pui32Src,
|
||||
uint32_t *pui32Dest, uint32_t ui32Length);
|
||||
extern bool AESDataAuth(uint32_t ui32Base, uint32_t *pui32Src,
|
||||
uint32_t ui32Length, uint32_t *pui32Tag);
|
||||
extern bool AESDataProcessAuth(uint32_t ui32Base, uint32_t *pui32Src,
|
||||
uint32_t *pui32Dest, uint32_t ui32Length,
|
||||
uint32_t *pui32AuthSrc,
|
||||
uint32_t ui32AuthLength, uint32_t *pui32Tag);
|
||||
extern void AESDataWrite(uint32_t ui32Base, uint32_t *pui32Src);
|
||||
extern bool AESDataWriteNonBlocking(uint32_t ui32Base, uint32_t *pui32Src);
|
||||
extern void AESDMADisable(uint32_t ui32Base, uint32_t ui32Flags);
|
||||
extern void AESDMAEnable(uint32_t ui32Base, uint32_t ui32Flags);
|
||||
extern void AESIntClear(uint32_t ui32Base, uint32_t ui32IntFlags);
|
||||
extern void AESIntDisable(uint32_t ui32Base, uint32_t ui32IntFlags);
|
||||
extern void AESIntEnable(uint32_t ui32Base, uint32_t ui32IntFlags);
|
||||
extern void AESIntRegister(uint32_t ui32Base, void (*pfnHandler)(void));
|
||||
extern uint32_t AESIntStatus(uint32_t ui32Base, bool bMasked);
|
||||
extern void AESIntUnregister(uint32_t ui32Base);
|
||||
extern void AESIVSet(uint32_t ui32Base, uint32_t *pui32IVdata);
|
||||
extern void AESIVRead(uint32_t ui32Base, uint32_t *pui32IVdata);
|
||||
extern void AESKey1Set(uint32_t ui32Base, uint32_t *pui32Key,
|
||||
uint32_t ui32Keysize);
|
||||
extern void AESKey2Set(uint32_t ui32Base, uint32_t *pui32Key,
|
||||
uint32_t ui32Keysize);
|
||||
extern void AESKey3Set(uint32_t ui32Base, uint32_t *pui32Key);
|
||||
extern void AESLengthSet(uint32_t ui32Base, uint64_t ui64Length);
|
||||
extern void AESReset(uint32_t ui32Base);
|
||||
extern void AESTagRead(uint32_t ui32Base, uint32_t *pui32TagData);
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Mark the end of the C bindings section for C++ compilers.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // __DRIVERLIB_AES_H__
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,449 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// can.h - Defines and Macros for the CAN controller.
|
||||
//
|
||||
// Copyright (c) 2006-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __DRIVERLIB_CAN_H__
|
||||
#define __DRIVERLIB_CAN_H__
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! \addtogroup can_api
|
||||
//! @{
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// If building with a C++ compiler, make all of the definitions in this header
|
||||
// have a C binding.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Miscellaneous defines for Message ID Types
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// These are the flags used by the tCANMsgObject.ui32Flags value when calling
|
||||
// the CANMessageSet() and CANMessageGet() functions.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
//
|
||||
//! This indicates that transmit interrupts are enabled.
|
||||
//
|
||||
#define MSG_OBJ_TX_INT_ENABLE 0x00000001
|
||||
|
||||
//
|
||||
//! This indicates that receive interrupts are enabled.
|
||||
//
|
||||
#define MSG_OBJ_RX_INT_ENABLE 0x00000002
|
||||
|
||||
//
|
||||
//! This indicates that a message object is using an extended identifier.
|
||||
//
|
||||
#define MSG_OBJ_EXTENDED_ID 0x00000004
|
||||
|
||||
//
|
||||
//! This indicates that a message object is using filtering based on the
|
||||
//! object's message identifier.
|
||||
//
|
||||
#define MSG_OBJ_USE_ID_FILTER 0x00000008
|
||||
|
||||
//
|
||||
//! This indicates that new data was available in the message object.
|
||||
//
|
||||
#define MSG_OBJ_NEW_DATA 0x00000080
|
||||
|
||||
//
|
||||
//! This indicates that data was lost since this message object was last
|
||||
//! read.
|
||||
//
|
||||
#define MSG_OBJ_DATA_LOST 0x00000100
|
||||
|
||||
//
|
||||
//! This indicates that a message object uses or is using filtering
|
||||
//! based on the direction of the transfer. If the direction filtering is
|
||||
//! used, then ID filtering must also be enabled.
|
||||
//
|
||||
#define MSG_OBJ_USE_DIR_FILTER (0x00000010 | MSG_OBJ_USE_ID_FILTER)
|
||||
|
||||
//
|
||||
//! This indicates that a message object uses or is using message
|
||||
//! identifier filtering based on the extended identifier. If the extended
|
||||
//! identifier filtering is used, then ID filtering must also be enabled.
|
||||
//
|
||||
#define MSG_OBJ_USE_EXT_FILTER (0x00000020 | MSG_OBJ_USE_ID_FILTER)
|
||||
|
||||
//
|
||||
//! This indicates that a message object is a remote frame.
|
||||
//
|
||||
#define MSG_OBJ_REMOTE_FRAME 0x00000040
|
||||
|
||||
//
|
||||
//! This indicates that this message object is part of a FIFO structure and
|
||||
//! not the final message object in a FIFO.
|
||||
//
|
||||
#define MSG_OBJ_FIFO 0x00000200
|
||||
|
||||
//
|
||||
//! This indicates that a message object has no flags set.
|
||||
//
|
||||
#define MSG_OBJ_NO_FLAGS 0x00000000
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! This define is used with the flag values to allow checking only status
|
||||
//! flags and not configuration flags.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define MSG_OBJ_STATUS_MASK (MSG_OBJ_NEW_DATA | MSG_OBJ_DATA_LOST)
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! The structure used for encapsulating all the items associated with a CAN
|
||||
//! message object in the CAN controller.
|
||||
//
|
||||
//*****************************************************************************
|
||||
typedef struct
|
||||
{
|
||||
//
|
||||
//! The CAN message identifier used for 11 or 29 bit identifiers.
|
||||
//
|
||||
uint32_t ui32MsgID;
|
||||
|
||||
//
|
||||
//! The message identifier mask used when identifier filtering is enabled.
|
||||
//
|
||||
uint32_t ui32MsgIDMask;
|
||||
|
||||
//
|
||||
//! This value holds various status flags and settings specified by
|
||||
//! tCANObjFlags.
|
||||
//
|
||||
uint32_t ui32Flags;
|
||||
|
||||
//
|
||||
//! This value is the number of bytes of data in the message object.
|
||||
//
|
||||
uint32_t ui32MsgLen;
|
||||
|
||||
//
|
||||
//! This is a pointer to the message object's data.
|
||||
//
|
||||
uint8_t *pui8MsgData;
|
||||
}
|
||||
tCANMsgObject;
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! This structure is used for encapsulating the values associated with setting
|
||||
//! up the bit timing for a CAN controller. The structure is used when calling
|
||||
//! the CANGetBitTiming and CANSetBitTiming functions.
|
||||
//
|
||||
//*****************************************************************************
|
||||
typedef struct
|
||||
{
|
||||
//
|
||||
//! This value holds the sum of the Synchronization, Propagation, and Phase
|
||||
//! Buffer 1 segments, measured in time quanta. The valid values for this
|
||||
//! setting range from 2 to 16.
|
||||
//
|
||||
uint32_t ui32SyncPropPhase1Seg;
|
||||
|
||||
//
|
||||
//! This value holds the Phase Buffer 2 segment in time quanta. The valid
|
||||
//! values for this setting range from 1 to 8.
|
||||
//
|
||||
uint32_t ui32Phase2Seg;
|
||||
|
||||
//
|
||||
//! This value holds the Resynchronization Jump Width in time quanta. The
|
||||
//! valid values for this setting range from 1 to 4.
|
||||
//
|
||||
uint32_t ui32SJW;
|
||||
|
||||
//
|
||||
//! This value holds the CAN_CLK divider used to determine time quanta.
|
||||
//! The valid values for this setting range from 1 to 1023.
|
||||
//
|
||||
uint32_t ui32QuantumPrescaler;
|
||||
}
|
||||
tCANBitClkParms;
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! This data type is used to identify the interrupt status register. This is
|
||||
//! used when calling the CANIntStatus() function.
|
||||
//
|
||||
//*****************************************************************************
|
||||
typedef enum
|
||||
{
|
||||
//
|
||||
//! Read the CAN interrupt status information.
|
||||
//
|
||||
CAN_INT_STS_CAUSE,
|
||||
|
||||
//
|
||||
//! Read a message object's interrupt status.
|
||||
//
|
||||
CAN_INT_STS_OBJECT
|
||||
}
|
||||
tCANIntStsReg;
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! This data type is used to identify which of several status registers to
|
||||
//! read when calling the CANStatusGet() function.
|
||||
//
|
||||
//*****************************************************************************
|
||||
typedef enum
|
||||
{
|
||||
//
|
||||
//! Read the full CAN controller status.
|
||||
//
|
||||
CAN_STS_CONTROL,
|
||||
|
||||
//
|
||||
//! Read the full 32-bit mask of message objects with a transmit request
|
||||
//! set.
|
||||
//
|
||||
CAN_STS_TXREQUEST,
|
||||
|
||||
//
|
||||
//! Read the full 32-bit mask of message objects with new data available.
|
||||
//
|
||||
CAN_STS_NEWDAT,
|
||||
|
||||
//
|
||||
//! Read the full 32-bit mask of message objects that are enabled.
|
||||
//
|
||||
CAN_STS_MSGVAL
|
||||
}
|
||||
tCANStsReg;
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// These definitions are used to specify interrupt sources to CANIntEnable()
|
||||
// and CANIntDisable().
|
||||
//
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! This flag is used to allow a CAN controller to generate error
|
||||
//! interrupts.
|
||||
//
|
||||
#define CAN_INT_ERROR 0x00000008
|
||||
|
||||
//
|
||||
//! This flag is used to allow a CAN controller to generate status
|
||||
//! interrupts.
|
||||
//
|
||||
#define CAN_INT_STATUS 0x00000004
|
||||
|
||||
//
|
||||
//! This flag is used to allow a CAN controller to generate any CAN
|
||||
//! interrupts. If this is not set, then no interrupts are generated
|
||||
//! by the CAN controller.
|
||||
//
|
||||
#define CAN_INT_MASTER 0x00000002
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! This definition is used to determine the type of message object that is
|
||||
//! set up via a call to the CANMessageSet() API.
|
||||
//
|
||||
//*****************************************************************************
|
||||
typedef enum
|
||||
{
|
||||
//
|
||||
//! Transmit message object.
|
||||
//
|
||||
MSG_OBJ_TYPE_TX,
|
||||
|
||||
//
|
||||
//! Transmit remote request message object
|
||||
//
|
||||
MSG_OBJ_TYPE_TX_REMOTE,
|
||||
|
||||
//
|
||||
//! Receive message object.
|
||||
//
|
||||
MSG_OBJ_TYPE_RX,
|
||||
|
||||
//
|
||||
//! Receive remote request message object.
|
||||
//
|
||||
MSG_OBJ_TYPE_RX_REMOTE,
|
||||
|
||||
//
|
||||
//! Remote frame receive remote, with auto-transmit message object.
|
||||
//
|
||||
MSG_OBJ_TYPE_RXTX_REMOTE
|
||||
}
|
||||
tMsgObjType;
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following enumeration contains all error or status indicators that can
|
||||
// be returned when calling the CANStatusGet() function.
|
||||
//
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! CAN controller has entered a Bus Off state.
|
||||
//
|
||||
#define CAN_STATUS_BUS_OFF 0x00000080
|
||||
|
||||
//
|
||||
//! CAN controller error level has reached warning level.
|
||||
//
|
||||
#define CAN_STATUS_EWARN 0x00000040
|
||||
|
||||
//
|
||||
//! CAN controller error level has reached error passive level.
|
||||
//
|
||||
#define CAN_STATUS_EPASS 0x00000020
|
||||
|
||||
//
|
||||
//! A message was received successfully since the last read of this status.
|
||||
//
|
||||
#define CAN_STATUS_RXOK 0x00000010
|
||||
|
||||
//
|
||||
//! A message was transmitted successfully since the last read of this
|
||||
//! status.
|
||||
//
|
||||
#define CAN_STATUS_TXOK 0x00000008
|
||||
|
||||
//
|
||||
//! This is the mask for the last error code field.
|
||||
//
|
||||
#define CAN_STATUS_LEC_MSK 0x00000007
|
||||
|
||||
//
|
||||
//! There was no error.
|
||||
//
|
||||
#define CAN_STATUS_LEC_NONE 0x00000000
|
||||
|
||||
//
|
||||
//! A bit stuffing error has occurred.
|
||||
//
|
||||
#define CAN_STATUS_LEC_STUFF 0x00000001
|
||||
|
||||
//
|
||||
//! A formatting error has occurred.
|
||||
//
|
||||
#define CAN_STATUS_LEC_FORM 0x00000002
|
||||
|
||||
//
|
||||
//! An acknowledge error has occurred.
|
||||
//
|
||||
#define CAN_STATUS_LEC_ACK 0x00000003
|
||||
|
||||
//
|
||||
//! The bus remained a bit level of 1 for longer than is allowed.
|
||||
//
|
||||
#define CAN_STATUS_LEC_BIT1 0x00000004
|
||||
|
||||
//
|
||||
//! The bus remained a bit level of 0 for longer than is allowed.
|
||||
//
|
||||
#define CAN_STATUS_LEC_BIT0 0x00000005
|
||||
|
||||
//
|
||||
//! A CRC error has occurred.
|
||||
//
|
||||
#define CAN_STATUS_LEC_CRC 0x00000006
|
||||
|
||||
//
|
||||
//! This is the mask for the CAN Last Error Code (LEC).
|
||||
//
|
||||
#define CAN_STATUS_LEC_MASK 0x00000007
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Close the Doxygen group.
|
||||
//! @}
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// API Function prototypes
|
||||
//
|
||||
//*****************************************************************************
|
||||
extern void CANBitTimingGet(uint32_t ui32Base, tCANBitClkParms *psClkParms);
|
||||
extern void CANBitTimingSet(uint32_t ui32Base, tCANBitClkParms *psClkParms);
|
||||
extern uint32_t CANBitRateSet(uint32_t ui32Base, uint32_t ui32SourceClock,
|
||||
uint32_t ui32BitRate);
|
||||
extern void CANDisable(uint32_t ui32Base);
|
||||
extern void CANEnable(uint32_t ui32Base);
|
||||
extern bool CANErrCntrGet(uint32_t ui32Base, uint32_t *pui32RxCount,
|
||||
uint32_t *pui32TxCount);
|
||||
extern void CANInit(uint32_t ui32Base);
|
||||
extern void CANIntClear(uint32_t ui32Base, uint32_t ui32IntClr);
|
||||
extern void CANIntDisable(uint32_t ui32Base, uint32_t ui32IntFlags);
|
||||
extern void CANIntEnable(uint32_t ui32Base, uint32_t ui32IntFlags);
|
||||
extern void CANIntRegister(uint32_t ui32Base, void (*pfnHandler)(void));
|
||||
extern uint32_t CANIntStatus(uint32_t ui32Base, tCANIntStsReg eIntStsReg);
|
||||
extern void CANIntUnregister(uint32_t ui32Base);
|
||||
extern void CANMessageClear(uint32_t ui32Base, uint32_t ui32ObjID);
|
||||
extern void CANMessageGet(uint32_t ui32Base, uint32_t ui32ObjID,
|
||||
tCANMsgObject *psMsgObject, bool bClrPendingInt);
|
||||
extern void CANMessageSet(uint32_t ui32Base, uint32_t ui32ObjID,
|
||||
tCANMsgObject *psMsgObject, tMsgObjType eMsgType);
|
||||
extern bool CANRetryGet(uint32_t ui32Base);
|
||||
extern void CANRetrySet(uint32_t ui32Base, bool bAutoRetry);
|
||||
extern uint32_t CANStatusGet(uint32_t ui32Base, tCANStsReg eStatusReg);
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Mark the end of the C bindings section for C++ compilers.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // __DRIVERLIB_CAN_H__
|
|
@ -0,0 +1,452 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// comp.c - Driver for the analog comparator.
|
||||
//
|
||||
// Copyright (c) 2005-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! \addtogroup comp_api
|
||||
//! @{
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include "inc/hw_comp.h"
|
||||
#include "inc/hw_ints.h"
|
||||
#include "inc/hw_memmap.h"
|
||||
#include "inc/hw_types.h"
|
||||
#include "driverlib/comp.h"
|
||||
#include "driverlib/debug.h"
|
||||
#include "driverlib/interrupt.h"
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Configures a comparator.
|
||||
//!
|
||||
//! \param ui32Base is the base address of the comparator module.
|
||||
//! \param ui32Comp is the index of the comparator to configure.
|
||||
//! \param ui32Config is the configuration of the comparator.
|
||||
//!
|
||||
//! This function configures a comparator. The \e ui32Config parameter is the
|
||||
//! result of a logical OR operation between the \b COMP_TRIG_xxx,
|
||||
//! \b COMP_INT_xxx, \b COMP_ASRCP_xxx, and \b COMP_OUTPUT_xxx values.
|
||||
//!
|
||||
//! The \b COMP_TRIG_xxx term can take on the following values:
|
||||
//!
|
||||
//! - \b COMP_TRIG_NONE to have no trigger to the ADC.
|
||||
//! - \b COMP_TRIG_HIGH to trigger the ADC when the comparator output is high.
|
||||
//! - \b COMP_TRIG_LOW to trigger the ADC when the comparator output is low.
|
||||
//! - \b COMP_TRIG_FALL to trigger the ADC when the comparator output goes low.
|
||||
//! - \b COMP_TRIG_RISE to trigger the ADC when the comparator output goes
|
||||
//! high.
|
||||
//! - \b COMP_TRIG_BOTH to trigger the ADC when the comparator output goes low
|
||||
//! or high.
|
||||
//!
|
||||
//! The \b COMP_INT_xxx term can take on the following values:
|
||||
//!
|
||||
//! - \b COMP_INT_HIGH to generate an interrupt when the comparator output is
|
||||
//! high.
|
||||
//! - \b COMP_INT_LOW to generate an interrupt when the comparator output is
|
||||
//! low.
|
||||
//! - \b COMP_INT_FALL to generate an interrupt when the comparator output goes
|
||||
//! low.
|
||||
//! - \b COMP_INT_RISE to generate an interrupt when the comparator output goes
|
||||
//! high.
|
||||
//! - \b COMP_INT_BOTH to generate an interrupt when the comparator output goes
|
||||
//! low or high.
|
||||
//!
|
||||
//! The \b COMP_ASRCP_xxx term can take on the following values:
|
||||
//!
|
||||
//! - \b COMP_ASRCP_PIN to use the dedicated Comp+ pin as the reference
|
||||
//! voltage.
|
||||
//! - \b COMP_ASRCP_PIN0 to use the Comp0+ pin as the reference voltage (this
|
||||
//! the same as \b COMP_ASRCP_PIN for the comparator 0).
|
||||
//! - \b COMP_ASRCP_REF to use the internally generated voltage as the
|
||||
//! reference voltage.
|
||||
//!
|
||||
//! The \b COMP_OUTPUT_xxx term can take on the following values:
|
||||
//!
|
||||
//! - \b COMP_OUTPUT_NORMAL to enable a non-inverted output from the comparator
|
||||
//! to a device pin.
|
||||
//! - \b COMP_OUTPUT_INVERT to enable an inverted output from the comparator to
|
||||
//! a device pin.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
ComparatorConfigure(uint32_t ui32Base, uint32_t ui32Comp, uint32_t ui32Config)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT(ui32Base == COMP_BASE);
|
||||
ASSERT(ui32Comp < 3);
|
||||
|
||||
//
|
||||
// Configure this comparator.
|
||||
//
|
||||
HWREG(ui32Base + (ui32Comp * 0x20) + COMP_O_ACCTL0) = ui32Config;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Sets the internal reference voltage.
|
||||
//!
|
||||
//! \param ui32Base is the base address of the comparator module.
|
||||
//! \param ui32Ref is the desired reference voltage.
|
||||
//!
|
||||
//! This function sets the internal reference voltage value. The voltage is
|
||||
//! specified as one of the following values:
|
||||
//!
|
||||
//! - \b COMP_REF_OFF to turn off the reference voltage
|
||||
//! - \b COMP_REF_0V to set the reference voltage to 0 V
|
||||
//! - \b COMP_REF_0_1375V to set the reference voltage to 0.1375 V
|
||||
//! - \b COMP_REF_0_275V to set the reference voltage to 0.275 V
|
||||
//! - \b COMP_REF_0_4125V to set the reference voltage to 0.4125 V
|
||||
//! - \b COMP_REF_0_55V to set the reference voltage to 0.55 V
|
||||
//! - \b COMP_REF_0_6875V to set the reference voltage to 0.6875 V
|
||||
//! - \b COMP_REF_0_825V to set the reference voltage to 0.825 V
|
||||
//! - \b COMP_REF_0_928125V to set the reference voltage to 0.928125 V
|
||||
//! - \b COMP_REF_0_9625V to set the reference voltage to 0.9625 V
|
||||
//! - \b COMP_REF_1_03125V to set the reference voltage to 1.03125 V
|
||||
//! - \b COMP_REF_1_134375V to set the reference voltage to 1.134375 V
|
||||
//! - \b COMP_REF_1_1V to set the reference voltage to 1.1 V
|
||||
//! - \b COMP_REF_1_2375V to set the reference voltage to 1.2375 V
|
||||
//! - \b COMP_REF_1_340625V to set the reference voltage to 1.340625 V
|
||||
//! - \b COMP_REF_1_375V to set the reference voltage to 1.375 V
|
||||
//! - \b COMP_REF_1_44375V to set the reference voltage to 1.44375 V
|
||||
//! - \b COMP_REF_1_5125V to set the reference voltage to 1.5125 V
|
||||
//! - \b COMP_REF_1_546875V to set the reference voltage to 1.546875 V
|
||||
//! - \b COMP_REF_1_65V to set the reference voltage to 1.65 V
|
||||
//! - \b COMP_REF_1_753125V to set the reference voltage to 1.753125 V
|
||||
//! - \b COMP_REF_1_7875V to set the reference voltage to 1.7875 V
|
||||
//! - \b COMP_REF_1_85625V to set the reference voltage to 1.85625 V
|
||||
//! - \b COMP_REF_1_925V to set the reference voltage to 1.925 V
|
||||
//! - \b COMP_REF_1_959375V to set the reference voltage to 1.959375 V
|
||||
//! - \b COMP_REF_2_0625V to set the reference voltage to 2.0625 V
|
||||
//! - \b COMP_REF_2_165625V to set the reference voltage to 2.165625 V
|
||||
//! - \b COMP_REF_2_26875V to set the reference voltage to 2.26875 V
|
||||
//! - \b COMP_REF_2_371875V to set the reference voltage to 2.371875 V
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
ComparatorRefSet(uint32_t ui32Base, uint32_t ui32Ref)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT(ui32Base == COMP_BASE);
|
||||
|
||||
//
|
||||
// Set the voltage reference voltage as requested.
|
||||
//
|
||||
HWREG(ui32Base + COMP_O_ACREFCTL) = ui32Ref;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Gets the current comparator output value.
|
||||
//!
|
||||
//! \param ui32Base is the base address of the comparator module.
|
||||
//! \param ui32Comp is the index of the comparator.
|
||||
//!
|
||||
//! This function retrieves the current value of the comparator output.
|
||||
//!
|
||||
//! \return Returns \b true if the comparator output is high and \b false if
|
||||
//! the comparator output is low.
|
||||
//
|
||||
//*****************************************************************************
|
||||
bool
|
||||
ComparatorValueGet(uint32_t ui32Base, uint32_t ui32Comp)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT(ui32Base == COMP_BASE);
|
||||
ASSERT(ui32Comp < 3);
|
||||
|
||||
//
|
||||
// Return the appropriate value based on the comparator's present output
|
||||
// value.
|
||||
//
|
||||
if(HWREG(ui32Base + (ui32Comp * 0x20) + COMP_O_ACSTAT0) &
|
||||
COMP_ACSTAT0_OVAL)
|
||||
{
|
||||
return(true);
|
||||
}
|
||||
else
|
||||
{
|
||||
return(false);
|
||||
}
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Registers an interrupt handler for the comparator interrupt.
|
||||
//!
|
||||
//! \param ui32Base is the base address of the comparator module.
|
||||
//! \param ui32Comp is the index of the comparator.
|
||||
//! \param pfnHandler is a pointer to the function to be called when the
|
||||
//! comparator interrupt occurs.
|
||||
//!
|
||||
//! This function sets the handler to be called when the comparator interrupt
|
||||
//! occurs and enables the interrupt in the interrupt controller. It is the
|
||||
//! interrupt handler's responsibility to clear the interrupt source via
|
||||
//! ComparatorIntClear().
|
||||
//!
|
||||
//! \sa IntRegister() for important information about registering interrupt
|
||||
//! handlers.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
ComparatorIntRegister(uint32_t ui32Base, uint32_t ui32Comp,
|
||||
void (*pfnHandler)(void))
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT(ui32Base == COMP_BASE);
|
||||
ASSERT(ui32Comp < 3);
|
||||
|
||||
//
|
||||
// Register the interrupt handler, returning an error if an error occurs.
|
||||
//
|
||||
IntRegister(INT_COMP0_TM4C123 + ui32Comp, pfnHandler);
|
||||
|
||||
//
|
||||
// Enable the interrupt in the interrupt controller.
|
||||
//
|
||||
IntEnable(INT_COMP0_TM4C123 + ui32Comp);
|
||||
|
||||
//
|
||||
// Enable the comparator interrupt.
|
||||
//
|
||||
HWREG(ui32Base + COMP_O_ACINTEN) |= 1 << ui32Comp;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Unregisters an interrupt handler for a comparator interrupt.
|
||||
//!
|
||||
//! \param ui32Base is the base address of the comparator module.
|
||||
//! \param ui32Comp is the index of the comparator.
|
||||
//!
|
||||
//! This function clears the handler to be called when a comparator 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
|
||||
ComparatorIntUnregister(uint32_t ui32Base, uint32_t ui32Comp)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT(ui32Base == COMP_BASE);
|
||||
ASSERT(ui32Comp < 3);
|
||||
|
||||
//
|
||||
// Disable the comparator interrupt.
|
||||
//
|
||||
HWREG(ui32Base + COMP_O_ACINTEN) &= ~(1 << ui32Comp);
|
||||
|
||||
//
|
||||
// Disable the interrupt in the interrupt controller.
|
||||
//
|
||||
IntDisable(INT_COMP0_TM4C123 + ui32Comp);
|
||||
|
||||
//
|
||||
// Unregister the interrupt handler.
|
||||
//
|
||||
IntUnregister(INT_COMP0_TM4C123 + ui32Comp);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Enables the comparator interrupt.
|
||||
//!
|
||||
//! \param ui32Base is the base address of the comparator module.
|
||||
//! \param ui32Comp is the index of the comparator.
|
||||
//!
|
||||
//! This function enables generation of an interrupt from the specified
|
||||
//! comparator. Only enabled comparator interrupts can be reflected
|
||||
//! to the processor.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
ComparatorIntEnable(uint32_t ui32Base, uint32_t ui32Comp)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT(ui32Base == COMP_BASE);
|
||||
ASSERT(ui32Comp < 3);
|
||||
|
||||
//
|
||||
// Enable the comparator interrupt.
|
||||
//
|
||||
HWREG(ui32Base + COMP_O_ACINTEN) |= 1 << ui32Comp;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Disables the comparator interrupt.
|
||||
//!
|
||||
//! \param ui32Base is the base address of the comparator module.
|
||||
//! \param ui32Comp is the index of the comparator.
|
||||
//!
|
||||
//! This function disables generation of an interrupt from the specified
|
||||
//! comparator. Only enabled comparator interrupts can be reflected
|
||||
//! to the processor.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
ComparatorIntDisable(uint32_t ui32Base, uint32_t ui32Comp)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT(ui32Base == COMP_BASE);
|
||||
ASSERT(ui32Comp < 3);
|
||||
|
||||
//
|
||||
// Disable the comparator interrupt.
|
||||
//
|
||||
HWREG(ui32Base + COMP_O_ACINTEN) &= ~(1 << ui32Comp);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Gets the current interrupt status.
|
||||
//!
|
||||
//! \param ui32Base is the base address of the comparator module.
|
||||
//! \param ui32Comp is the index of the comparator.
|
||||
//! \param bMasked is \b false if the raw interrupt status is required and
|
||||
//! \b true if the masked interrupt status is required.
|
||||
//!
|
||||
//! This function returns the interrupt status for the comparator. Either the
|
||||
//! raw or the masked interrupt status can be returned.
|
||||
//!
|
||||
//! \return \b true if the interrupt is asserted and \b false if it is not
|
||||
//! asserted.
|
||||
//
|
||||
//*****************************************************************************
|
||||
bool
|
||||
ComparatorIntStatus(uint32_t ui32Base, uint32_t ui32Comp, bool bMasked)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT(ui32Base == COMP_BASE);
|
||||
ASSERT(ui32Comp < 3);
|
||||
|
||||
//
|
||||
// Return either the interrupt status or the raw interrupt status as
|
||||
// requested.
|
||||
//
|
||||
if(bMasked)
|
||||
{
|
||||
return(((HWREG(ui32Base + COMP_O_ACMIS) >> ui32Comp) & 1) ? true :
|
||||
false);
|
||||
}
|
||||
else
|
||||
{
|
||||
return(((HWREG(ui32Base + COMP_O_ACRIS) >> ui32Comp) & 1) ? true :
|
||||
false);
|
||||
}
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Clears a comparator interrupt.
|
||||
//!
|
||||
//! \param ui32Base is the base address of the comparator module.
|
||||
//! \param ui32Comp is the index of the comparator.
|
||||
//!
|
||||
//! The comparator interrupt is cleared, so that it no longer asserts. This
|
||||
//! function must be called in the interrupt handler to keep the handler from
|
||||
//! being called again immediately upon exit. Note that for a level-triggered
|
||||
//! interrupt, the interrupt cannot be cleared until it stops asserting.
|
||||
//!
|
||||
//! \note Because there is a write buffer in the Cortex-M 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
|
||||
ComparatorIntClear(uint32_t ui32Base, uint32_t ui32Comp)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT(ui32Base == COMP_BASE);
|
||||
ASSERT(ui32Comp < 3);
|
||||
|
||||
//
|
||||
// Clear the interrupt.
|
||||
//
|
||||
HWREG(ui32Base + COMP_O_ACMIS) = 1 << ui32Comp;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Close the Doxygen group.
|
||||
//! @}
|
||||
//
|
||||
//*****************************************************************************
|
|
@ -0,0 +1,141 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// comp.h - Prototypes for the analog comparator driver.
|
||||
//
|
||||
// Copyright (c) 2005-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __DRIVERLIB_COMP_H__
|
||||
#define __DRIVERLIB_COMP_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 ComparatorConfigure() as the ui32Config
|
||||
// parameter. For each group (in other words, COMP_TRIG_xxx, COMP_INT_xxx, and
|
||||
// so on), one of the values may be selected and combined together with values
|
||||
// from the other groups via a logical OR.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define COMP_TRIG_NONE 0x00000000 // No ADC trigger
|
||||
#define COMP_TRIG_HIGH 0x00000880 // Trigger when high
|
||||
#define COMP_TRIG_LOW 0x00000800 // Trigger when low
|
||||
#define COMP_TRIG_FALL 0x00000820 // Trigger on falling edge
|
||||
#define COMP_TRIG_RISE 0x00000840 // Trigger on rising edge
|
||||
#define COMP_TRIG_BOTH 0x00000860 // Trigger on both edges
|
||||
#define COMP_INT_HIGH 0x00000010 // Interrupt when high
|
||||
#define COMP_INT_LOW 0x00000000 // Interrupt when low
|
||||
#define COMP_INT_FALL 0x00000004 // Interrupt on falling edge
|
||||
#define COMP_INT_RISE 0x00000008 // Interrupt on rising edge
|
||||
#define COMP_INT_BOTH 0x0000000C // Interrupt on both edges
|
||||
#define COMP_ASRCP_PIN 0x00000000 // Dedicated Comp+ pin
|
||||
#define COMP_ASRCP_PIN0 0x00000200 // Comp0+ pin
|
||||
#define COMP_ASRCP_REF 0x00000400 // Internal voltage reference
|
||||
#define COMP_OUTPUT_NORMAL 0x00000000 // Comparator output normal
|
||||
#define COMP_OUTPUT_INVERT 0x00000002 // Comparator output inverted
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to ComparatorSetRef() as the ui32Ref parameter.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define COMP_REF_OFF 0x00000000 // Turn off the internal reference
|
||||
#define COMP_REF_0V 0x00000300 // Internal reference of 0V
|
||||
#define COMP_REF_0_1375V 0x00000301 // Internal reference of 0.1375V
|
||||
#define COMP_REF_0_275V 0x00000302 // Internal reference of 0.275V
|
||||
#define COMP_REF_0_4125V 0x00000303 // Internal reference of 0.4125V
|
||||
#define COMP_REF_0_55V 0x00000304 // Internal reference of 0.55V
|
||||
#define COMP_REF_0_6875V 0x00000305 // Internal reference of 0.6875V
|
||||
#define COMP_REF_0_825V 0x00000306 // Internal reference of 0.825V
|
||||
#define COMP_REF_0_928125V 0x00000201 // Internal reference of 0.928125V
|
||||
#define COMP_REF_0_9625V 0x00000307 // Internal reference of 0.9625V
|
||||
#define COMP_REF_1_03125V 0x00000202 // Internal reference of 1.03125V
|
||||
#define COMP_REF_1_134375V 0x00000203 // Internal reference of 1.134375V
|
||||
#define COMP_REF_1_1V 0x00000308 // Internal reference of 1.1V
|
||||
#define COMP_REF_1_2375V 0x00000309 // Internal reference of 1.2375V
|
||||
#define COMP_REF_1_340625V 0x00000205 // Internal reference of 1.340625V
|
||||
#define COMP_REF_1_375V 0x0000030A // Internal reference of 1.375V
|
||||
#define COMP_REF_1_44375V 0x00000206 // Internal reference of 1.44375V
|
||||
#define COMP_REF_1_5125V 0x0000030B // Internal reference of 1.5125V
|
||||
#define COMP_REF_1_546875V 0x00000207 // Internal reference of 1.546875V
|
||||
#define COMP_REF_1_65V 0x0000030C // Internal reference of 1.65V
|
||||
#define COMP_REF_1_753125V 0x00000209 // Internal reference of 1.753125V
|
||||
#define COMP_REF_1_7875V 0x0000030D // Internal reference of 1.7875V
|
||||
#define COMP_REF_1_85625V 0x0000020A // Internal reference of 1.85625V
|
||||
#define COMP_REF_1_925V 0x0000030E // Internal reference of 1.925V
|
||||
#define COMP_REF_1_959375V 0x0000020B // Internal reference of 1.959375V
|
||||
#define COMP_REF_2_0625V 0x0000030F // Internal reference of 2.0625V
|
||||
#define COMP_REF_2_165625V 0x0000020D // Internal reference of 2.165625V
|
||||
#define COMP_REF_2_26875V 0x0000020E // Internal reference of 2.26875V
|
||||
#define COMP_REF_2_371875V 0x0000020F // Internal reference of 2.371875V
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Prototypes for the APIs.
|
||||
//
|
||||
//*****************************************************************************
|
||||
extern void ComparatorConfigure(uint32_t ui32Base, uint32_t ui32Comp,
|
||||
uint32_t ui32Config);
|
||||
extern void ComparatorRefSet(uint32_t ui32Base, uint32_t ui32Ref);
|
||||
extern bool ComparatorValueGet(uint32_t ui32Base, uint32_t ui32Comp);
|
||||
extern void ComparatorIntRegister(uint32_t ui32Base, uint32_t ui32Comp,
|
||||
void (*pfnHandler)(void));
|
||||
extern void ComparatorIntUnregister(uint32_t ui32Base, uint32_t ui32Comp);
|
||||
extern void ComparatorIntEnable(uint32_t ui32Base, uint32_t ui32Comp);
|
||||
extern void ComparatorIntDisable(uint32_t ui32Base, uint32_t ui32Comp);
|
||||
extern bool ComparatorIntStatus(uint32_t ui32Base, uint32_t ui32Comp,
|
||||
bool bMasked);
|
||||
extern void ComparatorIntClear(uint32_t ui32Base, uint32_t ui32Comp);
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Mark the end of the C bindings section for C++ compilers.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // __DRIVERLIB_COMP_H__
|
|
@ -0,0 +1,457 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// cpu.c - Instruction wrappers for special CPU instructions needed by the
|
||||
// drivers.
|
||||
//
|
||||
// Copyright (c) 2006-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#include <stdint.h>
|
||||
#include "driverlib/cpu.h"
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Wrapper function for the CPSID instruction. Returns the state of PRIMASK
|
||||
// on entry.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#if defined(codered) || defined(gcc) || defined(sourcerygxx)
|
||||
uint32_t __attribute__((naked))
|
||||
CPUcpsid(void)
|
||||
{
|
||||
uint32_t ui32Ret;
|
||||
|
||||
//
|
||||
// Read PRIMASK and disable interrupts.
|
||||
//
|
||||
__asm(" mrs r0, PRIMASK\n"
|
||||
" cpsid i\n"
|
||||
" bx lr\n"
|
||||
: "=r" (ui32Ret));
|
||||
|
||||
//
|
||||
// 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(ui32Ret);
|
||||
}
|
||||
#endif
|
||||
#if defined(ewarm)
|
||||
uint32_t
|
||||
CPUcpsid(void)
|
||||
{
|
||||
//
|
||||
// Read PRIMASK and disable interrupts.
|
||||
//
|
||||
__asm(" mrs r0, PRIMASK\n"
|
||||
" cpsid i\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(rvmdk) || defined(__ARMCC_VERSION)
|
||||
__asm uint32_t
|
||||
CPUcpsid(void)
|
||||
{
|
||||
//
|
||||
// Read PRIMASK and disable interrupts.
|
||||
//
|
||||
mrs r0, PRIMASK;
|
||||
cpsid i;
|
||||
bx lr
|
||||
}
|
||||
#endif
|
||||
#if defined(ccs)
|
||||
uint32_t
|
||||
CPUcpsid(void)
|
||||
{
|
||||
//
|
||||
// Read PRIMASK and disable interrupts.
|
||||
//
|
||||
__asm(" mrs r0, PRIMASK\n"
|
||||
" cpsid i\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(codered) || defined(gcc) || defined(sourcerygxx)
|
||||
uint32_t __attribute__((naked))
|
||||
CPUprimask(void)
|
||||
{
|
||||
uint32_t ui32Ret;
|
||||
|
||||
//
|
||||
// Read PRIMASK and disable interrupts.
|
||||
//
|
||||
__asm(" mrs r0, PRIMASK\n"
|
||||
" bx lr\n"
|
||||
: "=r" (ui32Ret));
|
||||
|
||||
//
|
||||
// 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(ui32Ret);
|
||||
}
|
||||
#endif
|
||||
#if defined(ewarm)
|
||||
uint32_t
|
||||
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(rvmdk) || defined(__ARMCC_VERSION)
|
||||
__asm uint32_t
|
||||
CPUprimask(void)
|
||||
{
|
||||
//
|
||||
// Read PRIMASK and disable interrupts.
|
||||
//
|
||||
mrs r0, PRIMASK;
|
||||
bx lr
|
||||
}
|
||||
#endif
|
||||
#if defined(ccs)
|
||||
uint32_t
|
||||
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(codered) || defined(gcc) || defined(sourcerygxx)
|
||||
uint32_t __attribute__((naked))
|
||||
CPUcpsie(void)
|
||||
{
|
||||
uint32_t ui32Ret;
|
||||
|
||||
//
|
||||
// Read PRIMASK and enable interrupts.
|
||||
//
|
||||
__asm(" mrs r0, PRIMASK\n"
|
||||
" cpsie i\n"
|
||||
" bx lr\n"
|
||||
: "=r" (ui32Ret));
|
||||
|
||||
//
|
||||
// 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(ui32Ret);
|
||||
}
|
||||
#endif
|
||||
#if defined(ewarm)
|
||||
uint32_t
|
||||
CPUcpsie(void)
|
||||
{
|
||||
//
|
||||
// Read PRIMASK and enable interrupts.
|
||||
//
|
||||
__asm(" mrs r0, PRIMASK\n"
|
||||
" cpsie i\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(rvmdk) || defined(__ARMCC_VERSION)
|
||||
__asm uint32_t
|
||||
CPUcpsie(void)
|
||||
{
|
||||
//
|
||||
// Read PRIMASK and enable interrupts.
|
||||
//
|
||||
mrs r0, PRIMASK;
|
||||
cpsie i;
|
||||
bx lr
|
||||
}
|
||||
#endif
|
||||
#if defined(ccs)
|
||||
uint32_t
|
||||
CPUcpsie(void)
|
||||
{
|
||||
//
|
||||
// Read PRIMASK and enable interrupts.
|
||||
//
|
||||
__asm(" mrs r0, PRIMASK\n"
|
||||
" cpsie i\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(codered) || defined(gcc) || defined(sourcerygxx)
|
||||
void __attribute__((naked))
|
||||
CPUwfi(void)
|
||||
{
|
||||
//
|
||||
// Wait for the next interrupt.
|
||||
//
|
||||
__asm(" wfi\n"
|
||||
" bx lr\n");
|
||||
}
|
||||
#endif
|
||||
#if defined(ewarm)
|
||||
void
|
||||
CPUwfi(void)
|
||||
{
|
||||
//
|
||||
// Wait for the next interrupt.
|
||||
//
|
||||
__asm(" wfi\n");
|
||||
}
|
||||
#endif
|
||||
#if defined(rvmdk) || defined(__ARMCC_VERSION)
|
||||
__asm void
|
||||
CPUwfi(void)
|
||||
{
|
||||
//
|
||||
// Wait for the next interrupt.
|
||||
//
|
||||
wfi;
|
||||
bx lr
|
||||
}
|
||||
#endif
|
||||
#if defined(ccs)
|
||||
void
|
||||
CPUwfi(void)
|
||||
{
|
||||
//
|
||||
// Wait for the next interrupt.
|
||||
//
|
||||
__asm(" wfi\n");
|
||||
}
|
||||
#endif
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Wrapper function for writing the BASEPRI register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#if defined(codered) || defined(gcc) || defined(sourcerygxx)
|
||||
void __attribute__((naked))
|
||||
CPUbasepriSet(uint32_t ui32NewBasepri)
|
||||
{
|
||||
//
|
||||
// Set the BASEPRI register
|
||||
//
|
||||
__asm(" msr BASEPRI, r0\n"
|
||||
" bx lr\n");
|
||||
}
|
||||
#endif
|
||||
#if defined(ewarm)
|
||||
void
|
||||
CPUbasepriSet(uint32_t ui32NewBasepri)
|
||||
{
|
||||
//
|
||||
// Set the BASEPRI register
|
||||
//
|
||||
__asm(" msr BASEPRI, r0\n");
|
||||
}
|
||||
#endif
|
||||
#if defined(rvmdk) || defined(__ARMCC_VERSION)
|
||||
__asm void
|
||||
CPUbasepriSet(uint32_t ui32NewBasepri)
|
||||
{
|
||||
//
|
||||
// Set the BASEPRI register
|
||||
//
|
||||
msr BASEPRI, r0;
|
||||
bx lr
|
||||
}
|
||||
#endif
|
||||
#if defined(ccs)
|
||||
void
|
||||
CPUbasepriSet(uint32_t ui32NewBasepri)
|
||||
{
|
||||
//
|
||||
// Set the BASEPRI register
|
||||
//
|
||||
__asm(" msr BASEPRI, r0\n");
|
||||
}
|
||||
#endif
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Wrapper function for reading the BASEPRI register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#if defined(codered) || defined(gcc) || defined(sourcerygxx)
|
||||
uint32_t __attribute__((naked))
|
||||
CPUbasepriGet(void)
|
||||
{
|
||||
uint32_t ui32Ret;
|
||||
|
||||
//
|
||||
// Read BASEPRI
|
||||
//
|
||||
__asm(" mrs r0, BASEPRI\n"
|
||||
" bx lr\n"
|
||||
: "=r" (ui32Ret));
|
||||
|
||||
//
|
||||
// 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(ui32Ret);
|
||||
}
|
||||
#endif
|
||||
#if defined(ewarm)
|
||||
uint32_t
|
||||
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(rvmdk) || defined(__ARMCC_VERSION)
|
||||
__asm uint32_t
|
||||
CPUbasepriGet(void)
|
||||
{
|
||||
//
|
||||
// Read BASEPRI
|
||||
//
|
||||
mrs r0, BASEPRI;
|
||||
bx lr
|
||||
}
|
||||
#endif
|
||||
#if defined(ccs)
|
||||
uint32_t
|
||||
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
|
|
@ -0,0 +1,75 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// cpu.h - Prototypes for the CPU instruction wrapper functions.
|
||||
//
|
||||
// Copyright (c) 2006-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __DRIVERLIB_CPU_H__
|
||||
#define __DRIVERLIB_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 uint32_t CPUcpsid(void);
|
||||
extern uint32_t CPUcpsie(void);
|
||||
extern uint32_t CPUprimask(void);
|
||||
extern void CPUwfi(void);
|
||||
extern uint32_t CPUbasepriGet(void);
|
||||
extern void CPUbasepriSet(uint32_t ui32NewBasepri);
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Mark the end of the C bindings section for C++ compilers.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // __DRIVERLIB_CPU_H__
|
|
@ -0,0 +1,311 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// crc.c - Driver for the CRC module.
|
||||
//
|
||||
// Copyright (c) 2012-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! \addtogroup crc_api
|
||||
//! @{
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include "inc/hw_ccm.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 CRC_CFG_INIT_SEED - Initialize with seed value
|
||||
//! - \b CRC_CFG_INIT_0 - Initialize to all '0s'
|
||||
//! - \b CRC_CFG_INIT_1 - Initialize to all '1s'
|
||||
//!
|
||||
//! Input Data Size
|
||||
//! - \b CRC_CFG_SIZE_8BIT - Input data size of 8 bits
|
||||
//! - \b CRC_CFG_SIZE_32BIT - Input data size of 32 bits
|
||||
//!
|
||||
//! Post Process Reverse/Inverse
|
||||
//! - \b CRC_CFG_RESINV - Result inverse enable
|
||||
//! - \b CRC_CFG_OBR - Output reverse enable
|
||||
//!
|
||||
//! Input Bit Reverse
|
||||
//! - \b CRC_CFG_IBR - Bit reverse enable
|
||||
//!
|
||||
//! Endian Control
|
||||
//! - \b CRC_CFG_ENDIAN_SBHW - Swap byte in half-word
|
||||
//! - \b CRC_CFG_ENDIAN_SHW - Swap half-word
|
||||
//!
|
||||
//! Operation Type
|
||||
//! - \b CRC_CFG_TYPE_P8005 - Polynomial 0x8005
|
||||
//! - \b CRC_CFG_TYPE_P1021 - Polynomial 0x1021
|
||||
//! - \b CRC_CFG_TYPE_P4C11DB7 - Polynomial 0x4C11DB7
|
||||
//! - \b CRC_CFG_TYPE_P1EDC6F41 - Polynomial 0x1EDC6F41
|
||||
//! - \b CRC_CFG_TYPE_TCPCHKSUM - TCP checksum
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
CRCConfigSet(uint32_t ui32Base, uint32_t ui32CRCConfig)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT(ui32Base == CCM0_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 + CCM_O_CRCCTRL) = 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 CRC_CFG_INIT_SEED is
|
||||
//! set with the CRCConfigSet() function.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
CRCSeedSet(uint32_t ui32Base, uint32_t ui32Seed)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT(ui32Base == CCM0_BASE);
|
||||
|
||||
//
|
||||
// Write the seed value to the seed register.
|
||||
//
|
||||
HWREG(ui32Base + CCM_O_CRCSEED) = 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 CRC_CFG_SIZE_8BIT or \b CRC_CFG_SIZE_32BIT flag
|
||||
//! is set using the CRCConfigSet() function.
|
||||
//!
|
||||
//! When writing 8 bits of data, ensure the data is in the least significant
|
||||
//! 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 == CCM0_BASE);
|
||||
|
||||
//
|
||||
// Write the data
|
||||
//
|
||||
HWREG(ui32Base + CCM_O_CRCDIN) = ui32Data;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Reads the result of a CRC operation in the EC module.
|
||||
//!
|
||||
//! \param ui32Base is the base address of the EC module.
|
||||
//! \param bPPResult is \b true to read the post-processed result, or \b false
|
||||
//! to read the unmodified result.
|
||||
//!
|
||||
//! 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 CRC_CFG_RESINV and \b CRC_CFG_OBR
|
||||
//! parameters in the CRCConfigSet() function.
|
||||
//!
|
||||
//! \return The CRC result.
|
||||
//
|
||||
//*****************************************************************************
|
||||
uint32_t
|
||||
CRCResultRead(uint32_t ui32Base, bool bPPResult)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT(ui32Base == CCM0_BASE);
|
||||
|
||||
//
|
||||
// Depending on the value of bPPResult, read the appropriate register and
|
||||
// return value.
|
||||
//
|
||||
if(bPPResult)
|
||||
{
|
||||
return(HWREG(ui32Base + CCM_O_CRCRSLTPP));
|
||||
}
|
||||
else
|
||||
{
|
||||
return(HWREG(ui32Base + CCM_O_CRCSEED));
|
||||
}
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Process data to generate a CRC with the EC module.
|
||||
//!
|
||||
//! \param ui32Base is the base address of the EC module.
|
||||
//! \param pui32DataIn 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 bPPResult is \b true to read the post-processed result, or \b false
|
||||
//! to read the unmodified result.
|
||||
//!
|
||||
//! This function processes an array of data to produce a CRC result.
|
||||
//!
|
||||
//! 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 CRC_CFG_SIZE_8BIT and
|
||||
//! \b 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 CRC_CFG_RESINV and
|
||||
//! \b CRC_CFG_OBR parameters.
|
||||
//!
|
||||
//! \return The CRC result.
|
||||
//
|
||||
//*****************************************************************************
|
||||
uint32_t
|
||||
CRCDataProcess(uint32_t ui32Base, uint32_t *pui32DataIn,
|
||||
uint32_t ui32DataLength, bool bPPResult)
|
||||
{
|
||||
uint8_t *pui8DataIn;
|
||||
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT(ui32Base == CCM0_BASE);
|
||||
|
||||
//
|
||||
// See if the CRC is operating in 8-bit or 32-bit mode.
|
||||
//
|
||||
if(HWREG(ui32Base + CCM_O_CRCCTRL) & CCM_CRCCTRL_SIZE)
|
||||
{
|
||||
//
|
||||
// The CRC is operating in 8-bit mode, so create an 8-bit pointer to
|
||||
// the data.
|
||||
//
|
||||
pui8DataIn = (uint8_t *)pui32DataIn;
|
||||
|
||||
//
|
||||
// Loop through the input data.
|
||||
//
|
||||
while(ui32DataLength--)
|
||||
{
|
||||
//
|
||||
// Write the next data byte.
|
||||
//
|
||||
HWREG(ui32Base + CCM_O_CRCDIN) = *pui8DataIn++;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
//
|
||||
// The CRC is operating in 32-bit mode, so loop through the input data.
|
||||
//
|
||||
while(ui32DataLength--)
|
||||
{
|
||||
//
|
||||
// Write the next data word.
|
||||
//
|
||||
HWREG(ui32Base + CCM_O_CRCDIN) = *pui32DataIn++;
|
||||
}
|
||||
}
|
||||
|
||||
//
|
||||
// Return the result.
|
||||
//
|
||||
return(CRCResultRead(ui32Base, bPPResult));
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Close the Doxygen group.
|
||||
//! @}
|
||||
//
|
||||
//*****************************************************************************
|
|
@ -0,0 +1,101 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// crc.h - Defines and Macros for CRC module.
|
||||
//
|
||||
// Copyright (c) 2012-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#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.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#if 0
|
||||
extern void ECClockGatingReqest(uint32_t ui32Base, uint32_t ui32ECIP,
|
||||
bool bGate);
|
||||
#endif
|
||||
extern void CRCConfigSet(uint32_t ui32Base, uint32_t ui32CRCConfig);
|
||||
extern uint32_t CRCDataProcess(uint32_t ui32Base, uint32_t *pui32DataIn,
|
||||
uint32_t ui32DataLength, bool bPPResult);
|
||||
extern void CRCDataWrite(uint32_t ui32Base, uint32_t ui32Data);
|
||||
extern uint32_t CRCResultRead(uint32_t ui32Base, bool bPPResult);
|
||||
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__
|
|
@ -0,0 +1,70 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// debug.h - Macros for assisting debug of the driver library.
|
||||
//
|
||||
// Copyright (c) 2006-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __DRIVERLIB_DEBUG_H__
|
||||
#define __DRIVERLIB_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, uint32_t ui32Line);
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The ASSERT macro, which does the actual assertion checking. Typically, this
|
||||
// will be for procedure arguments.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifdef DEBUG
|
||||
#define ASSERT(expr) do \
|
||||
{ \
|
||||
if(!(expr)) \
|
||||
{ \
|
||||
__error__(__FILE__, __LINE__); \
|
||||
} \
|
||||
} \
|
||||
while(0)
|
||||
#else
|
||||
#define ASSERT(expr)
|
||||
#endif
|
||||
|
||||
#endif // __DRIVERLIB_DEBUG_H__
|
|
@ -0,0 +1,807 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// des.c - Driver for the DES data transformation.
|
||||
//
|
||||
// Copyright (c) 2012-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! \addtogroup des_api
|
||||
//! @{
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include "inc/hw_des.h"
|
||||
#include "inc/hw_ints.h"
|
||||
#include "inc/hw_memmap.h"
|
||||
#include "inc/hw_types.h"
|
||||
#include "driverlib/debug.h"
|
||||
#include "driverlib/des.h"
|
||||
#include "driverlib/interrupt.h"
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Resets the DES Module.
|
||||
//!
|
||||
//! \param ui32Base is the base address of the DES module.
|
||||
//!
|
||||
//! This function performs a soft-reset sequence of the DES module.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
DESReset(uint32_t ui32Base)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT(ui32Base == DES_BASE);
|
||||
|
||||
//
|
||||
// Trigger the soft reset.
|
||||
//
|
||||
HWREG(ui32Base + DES_O_SYSCONFIG) |= DES_SYSCONFIG_SOFTRESET;
|
||||
|
||||
//
|
||||
// Wait for the reset to finish.
|
||||
//
|
||||
while((HWREG(ui32Base + DES_O_SYSSTATUS) &
|
||||
DES_SYSSTATUS_RESETDONE) == 0)
|
||||
{
|
||||
}
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! 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 pui32Key is a pointer to an array that holds the key
|
||||
//!
|
||||
//! This function sets the key used for DES operations.
|
||||
//!
|
||||
//! \e pui32Key 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, uint32_t *pui32Key)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT(ui32Base == DES_BASE);
|
||||
|
||||
//
|
||||
// Write the first part of the key.
|
||||
//
|
||||
HWREG(ui32Base + DES_O_KEY1_L) = pui32Key[0];
|
||||
HWREG(ui32Base + DES_O_KEY1_H) = pui32Key[1];
|
||||
|
||||
//
|
||||
// If we are performing tripe 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) = pui32Key[2];
|
||||
HWREG(ui32Base + DES_O_KEY2_H) = pui32Key[3];
|
||||
HWREG(ui32Base + DES_O_KEY3_L) = pui32Key[4];
|
||||
HWREG(ui32Base + DES_O_KEY3_H) = pui32Key[5];
|
||||
}
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Sets the initialization vector in the DES module.
|
||||
//!
|
||||
//! \param ui32Base is the base address of the DES module.
|
||||
//! \param pui32IVdata 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, uint32_t *pui32IVdata)
|
||||
{
|
||||
//
|
||||
// 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) = pui32IVdata[0];
|
||||
HWREG(ui32Base + DES_O_IV_H) = pui32IVdata[1];
|
||||
|
||||
//
|
||||
// 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 triggered to start using this
|
||||
//! context.
|
||||
//!
|
||||
//! \note Data lengths up to (2^32 - 1) bytes are allowed.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
DESLengthSet(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 pui32Dest is a pointer to an array of 2 words.
|
||||
//!
|
||||
//! 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, uint32_t *pui32Dest)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT(ui32Base == DES_BASE);
|
||||
|
||||
//
|
||||
// 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);
|
||||
|
||||
//
|
||||
// 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 pui32Dest is a pointer to an array of bytes.
|
||||
//!
|
||||
//! This function waits until the DES module is finished and encrypted or
|
||||
//! decrypted data is ready. The output data is then stored in the pui32Dest
|
||||
//! array.
|
||||
//!
|
||||
//! \return None
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
DESDataRead(uint32_t ui32Base, uint32_t *pui32Dest)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT(ui32Base == DES_BASE);
|
||||
|
||||
//
|
||||
// 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);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Writes plaintext/ciphertext to data registers without blocking
|
||||
//!
|
||||
//! \param ui32Base is the base address of the DES module.
|
||||
//! \param pui32Src is a pointer to an array of 2 words.
|
||||
//!
|
||||
//! 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, uint32_t *pui32Src)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT(ui32Base == DES_BASE);
|
||||
|
||||
//
|
||||
// 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);
|
||||
}
|
||||
|
||||
//
|
||||
// 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 pui32Src is a pointer to an array of bytes.
|
||||
//!
|
||||
//! This function waits until the DES module is ready before writing the
|
||||
//! data contained in the pui32Src array.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
DESDataWrite(uint32_t ui32Base, uint32_t *pui32Src)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT(ui32Base == DES_BASE);
|
||||
|
||||
//
|
||||
// Wait for the input ready bit to go high.
|
||||
//
|
||||
while(((HWREG(ui32Base + DES_O_CTRL) & DES_CTRL_INPUT_READY)) == 0)
|
||||
{
|
||||
}
|
||||
|
||||
//
|
||||
// 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 pui32Src is a pointer to an array of words that contains the
|
||||
//! source data for processing.
|
||||
//! \param pui32Dest 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 pui32Src array and processes
|
||||
//! it using the DES engine. The resulting data is stored in the
|
||||
//! pui32Dest 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, uint32_t *pui32Src, uint32_t *pui32Dest,
|
||||
uint32_t ui32Length)
|
||||
{
|
||||
uint32_t ui32Count;
|
||||
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
for(ui32Count = 0; ui32Count < (ui32Length / 4); ui32Count += 2)
|
||||
{
|
||||
//
|
||||
// Check if the input ready is fine
|
||||
//
|
||||
while((DES_CTRL_INPUT_READY & (HWREG(ui32Base + DES_O_CTRL))) == 0)
|
||||
{
|
||||
}
|
||||
|
||||
//
|
||||
// Write the block data.
|
||||
//
|
||||
DESDataWriteNonBlocking(ui32Base, pui32Src + ui32Count);
|
||||
|
||||
//
|
||||
// Wait for the output ready
|
||||
//
|
||||
while((DES_CTRL_OUTPUT_READY & (HWREG(ui32Base + DES_O_CTRL))) == 0)
|
||||
{
|
||||
}
|
||||
|
||||
//
|
||||
// Read the processed data block.
|
||||
//
|
||||
DESDataReadNonBlocking(ui32Base, pui32Dest + ui32Count);
|
||||
}
|
||||
|
||||
//
|
||||
// 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 ui32Status, ui32Enable;
|
||||
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT(ui32Base == DES_BASE);
|
||||
|
||||
//
|
||||
// Read the status register and return the value.
|
||||
//
|
||||
ui32Status = HWREG(ui32Base + DES_O_IRQSTATUS);
|
||||
if(bMasked)
|
||||
{
|
||||
ui32Enable = HWREG(ui32Base + DES_O_IRQENABLE);
|
||||
return((ui32Status & ui32Enable) |
|
||||
(HWREG(ui32Base + DES_O_DMAMIS) << 16));
|
||||
}
|
||||
else
|
||||
{
|
||||
return(ui32Status | (HWREG(ui32Base + DES_O_DMARIS) << 16));
|
||||
}
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! 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(ui32Base + DES_O_DMAIM) |= (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(ui32Base + DES_O_DMAIM) &= ~((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(ui32Base + DES_O_DMAIC) = (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_DES0_TM4C129, pfnHandler);
|
||||
|
||||
//
|
||||
// Enable the interrupt.
|
||||
//
|
||||
IntEnable(INT_DES0_TM4C129);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! 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_DES0_TM4C129);
|
||||
|
||||
//
|
||||
// Unregister the interrupt handler.
|
||||
//
|
||||
IntUnregister(INT_DES0_TM4C129);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! 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.
|
||||
//! @}
|
||||
//
|
||||
//*****************************************************************************
|
|
@ -0,0 +1,140 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// des.h - Defines and Macros for the DES module.
|
||||
//
|
||||
// Copyright (c) 2012-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#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, uint32_t *pui32Dest);
|
||||
extern bool DESDataReadNonBlocking(uint32_t ui32Base, uint32_t *pui32Dest);
|
||||
extern bool DESDataProcess(uint32_t ui32Base, uint32_t *pui32Src,
|
||||
uint32_t *pui32Dest, uint32_t ui32Length);
|
||||
extern void DESDataWrite(uint32_t ui32Base, uint32_t *pui32Src);
|
||||
extern bool DESDataWriteNonBlocking(uint32_t ui32Base, uint32_t *pui32Src);
|
||||
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, uint32_t *pui32IVdata);
|
||||
extern void DESKeySet(uint32_t ui32Base, uint32_t *pui32Key);
|
||||
extern void DESLengthSet(uint32_t ui32Base, uint32_t ui32Length);
|
||||
extern void DESReset(uint32_t ui32Base);
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Mark the end of the C bindings section for C++ compilers.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // __DRIVERLIB_DES_H__
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,284 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// eeprom.h - Prototypes for the EEPROM driver.
|
||||
//
|
||||
// Copyright (c) 2010-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __DRIVERLIB_EEPROM_H__
|
||||
#define __DRIVERLIB_EEPROM_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 eeprom_api
|
||||
//! @{
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values returned by EEPROMInit.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
//
|
||||
//! This value may be returned from a call to EEPROMInit(). It indicates that
|
||||
//! no previous write operations were interrupted by a reset event and that the
|
||||
//! EEPROM peripheral is ready for use.
|
||||
//
|
||||
#define EEPROM_INIT_OK 0
|
||||
|
||||
//
|
||||
//! This value may be returned from a call to EEPROMInit(). It indicates that
|
||||
//! a previous data or protection write operation was interrupted by a reset
|
||||
//! event and that the EEPROM peripheral was unable to clean up after the
|
||||
//! problem. This situation may be resolved with another reset or may be fatal
|
||||
//! depending upon the cause of the problem. For example, if the voltage to
|
||||
//! the part is unstable, retrying once the voltage has stabilized may clear
|
||||
//! the error.
|
||||
//
|
||||
#define EEPROM_INIT_ERROR 2
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Error indicators returned by various EEPROM API calls. These will be ORed
|
||||
// together into the final return code.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
//
|
||||
//! This return code bit indicates that an attempt was made to read from
|
||||
//! the EEPROM while a write operation was in progress.
|
||||
//
|
||||
#define EEPROM_RC_WRBUSY 0x00000020
|
||||
|
||||
//
|
||||
//! This return code bit indicates that an attempt was made to write a
|
||||
//! value but the destination permissions disallow write operations. This
|
||||
//! may be due to the destination block being locked, access protection set
|
||||
//! to prohibit writes or an attempt to write a password when one is already
|
||||
//! written.
|
||||
//
|
||||
#define EEPROM_RC_NOPERM 0x00000010
|
||||
|
||||
//
|
||||
//! This return code bit indicates that the EEPROM programming state machine
|
||||
//! is currently copying to or from the internal copy buffer to make room for
|
||||
//! a newly written value. It is provided as a status indicator and does not
|
||||
//! indicate an error.
|
||||
//
|
||||
#define EEPROM_RC_WKCOPY 0x00000008
|
||||
|
||||
//
|
||||
//! This return code bit indicates that the EEPROM programming state machine
|
||||
//! is currently erasing the internal copy buffer. It is provided as a
|
||||
//! status indicator and does not indicate an error.
|
||||
//
|
||||
#define EEPROM_RC_WKERASE 0x00000004
|
||||
|
||||
//
|
||||
//! This return code bit indicates that the EEPROM programming state machine
|
||||
//! is currently working. No new write operations should be attempted until
|
||||
//! this bit is clear.
|
||||
//
|
||||
#define EEPROM_RC_WORKING 0x00000001
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to EEPROMBlockProtectSet() in the ui32Protect
|
||||
// parameter, and returned by EEPROMBlockProtectGet().
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
//
|
||||
//! This bit may be ORed with the protection option passed to
|
||||
//! EEPROMBlockProtectSet() or returned from EEPROMBlockProtectGet(). It
|
||||
//! restricts EEPROM access to threads running in supervisor mode and prevents
|
||||
//! access to an EEPROM block when the CPU is in user mode.
|
||||
//
|
||||
#define EEPROM_PROT_SUPERVISOR_ONLY 0x00000008
|
||||
|
||||
//
|
||||
//! This value may be passed to EEPROMBlockProtectSet() or returned from
|
||||
//! EEPROMBlockProtectGet(). It indicates that the block should offer
|
||||
//! read/write access when no password is set or when a password is set and
|
||||
//! the block is unlocked, and read-only access when a password is set but
|
||||
//! the block is locked.
|
||||
//
|
||||
#define EEPROM_PROT_RW_LRO_URW 0x00000000
|
||||
|
||||
//
|
||||
//! This value may be passed to EEPROMBlockProtectSet() or returned from
|
||||
//! EEPROMBlockProtectGet(). It indicates that the block should offer neither
|
||||
//! read nor write access unless it is protected by a password and unlocked.
|
||||
//
|
||||
#define EEPROM_PROT_NA_LNA_URW 0x00000001
|
||||
|
||||
//
|
||||
//! This value may be passed to EEPROMBlockProtectSet() or returned from
|
||||
//! EEPROMBlockProtectGet(). It indicates that the block should offer
|
||||
//! read-only access when no password is set or when a password is set and the
|
||||
//! block is unlocked. When a password is set and the block is locked, neither
|
||||
//! read nor write access is permitted.
|
||||
//
|
||||
#define EEPROM_PROT_RO_LNA_URO 0x00000002
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! This value may be passed to EEPROMIntEnable() and EEPROMIntDisable() and is
|
||||
//! returned by EEPROMIntStatus() if an EEPROM interrupt is currently being
|
||||
//! signaled.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EEPROM_INT_PROGRAM 0x00000004
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Returns the EEPROM block number containing a given offset address.
|
||||
//!
|
||||
//! \param ui32Addr is the linear, byte address of the EEPROM location whose
|
||||
//! block number is to be returned. This is a zero-based offset from the start
|
||||
//! of the EEPROM storage.
|
||||
//!
|
||||
//! This macro may be used to translate an EEPROM address offset into a
|
||||
//! block number suitable for use in any of the driver's block protection
|
||||
//! functions. The address provided is expressed as a byte offset from the
|
||||
//! base of the EEPROM.
|
||||
//!
|
||||
//! \return Returns the zero-based block number which contains the passed
|
||||
//! address.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EEPROMBlockFromAddr(ui32Addr) ((ui32Addr) >> 6)
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Returns the offset address of the first word in an EEPROM block.
|
||||
//!
|
||||
//! \param ui32Block is the index of the EEPROM block whose first word address
|
||||
//! is to be returned.
|
||||
//!
|
||||
//! This macro may be used to determine the address of the first word in a
|
||||
//! given EEPROM block. The address returned is expressed as a byte offset
|
||||
//! from the base of EEPROM storage.
|
||||
//!
|
||||
//! \return Returns the address of the first word in the given EEPROM block.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EEPROMAddrFromBlock(ui32Block) ((ui32Block) << 6)
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Close the Doxygen group.
|
||||
//! @}
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Prototypes for the APIs.
|
||||
//
|
||||
//*****************************************************************************
|
||||
extern uint32_t EEPROMInit(void);
|
||||
extern uint32_t EEPROMSizeGet(void);
|
||||
extern uint32_t EEPROMBlockCountGet(void);
|
||||
extern void EEPROMRead(uint32_t *pui32Data, uint32_t ui32Address,
|
||||
uint32_t ui32Count);
|
||||
extern uint32_t EEPROMProgram(uint32_t *pui32Data,
|
||||
uint32_t ui32Address,
|
||||
uint32_t ui32Count);
|
||||
extern uint32_t EEPROMProgramNonBlocking(uint32_t ui32Data,
|
||||
uint32_t ui32Address);
|
||||
extern uint32_t EEPROMStatusGet(void);
|
||||
extern uint32_t EEPROMMassErase(void);
|
||||
extern uint32_t EEPROMBlockProtectGet(uint32_t ui32Block);
|
||||
extern uint32_t EEPROMBlockProtectSet(uint32_t ui32Block,
|
||||
uint32_t ui32Protect);
|
||||
extern uint32_t EEPROMBlockPasswordSet(uint32_t ui32Block,
|
||||
uint32_t *pui32Password,
|
||||
uint32_t ui32Count);
|
||||
extern uint32_t EEPROMBlockLock(uint32_t ui32Block);
|
||||
extern uint32_t EEPROMBlockUnlock(uint32_t ui32Block,
|
||||
uint32_t *pui32Password,
|
||||
uint32_t ui32Count);
|
||||
extern void EEPROMBlockHide(uint32_t ui32Block);
|
||||
extern void EEPROMIntEnable(uint32_t ui32IntFlags);
|
||||
extern void EEPROMIntDisable(uint32_t ui32IntFlags);
|
||||
extern uint32_t EEPROMIntStatus(bool bMasked);
|
||||
extern void EEPROMIntClear(uint32_t ui32IntFlags);
|
||||
|
||||
#ifndef DEPRECATED
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following definitions appeared in previous revisions of this file
|
||||
// but have been deprecated and should not be used by applications.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
//
|
||||
// This value used to be one of those which could be returned from a call to
|
||||
// EEPROMInit(). It transpires that it is was incorrect and has been removed
|
||||
// after EEPROMInit() was reworked for TivaWare 2.1.
|
||||
//
|
||||
#define EEPROM_INIT_RETRY 1
|
||||
|
||||
//
|
||||
// This return code is not available from any Tiva part and has been removed.
|
||||
//
|
||||
#define EEPROM_RC_INVPL 0x00000100
|
||||
|
||||
#endif
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Mark the end of the C bindings section for C++ compilers.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // __DRIVERLIB_EEPROM_H__
|
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,762 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// epi.h - Prototypes and macros for the EPI module.
|
||||
//
|
||||
// Copyright (c) 2008-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __DRIVERLIB_EPI_H__
|
||||
#define __DRIVERLIB_EPI_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 EPIModeSet()
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_MODE_GENERAL 0x00000010
|
||||
#define EPI_MODE_SDRAM 0x00000011
|
||||
#define EPI_MODE_HB8 0x00000012
|
||||
#define EPI_MODE_HB16 0x00000013
|
||||
#define EPI_MODE_DISABLE 0x00000000
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to EPIConfigSDRAMSet()
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_SDRAM_CORE_FREQ_0_15 \
|
||||
0x00000000
|
||||
#define EPI_SDRAM_CORE_FREQ_15_30 \
|
||||
0x40000000
|
||||
#define EPI_SDRAM_CORE_FREQ_30_50 \
|
||||
0x80000000
|
||||
#define EPI_SDRAM_CORE_FREQ_50_100 \
|
||||
0xC0000000
|
||||
#define EPI_SDRAM_LOW_POWER 0x00000200
|
||||
#define EPI_SDRAM_FULL_POWER 0x00000000
|
||||
#define EPI_SDRAM_SIZE_64MBIT 0x00000000
|
||||
#define EPI_SDRAM_SIZE_128MBIT 0x00000001
|
||||
#define EPI_SDRAM_SIZE_256MBIT 0x00000002
|
||||
#define EPI_SDRAM_SIZE_512MBIT 0x00000003
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to EPIConfigGPModeSet()
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_GPMODE_CLKPIN 0x80000000
|
||||
#define EPI_GPMODE_CLKGATE 0x40000000
|
||||
#define EPI_GPMODE_FRAME50 0x04000000
|
||||
#define EPI_GPMODE_WRITE2CYCLE 0x00080000
|
||||
#define EPI_GPMODE_ASIZE_NONE 0x00000000
|
||||
#define EPI_GPMODE_ASIZE_4 0x00000010
|
||||
#define EPI_GPMODE_ASIZE_12 0x00000020
|
||||
#define EPI_GPMODE_ASIZE_20 0x00000030
|
||||
#define EPI_GPMODE_DSIZE_8 0x00000000
|
||||
#define EPI_GPMODE_DSIZE_16 0x00000001
|
||||
#define EPI_GPMODE_DSIZE_24 0x00000002
|
||||
#define EPI_GPMODE_DSIZE_32 0x00000003
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to EPIConfigHB8ModeSet()
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_HB8_USE_TXEMPTY 0x00800000
|
||||
#define EPI_HB8_USE_RXFULL 0x00400000
|
||||
#define EPI_HB8_WRHIGH 0x00200000
|
||||
#define EPI_HB8_RDHIGH 0x00100000
|
||||
#define EPI_HB8_ALE_HIGH 0x00080000
|
||||
#define EPI_HB8_ALE_LOW 0x00000000
|
||||
#define EPI_HB8_WRWAIT_0 0x00000000
|
||||
#define EPI_HB8_WRWAIT_1 0x00000040
|
||||
#define EPI_HB8_WRWAIT_2 0x00000080
|
||||
#define EPI_HB8_WRWAIT_3 0x000000C0
|
||||
#define EPI_HB8_RDWAIT_0 0x00000000
|
||||
#define EPI_HB8_RDWAIT_1 0x00000010
|
||||
#define EPI_HB8_RDWAIT_2 0x00000020
|
||||
#define EPI_HB8_RDWAIT_3 0x00000030
|
||||
#define EPI_HB8_MODE_ADMUX 0x00000000
|
||||
#define EPI_HB8_MODE_ADDEMUX 0x00000001
|
||||
#define EPI_HB8_MODE_SRAM 0x00000002
|
||||
#define EPI_HB8_MODE_FIFO 0x00000003
|
||||
#define EPI_HB8_WORD_ACCESS 0x00000100
|
||||
#define EPI_HB8_CSCFG_ALE 0x00000000
|
||||
#define EPI_HB8_CSCFG_CS 0x00000200
|
||||
#define EPI_HB8_CSCFG_DUAL_CS 0x00000400
|
||||
#define EPI_HB8_CSCFG_ALE_DUAL_CS \
|
||||
0x00000600
|
||||
#define EPI_HB8_CSCFG_ALE_SINGLE_CS \
|
||||
0x00001000
|
||||
#define EPI_HB8_CSCFG_QUAD_CS 0x00001200
|
||||
#define EPI_HB8_CSCFG_ALE_QUAD_CS \
|
||||
0x00001400
|
||||
#define EPI_HB8_CSBAUD 0x00000800
|
||||
#define EPI_HB8_CLOCK_GATE 0x80000000
|
||||
#define EPI_HB8_CLOCK_GATE_IDLE \
|
||||
0x40000000
|
||||
#define EPI_HB8_CLOCK_INVERT 0x20000000
|
||||
#define EPI_HB8_IN_READY_EN 0x10000000
|
||||
#define EPI_HB8_IN_READY_EN_INVERT \
|
||||
0x18000000
|
||||
#define EPI_HB8_CSCFG_MASK 0x00001600
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to EPIConfigHB16ModeSet()
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_HB16_USE_TXEMPTY 0x00800000
|
||||
#define EPI_HB16_USE_RXFULL 0x00400000
|
||||
#define EPI_HB16_WRHIGH 0x00200000
|
||||
#define EPI_HB16_RDHIGH 0x00100000
|
||||
#define EPI_HB16_WRWAIT_0 0x00000000
|
||||
#define EPI_HB16_WRWAIT_1 0x00000040
|
||||
#define EPI_HB16_WRWAIT_2 0x00000080
|
||||
#define EPI_HB16_WRWAIT_3 0x000000C0
|
||||
#define EPI_HB16_RDWAIT_0 0x00000000
|
||||
#define EPI_HB16_RDWAIT_1 0x00000010
|
||||
#define EPI_HB16_RDWAIT_2 0x00000020
|
||||
#define EPI_HB16_RDWAIT_3 0x00000030
|
||||
#define EPI_HB16_MODE_ADMUX 0x00000000
|
||||
#define EPI_HB16_MODE_ADDEMUX 0x00000001
|
||||
#define EPI_HB16_MODE_SRAM 0x00000002
|
||||
#define EPI_HB16_MODE_FIFO 0x00000003
|
||||
#define EPI_HB16_BSEL 0x00000004
|
||||
#define EPI_HB16_WORD_ACCESS 0x00000100
|
||||
#define EPI_HB16_CSCFG_ALE 0x00000000
|
||||
#define EPI_HB16_CSCFG_CS 0x00000200
|
||||
#define EPI_HB16_CSCFG_DUAL_CS 0x00000400
|
||||
#define EPI_HB16_CSCFG_ALE_DUAL_CS \
|
||||
0x00000600
|
||||
#define EPI_HB16_CSCFG_ALE_SINGLE_CS \
|
||||
0x00001000
|
||||
#define EPI_HB16_CSCFG_QUAD_CS 0x00001200
|
||||
#define EPI_HB16_CSCFG_ALE_QUAD_CS \
|
||||
0x00001400
|
||||
#define EPI_HB16_CLOCK_GATE 0x80000000
|
||||
#define EPI_HB16_CLOCK_GATE_IDLE \
|
||||
0x40000000
|
||||
#define EPI_HB16_CLOCK_INVERT 0x20000000
|
||||
#define EPI_HB16_IN_READY_EN 0x10000000
|
||||
#define EPI_HB16_IN_READY_EN_INVERTED \
|
||||
0x18000000
|
||||
#define EPI_HB16_ALE_HIGH 0x00080000
|
||||
#define EPI_HB16_ALE_LOW 0x00000000
|
||||
#define EPI_HB16_BURST_TRAFFIC 0x00010000
|
||||
#define EPI_HB16_CSBAUD 0x00000800
|
||||
#define EPI_HB16_CSCFG_MASK 0x00001600
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to EPIConfigHB8TimingSet().
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_HB8_IN_READY_DELAY_1 \
|
||||
0x01000000
|
||||
#define EPI_HB8_IN_READY_DELAY_2 \
|
||||
0x02000000
|
||||
#define EPI_HB8_IN_READY_DELAY_3 \
|
||||
0x03000000
|
||||
#define EPI_HB8_CAP_WIDTH_1 0x00001000
|
||||
#define EPI_HB8_CAP_WIDTH_2 0x00002000
|
||||
#define EPI_HB8_WRWAIT_MINUS_DISABLE \
|
||||
0x00000000
|
||||
#define EPI_HB8_WRWAIT_MINUS_ENABLE \
|
||||
0x00000010
|
||||
#define EPI_HB8_RDWAIT_MINUS_DISABLE \
|
||||
0x00000000
|
||||
#define EPI_HB8_RDWAIT_MINUS_ENABLE \
|
||||
0x00000001
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to EPIConfigHB16TimingSet().
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_HB16_IN_READY_DELAY_1 \
|
||||
0x01000000
|
||||
#define EPI_HB16_IN_READY_DELAY_2 \
|
||||
0x02000000
|
||||
#define EPI_HB16_IN_READY_DELAY_3 \
|
||||
0x03000000
|
||||
#define EPI_HB16_PSRAM_NO_LIMIT 0x00000000
|
||||
#define EPI_HB16_PSRAM_128 0x00010000
|
||||
#define EPI_HB16_PSRAM_256 0x00020000
|
||||
#define EPI_HB16_PSRAM_512 0x00030000
|
||||
#define EPI_HB16_PSRAM_1024 0x00040000
|
||||
#define EPI_HB16_PSRAM_2048 0x00050000
|
||||
#define EPI_HB16_PSRAM_4096 0x00060000
|
||||
#define EPI_HB16_PSRAM_8192 0x00070000
|
||||
#define EPI_HB16_CAP_WIDTH_1 0x00001000
|
||||
#define EPI_HB16_CAP_WIDTH_2 0x00002000
|
||||
#define EPI_HB16_WRWAIT_MINUS_DISABLE \
|
||||
0x00000000
|
||||
#define EPI_HB16_WRWAIT_MINUS_ENABLE \
|
||||
0x00000008
|
||||
#define EPI_HB16_RDWAIT_MINUS_DISABLE \
|
||||
0x00000000
|
||||
#define EPI_HB16_RDWAIT_MINUS_ENABLE \
|
||||
0x00000001
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to EPIAddressMapSet().
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_ADDR_PER_SIZE_256B 0x00000000
|
||||
#define EPI_ADDR_PER_SIZE_64KB 0x00000040
|
||||
#define EPI_ADDR_PER_SIZE_16MB 0x00000080
|
||||
#define EPI_ADDR_PER_SIZE_256MB 0x000000C0
|
||||
#define EPI_ADDR_PER_BASE_NONE 0x00000000
|
||||
#define EPI_ADDR_PER_BASE_A 0x00000010
|
||||
#define EPI_ADDR_PER_BASE_C 0x00000020
|
||||
#define EPI_ADDR_RAM_SIZE_256B 0x00000000
|
||||
#define EPI_ADDR_RAM_SIZE_64KB 0x00000004
|
||||
#define EPI_ADDR_RAM_SIZE_16MB 0x00000008
|
||||
#define EPI_ADDR_RAM_SIZE_256MB 0x0000000C
|
||||
#define EPI_ADDR_RAM_BASE_NONE 0x00000000
|
||||
#define EPI_ADDR_RAM_BASE_6 0x00000001
|
||||
#define EPI_ADDR_RAM_BASE_8 0x00000002
|
||||
#define EPI_ADDR_QUAD_MODE 0x00000033
|
||||
#define EPI_ADDR_CODE_SIZE_256B 0x00000000
|
||||
#define EPI_ADDR_CODE_SIZE_64KB 0x00000400
|
||||
#define EPI_ADDR_CODE_SIZE_16MB 0x00000800
|
||||
#define EPI_ADDR_CODE_SIZE_256MB \
|
||||
0x00000C00
|
||||
#define EPI_ADDR_CODE_BASE_NONE 0x00000000
|
||||
#define EPI_ADDR_CODE_BASE_1 0x00000100
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to EPINonBlockingReadConfigure()
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_NBCONFIG_SIZE_8 1
|
||||
#define EPI_NBCONFIG_SIZE_16 2
|
||||
#define EPI_NBCONFIG_SIZE_32 3
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to EPIFIFOConfig()
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_FIFO_CONFIG_WTFULLERR \
|
||||
0x00020000
|
||||
#define EPI_FIFO_CONFIG_RSTALLERR \
|
||||
0x00010000
|
||||
#define EPI_FIFO_CONFIG_TX_EMPTY \
|
||||
0x00000000
|
||||
#define EPI_FIFO_CONFIG_TX_1_4 0x00000020
|
||||
#define EPI_FIFO_CONFIG_TX_1_2 0x00000030
|
||||
#define EPI_FIFO_CONFIG_TX_3_4 0x00000040
|
||||
#define EPI_FIFO_CONFIG_RX_1_8 0x00000001
|
||||
#define EPI_FIFO_CONFIG_RX_1_4 0x00000002
|
||||
#define EPI_FIFO_CONFIG_RX_1_2 0x00000003
|
||||
#define EPI_FIFO_CONFIG_RX_3_4 0x00000004
|
||||
#define EPI_FIFO_CONFIG_RX_7_8 0x00000005
|
||||
#define EPI_FIFO_CONFIG_RX_FULL 0x00000006
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to EPIIntEnable(), EPIIntDisable(), or returned
|
||||
// as flags from EPIIntStatus()
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_INT_DMA_TX_DONE 0x00000010
|
||||
#define EPI_INT_DMA_RX_DONE 0x00000008
|
||||
#define EPI_INT_TXREQ 0x00000004
|
||||
#define EPI_INT_RXREQ 0x00000002
|
||||
#define EPI_INT_ERR 0x00000001
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to EPIIntErrorClear(), or returned as flags from
|
||||
// EPIIntErrorStatus()
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_INT_ERR_DMAWRIC 0x00000010
|
||||
#define EPI_INT_ERR_DMARDIC 0x00000008
|
||||
#define EPI_INT_ERR_WTFULL 0x00000004
|
||||
#define EPI_INT_ERR_RSTALL 0x00000002
|
||||
#define EPI_INT_ERR_TIMEOUT 0x00000001
|
||||
|
||||
#ifdef rvmdk
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Keil case.
|
||||
//
|
||||
//*****************************************************************************
|
||||
inline void
|
||||
EPIWorkaroundWordWrite(uint32_t *pui32Addr, uint32_t ui32Value)
|
||||
{
|
||||
uint32_t ui32Scratch;
|
||||
|
||||
__asm
|
||||
{
|
||||
//
|
||||
// Add a NOP to ensure we don’t have a flash read immediately before
|
||||
// the EPI read.
|
||||
//
|
||||
NOP
|
||||
|
||||
//
|
||||
// Perform the write we're actually interested in.
|
||||
//
|
||||
STR ui32Value, [pui32Addr]
|
||||
|
||||
//
|
||||
// Read from SRAM to ensure that we don't have an EPI write followed by
|
||||
// a flash read.
|
||||
//
|
||||
LDR ui32Scratch, [__current_sp()]
|
||||
}
|
||||
}
|
||||
|
||||
inline uint32_t
|
||||
EPIWorkaroundWordRead(uint32_t *pui32Addr)
|
||||
{
|
||||
uint32_t ui32Value, ui32Scratch;
|
||||
|
||||
__asm
|
||||
{
|
||||
//
|
||||
// Add a NOP to ensure we don’t have a flash read immediately before
|
||||
// the EPI read.
|
||||
//
|
||||
NOP
|
||||
|
||||
//
|
||||
// Perform the read we're actually interested in.
|
||||
//
|
||||
LDR ui32Value, [pui32Addr]
|
||||
|
||||
//
|
||||
// Read from SRAM to ensure that we don't have an EPI read followed by
|
||||
// a flash read.
|
||||
//
|
||||
LDR ui32Scratch, [__current_sp()]
|
||||
}
|
||||
|
||||
return(ui32Value);
|
||||
}
|
||||
|
||||
inline void
|
||||
EPIWorkaroundHWordWrite(uint16_t *pui16Addr, uint16_t ui16Value)
|
||||
{
|
||||
uint32_t ui32Scratch;
|
||||
|
||||
__asm
|
||||
{
|
||||
//
|
||||
// Add a NOP to ensure we don’t have a flash read immediately before
|
||||
// the EPI read.
|
||||
//
|
||||
NOP
|
||||
|
||||
//
|
||||
// Perform the write we're actually interested in.
|
||||
//
|
||||
STRH ui16Value, [pui16Addr]
|
||||
|
||||
//
|
||||
// Read from SRAM to ensure that we don't have an EPI write followed by
|
||||
// a flash read.
|
||||
//
|
||||
LDR ui32Scratch, [__current_sp()]
|
||||
}
|
||||
}
|
||||
|
||||
inline uint16_t
|
||||
EPIWorkaroundHWordRead(uint16_t *pui16Addr)
|
||||
{
|
||||
uint32_t ui32Scratch;
|
||||
uint16_t ui16Value;
|
||||
|
||||
__asm
|
||||
{
|
||||
//
|
||||
// Add a NOP to ensure we don’t have a flash read immediately before
|
||||
// the EPI read.
|
||||
//
|
||||
NOP
|
||||
|
||||
//
|
||||
// Perform the read we're actually interested in.
|
||||
//
|
||||
LDRH ui16Value, [pui16Addr]
|
||||
|
||||
//
|
||||
// Read from SRAM to ensure that we don't have an EPI read followed by
|
||||
// a flash read.
|
||||
//
|
||||
LDR ui32Scratch, [__current_sp()]
|
||||
}
|
||||
|
||||
return(ui16Value);
|
||||
}
|
||||
|
||||
inline void
|
||||
EPIWorkaroundByteWrite(uint8_t *pui8Addr, uint8_t ui8Value)
|
||||
{
|
||||
uint32_t ui32Scratch;
|
||||
|
||||
__asm
|
||||
{
|
||||
//
|
||||
// Add a NOP to ensure we don’t have a flash read immediately before
|
||||
// the EPI read.
|
||||
//
|
||||
NOP
|
||||
|
||||
//
|
||||
// Perform the write we're actually interested in.
|
||||
//
|
||||
STRB ui8Value, [pui8Addr]
|
||||
|
||||
//
|
||||
// Read from SRAM to ensure that we don't have an EPI write followed by
|
||||
// a flash read.
|
||||
//
|
||||
LDR ui32Scratch, [__current_sp()]
|
||||
}
|
||||
}
|
||||
|
||||
inline uint8_t
|
||||
EPIWorkaroundByteRead(uint8_t *pui8Addr)
|
||||
{
|
||||
uint32_t ui32Scratch;
|
||||
uint8_t ui8Value;
|
||||
|
||||
__asm
|
||||
{
|
||||
//
|
||||
// Add a NOP to ensure we don’t have a flash read immediately before
|
||||
// the EPI read.
|
||||
//
|
||||
NOP
|
||||
|
||||
//
|
||||
// Perform the read we're actually interested in.
|
||||
//
|
||||
LDRB ui8Value, [pui8Addr]
|
||||
|
||||
//
|
||||
// Read from SRAM to ensure that we don't have an EPI read followed by
|
||||
// a flash read.
|
||||
//
|
||||
LDR ui32Scratch, [__current_sp()]
|
||||
}
|
||||
|
||||
return(ui8Value);
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef ccs
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Code Composer Studio versions of these functions can be found in separate
|
||||
// source file epi_workaround_ccs.s.
|
||||
//
|
||||
//*****************************************************************************
|
||||
extern void EPIWorkaroundWordWrite(uint32_t *pui32Addr, uint32_t ui32Value);
|
||||
extern uint32_t EPIWorkaroundWordRead(uint32_t *pui32Addr);
|
||||
extern void EPIWorkaroundHWordWrite(uint16_t *pui16Addr, uint16_t ui16Value);
|
||||
extern uint16_t EPIWorkaroundHWordRead(uint16_t *pui16Addr);
|
||||
extern void EPIWorkaroundByteWrite(uint8_t *pui8Addr, uint8_t ui8Value);
|
||||
extern uint8_t EPIWorkaroundByteRead(uint8_t *pui8Addr);
|
||||
|
||||
#endif
|
||||
|
||||
#if (defined gcc) || (defined ewarm) || (defined sourcerygxx) || \
|
||||
(defined codered)
|
||||
//*****************************************************************************
|
||||
//
|
||||
// GCC-based toolchain and IAR case.
|
||||
//
|
||||
//*****************************************************************************
|
||||
inline void
|
||||
EPIWorkaroundWordWrite(uint32_t *pui32Addr, uint32_t ui32Value)
|
||||
{
|
||||
volatile register uint32_t ui32Scratch;
|
||||
|
||||
__asm volatile (
|
||||
//
|
||||
// Add a NOP to ensure we don’t have a flash read immediately before
|
||||
// the EPI read.
|
||||
//
|
||||
" NOP\n"
|
||||
" STR %[value],[%[addr]]\n"
|
||||
" LDR %[scratch],[sp]\n"
|
||||
: [scratch] "=r" (ui32Scratch)
|
||||
: [addr] "r" (pui32Addr), [value] "r" (ui32Value)
|
||||
);
|
||||
|
||||
//
|
||||
// Keep the compiler from generating a warning.
|
||||
//
|
||||
ui32Scratch = ui32Scratch;
|
||||
}
|
||||
|
||||
inline uint32_t
|
||||
EPIWorkaroundWordRead(uint32_t *pui32Addr)
|
||||
{
|
||||
volatile register uint32_t ui32Data, ui32Scratch;
|
||||
|
||||
//
|
||||
// ui32Scratch is not used other than to add a padding read following the
|
||||
// "real" read.
|
||||
//
|
||||
|
||||
__asm volatile(
|
||||
//
|
||||
// Add a NOP to ensure we don’t have a flash read immediately before
|
||||
// the EPI read.
|
||||
//
|
||||
" NOP\n"
|
||||
" LDR %[ret],[%[addr]]\n"
|
||||
" LDR %[scratch],[sp]\n"
|
||||
: [ret] "=r" (ui32Data),
|
||||
[scratch] "=r" (ui32Scratch)
|
||||
: [addr] "r" (pui32Addr)
|
||||
);
|
||||
|
||||
|
||||
//
|
||||
// Keep the compiler from generating a warning.
|
||||
//
|
||||
ui32Scratch = ui32Scratch;
|
||||
|
||||
return(ui32Data);
|
||||
}
|
||||
|
||||
inline void
|
||||
EPIWorkaroundHWordWrite(uint16_t *pui16Addr, uint16_t ui16Value)
|
||||
{
|
||||
volatile register uint32_t ui32Scratch;
|
||||
|
||||
__asm volatile (
|
||||
//
|
||||
// Add a NOP to ensure we don’t have a flash read immediately before
|
||||
// the EPI read.
|
||||
//
|
||||
" NOP\n"
|
||||
" STRH %[value],[%[addr]]\n"
|
||||
" LDR %[scratch],[sp]\n"
|
||||
: [scratch] "=r" (ui32Scratch)
|
||||
: [addr] "r" (pui16Addr), [value] "r" (ui16Value)
|
||||
);
|
||||
|
||||
|
||||
//
|
||||
// Keep the compiler from generating a warning.
|
||||
//
|
||||
ui32Scratch = ui32Scratch;
|
||||
}
|
||||
|
||||
inline uint16_t
|
||||
EPIWorkaroundHWordRead(uint16_t *pui16Addr)
|
||||
{
|
||||
register uint16_t ui16Data;
|
||||
register uint32_t ui32Scratch;
|
||||
|
||||
//
|
||||
// ui32Scratch is not used other than to add a padding read following the
|
||||
// "real" read.
|
||||
//
|
||||
|
||||
__asm volatile(
|
||||
//
|
||||
// Add a NOP to ensure we don’t have a flash read immediately before
|
||||
// the EPI read.
|
||||
//
|
||||
" NOP\n"
|
||||
" LDRH %[ret],[%[addr]]\n"
|
||||
" LDR %[scratch],[sp]\n"
|
||||
: [ret] "=r" (ui16Data),
|
||||
[scratch] "=r" (ui32Scratch)
|
||||
: [addr] "r" (pui16Addr)
|
||||
);
|
||||
|
||||
//
|
||||
// Keep the compiler from generating a warning.
|
||||
//
|
||||
ui32Scratch = ui32Scratch;
|
||||
|
||||
return(ui16Data);
|
||||
}
|
||||
|
||||
inline void
|
||||
EPIWorkaroundByteWrite(uint8_t *pui8Addr, uint8_t ui8Value)
|
||||
{
|
||||
volatile register uint32_t ui32Scratch;
|
||||
|
||||
__asm volatile (
|
||||
//
|
||||
// Add a NOP to ensure we don’t have a flash read immediately before
|
||||
// the EPI read.
|
||||
//
|
||||
" NOP\n"
|
||||
" STRB %[value],[%[addr]]\n"
|
||||
" LDR %[scratch],[sp]\n"
|
||||
: [scratch] "=r" (ui32Scratch)
|
||||
: [addr] "r" (pui8Addr), [value] "r" (ui8Value)
|
||||
);
|
||||
|
||||
//
|
||||
// Keep the compiler from generating a warning.
|
||||
//
|
||||
ui32Scratch = ui32Scratch;
|
||||
}
|
||||
|
||||
inline uint8_t
|
||||
EPIWorkaroundByteRead(uint8_t *pui8Addr)
|
||||
{
|
||||
register uint8_t ui8Data;
|
||||
register uint32_t ui32Scratch;
|
||||
|
||||
//
|
||||
// ui32Scratch is not used other than to add a padding read following the
|
||||
// "real" read.
|
||||
//
|
||||
|
||||
__asm volatile(
|
||||
//
|
||||
// Add a NOP to ensure we don’t have a flash read immediately before
|
||||
// the EPI read.
|
||||
//
|
||||
" NOP\n"
|
||||
" LDRB %[ret],[%[addr]]\n"
|
||||
" LDR %[scratch],[sp]\n"
|
||||
: [ret] "=r" (ui8Data),
|
||||
[scratch] "=r" (ui32Scratch)
|
||||
: [addr] "r" (pui8Addr)
|
||||
);
|
||||
|
||||
//
|
||||
// Keep the compiler from generating a warning.
|
||||
//
|
||||
ui32Scratch = ui32Scratch;
|
||||
|
||||
return(ui8Data);
|
||||
}
|
||||
#endif
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// API Function prototypes
|
||||
//
|
||||
//*****************************************************************************
|
||||
extern void EPIModeSet(uint32_t ui32Base, uint32_t ui32Mode);
|
||||
extern void EPIDividerSet(uint32_t ui32Base, uint32_t ui32Divider);
|
||||
extern void EPIDividerCSSet(uint32_t ui32Base, uint32_t ui32CS,
|
||||
uint32_t ui32Divider);
|
||||
extern void EPIDMATxCount(uint32_t ui32Base, uint32_t ui32Count);
|
||||
extern void EPIConfigGPModeSet(uint32_t ui32Base, uint32_t ui32Config,
|
||||
uint32_t ui32FrameCount, uint32_t ui32MaxWait);
|
||||
extern void EPIConfigHB8Set(uint32_t ui32Base, uint32_t ui32Config,
|
||||
uint32_t ui32MaxWait);
|
||||
extern void EPIConfigHB16Set(uint32_t ui32Base, uint32_t ui32Config,
|
||||
uint32_t ui32MaxWait);
|
||||
extern void EPIConfigHB8CSSet(uint32_t ui32Base, uint32_t ui32CS,
|
||||
uint32_t ui32Config);
|
||||
extern void EPIConfigHB16CSSet(uint32_t ui32Base, uint32_t ui32CS,
|
||||
uint32_t ui32Config);
|
||||
extern void EPIConfigHB8TimingSet(uint32_t ui32Base, uint32_t ui32CS,
|
||||
uint32_t ui32Config);
|
||||
extern void EPIConfigHB16TimingSet(uint32_t ui32Base, uint32_t ui32CS,
|
||||
uint32_t ui32Config);
|
||||
extern void EPIPSRAMConfigRegSet(uint32_t ui32Base, uint32_t ui32CS,
|
||||
uint32_t ui32CR);
|
||||
extern void EPIPSRAMConfigRegRead(uint32_t ui32Base, uint32_t ui32CS);
|
||||
extern bool EPIPSRAMConfigRegGetNonBlocking(uint32_t ui32Base,
|
||||
uint32_t ui32CS,
|
||||
uint32_t *pui32CR);
|
||||
extern uint32_t EPIPSRAMConfigRegGet(uint32_t ui32Base, uint32_t ui32CS);
|
||||
extern void EPIConfigSDRAMSet(uint32_t ui32Base, uint32_t ui32Config,
|
||||
uint32_t ui32Refresh);
|
||||
extern void EPIAddressMapSet(uint32_t ui32Base, uint32_t ui32Map);
|
||||
extern void EPINonBlockingReadConfigure(uint32_t ui32Base,
|
||||
uint32_t ui32Channel,
|
||||
uint32_t ui32DataSize,
|
||||
uint32_t ui32Address);
|
||||
extern void EPINonBlockingReadStart(uint32_t ui32Base,
|
||||
uint32_t ui32Channel,
|
||||
uint32_t ui32Count);
|
||||
extern void EPINonBlockingReadStop(uint32_t ui32Base,
|
||||
uint32_t ui32Channel);
|
||||
extern uint32_t EPINonBlockingReadCount(uint32_t ui32Base,
|
||||
uint32_t ui32Channel);
|
||||
extern uint32_t EPINonBlockingReadAvail(uint32_t ui32Base);
|
||||
extern uint32_t EPINonBlockingReadGet32(uint32_t ui32Base,
|
||||
uint32_t ui32Count,
|
||||
uint32_t *pui32Buf);
|
||||
extern uint32_t EPINonBlockingReadGet16(uint32_t ui32Base,
|
||||
uint32_t ui32Count,
|
||||
uint16_t *pui16Buf);
|
||||
extern uint32_t EPINonBlockingReadGet8(uint32_t ui32Base,
|
||||
uint32_t ui32Count,
|
||||
uint8_t *pui8Buf);
|
||||
extern void EPIFIFOConfig(uint32_t ui32Base, uint32_t ui32Config);
|
||||
extern uint32_t EPIWriteFIFOCountGet(uint32_t ui32Base);
|
||||
extern void EPIIntEnable(uint32_t ui32Base, uint32_t ui32IntFlags);
|
||||
extern void EPIIntDisable(uint32_t ui32Base, uint32_t ui32IntFlags);
|
||||
extern uint32_t EPIIntStatus(uint32_t ui32Base, bool bMasked);
|
||||
extern uint32_t EPIIntErrorStatus(uint32_t ui32Base);
|
||||
extern void EPIIntErrorClear(uint32_t ui32Base, uint32_t ui32ErrFlags);
|
||||
extern void EPIIntRegister(uint32_t ui32Base, void (*pfnHandler)(void));
|
||||
extern void EPIIntUnregister(uint32_t ui32Base);
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Mark the end of the C bindings section for C++ compilers.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // __DRIVERLIB_EPI_H__
|
|
@ -0,0 +1,851 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// flash.c - Driver for programming the on-chip flash.
|
||||
//
|
||||
// Copyright (c) 2005-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! \addtogroup flash_api
|
||||
//! @{
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include "inc/hw_flash.h"
|
||||
#include "inc/hw_ints.h"
|
||||
#include "inc/hw_sysctl.h"
|
||||
#include "inc/hw_types.h"
|
||||
#include "driverlib/debug.h"
|
||||
#include "driverlib/flash.h"
|
||||
#include "driverlib/interrupt.h"
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// An array that maps the specified memory bank to the appropriate Flash
|
||||
// Memory Protection Program Enable (FMPPE) register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
static const uint32_t g_pui32FMPPERegs[] =
|
||||
{
|
||||
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 uint32_t g_pui32FMPRERegs[] =
|
||||
{
|
||||
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,
|
||||
};
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Erases a block of flash.
|
||||
//!
|
||||
//! \param ui32Address is the start address of the flash block to be erased.
|
||||
//!
|
||||
//! This function erases a block of the on-chip flash. After erasing, the
|
||||
//! block is filled with 0xFF bytes. Read-only and execute-only blocks cannot
|
||||
//! be erased.
|
||||
//!
|
||||
//! The flash block size is device-class dependent. All TM4C123x devices use
|
||||
//! 1-KB blocks but TM4C129x devices use 16-KB blocks. Please consult the
|
||||
//! device datasheet to determine the block size in use.
|
||||
//!
|
||||
//! This function does 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.
|
||||
//
|
||||
//*****************************************************************************
|
||||
int32_t
|
||||
FlashErase(uint32_t ui32Address)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT(!(ui32Address & (FLASH_ERASE_SIZE - 1)));
|
||||
|
||||
//
|
||||
// Clear the flash access and error interrupts.
|
||||
//
|
||||
HWREG(FLASH_FCMISC) = (FLASH_FCMISC_AMISC | FLASH_FCMISC_VOLTMISC |
|
||||
FLASH_FCMISC_ERMISC);
|
||||
|
||||
//
|
||||
// Erase the block.
|
||||
//
|
||||
HWREG(FLASH_FMA) = ui32Address;
|
||||
HWREG(FLASH_FMC) = FLASH_FMC_WRKEY | FLASH_FMC_ERASE;
|
||||
|
||||
//
|
||||
// Wait until the block has been erased.
|
||||
//
|
||||
while(HWREG(FLASH_FMC) & FLASH_FMC_ERASE)
|
||||
{
|
||||
}
|
||||
|
||||
//
|
||||
// Return an error if an access violation or erase error occurred.
|
||||
//
|
||||
if(HWREG(FLASH_FCRIS) & (FLASH_FCRIS_ARIS | FLASH_FCRIS_VOLTRIS |
|
||||
FLASH_FCRIS_ERRIS))
|
||||
{
|
||||
return(-1);
|
||||
}
|
||||
|
||||
//
|
||||
// Success.
|
||||
//
|
||||
return(0);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Programs flash.
|
||||
//!
|
||||
//! \param pui32Data is a pointer to the data to be programmed.
|
||||
//! \param ui32Address is the starting address in flash to be programmed. Must
|
||||
//! be a multiple of four.
|
||||
//! \param ui32Count is the number of bytes to be programmed. Must be a
|
||||
//! multiple of four.
|
||||
//!
|
||||
//! This function programs a sequence of words into the on-chip flash.
|
||||
//! Because 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 does not return until the data has been programmed.
|
||||
//!
|
||||
//! \return Returns 0 on success, or -1 if a programming error is encountered.
|
||||
//
|
||||
//*****************************************************************************
|
||||
int32_t
|
||||
FlashProgram(uint32_t *pui32Data, uint32_t ui32Address, uint32_t ui32Count)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT(!(ui32Address & 3));
|
||||
ASSERT(!(ui32Count & 3));
|
||||
|
||||
//
|
||||
// Clear the flash access and error interrupts.
|
||||
//
|
||||
HWREG(FLASH_FCMISC) = (FLASH_FCMISC_AMISC | FLASH_FCMISC_VOLTMISC |
|
||||
FLASH_FCMISC_INVDMISC | FLASH_FCMISC_PROGMISC);
|
||||
|
||||
//
|
||||
// Loop over the words to be programmed.
|
||||
//
|
||||
while(ui32Count)
|
||||
{
|
||||
//
|
||||
// Set the address of this block of words.
|
||||
//
|
||||
HWREG(FLASH_FMA) = ui32Address & ~(0x7f);
|
||||
|
||||
//
|
||||
// Loop over the words in this 32-word block.
|
||||
//
|
||||
while(((ui32Address & 0x7c) || (HWREG(FLASH_FWBVAL) == 0)) &&
|
||||
(ui32Count != 0))
|
||||
{
|
||||
//
|
||||
// Write this word into the write buffer.
|
||||
//
|
||||
HWREG(FLASH_FWBN + (ui32Address & 0x7c)) = *pui32Data++;
|
||||
ui32Address += 4;
|
||||
ui32Count -= 4;
|
||||
}
|
||||
|
||||
//
|
||||
// Program the contents of the write buffer into flash.
|
||||
//
|
||||
HWREG(FLASH_FMC2) = FLASH_FMC2_WRKEY | FLASH_FMC2_WRBUF;
|
||||
|
||||
//
|
||||
// Wait until the write buffer has been programmed.
|
||||
//
|
||||
while(HWREG(FLASH_FMC2) & FLASH_FMC2_WRBUF)
|
||||
{
|
||||
}
|
||||
}
|
||||
|
||||
//
|
||||
// Return an error if an access violation occurred.
|
||||
//
|
||||
if(HWREG(FLASH_FCRIS) & (FLASH_FCRIS_ARIS | FLASH_FCRIS_VOLTRIS |
|
||||
FLASH_FCRIS_INVDRIS | FLASH_FCRIS_PROGRIS))
|
||||
{
|
||||
return(-1);
|
||||
}
|
||||
|
||||
//
|
||||
// Success.
|
||||
//
|
||||
return(0);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Gets the protection setting for a block of flash.
|
||||
//!
|
||||
//! \param ui32Address is the start address of the flash block to be queried.
|
||||
//!
|
||||
//! This function gets the current protection for the specified block of flash.
|
||||
//! Refer to the device data sheet to determine the granularity for each
|
||||
//! protection option. A 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(uint32_t ui32Address)
|
||||
{
|
||||
uint32_t ui32FMPRE, ui32FMPPE;
|
||||
uint32_t ui32Bank;
|
||||
|
||||
//
|
||||
// Check the argument.
|
||||
//
|
||||
ASSERT(!(ui32Address & (FLASH_PROTECT_SIZE - 1)));
|
||||
|
||||
//
|
||||
// Calculate the Flash Bank from Base Address, and mask off the Bank
|
||||
// from ui32Address for subsequent reference.
|
||||
//
|
||||
ui32Bank = (((ui32Address / FLASH_PROTECT_SIZE) / 32) % 4);
|
||||
ui32Address &= ((FLASH_PROTECT_SIZE * 32) - 1);
|
||||
|
||||
//
|
||||
// Read the appropriate flash protection registers for the specified
|
||||
// flash bank.
|
||||
//
|
||||
ui32FMPRE = HWREG(g_pui32FMPRERegs[ui32Bank]);
|
||||
ui32FMPPE = HWREG(g_pui32FMPPERegs[ui32Bank]);
|
||||
|
||||
//
|
||||
// Check the appropriate protection bits for the block of memory that
|
||||
// is specified by the address.
|
||||
//
|
||||
switch((((ui32FMPRE >> (ui32Address / FLASH_PROTECT_SIZE)) & 0x1) << 1) |
|
||||
((ui32FMPPE >> (ui32Address / FLASH_PROTECT_SIZE)) & 0x1))
|
||||
{
|
||||
//
|
||||
// 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);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Sets the protection setting for a block of flash.
|
||||
//!
|
||||
//! \param ui32Address is the start address of the flash block to be protected.
|
||||
//! \param eProtect is the protection to be applied to the block. Can be one
|
||||
//! of \b FlashReadWrite, \b FlashReadOnly, or \b FlashExecuteOnly.
|
||||
//!
|
||||
//! This function sets the protection for the specified block of flash. Refer
|
||||
//! to the device data sheet to determine the granularity for each protection
|
||||
//! option. Blocks that are read/write can be made read-only or execute-only.
|
||||
//! Blocks that are read-only can be made execute-only. Blocks that are
|
||||
//! execute-only cannot have their protection modified. Attempts to make the
|
||||
//! block protection less stringent (that is, read-only to read/write)
|
||||
//! result in a failure (and are prevented by the hardware).
|
||||
//!
|
||||
//! Changes to the flash protection are maintained only until the next reset.
|
||||
//! This protocol allows the application to be executed in the desired flash
|
||||
//! protection environment to check for inappropriate flash access (via the
|
||||
//! flash interrupt). To make the flash protection permanent, use the
|
||||
//! FlashProtectSave() function.
|
||||
//!
|
||||
//! \return Returns 0 on success, or -1 if an invalid address or an invalid
|
||||
//! protection was specified.
|
||||
//
|
||||
//*****************************************************************************
|
||||
int32_t
|
||||
FlashProtectSet(uint32_t ui32Address, tFlashProtection eProtect)
|
||||
{
|
||||
uint32_t ui32ProtectRE, ui32ProtectPE;
|
||||
uint32_t ui32Bank;
|
||||
|
||||
//
|
||||
// Check the argument.
|
||||
//
|
||||
ASSERT(!(ui32Address & (FLASH_PROTECT_SIZE - 1)));
|
||||
ASSERT((eProtect == FlashReadWrite) || (eProtect == FlashReadOnly) ||
|
||||
(eProtect == FlashExecuteOnly));
|
||||
|
||||
//
|
||||
// Convert the address into a block number.
|
||||
//
|
||||
ui32Address /= FLASH_PROTECT_SIZE;
|
||||
|
||||
//
|
||||
// ui32Address contains a "raw" block number. Derive the Flash Bank from
|
||||
// the "raw" block number, and convert ui32Address to a "relative"
|
||||
// block number.
|
||||
//
|
||||
ui32Bank = ((ui32Address / 32) % 4);
|
||||
ui32Address %= 32;
|
||||
|
||||
//
|
||||
// Get the current protection for the specified flash bank.
|
||||
//
|
||||
ui32ProtectRE = HWREG(g_pui32FMPRERegs[ui32Bank]);
|
||||
ui32ProtectPE = HWREG(g_pui32FMPPERegs[ui32Bank]);
|
||||
|
||||
//
|
||||
// Set the protection based on the requested protection.
|
||||
//
|
||||
switch(eProtect)
|
||||
{
|
||||
//
|
||||
// Make this block execute only.
|
||||
//
|
||||
case FlashExecuteOnly:
|
||||
{
|
||||
//
|
||||
// Turn off the read and program bits for this block.
|
||||
//
|
||||
ui32ProtectRE &= ~(0x1 << ui32Address);
|
||||
ui32ProtectPE &= ~(0x1 << ui32Address);
|
||||
|
||||
//
|
||||
// We're done handling this protection.
|
||||
//
|
||||
break;
|
||||
}
|
||||
|
||||
//
|
||||
// Make this block read only.
|
||||
//
|
||||
case FlashReadOnly:
|
||||
{
|
||||
//
|
||||
// The block can not be made read only if it is execute only.
|
||||
//
|
||||
if(((ui32ProtectRE >> ui32Address) & 0x1) != 0x1)
|
||||
{
|
||||
return(-1);
|
||||
}
|
||||
|
||||
//
|
||||
// Make this block read only.
|
||||
//
|
||||
ui32ProtectPE &= ~(0x1 << ui32Address);
|
||||
|
||||
//
|
||||
// We're done handling this protection.
|
||||
//
|
||||
break;
|
||||
}
|
||||
|
||||
//
|
||||
// Make this block read/write.
|
||||
//
|
||||
case FlashReadWrite:
|
||||
default:
|
||||
{
|
||||
//
|
||||
// The block can not be made read/write if it is not already
|
||||
// read/write.
|
||||
//
|
||||
if((((ui32ProtectRE >> ui32Address) & 0x1) != 0x1) ||
|
||||
(((ui32ProtectPE >> ui32Address) & 0x1) != 0x1))
|
||||
{
|
||||
return(-1);
|
||||
}
|
||||
|
||||
//
|
||||
// The block is already read/write, so there is nothing to do.
|
||||
//
|
||||
return(0);
|
||||
}
|
||||
}
|
||||
|
||||
//
|
||||
// Set the new protection for the specified flash bank.
|
||||
//
|
||||
HWREG(g_pui32FMPRERegs[ui32Bank]) = ui32ProtectRE;
|
||||
HWREG(g_pui32FMPPERegs[ui32Bank]) = ui32ProtectPE;
|
||||
|
||||
//
|
||||
// Success.
|
||||
//
|
||||
return(0);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Saves the flash protection settings.
|
||||
//!
|
||||
//! This function makes the currently programmed flash protection settings
|
||||
//! permanent. This operation is non-reversible; a chip reset or power cycle
|
||||
//! does not change the flash protection.
|
||||
//!
|
||||
//! This function does not return until the protection has been saved.
|
||||
//!
|
||||
//! \return Returns 0 on success, or -1 if a hardware error is encountered.
|
||||
//
|
||||
//*****************************************************************************
|
||||
int32_t
|
||||
FlashProtectSave(void)
|
||||
{
|
||||
uint32_t ui32Temp;
|
||||
|
||||
//
|
||||
// Save the entire bank of 8 flash protection registers.
|
||||
//
|
||||
for(ui32Temp = 0; ui32Temp < 8; ui32Temp++)
|
||||
{
|
||||
//
|
||||
// Tell the flash controller to write the flash protection register.
|
||||
//
|
||||
HWREG(FLASH_FMA) = ui32Temp;
|
||||
HWREG(FLASH_FMC) = FLASH_FMC_WRKEY | FLASH_FMC_COMT;
|
||||
|
||||
//
|
||||
// Wait until the write has completed.
|
||||
//
|
||||
while(HWREG(FLASH_FMC) & FLASH_FMC_COMT)
|
||||
{
|
||||
}
|
||||
}
|
||||
|
||||
//
|
||||
// Success.
|
||||
//
|
||||
return(0);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Gets the user registers.
|
||||
//!
|
||||
//! \param pui32User0 is a pointer to the location to store USER Register 0.
|
||||
//! \param pui32User1 is a pointer to the location to store USER Register 1.
|
||||
//!
|
||||
//! This function reads the contents of user registers 0 and 1, and
|
||||
//! stores them in the specified locations.
|
||||
//!
|
||||
//! \return Returns 0 on success, or -1 if a hardware error is encountered.
|
||||
//
|
||||
//*****************************************************************************
|
||||
int32_t
|
||||
FlashUserGet(uint32_t *pui32User0, uint32_t *pui32User1)
|
||||
{
|
||||
//
|
||||
// Verify that the pointers are valid.
|
||||
//
|
||||
ASSERT(pui32User0 != 0);
|
||||
ASSERT(pui32User1 != 0);
|
||||
|
||||
//
|
||||
// Get and store the current value of the user registers.
|
||||
//
|
||||
*pui32User0 = HWREG(FLASH_USERREG0);
|
||||
*pui32User1 = HWREG(FLASH_USERREG1);
|
||||
|
||||
//
|
||||
// Success.
|
||||
//
|
||||
return(0);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Sets the user registers.
|
||||
//!
|
||||
//! \param ui32User0 is the value to store in USER Register 0.
|
||||
//! \param ui32User1 is the value to store in USER Register 1.
|
||||
//!
|
||||
//! This function sets the contents of the user registers 0 and 1 to
|
||||
//! the specified values.
|
||||
//!
|
||||
//! \return Returns 0 on success, or -1 if a hardware error is encountered.
|
||||
//
|
||||
//*****************************************************************************
|
||||
int32_t
|
||||
FlashUserSet(uint32_t ui32User0, uint32_t ui32User1)
|
||||
{
|
||||
//
|
||||
// Save the new values into the user registers.
|
||||
//
|
||||
HWREG(FLASH_USERREG0) = ui32User0;
|
||||
HWREG(FLASH_USERREG1) = ui32User1;
|
||||
|
||||
//
|
||||
// Success.
|
||||
//
|
||||
return(0);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Saves the user registers.
|
||||
//!
|
||||
//! This function makes the currently programmed user register 0 and 1 settings
|
||||
//! permanent. This operation is non-reversible; a chip reset or power cycle
|
||||
//! does not change the flash protection.
|
||||
//!
|
||||
//! This function does not return until the protection has been saved.
|
||||
//!
|
||||
//! \return Returns 0 on success, or -1 if a hardware error is encountered.
|
||||
//
|
||||
//*****************************************************************************
|
||||
int32_t
|
||||
FlashUserSave(void)
|
||||
{
|
||||
//
|
||||
// Setting the MSB of FMA will trigger a permanent save of a USER
|
||||
// register. Bit 0 will indicate User 0 (0) or User 1 (1).
|
||||
//
|
||||
HWREG(FLASH_FMA) = 0x80000000;
|
||||
HWREG(FLASH_FMC) = FLASH_FMC_WRKEY | FLASH_FMC_COMT;
|
||||
|
||||
//
|
||||
// Wait until the write has completed.
|
||||
//
|
||||
while(HWREG(FLASH_FMC) & FLASH_FMC_COMT)
|
||||
{
|
||||
}
|
||||
|
||||
//
|
||||
// Tell the flash controller to write the USER1 Register.
|
||||
//
|
||||
HWREG(FLASH_FMA) = 0x80000001;
|
||||
HWREG(FLASH_FMC) = FLASH_FMC_WRKEY | FLASH_FMC_COMT;
|
||||
|
||||
//
|
||||
// Wait until the write has completed.
|
||||
//
|
||||
while(HWREG(FLASH_FMC) & FLASH_FMC_COMT)
|
||||
{
|
||||
}
|
||||
|
||||
//
|
||||
// Success.
|
||||
//
|
||||
return(0);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! 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 function 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
|
||||
//! is 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_TM4C123, pfnHandler);
|
||||
|
||||
//
|
||||
// Enable the flash interrupt.
|
||||
//
|
||||
IntEnable(INT_FLASH_TM4C123);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Unregisters the interrupt handler for the flash interrupt.
|
||||
//!
|
||||
//! This function clears the handler to be called when the flash interrupt
|
||||
//! occurs. This function also masks 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_TM4C123);
|
||||
|
||||
//
|
||||
// Unregister the interrupt handler.
|
||||
//
|
||||
IntUnregister(INT_FLASH_TM4C123);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Enables individual flash controller interrupt sources.
|
||||
//!
|
||||
//! \param ui32IntFlags is a bit mask of the interrupt sources to be enabled.
|
||||
//! The ui32IntFlags parameter can be the logical OR of any of the following
|
||||
//! values:
|
||||
//!
|
||||
//! - \b FLASH_INT_ACCESS occurs when a program or erase action was attempted
|
||||
//! on a block of flash that is marked as read-only or execute-only.
|
||||
//! - \b FLASH_INT_PROGRAM occurs when a programming or erase cycle completes.
|
||||
//! - \b FLASH_INT_EEPROM occurs when an EEPROM interrupt occurs. The source of
|
||||
//! the EEPROM interrupt can be determined by reading the EEDONE register.
|
||||
//! - \b FLASH_INT_VOLTAGE_ERR occurs when the voltage was out of spec during
|
||||
//! the flash operation and the operation was terminated.
|
||||
//! - \b FLASH_INT_DATA_ERR occurs when an operation attempts to program a bit that
|
||||
//! contains a 0 to a 1.
|
||||
//! - \b FLASH_INT_ERASE_ERR occurs when an erase operation fails.
|
||||
//! - \b FLASH_INT_PROGRAM_ERR occurs when a program operation fails.
|
||||
//!
|
||||
//! This function 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(uint32_t ui32IntFlags)
|
||||
{
|
||||
//
|
||||
// Enable the specified interrupts.
|
||||
//
|
||||
HWREG(FLASH_FCIM) |= ui32IntFlags;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Disables individual flash controller interrupt sources.
|
||||
//!
|
||||
//! \param ui32IntFlags is a bit mask of the interrupt sources to be disabled.
|
||||
//! The ui32IntFlags parameter can be the logical OR of any of the following
|
||||
//! values:
|
||||
//!
|
||||
//! - \b FLASH_INT_ACCESS occurs when a program or erase action was attempted
|
||||
//! on a block of flash that is marked as read-only or execute-only.
|
||||
//! - \b FLASH_INT_PROGRAM occurs when a programming or erase cycle completes.
|
||||
//! - \b FLASH_INT_EEPROM occurs when an EEPROM interrupt occurs. The source of
|
||||
//! the EEPROM interrupt can be determined by reading the EEDONE register.
|
||||
//! - \b FLASH_INT_VOLTAGE_ERR occurs when the voltage was out of spec during
|
||||
//! the flash operation and the operation was terminated.
|
||||
//! - \b FLASH_INT_DATA_ERR occurs when an operation attempts to program a bit that
|
||||
//! contains a 0 to a 1.
|
||||
//! - \b FLASH_INT_ERASE_ERR occurs when an erase operation fails.
|
||||
//! - \b FLASH_INT_PROGRAM_ERR occurs when a program operation fails.
|
||||
//!
|
||||
//! This function 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(uint32_t ui32IntFlags)
|
||||
{
|
||||
//
|
||||
// Disable the specified interrupts.
|
||||
//
|
||||
HWREG(FLASH_FCIM) &= ~(ui32IntFlags);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! 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 function 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_INT_ACCESS, \b FLASH_INT_PROGRAM, \b FLASH_INT_EEPROM,
|
||||
//! FLASH_INT_VOLTAGE_ERR, FLASH_INT_DATA_ERR, FLASH_INT_ERASE_ERR, and
|
||||
//! FLASH_INT_PROGRAM_ERR.
|
||||
//
|
||||
//*****************************************************************************
|
||||
uint32_t
|
||||
FlashIntStatus(bool bMasked)
|
||||
{
|
||||
//
|
||||
// Return either the interrupt status or the raw interrupt status as
|
||||
// requested.
|
||||
//
|
||||
if(bMasked)
|
||||
{
|
||||
return(HWREG(FLASH_FCMISC));
|
||||
}
|
||||
else
|
||||
{
|
||||
return(HWREG(FLASH_FCRIS));
|
||||
}
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Clears flash controller interrupt sources.
|
||||
//!
|
||||
//! \param ui32IntFlags is the bit mask of the interrupt sources to be cleared.
|
||||
//!
|
||||
//! The specified flash controller interrupt sources are cleared, so that they
|
||||
//! no longer assert. The
|
||||
//! ui32IntFlags parameter can be the logical OR of any of the following
|
||||
//! values:
|
||||
//!
|
||||
//! - \b FLASH_INT_ACCESS occurs when a program or erase action was attempted
|
||||
//! on a block of flash that is marked as read-only or execute-only.
|
||||
//! - \b FLASH_INT_PROGRAM occurs when a programming or erase cycle completes.
|
||||
//! - \b FLASH_INT_EEPROM occurs when an EEPROM interrupt occurs. The source of
|
||||
//! the EEPROM interrupt can be determined by reading the EEDONE register.
|
||||
//! - \b FLASH_INT_VOLTAGE_ERR occurs when the voltage was out of spec during
|
||||
//! the flash operation and the operation was terminated.
|
||||
//! - \b FLASH_INT_DATA_ERR occurs when an operation attempts to program a bit that
|
||||
//! contains a 0 to a 1.
|
||||
//! - \b FLASH_INT_ERASE_ERR occurs when an erase operation fails.
|
||||
//! - \b FLASH_INT_PROGRAM_ERR occurs when a program operation fails.
|
||||
//!
|
||||
//! This function must be called in the interrupt handler to keep the
|
||||
//! interrupt from being triggered again immediately upon exit.
|
||||
//!
|
||||
//! \note Because there is a write buffer in the Cortex-M 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(uint32_t ui32IntFlags)
|
||||
{
|
||||
//
|
||||
// Clear the flash interrupt.
|
||||
//
|
||||
HWREG(FLASH_FCMISC) = ui32IntFlags;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Close the Doxygen group.
|
||||
//! @}
|
||||
//
|
||||
//*****************************************************************************
|
|
@ -0,0 +1,113 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// flash.h - Prototypes for the flash driver.
|
||||
//
|
||||
// Copyright (c) 2005-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __DRIVERLIB_FLASH_H__
|
||||
#define __DRIVERLIB_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 int32_t FlashErase(uint32_t ui32Address);
|
||||
extern int32_t FlashProgram(uint32_t *pui32Data, uint32_t ui32Address,
|
||||
uint32_t ui32Count);
|
||||
extern tFlashProtection FlashProtectGet(uint32_t ui32Address);
|
||||
extern int32_t FlashProtectSet(uint32_t ui32Address,
|
||||
tFlashProtection eProtect);
|
||||
extern int32_t FlashProtectSave(void);
|
||||
extern int32_t FlashUserGet(uint32_t *pui32User0, uint32_t *pui32User1);
|
||||
extern int32_t FlashUserSet(uint32_t ui32User0, uint32_t ui32User1);
|
||||
extern int32_t FlashUserSave(void);
|
||||
extern void FlashIntRegister(void (*pfnHandler)(void));
|
||||
extern void FlashIntUnregister(void);
|
||||
extern void FlashIntEnable(uint32_t ui32IntFlags);
|
||||
extern void FlashIntDisable(uint32_t ui32IntFlags);
|
||||
extern uint32_t FlashIntStatus(bool bMasked);
|
||||
extern void FlashIntClear(uint32_t ui32IntFlags);
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Mark the end of the C bindings section for C++ compilers.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // __DRIVERLIB_FLASH_H__
|
|
@ -0,0 +1,300 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// fpu.c - Routines for manipulating the floating-point unit in the Cortex-M
|
||||
// processor.
|
||||
//
|
||||
// Copyright (c) 2011-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! \addtogroup fpu_api
|
||||
//! @{
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#include <stdint.h>
|
||||
#include "inc/hw_nvic.h"
|
||||
#include "inc/hw_types.h"
|
||||
#include "driverlib/fpu.h"
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Enables the floating-point unit.
|
||||
//!
|
||||
//! This function enables the floating-point unit, allowing the floating-point
|
||||
//! instructions to be executed. This function must be called prior to
|
||||
//! performing any hardware floating-point operations; failure to do so results
|
||||
//! in a NOCP usage fault.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
FPUEnable(void)
|
||||
{
|
||||
//
|
||||
// Enable the coprocessors used by the floating-point unit.
|
||||
//
|
||||
HWREG(NVIC_CPAC) = ((HWREG(NVIC_CPAC) &
|
||||
~(NVIC_CPAC_CP10_M | NVIC_CPAC_CP11_M)) |
|
||||
NVIC_CPAC_CP10_FULL | NVIC_CPAC_CP11_FULL);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Disables the floating-point unit.
|
||||
//!
|
||||
//! This function disables the floating-point unit, preventing floating-point
|
||||
//! instructions from executing (generating a NOCP usage fault instead).
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
FPUDisable(void)
|
||||
{
|
||||
//
|
||||
// Disable the coprocessors used by the floating-point unit.
|
||||
//
|
||||
HWREG(NVIC_CPAC) = ((HWREG(NVIC_CPAC) &
|
||||
~(NVIC_CPAC_CP10_M | NVIC_CPAC_CP11_M)) |
|
||||
NVIC_CPAC_CP10_DIS | NVIC_CPAC_CP11_DIS);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Enables the stacking of floating-point registers.
|
||||
//!
|
||||
//! This function enables the stacking of floating-point registers s0-s15 when
|
||||
//! an interrupt is handled. When enabled, space is reserved on the stack for
|
||||
//! the floating-point context and the floating-point state is saved into this
|
||||
//! stack space. Upon return from the interrupt, the floating-point context is
|
||||
//! restored.
|
||||
//!
|
||||
//! If the floating-point registers are not stacked, floating-point
|
||||
//! instructions cannot be safely executed in an interrupt handler because the
|
||||
//! values of s0-s15 are not likely to be preserved for the interrupted code.
|
||||
//! On the other hand, stacking the floating-point registers increases the
|
||||
//! stacking operation from 8 words to 26 words, also increasing the interrupt
|
||||
//! response latency.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
FPUStackingEnable(void)
|
||||
{
|
||||
//
|
||||
// Enable automatic state preservation for the floating-point unit, and
|
||||
// disable lazy state preservation (meaning that the floating-point state
|
||||
// is always stacked when floating-point instructions are used).
|
||||
//
|
||||
HWREG(NVIC_FPCC) = (HWREG(NVIC_FPCC) & ~NVIC_FPCC_LSPEN) | NVIC_FPCC_ASPEN;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Enables the lazy stacking of floating-point registers.
|
||||
//!
|
||||
//! This function enables the lazy stacking of floating-point registers s0-s15
|
||||
//! when an interrupt is handled. When lazy stacking is enabled, space is
|
||||
//! reserved on the stack for the floating-point context, but the
|
||||
//! floating-point state is not saved. If a floating-point instruction is
|
||||
//! executed from within the interrupt context, the floating-point context is
|
||||
//! first saved into the space reserved on the stack. On completion of the
|
||||
//! interrupt handler, the floating-point context is only restored if it was
|
||||
//! saved (as the result of executing a floating-point instruction).
|
||||
//!
|
||||
//! This method provides a compromise between fast interrupt response (because
|
||||
//! the floating-point state is not saved on interrupt entry) and the ability
|
||||
//! to use floating-point in interrupt handlers (because the floating-point
|
||||
//! state is saved if floating-point instructions are used).
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
FPULazyStackingEnable(void)
|
||||
{
|
||||
//
|
||||
// Enable automatic and lazy state preservation for the floating-point
|
||||
// unit.
|
||||
//
|
||||
HWREG(NVIC_FPCC) |= NVIC_FPCC_ASPEN | NVIC_FPCC_LSPEN;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Disables the stacking of floating-point registers.
|
||||
//!
|
||||
//! This function disables the stacking of floating-point registers s0-s15 when
|
||||
//! an interrupt is handled. When floating-point context stacking is disabled,
|
||||
//! floating-point operations performed in an interrupt handler destroy the
|
||||
//! floating-point context of the main thread of execution.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
FPUStackingDisable(void)
|
||||
{
|
||||
//
|
||||
// Disable automatic and lazy state preservation for the floating-point
|
||||
// unit.
|
||||
//
|
||||
HWREG(NVIC_FPCC) &= ~(NVIC_FPCC_ASPEN | NVIC_FPCC_LSPEN);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Selects the format of half-precision floating-point values.
|
||||
//!
|
||||
//! \param ui32Mode is the format for half-precision floating-point value,
|
||||
//! which is either \b FPU_HALF_IEEE or \b FPU_HALF_ALTERNATE.
|
||||
//!
|
||||
//! This function selects between the IEEE half-precision floating-point
|
||||
//! representation and the Cortex-M processor alternative representation. The
|
||||
//! alternative representation has a larger range but does not have a way to
|
||||
//! encode infinity (positive or negative) or NaN (quiet or signaling). The
|
||||
//! default setting is the IEEE format.
|
||||
//!
|
||||
//! \note Unless this function is called prior to executing any floating-point
|
||||
//! instructions, the default mode is used.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
FPUHalfPrecisionModeSet(uint32_t ui32Mode)
|
||||
{
|
||||
//
|
||||
// Set the half-precision floating-point format.
|
||||
//
|
||||
HWREG(NVIC_FPDSC) = (HWREG(NVIC_FPDSC) & ~(NVIC_FPDSC_AHP)) | ui32Mode;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Selects the NaN mode.
|
||||
//!
|
||||
//! \param ui32Mode is the mode for NaN results; which is either
|
||||
//! \b FPU_NAN_PROPAGATE or \b FPU_NAN_DEFAULT.
|
||||
//!
|
||||
//! This function selects the handling of NaN results during floating-point
|
||||
//! computations. NaNs can either propagate (the default), or they can return
|
||||
//! the default NaN.
|
||||
//!
|
||||
//! \note Unless this function is called prior to executing any floating-point
|
||||
//! instructions, the default mode is used.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
FPUNaNModeSet(uint32_t ui32Mode)
|
||||
{
|
||||
//
|
||||
// Set the NaN mode.
|
||||
//
|
||||
HWREG(NVIC_FPDSC) = (HWREG(NVIC_FPDSC) & ~(NVIC_FPDSC_DN)) | ui32Mode;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Selects the flush-to-zero mode.
|
||||
//!
|
||||
//! \param ui32Mode is the flush-to-zero mode; which is either
|
||||
//! \b FPU_FLUSH_TO_ZERO_DIS or \b FPU_FLUSH_TO_ZERO_EN.
|
||||
//!
|
||||
//! This function enables or disables the flush-to-zero mode of the
|
||||
//! floating-point unit. When disabled (the default), the floating-point unit
|
||||
//! is fully IEEE compliant. When enabled, values close to zero are treated as
|
||||
//! zero, greatly improving the execution speed at the expense of some accuracy
|
||||
//! (as well as IEEE compliance).
|
||||
//!
|
||||
//! \note Unless this function is called prior to executing any floating-point
|
||||
//! instructions, the default mode is used.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
FPUFlushToZeroModeSet(uint32_t ui32Mode)
|
||||
{
|
||||
//
|
||||
// Set the flush-to-zero mode.
|
||||
//
|
||||
HWREG(NVIC_FPDSC) = (HWREG(NVIC_FPDSC) & ~(NVIC_FPDSC_FZ)) | ui32Mode;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Selects the rounding mode for floating-point results.
|
||||
//!
|
||||
//! \param ui32Mode is the rounding mode.
|
||||
//!
|
||||
//! This function selects the rounding mode for floating-point results. After
|
||||
//! a floating-point operation, the result is rounded toward the specified
|
||||
//! value. The default mode is \b FPU_ROUND_NEAREST.
|
||||
//!
|
||||
//! The following rounding modes are available (as specified by \e ui32Mode):
|
||||
//!
|
||||
//! - \b FPU_ROUND_NEAREST - round toward the nearest value
|
||||
//! - \b FPU_ROUND_POS_INF - round toward positive infinity
|
||||
//! - \b FPU_ROUND_NEG_INF - round toward negative infinity
|
||||
//! - \b FPU_ROUND_ZERO - round toward zero
|
||||
//!
|
||||
//! \note Unless this function is called prior to executing any floating-point
|
||||
//! instructions, the default mode is used.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
FPURoundingModeSet(uint32_t ui32Mode)
|
||||
{
|
||||
//
|
||||
// Set the rounding mode.
|
||||
//
|
||||
HWREG(NVIC_FPDSC) = (HWREG(NVIC_FPDSC) & ~(NVIC_FPDSC_RMODE_M)) | ui32Mode;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Close the Doxygen group.
|
||||
//! @}
|
||||
//
|
||||
//*****************************************************************************
|
|
@ -0,0 +1,113 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// fpu.h - Prototypes for the floatint point manipulation routines.
|
||||
//
|
||||
// Copyright (c) 2011-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __DRIVERLIB_FPU_H__
|
||||
#define __DRIVERLIB_FPU_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 FPUHalfPrecisionSet as the ui32Mode parameter.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FPU_HALF_IEEE 0x00000000
|
||||
#define FPU_HALF_ALTERNATE 0x04000000
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to FPUNaNModeSet as the ui32Mode parameter.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FPU_NAN_PROPAGATE 0x00000000
|
||||
#define FPU_NAN_DEFAULT 0x02000000
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to FPUFlushToZeroModeSet as the ui32Mode
|
||||
// parameter.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FPU_FLUSH_TO_ZERO_DIS 0x00000000
|
||||
#define FPU_FLUSH_TO_ZERO_EN 0x01000000
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to FPURoundingModeSet as the ui32Mode parameter.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FPU_ROUND_NEAREST 0x00000000
|
||||
#define FPU_ROUND_POS_INF 0x00400000
|
||||
#define FPU_ROUND_NEG_INF 0x00800000
|
||||
#define FPU_ROUND_ZERO 0x00c00000
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Prototypes.
|
||||
//
|
||||
//*****************************************************************************
|
||||
extern void FPUEnable(void);
|
||||
extern void FPUDisable(void);
|
||||
extern void FPUStackingEnable(void);
|
||||
extern void FPULazyStackingEnable(void);
|
||||
extern void FPUStackingDisable(void);
|
||||
extern void FPUHalfPrecisionModeSet(uint32_t ui32Mode);
|
||||
extern void FPUNaNModeSet(uint32_t ui32Mode);
|
||||
extern void FPUFlushToZeroModeSet(uint32_t ui32Mode);
|
||||
extern void FPURoundingModeSet(uint32_t ui32Mode);
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Mark the end of the C bindings section for C++ compilers.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // __DRIVERLIB_FPU_H__
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,196 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// gpio.h - Defines and Macros for GPIO API.
|
||||
//
|
||||
// Copyright (c) 2005-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __DRIVERLIB_GPIO_H__
|
||||
#define __DRIVERLIB_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 ui8Pins 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 ui32PinIO 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
|
||||
#define GPIO_DIR_MODE_HW 0x00000002 // Pin is a peripheral function
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to GPIOIntTypeSet as the ui32IntType 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
|
||||
#define GPIO_DISCRETE_INT 0x00010000 // Interrupt for individual pins
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to GPIOPadConfigSet as the ui32Strength parameter,
|
||||
// and returned by GPIOPadConfigGet in the *pui32Strength parameter.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define GPIO_STRENGTH_2MA 0x00000001 // 2mA drive strength
|
||||
#define GPIO_STRENGTH_4MA 0x00000002 // 4mA drive strength
|
||||
#define GPIO_STRENGTH_6MA 0x00000065 // 6mA drive strength
|
||||
#define GPIO_STRENGTH_8MA 0x00000066 // 8mA drive strength
|
||||
#define GPIO_STRENGTH_8MA_SC 0x0000006E // 8mA drive with slew rate control
|
||||
#define GPIO_STRENGTH_10MA 0x00000075 // 10mA drive strength
|
||||
#define GPIO_STRENGTH_12MA 0x00000077 // 12mA drive strength
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to GPIOPadConfigSet as the ui32PadType parameter,
|
||||
// and returned by GPIOPadConfigGet in the *pui32PadType parameter.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define GPIO_PIN_TYPE_STD 0x00000008 // Push-pull
|
||||
#define GPIO_PIN_TYPE_STD_WPU 0x0000000A // Push-pull with weak pull-up
|
||||
#define GPIO_PIN_TYPE_STD_WPD 0x0000000C // Push-pull with weak pull-down
|
||||
#define GPIO_PIN_TYPE_OD 0x00000009 // Open-drain
|
||||
#define GPIO_PIN_TYPE_ANALOG 0x00000000 // Analog comparator
|
||||
#define GPIO_PIN_TYPE_WAKE_HIGH 0x00000208 // Hibernate wake, high
|
||||
#define GPIO_PIN_TYPE_WAKE_LOW 0x00000108 // Hibernate wake, low
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to GPIOIntEnable() and GPIOIntDisable() functions
|
||||
// in the ui32IntFlags parameter.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#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
|
||||
#define GPIO_INT_DMA 0x00000100
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Prototypes for the APIs.
|
||||
//
|
||||
//*****************************************************************************
|
||||
extern void GPIODirModeSet(uint32_t ui32Port, uint8_t ui8Pins,
|
||||
uint32_t ui32PinIO);
|
||||
extern uint32_t GPIODirModeGet(uint32_t ui32Port, uint8_t ui8Pin);
|
||||
extern void GPIOIntTypeSet(uint32_t ui32Port, uint8_t ui8Pins,
|
||||
uint32_t ui32IntType);
|
||||
extern uint32_t GPIOIntTypeGet(uint32_t ui32Port, uint8_t ui8Pin);
|
||||
extern void GPIOPadConfigSet(uint32_t ui32Port, uint8_t ui8Pins,
|
||||
uint32_t ui32Strength, uint32_t ui32PadType);
|
||||
extern void GPIOPadConfigGet(uint32_t ui32Port, uint8_t ui8Pin,
|
||||
uint32_t *pui32Strength, uint32_t *pui32PadType);
|
||||
extern void GPIOIntEnable(uint32_t ui32Port, uint32_t ui32IntFlags);
|
||||
extern void GPIOIntDisable(uint32_t ui32Port, uint32_t ui32IntFlags);
|
||||
extern uint32_t GPIOIntStatus(uint32_t ui32Port, bool bMasked);
|
||||
extern void GPIOIntClear(uint32_t ui32Port, uint32_t ui32IntFlags);
|
||||
extern void GPIOIntRegister(uint32_t ui32Port, void (*pfnIntHandler)(void));
|
||||
extern void GPIOIntUnregister(uint32_t ui32Port);
|
||||
extern int32_t GPIOPinRead(uint32_t ui32Port, uint8_t ui8Pins);
|
||||
extern void GPIOPinWrite(uint32_t ui32Port, uint8_t ui8Pins, uint8_t ui8Val);
|
||||
extern void GPIOPinConfigure(uint32_t ui32PinConfig);
|
||||
extern void GPIOPinTypeADC(uint32_t ui32Port, uint8_t ui8Pins);
|
||||
extern void GPIOPinTypeCAN(uint32_t ui32Port, uint8_t ui8Pins);
|
||||
extern void GPIOPinTypeComparator(uint32_t ui32Port, uint8_t ui8Pins);
|
||||
extern void GPIOPinTypeEPI(uint32_t ui32Port, uint8_t ui8Pins);
|
||||
extern void GPIOPinTypeEthernetLED(uint32_t ui32Port, uint8_t ui8Pins);
|
||||
extern void GPIOPinTypeEthernetMII(uint32_t ui32Port, uint8_t ui8Pins);
|
||||
extern void GPIOPinTypeGPIOInput(uint32_t ui32Port, uint8_t ui8Pins);
|
||||
extern void GPIOPinTypeGPIOOutput(uint32_t ui32Port, uint8_t ui8Pins);
|
||||
extern void GPIOPinTypeGPIOOutputOD(uint32_t ui32Port, uint8_t ui8Pins);
|
||||
extern void GPIOPinTypeI2C(uint32_t ui32Port, uint8_t ui8Pins);
|
||||
extern void GPIOPinTypeI2CSCL(uint32_t ui32Port, uint8_t ui8Pins);
|
||||
extern void GPIOPinTypeLCD(uint32_t ui32Port, uint8_t ui8Pins);
|
||||
extern void GPIOPinTypePWM(uint32_t ui32Port, uint8_t ui8Pins);
|
||||
extern void GPIOPinTypeQEI(uint32_t ui32Port, uint8_t ui8Pins);
|
||||
extern void GPIOPinTypeSSI(uint32_t ui32Port, uint8_t ui8Pins);
|
||||
extern void GPIOPinTypeTimer(uint32_t ui32Port, uint8_t ui8Pins);
|
||||
extern void GPIOPinTypeUART(uint32_t ui32Port, uint8_t ui8Pins);
|
||||
extern void GPIOPinTypeUSBAnalog(uint32_t ui32Port, uint8_t ui8Pins);
|
||||
extern void GPIOPinTypeUSBDigital(uint32_t ui32Port, uint8_t ui8Pins);
|
||||
extern void GPIOPinTypeWakeHigh(uint32_t ui32Port, uint8_t ui8Pins);
|
||||
extern void GPIOPinTypeWakeLow(uint32_t ui32Port, uint8_t ui8Pins);
|
||||
extern uint32_t GPIOPinWakeStatus(uint32_t ui32Port);
|
||||
extern void GPIODMATriggerEnable(uint32_t ui32Port, uint8_t ui8Pins);
|
||||
extern void GPIODMATriggerDisable(uint32_t ui32Port, uint8_t ui8Pins);
|
||||
extern void GPIOADCTriggerEnable(uint32_t ui32Port, uint8_t ui8Pins);
|
||||
extern void GPIOADCTriggerDisable(uint32_t ui32Port, uint8_t ui8Pins);
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Mark the end of the C bindings section for C++ compilers.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // __DRIVERLIB_GPIO_H__
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,257 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// hibernate.h - API definition for the Hibernation module.
|
||||
//
|
||||
// Copyright (c) 2007-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __DRIVERLIB_HIBERNATE_H__
|
||||
#define __DRIVERLIB_HIBERNATE_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 need to configure wake events for HibernateWakeSet()
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define HIBERNATE_WAKE_PIN 0x00000010
|
||||
#define HIBERNATE_WAKE_RTC 0x00000008
|
||||
#define HIBERNATE_WAKE_LOW_BAT 0x00000200
|
||||
#define HIBERNATE_WAKE_GPIO 0x00000010
|
||||
#define HIBERNATE_WAKE_RESET 0x00100010
|
||||
#define HIBERNATE_WAKE_TAMPER 0x08000010
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Macros needed to configure low battery detect for HibernateLowBatSet()
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define HIBERNATE_LOW_BAT_DETECT \
|
||||
0x00000020
|
||||
#define HIBERNATE_LOW_BAT_ABORT 0x000000A0
|
||||
#define HIBERNATE_LOW_BAT_1_9V 0x00000000
|
||||
#define HIBERNATE_LOW_BAT_2_1V 0x00002000
|
||||
#define HIBERNATE_LOW_BAT_2_3V 0x00004000
|
||||
#define HIBERNATE_LOW_BAT_2_5V 0x00006000
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Macros defining interrupt source bits for the interrupt functions.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define HIBERNATE_INT_VDDFAIL 0x00000080
|
||||
#define HIBERNATE_INT_RESET_WAKE \
|
||||
0x00000040
|
||||
#define HIBERNATE_INT_GPIO_WAKE 0x00000020
|
||||
#define HIBERNATE_INT_WR_COMPLETE \
|
||||
0x00000010
|
||||
#define HIBERNATE_INT_PIN_WAKE 0x00000008
|
||||
#define HIBERNATE_INT_LOW_BAT 0x00000004
|
||||
#define HIBERNATE_INT_RTC_MATCH_0 \
|
||||
0x00000001
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Macros defining oscillator configuration options for the
|
||||
// HibernateClockConfig() function.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define HIBERNATE_OSC_LFIOSC 0x00080000
|
||||
#define HIBERNATE_OSC_LOWDRIVE 0x00000000
|
||||
#define HIBERNATE_OSC_HIGHDRIVE 0x00020000
|
||||
#define HIBERNATE_OSC_DISABLE 0x00010000
|
||||
#define HIBERNATE_OUT_WRSTALL 0x20000000
|
||||
#define HIBERNATE_OUT_SYSCLK 0x00000001
|
||||
#define HIBERNATE_OUT_ALT1CLK 0x00000002
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following defines are used with the HibernateCounterMode() API.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define HIBERNATE_COUNTER_RTC 0x00000000
|
||||
#define HIBERNATE_COUNTER_12HR 0x00000001
|
||||
#define HIBERNATE_COUNTER_24HR 0x00000005
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Tamper event configuration options used with HibernateTamperEventsConfig().
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define HIBERNATE_TAMPER_EVENTS_NO_HIB_WAKE \
|
||||
0x00000000
|
||||
#define HIBERNATE_TAMPER_EVENTS_HIB_WAKE \
|
||||
0x00000800
|
||||
#define HIBERNATE_TAMPER_EVENTS_NO_ERASE_HIB_MEM \
|
||||
0x00000000
|
||||
#define HIBERNATE_TAMPER_EVENTS_ERASE_LOW_HIB_MEM \
|
||||
0x00000100
|
||||
#define HIBERNATE_TAMPER_EVENTS_ERASE_HIGH_HIB_MEM \
|
||||
0x00000200
|
||||
#define HIBERNATE_TAMPER_EVENTS_ERASE_ALL_HIB_MEM \
|
||||
0x00000300
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Status flags returned by the HibernateTamperStatus() function.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define HIBERNATE_TAMPER_STATUS_INACTIVE \
|
||||
0x00000010
|
||||
#define HIBERNATE_TAMPER_STATUS_ACTIVE \
|
||||
0x00000020
|
||||
#define HIBERNATE_TAMPER_STATUS_EVENT \
|
||||
0x00000040
|
||||
#define HIBERNATE_TAMPER_STATUS_EXT_OSC_ACTIVE \
|
||||
0x00000008
|
||||
#define HIBERNATE_TAMPER_STATUS_EXT_OSC_INACTIVE \
|
||||
0x00000002
|
||||
#define HIBERNATE_TAMPER_STATUS_EXT_OSC_VALID \
|
||||
0x00000004
|
||||
#define HIBERNATE_TAMPER_STATUS_EXT_OSC_FAILED \
|
||||
0x00000001
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Configuration options used with HibernateTamperIOEnable().
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define HIBERNATE_TAMPER_IO_TRIGGER_LOW \
|
||||
0x00000000
|
||||
#define HIBERNATE_TAMPER_IO_TRIGGER_HIGH \
|
||||
0x00000002
|
||||
#define HIBERNATE_TAMPER_IO_WPU_DISABLED \
|
||||
0x00000000
|
||||
#define HIBERNATE_TAMPER_IO_WPU_ENABLED \
|
||||
0x00000004
|
||||
#define HIBERNATE_TAMPER_IO_MATCH_SHORT \
|
||||
0x00000000
|
||||
#define HIBERNATE_TAMPER_IO_MATCH_LONG \
|
||||
0x00000008
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Tamper log event flags.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define HIBERNATE_TAMPER_EVENT_0 \
|
||||
0x00000001
|
||||
#define HIBERNATE_TAMPER_EVENT_1 \
|
||||
0x00000002
|
||||
#define HIBERNATE_TAMPER_EVENT_2 \
|
||||
0x00000004
|
||||
#define HIBERNATE_TAMPER_EVENT_3 \
|
||||
0x00000008
|
||||
#define HIBERNATE_TAMPER_EVENT_EXT_OSC \
|
||||
0x00010000
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// API Function prototypes
|
||||
//
|
||||
//*****************************************************************************
|
||||
extern void HibernateGPIORetentionEnable(void);
|
||||
extern void HibernateGPIORetentionDisable(void);
|
||||
extern bool HibernateGPIORetentionGet(void);
|
||||
extern void HibernateEnableExpClk(uint32_t ui32HibClk);
|
||||
extern void HibernateDisable(void);
|
||||
extern void HibernateRTCEnable(void);
|
||||
extern void HibernateRTCDisable(void);
|
||||
extern void HibernateWakeSet(uint32_t ui32WakeFlags);
|
||||
extern uint32_t HibernateWakeGet(void);
|
||||
extern void HibernateLowBatSet(uint32_t ui32LowBatFlags);
|
||||
extern uint32_t HibernateLowBatGet(void);
|
||||
extern void HibernateRTCSet(uint32_t ui32RTCValue);
|
||||
extern uint32_t HibernateRTCGet(void);
|
||||
extern void HibernateRTCMatchSet(uint32_t ui32Match, uint32_t ui32Value);
|
||||
extern uint32_t HibernateRTCMatchGet(uint32_t ui32Match);
|
||||
extern void HibernateRTCTrimSet(uint32_t ui32Trim);
|
||||
extern uint32_t HibernateRTCTrimGet(void);
|
||||
extern void HibernateDataSet(uint32_t *pui32Data, uint32_t ui32Count);
|
||||
extern void HibernateDataGet(uint32_t *pui32Data, uint32_t ui32Count);
|
||||
extern void HibernateRequest(void);
|
||||
extern void HibernateIntEnable(uint32_t ui32IntFlags);
|
||||
extern void HibernateIntDisable(uint32_t ui32IntFlags);
|
||||
extern void HibernateIntRegister(void (*pfnHandler)(void));
|
||||
extern void HibernateIntUnregister(void);
|
||||
extern uint32_t HibernateIntStatus(bool bMasked);
|
||||
extern void HibernateIntClear(uint32_t ui32IntFlags);
|
||||
extern uint32_t HibernateIsActive(void);
|
||||
extern void HibernateRTCSSMatchSet(uint32_t ui32Match, uint32_t ui32Value);
|
||||
extern uint32_t HibernateRTCSSMatchGet(uint32_t ui32Match);
|
||||
extern uint32_t HibernateRTCSSGet(void);
|
||||
extern void HibernateClockConfig(uint32_t ui32Config);
|
||||
extern void HibernateBatCheckStart(void);
|
||||
extern uint32_t HibernateBatCheckDone(void);
|
||||
extern void HibernateCounterMode(uint32_t ui32Config);
|
||||
extern void HibernateCalendarSet(struct tm *psTime);
|
||||
extern int HibernateCalendarGet(struct tm *psTime);
|
||||
extern void HibernateCalendarMatchSet(uint32_t ui32Index, struct tm *psTime);
|
||||
extern void HibernateCalendarMatchGet(uint32_t ui32Index, struct tm *psTime);
|
||||
extern void HibernateTamperEnable(void);
|
||||
extern void HibernateTamperEventsConfig(uint32_t ui32Config);
|
||||
extern bool HibernateTamperEventsGet(uint32_t ui32Index, uint32_t *pui32RTC,
|
||||
uint32_t *pui32Event);
|
||||
extern void HibernateTamperEventsClear(void);
|
||||
extern void HibernateTamperEventsClearNoLock(void);
|
||||
extern void HibernateTamperUnLock(void);
|
||||
extern void HibernateTamperLock(void);
|
||||
extern void HibernateTamperDisable(void);
|
||||
extern void HibernateTamperIOEnable(uint32_t ui32Input, uint32_t ui32Config);
|
||||
extern void HibernateTamperIODisable(uint32_t ui32Input);
|
||||
extern uint32_t HibernateTamperStatusGet(void);
|
||||
extern void HibernateTamperExtOscRecover(void);
|
||||
extern bool HibernateTamperExtOscValid(void);
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Mark the end of the C bindings section for C++ compilers.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // __DRIVERLIB_HIBERNATE_H__
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,361 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// i2c.h - Prototypes for the I2C Driver.
|
||||
//
|
||||
// Copyright (c) 2005-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#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__
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,94 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// interrupt.h - Prototypes for the NVIC Interrupt Controller Driver.
|
||||
//
|
||||
// Copyright (c) 2005-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __DRIVERLIB_INTERRUPT_H__
|
||||
#define __DRIVERLIB_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
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// 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)
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Prototypes for the APIs.
|
||||
//
|
||||
//*****************************************************************************
|
||||
extern bool IntMasterEnable(void);
|
||||
extern bool IntMasterDisable(void);
|
||||
extern void IntRegister(uint32_t ui32Interrupt, void (*pfnHandler)(void));
|
||||
extern void IntUnregister(uint32_t ui32Interrupt);
|
||||
extern void IntPriorityGroupingSet(uint32_t ui32Bits);
|
||||
extern uint32_t IntPriorityGroupingGet(void);
|
||||
extern void IntPrioritySet(uint32_t ui32Interrupt,
|
||||
uint8_t ui8Priority);
|
||||
extern int32_t IntPriorityGet(uint32_t ui32Interrupt);
|
||||
extern void IntEnable(uint32_t ui32Interrupt);
|
||||
extern void IntDisable(uint32_t ui32Interrupt);
|
||||
extern uint32_t IntIsEnabled(uint32_t ui32Interrupt);
|
||||
extern void IntPendSet(uint32_t ui32Interrupt);
|
||||
extern void IntPendClear(uint32_t ui32Interrupt);
|
||||
extern void IntPriorityMaskSet(uint32_t ui32PriorityMask);
|
||||
extern uint32_t IntPriorityMaskGet(void);
|
||||
extern void IntTrigger(uint32_t ui32Interrupt);
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Mark the end of the C bindings section for C++ compilers.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // __DRIVERLIB_INTERRUPT_H__
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,487 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// lcd.h - Defines and Macros for the LCD Controller module.
|
||||
//
|
||||
// Copyright (c) 2012-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __DRIVERLIB_LCD_H__
|
||||
#define __DRIVERLIB_LCD_H__
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! \addtogroup lcd_api
|
||||
//! @{
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// If building with a C++ compiler, make all of the definitions in this header
|
||||
// have a C binding.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! This macro can be used to convert a 24-bit RGB color value as used by the
|
||||
//! TivaWare Graphics Library into a 12-bit LCD controller color palette
|
||||
//! entry.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define PAL_FROM_RGB(ui32RGBColor) (((ui32RGBColor & 0xF0) >> 4) | \
|
||||
((ui32RGBColor & 0xF000) >> 8) | \
|
||||
((ui32RGBColor & 0xF00000) >> 12))
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! This macro can be used to convert from time in microseconds to periods of
|
||||
//! the supplied clock in Hertz as required when setting up the LIDD and raster
|
||||
//! timing structures. The calculation will round such that the number of
|
||||
//! cycles returned represents no longer a time than specified in the
|
||||
//! ui32Time_uS parameter. Values of ui32Time_uS less than or equal to
|
||||
//! 4294967uS (4.29 seconds) are supported by the macro. Larger values will
|
||||
//! cause arithmetic overflow and yield incorrect values. It is further
|
||||
//! assumed that ui32ClockFreq is a non-zero multiple of 1000000 (1MHz).
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CYCLES_FROM_TIME_US(ui32ClockFreq, ui32Time_uS) \
|
||||
(((ui32Time_uS) == 0) ? 0 : \
|
||||
(((ui32ClockFreq) / 1000000) * ((((ui32Time_uS) * 1000) - 1) / 1000)) + 1)
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! This macro can be used to convert from time in nanoseconds to periods of
|
||||
//! the supplied clock in Hertz as required when setting up the LIDD and raster
|
||||
//! timing structures. The calculation will round such that the number of
|
||||
//! cycles returned represents no longer a time than specified in the
|
||||
//! ui32Time_nS parameter. Values of ui32Time_nS less than or equal to
|
||||
//! 35791394 (35.79 milliseconds) are supported by the macro. Larger values
|
||||
//! will cause arithmetic overflow and yield incorrect values. It is further
|
||||
//! assumed that ui32ClockFreq is a non-zero multiple of 1000000 (1MHz).
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CYCLES_FROM_TIME_NS(ui32ClockFreq, ui32Time_nS) \
|
||||
(((ui32Time_nS) == 0) ? 0 : \
|
||||
((((((ui32ClockFreq) / 1000000) * ((ui32Time_nS) - 1)) / 1000)) + 1))
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! A structure containing timing parameters for the LIDD (LCD Interface
|
||||
//! Display Driver) interface. This is used with the LCDIDDTimingSet function.
|
||||
//
|
||||
//*****************************************************************************
|
||||
typedef struct
|
||||
{
|
||||
//
|
||||
//! Write Strobe Set-Up cycles. When performing a write access, this
|
||||
//! field defines the number of MCLK cycles that Data Bus/Pad Output
|
||||
//! Enable, ALE, the Direction bit, and Chip Select have to be ready before
|
||||
//! the Write Strobe is asserted. Valid values are from 0 to 31.
|
||||
//
|
||||
uint8_t ui8WSSetup;
|
||||
|
||||
//
|
||||
//! Write Strobe Duration cycles. Field value defines the number of MCLK
|
||||
//! cycles for which the Write Strobe is held active when performing a
|
||||
//! write access. Valid values are from 1 to 63.
|
||||
//
|
||||
uint8_t ui8WSDuration;
|
||||
|
||||
//
|
||||
//! Write Strobe Hold cycles. Field value defines the number of MCLK
|
||||
//! cycles for which Data Bus/Pad Output Enable, ALE, the Direction bit,
|
||||
//! and Chip Select are held after the Write Strobe is deasserted when
|
||||
//! performing a write access. Valid values are from 1 to 15.
|
||||
//
|
||||
uint8_t ui8WSHold;
|
||||
|
||||
//
|
||||
//! Read Strobe Set-Up cycles. When performing a read access, this field
|
||||
//! defines the number of MCLK cycles that Data Bus/Pad Output Enable, ALE,
|
||||
//! the Direction bit, and Chip Select have to be ready before the Read
|
||||
//! Strobe is asserted. Valid values are from 0 to 31.
|
||||
//
|
||||
uint8_t ui8RSSetup;
|
||||
|
||||
//
|
||||
//! Read Strobe Duration cycles. Field value defines the number of MCLK
|
||||
//! cycles for which the Read Strobe is held active when performing a read
|
||||
//! access. Valid values are from 1 to 63.
|
||||
//
|
||||
uint8_t ui8RSDuration;
|
||||
|
||||
//
|
||||
//! Read Strobe Hold cycles. Field value defines the number of MCLK cycles
|
||||
//! for which Data Bus/Pad Output Enable, ALE, the Direction bit, and Chip
|
||||
//! Select are held after the Read Strobe is deasserted when performing a
|
||||
//! read access. Valid values are from 1 to 15.
|
||||
//
|
||||
uint8_t ui8RSHold;
|
||||
|
||||
//
|
||||
//! Field value defines the number of MCLK cycles between the end of one
|
||||
//! device access and the start of another device access using the same
|
||||
//! Chip Select unless the two accesses are both Reads. In this case,
|
||||
//! this delay is not incurred. Valid vales are from 1 to 4.
|
||||
//
|
||||
uint8_t ui8DelayCycles;
|
||||
}
|
||||
tLCDIDDTiming;
|
||||
|
||||
//
|
||||
// Values which can be ORed together within the ui32Flags field of the
|
||||
// tLCDRasterTiming structure.
|
||||
//
|
||||
#define RASTER_TIMING_SYNCS_OPPOSITE_PIXCLK \
|
||||
0x00000000
|
||||
#define RASTER_TIMING_SYNCS_ON_RISING_PIXCLK \
|
||||
0x02000000
|
||||
#define RASTER_TIMING_SYNCS_ON_FALLING_PIXCLK \
|
||||
0x03000000
|
||||
#define RASTER_TIMING_ACTIVE_HIGH_OE \
|
||||
0x00000000
|
||||
#define RASTER_TIMING_ACTIVE_LOW_OE \
|
||||
0x00800000
|
||||
#define RASTER_TIMING_ACTIVE_HIGH_PIXCLK \
|
||||
0x00000000
|
||||
#define RASTER_TIMING_ACTIVE_LOW_PIXCLK \
|
||||
0x00400000
|
||||
#define RASTER_TIMING_ACTIVE_HIGH_HSYNC \
|
||||
0x00000000
|
||||
#define RASTER_TIMING_ACTIVE_LOW_HSYNC \
|
||||
0x00200000
|
||||
#define RASTER_TIMING_ACTIVE_HIGH_VSYNC \
|
||||
0x00000000
|
||||
#define RASTER_TIMING_ACTIVE_LOW_VSYNC \
|
||||
0x00100000
|
||||
|
||||
//
|
||||
//! A structure containing timing parameters for the raster interface. This is
|
||||
//! used with the LCDRasterTimingSet function.
|
||||
//
|
||||
typedef struct
|
||||
{
|
||||
//
|
||||
//! Flags configuring the polarity and active edges of the various signals
|
||||
//! in the raster interface. This field is comprised of a logical OR of
|
||||
//! the labels with prefix ``RASTER_TIMING_''.
|
||||
//
|
||||
uint32_t ui32Flags;
|
||||
|
||||
//
|
||||
//! The number of pixels contained within each line on the LCD display.
|
||||
//! Valid values are multiple of 16 less than or equal to 2048.
|
||||
//
|
||||
uint16_t ui16PanelWidth;
|
||||
|
||||
//
|
||||
//! The number of lines on the LCD display. Valid values are from 1 to
|
||||
//! 2048.
|
||||
//
|
||||
uint16_t ui16PanelHeight;
|
||||
|
||||
//
|
||||
//! A value from 1 to 1024 that specifies the number of pixel clock periods
|
||||
//! to add to the end of each line after active video has ended.
|
||||
//
|
||||
uint16_t ui16HFrontPorch;
|
||||
|
||||
//
|
||||
//! A value from 1 to 1024 that specifies the number of pixel clock periods
|
||||
//! to add to the beginning of a line before active video is asserted.
|
||||
//
|
||||
uint16_t ui16HBackPorch;
|
||||
|
||||
//
|
||||
//! A value from 1 to 1024 that specifies the number of pixel clock periods
|
||||
//! to pulse the line clock at the end of each line.
|
||||
//
|
||||
uint16_t ui16HSyncWidth;
|
||||
|
||||
//
|
||||
//! A value from 0 to 255 that specifies the number of line clock periods
|
||||
//! to add to the end of each frame after the last active line.
|
||||
//
|
||||
uint8_t ui8VFrontPorch;
|
||||
|
||||
//
|
||||
//! A value from 0 to 255 that specifies the number of line clock periods
|
||||
//! to add to the beginning of a frame before the first active line is
|
||||
//! output to the display.
|
||||
//
|
||||
uint8_t ui8VBackPorch;
|
||||
|
||||
//
|
||||
//! In active mode, a value from 1 to 64 that specifies the number of
|
||||
//! line clock periods to set the lcd_fp pin active at the end of each
|
||||
//! frame after the vertical front porch period elapses. The number of
|
||||
//! The frame clock is used as the VSYNC signal in active mode.
|
||||
//!
|
||||
//! In passive mode, a value from 1 to 64 that specifies the number of
|
||||
//! extra line clock periods to insert after the vertical front porch
|
||||
//! period has elapsed. Note that the width of lcd_fp is not affected by
|
||||
//! this value in passive mode.
|
||||
//
|
||||
uint8_t ui8VSyncWidth;
|
||||
|
||||
//
|
||||
//! A value from 0 to 255 that specifies the number of line clocks to
|
||||
//! count before transitioning the AC Bias pin. This pin is used to
|
||||
//! periodically invert the polarity of the power supply to prevent DC
|
||||
//! charge build-up within the display.
|
||||
//
|
||||
uint8_t ui8ACBiasLineCount;
|
||||
}
|
||||
tLCDRasterTiming;
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Possible values for the ui8Mode parameter to LCDModeSet(). The label
|
||||
// LCD_MODE_AUTO_UFLOW_RESTART may be ORed with either of the other two.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define LCD_MODE_LIDD ((uint8_t)0x00)
|
||||
#define LCD_MODE_RASTER ((uint8_t)0x01)
|
||||
#define LCD_MODE_AUTO_UFLOW_RESTART \
|
||||
((uint8_t)0x02)
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values used to construct the ui32Config parameter to LCDIDDConfigSet().
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define LIDD_CONFIG_SYNC_MPU68 0x00000000
|
||||
#define LIDD_CONFIG_ASYNC_MPU68 0x00000001
|
||||
#define LIDD_CONFIG_SYNC_MPU80 0x00000002
|
||||
#define LIDD_CONFIG_ASYNC_MPU80 0x00000003
|
||||
#define LIDD_CONFIG_ASYNC_HITACHI \
|
||||
0x00000004
|
||||
#define LIDD_CONFIG_INVERT_ALE 0x00000008
|
||||
#define LIDD_CONFIG_INVERT_RS_EN \
|
||||
0x00000010
|
||||
#define LIDD_CONFIG_INVERT_WS_DIR \
|
||||
0x00000020
|
||||
#define LIDD_CONFIG_INVERT_CS0 0x00000040
|
||||
#define LIDD_CONFIG_INVERT_CS1 0x00000080
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values used to construct the ui32Config parameter to
|
||||
// LCDRasterConfigSet(). Valid parameters contain one of the RASTER_FMT_xxx
|
||||
// labels optionally ORed with the other flags. Only one of
|
||||
// RASTER_LOAD_DATA_ONLY and RASTER_LOAD_PALETTE_ONLY may be specified (if
|
||||
// neither is specified, the controller will load both palette and data when
|
||||
// scanning out the frame buffer).
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define RASTER_FMT_ACTIVE_24BPP_PACKED \
|
||||
0x02000080
|
||||
#define RASTER_FMT_ACTIVE_24BPP_UNPACKED \
|
||||
0x06000080
|
||||
#define RASTER_FMT_ACTIVE_PALETTIZED_12BIT \
|
||||
0x00000080
|
||||
#define RASTER_FMT_ACTIVE_PALETTIZED_16BIT \
|
||||
0x00800080
|
||||
#define RASTER_FMT_PASSIVE_MONO_4PIX \
|
||||
0x00000002
|
||||
#define RASTER_FMT_PASSIVE_MONO_8PIX \
|
||||
0x00000202
|
||||
#define RASTER_FMT_PASSIVE_PALETTIZED \
|
||||
0x00000000
|
||||
#define RASTER_FMT_PASSIVE_COLOR_12BIT \
|
||||
0x00000000
|
||||
#define RASTER_FMT_PASSIVE_COLOR_16BIT \
|
||||
0x01000000
|
||||
#define RASTER_ACTVID_DURING_BLANK \
|
||||
0x08000000
|
||||
#define RASTER_NIBBLE_MODE_ENABLED \
|
||||
0x00400000
|
||||
#define RASTER_LOAD_DATA_ONLY 0x00200000
|
||||
#define RASTER_LOAD_PALETTE_ONLY \
|
||||
0x00100000
|
||||
#define RASTER_READ_ORDER_REVERSED \
|
||||
0x00000100
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Interrupt sources for the LCD controller. These may be ORed together and
|
||||
// passed to LCDIntEnable(), LCDIntDisable() and LCDIntClear(). They are also
|
||||
// returned by LCDIntStatus().
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define LCD_INT_DMA_DONE 0x00000001
|
||||
#define LCD_INT_RASTER_FRAME_DONE \
|
||||
0x00000002
|
||||
#define LCD_INT_SYNC_LOST 0x00000004
|
||||
#define LCD_INT_AC_BIAS_CNT 0x00000008
|
||||
#define LCD_INT_UNDERFLOW 0x00000020
|
||||
#define LCD_INT_PAL_LOAD 0x00000040
|
||||
#define LCD_INT_EOF0 0x00000100
|
||||
#define LCD_INT_EOF1 0x00000200
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Configuration values used with LCDDMAConfigSet().
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define LCD_DMA_FIFORDY_8_WORDS 0x00000000
|
||||
#define LCD_DMA_FIFORDY_16_WORDS \
|
||||
0x00000100
|
||||
#define LCD_DMA_FIFORDY_32_WORDS \
|
||||
0x00000200
|
||||
#define LCD_DMA_FIFORDY_64_WORDS \
|
||||
0x00000300
|
||||
#define LCD_DMA_FIFORDY_128_WORDS \
|
||||
0x00000400
|
||||
#define LCD_DMA_FIFORDY_256_WORDS \
|
||||
0x00000500
|
||||
#define LCD_DMA_FIFORDY_512_WORDS \
|
||||
0x00000600
|
||||
#define LCD_DMA_BURST_1 0x00000010
|
||||
#define LCD_DMA_BURST_2 0x00000010
|
||||
#define LCD_DMA_BURST_4 0x00000020
|
||||
#define LCD_DMA_BURST_8 0x00000030
|
||||
#define LCD_DMA_BURST_16 0x00000040
|
||||
#define LCD_DMA_BYTE_ORDER_0123 0x00000000
|
||||
#define LCD_DMA_BYTE_ORDER_1023 0x00000008
|
||||
#define LCD_DMA_BYTE_ORDER_3210 0x00000002
|
||||
#define LCD_DMA_BYTE_ORDER_2301 0x0000000A
|
||||
#define LCD_DMA_PING_PONG 0x00000001
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Type values used with LCDRasterPaletteSet().
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define LCD_PALETTE_TYPE_1BPP 0x00000000
|
||||
#define LCD_PALETTE_TYPE_2BPP 0x00001000
|
||||
#define LCD_PALETTE_TYPE_4BPP 0x00002000
|
||||
#define LCD_PALETTE_TYPE_8BPP 0x00003000
|
||||
#define LCD_PALETTE_TYPE_DIRECT 0x00004000
|
||||
#define LCD_PALETTE_SRC_24BIT 0x80000000
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Flags used in the ui32Clocks parameter to LCDClockReset().
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define LCD_CLOCK_MAIN 0x00000008
|
||||
#define LCD_CLOCK_DMA 0x00000004
|
||||
#define LCD_CLOCK_LIDD 0x00000002
|
||||
#define LCD_CLOCK_CORE 0x00000001
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Flags used in with LCDSubPanelConfigSet().
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define LCD_SUBPANEL_AT_TOP 0x20000000
|
||||
#define LCD_SUBPANEL_AT_BOTTOM 0x00000000
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Close the Doxygen group.
|
||||
//! @}
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Function Prototypes.
|
||||
//
|
||||
//*****************************************************************************
|
||||
extern uint32_t LCDModeSet(uint32_t ui32Base, uint8_t ui8Mode,
|
||||
uint32_t ui32PixClk, uint32_t ui32SysClk);
|
||||
extern void LCDClockReset(uint32_t ui32Base, uint32_t ui32Clocks);
|
||||
extern void LCDIDDConfigSet(uint32_t ui32Base, uint32_t ui32Config);
|
||||
extern void LCDIDDTimingSet(uint32_t ui32Base, uint32_t ui32CS,
|
||||
const tLCDIDDTiming *pTiming);
|
||||
extern void LCDIDDDMADisable(uint32_t ui32Base);
|
||||
extern void LCDIDDCommandWrite(uint32_t ui32Base, uint32_t ui32CS,
|
||||
uint16_t ui16Cmd);
|
||||
extern void LCDIDDDataWrite(uint32_t ui32Base, uint32_t ui32CS,
|
||||
uint16_t ui16Data);
|
||||
extern void LCDIDDIndexedWrite(uint32_t ui32Base, uint32_t ui32CS,
|
||||
uint16_t ui16Addr, uint16_t ui16Data);
|
||||
extern uint16_t LCDIDDStatusRead(uint32_t ui32Base, uint32_t ui32CS);
|
||||
extern uint16_t LCDIDDDataRead(uint32_t ui32Base, uint32_t ui32CS);
|
||||
extern uint16_t LCDIDDIndexedRead(uint32_t ui32Base, uint32_t ui32CS,
|
||||
uint16_t ui16Addr);
|
||||
extern void LCDIDDDMAWrite(uint32_t ui32Base, uint32_t ui32CS,
|
||||
const uint32_t *pui32Data, uint32_t ui32Count);
|
||||
extern void LCDRasterConfigSet(uint32_t ui32Base, uint32_t ui32Config,
|
||||
uint8_t ui8PalLoadDelay);
|
||||
extern void LCDRasterTimingSet(uint32_t ui32Base,
|
||||
const tLCDRasterTiming *pTiming);
|
||||
extern void LCDRasterACBiasIntCountSet(uint32_t ui32Base, uint8_t ui8Count);
|
||||
extern void LCDRasterEnable(uint32_t ui32Base);
|
||||
extern bool LCDRasterEnabled(uint32_t ui32Base);
|
||||
extern void LCDRasterDisable(uint32_t ui32Base);
|
||||
extern void LCDRasterSubPanelConfigSet(uint32_t ui32Base, uint32_t ui32Flags,
|
||||
uint32_t ui32BottomLines,
|
||||
uint32_t ui32DefaultPixel);
|
||||
extern void LCDRasterSubPanelEnable(uint32_t ui32Base);
|
||||
extern void LCDRasterSubPanelDisable(uint32_t ui32Base);
|
||||
extern void LCDDMAConfigSet(uint32_t ui32Base, uint32_t ui32Config);
|
||||
extern void LCDRasterPaletteSet(uint32_t ui32Base, uint32_t ui32Type,
|
||||
uint32_t *pui32PalAddr,
|
||||
const uint32_t *pui32SrcColors,
|
||||
uint32_t ui32Start,
|
||||
uint32_t ui32Count);
|
||||
extern void LCDRasterFrameBufferSet(uint32_t ui32Base, uint8_t ui8Buffer,
|
||||
uint32_t *pui32Addr,
|
||||
uint32_t ui32NumBytes);
|
||||
extern void LCDIntEnable(uint32_t ui32Base, uint32_t ui32IntFlags);
|
||||
extern void LCDIntDisable(uint32_t ui32Base, uint32_t ui32IntFlags);
|
||||
extern uint32_t LCDIntStatus(uint32_t ui32Base, bool bMasked);
|
||||
extern void LCDIntClear(uint32_t ui32Base, uint32_t ui32IntFlags);
|
||||
extern void LCDIntRegister(uint32_t ui32Base, void (*pfnHandler)(void));
|
||||
extern void LCDIntUnregister(uint32_t ui32Base);
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Mark the end of the C bindings section for C++ compilers.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // __DRIVERLIB_LCD_H__
|
|
@ -0,0 +1,459 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// mpu.c - Driver for the Cortex-M3 memory protection unit (MPU).
|
||||
//
|
||||
// Copyright (c) 2007-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! \addtogroup mpu_api
|
||||
//! @{
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include "inc/hw_ints.h"
|
||||
#include "inc/hw_nvic.h"
|
||||
#include "inc/hw_types.h"
|
||||
#include "driverlib/debug.h"
|
||||
#include "driverlib/interrupt.h"
|
||||
#include "driverlib/mpu.h"
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Enables and configures the MPU for use.
|
||||
//!
|
||||
//! \param ui32MPUConfig is the logical OR of the possible configurations.
|
||||
//!
|
||||
//! This function enables the Cortex-M memory protection unit. It also
|
||||
//! configures the default behavior when in privileged mode and while handling
|
||||
//! a hard fault or NMI. Prior to enabling the MPU, at least one region must
|
||||
//! be set by calling MPURegionSet() or else by enabling the default region for
|
||||
//! privileged mode by passing the \b MPU_CONFIG_PRIV_DEFAULT flag to
|
||||
//! MPUEnable(). Once the MPU is enabled, a memory management fault is
|
||||
//! generated for memory access violations.
|
||||
//!
|
||||
//! The \e ui32MPUConfig parameter should be the logical OR of any of the
|
||||
//! following:
|
||||
//!
|
||||
//! - \b MPU_CONFIG_PRIV_DEFAULT enables the default memory map when in
|
||||
//! privileged mode and when no other regions are defined. If this option
|
||||
//! is not enabled, then there must be at least one valid region already
|
||||
//! defined when the MPU is enabled.
|
||||
//! - \b MPU_CONFIG_HARDFLT_NMI enables the MPU while in a hard fault or NMI
|
||||
//! exception handler. If this option is not enabled, then the MPU is
|
||||
//! disabled while in one of these exception handlers and the default
|
||||
//! memory map is applied.
|
||||
//! - \b MPU_CONFIG_NONE chooses none of the above options. In this case,
|
||||
//! no default memory map is provided in privileged mode, and the MPU is not
|
||||
//! enabled in the fault handlers.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
MPUEnable(uint32_t ui32MPUConfig)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT(!(ui32MPUConfig & ~(MPU_CONFIG_PRIV_DEFAULT |
|
||||
MPU_CONFIG_HARDFLT_NMI)));
|
||||
|
||||
//
|
||||
// Set the MPU control bits according to the flags passed by the user,
|
||||
// and also set the enable bit.
|
||||
//
|
||||
HWREG(NVIC_MPU_CTRL) = ui32MPUConfig | NVIC_MPU_CTRL_ENABLE;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Disables the MPU for use.
|
||||
//!
|
||||
//! This function disables the Cortex-M memory protection unit. When the
|
||||
//! MPU is disabled, the default memory map is used and memory management
|
||||
//! faults are not generated.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
MPUDisable(void)
|
||||
{
|
||||
//
|
||||
// Turn off the MPU enable bit.
|
||||
//
|
||||
HWREG(NVIC_MPU_CTRL) &= ~NVIC_MPU_CTRL_ENABLE;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Gets the count of regions supported by the MPU.
|
||||
//!
|
||||
//! This function is used to get the total number of regions that are supported
|
||||
//! by the MPU, including regions that are already programmed.
|
||||
//!
|
||||
//! \return The number of memory protection regions that are available
|
||||
//! for programming using MPURegionSet().
|
||||
//
|
||||
//*****************************************************************************
|
||||
uint32_t
|
||||
MPURegionCountGet(void)
|
||||
{
|
||||
//
|
||||
// Read the DREGION field of the MPU type register and mask off
|
||||
// the bits of interest to get the count of regions.
|
||||
//
|
||||
return((HWREG(NVIC_MPU_TYPE) & NVIC_MPU_TYPE_DREGION_M) >>
|
||||
NVIC_MPU_TYPE_DREGION_S);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Enables a specific region.
|
||||
//!
|
||||
//! \param ui32Region is the region number to enable.
|
||||
//!
|
||||
//! This function is used to enable a memory protection region. The region
|
||||
//! should already be configured with the MPURegionSet() function. Once
|
||||
//! enabled, the memory protection rules of the region are applied and access
|
||||
//! violations cause a memory management fault.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
MPURegionEnable(uint32_t ui32Region)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT(ui32Region < 8);
|
||||
|
||||
//
|
||||
// Select the region to modify.
|
||||
//
|
||||
HWREG(NVIC_MPU_NUMBER) = ui32Region;
|
||||
|
||||
//
|
||||
// Modify the enable bit in the region attributes.
|
||||
//
|
||||
HWREG(NVIC_MPU_ATTR) |= NVIC_MPU_ATTR_ENABLE;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Disables a specific region.
|
||||
//!
|
||||
//! \param ui32Region is the region number to disable.
|
||||
//!
|
||||
//! This function is used to disable a previously enabled memory protection
|
||||
//! region. The region remains configured if it is not overwritten with
|
||||
//! another call to MPURegionSet(), and can be enabled again by calling
|
||||
//! MPURegionEnable().
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
MPURegionDisable(uint32_t ui32Region)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT(ui32Region < 8);
|
||||
|
||||
//
|
||||
// Select the region to modify.
|
||||
//
|
||||
HWREG(NVIC_MPU_NUMBER) = ui32Region;
|
||||
|
||||
//
|
||||
// Modify the enable bit in the region attributes.
|
||||
//
|
||||
HWREG(NVIC_MPU_ATTR) &= ~NVIC_MPU_ATTR_ENABLE;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Sets up the access rules for a specific region.
|
||||
//!
|
||||
//! \param ui32Region is the region number to set up.
|
||||
//! \param ui32Addr is the base address of the region. It must be aligned
|
||||
//! according to the size of the region specified in ui32Flags.
|
||||
//! \param ui32Flags is a set of flags to define the attributes of the region.
|
||||
//!
|
||||
//! This function sets up the protection rules for a region. The region has
|
||||
//! a base address and a set of attributes including the size. The base
|
||||
//! address parameter, \e ui32Addr, must be aligned according to the size, and
|
||||
//! the size must be a power of 2.
|
||||
//!
|
||||
//! The \e ui32Flags parameter is the logical OR of all of the attributes
|
||||
//! of the region. It is a combination of choices for region size,
|
||||
//! execute permission, read/write permissions, disabled sub-regions,
|
||||
//! and a flag to determine if the region is enabled.
|
||||
//!
|
||||
//! The size flag determines the size of a region and must be one of the
|
||||
//! following:
|
||||
//!
|
||||
//! - \b MPU_RGN_SIZE_32B
|
||||
//! - \b MPU_RGN_SIZE_64B
|
||||
//! - \b MPU_RGN_SIZE_128B
|
||||
//! - \b MPU_RGN_SIZE_256B
|
||||
//! - \b MPU_RGN_SIZE_512B
|
||||
//! - \b MPU_RGN_SIZE_1K
|
||||
//! - \b MPU_RGN_SIZE_2K
|
||||
//! - \b MPU_RGN_SIZE_4K
|
||||
//! - \b MPU_RGN_SIZE_8K
|
||||
//! - \b MPU_RGN_SIZE_16K
|
||||
//! - \b MPU_RGN_SIZE_32K
|
||||
//! - \b MPU_RGN_SIZE_64K
|
||||
//! - \b MPU_RGN_SIZE_128K
|
||||
//! - \b MPU_RGN_SIZE_256K
|
||||
//! - \b MPU_RGN_SIZE_512K
|
||||
//! - \b MPU_RGN_SIZE_1M
|
||||
//! - \b MPU_RGN_SIZE_2M
|
||||
//! - \b MPU_RGN_SIZE_4M
|
||||
//! - \b MPU_RGN_SIZE_8M
|
||||
//! - \b MPU_RGN_SIZE_16M
|
||||
//! - \b MPU_RGN_SIZE_32M
|
||||
//! - \b MPU_RGN_SIZE_64M
|
||||
//! - \b MPU_RGN_SIZE_128M
|
||||
//! - \b MPU_RGN_SIZE_256M
|
||||
//! - \b MPU_RGN_SIZE_512M
|
||||
//! - \b MPU_RGN_SIZE_1G
|
||||
//! - \b MPU_RGN_SIZE_2G
|
||||
//! - \b MPU_RGN_SIZE_4G
|
||||
//!
|
||||
//! The execute permission flag must be one of the following:
|
||||
//!
|
||||
//! - \b MPU_RGN_PERM_EXEC enables the region for execution of code
|
||||
//! - \b MPU_RGN_PERM_NOEXEC disables the region for execution of code
|
||||
//!
|
||||
//! The read/write access permissions are applied separately for the
|
||||
//! privileged and user modes. The read/write access flags must be one
|
||||
//! of the following:
|
||||
//!
|
||||
//! - \b MPU_RGN_PERM_PRV_NO_USR_NO - no access in privileged or user mode
|
||||
//! - \b MPU_RGN_PERM_PRV_RW_USR_NO - privileged read/write, user no access
|
||||
//! - \b MPU_RGN_PERM_PRV_RW_USR_RO - privileged read/write, user read-only
|
||||
//! - \b MPU_RGN_PERM_PRV_RW_USR_RW - privileged read/write, user read/write
|
||||
//! - \b MPU_RGN_PERM_PRV_RO_USR_NO - privileged read-only, user no access
|
||||
//! - \b MPU_RGN_PERM_PRV_RO_USR_RO - privileged read-only, user read-only
|
||||
//!
|
||||
//! The region is automatically divided into 8 equally-sized sub-regions by
|
||||
//! the MPU. Sub-regions can only be used in regions of size 256 bytes
|
||||
//! or larger. Any of these 8 sub-regions can be disabled, allowing for
|
||||
//! creation of ``holes'' in a region which can be left open, or overlaid
|
||||
//! by another region with different attributes. Any of the 8 sub-regions
|
||||
//! can be disabled with a logical OR of any of the following flags:
|
||||
//!
|
||||
//! - \b MPU_SUB_RGN_DISABLE_0
|
||||
//! - \b MPU_SUB_RGN_DISABLE_1
|
||||
//! - \b MPU_SUB_RGN_DISABLE_2
|
||||
//! - \b MPU_SUB_RGN_DISABLE_3
|
||||
//! - \b MPU_SUB_RGN_DISABLE_4
|
||||
//! - \b MPU_SUB_RGN_DISABLE_5
|
||||
//! - \b MPU_SUB_RGN_DISABLE_6
|
||||
//! - \b MPU_SUB_RGN_DISABLE_7
|
||||
//!
|
||||
//! Finally, the region can be initially enabled or disabled with one of
|
||||
//! the following flags:
|
||||
//!
|
||||
//! - \b MPU_RGN_ENABLE
|
||||
//! - \b MPU_RGN_DISABLE
|
||||
//!
|
||||
//! As an example, to set a region with the following attributes: size of
|
||||
//! 32 KB, execution enabled, read-only for both privileged and user, one
|
||||
//! sub-region disabled, and initially enabled; the \e ui32Flags parameter
|
||||
//! would have the following value:
|
||||
//!
|
||||
//! <code>
|
||||
//! (MPU_RGN_SIZE_32K | MPU_RGN_PERM_EXEC | MPU_RGN_PERM_PRV_RO_USR_RO |
|
||||
//! MPU_SUB_RGN_DISABLE_2 | MPU_RGN_ENABLE)
|
||||
//! </code>
|
||||
//!
|
||||
//! \note This function writes to multiple registers and is not protected
|
||||
//! from interrupts. It is possible that an interrupt which accesses a
|
||||
//! region may occur while that region is in the process of being changed.
|
||||
//! The safest way to handle this is to disable a region before changing it.
|
||||
//! Refer to the discussion of this in the API Detailed Description section.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
MPURegionSet(uint32_t ui32Region, uint32_t ui32Addr, uint32_t ui32Flags)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT(ui32Region < 8);
|
||||
ASSERT(ui32Addr ==
|
||||
(ui32Addr & ~0 << (((ui32Flags & NVIC_MPU_ATTR_SIZE_M) >> 1) + 1)));
|
||||
|
||||
//
|
||||
// Program the base address, use the region field to select the
|
||||
// region at the same time.
|
||||
//
|
||||
HWREG(NVIC_MPU_BASE) = ui32Addr | ui32Region | NVIC_MPU_BASE_VALID;
|
||||
|
||||
//
|
||||
// Program the region attributes. Set the TEX field and the S, C,
|
||||
// and B bits to fixed values that are suitable for all Tiva C and
|
||||
// E Series memory.
|
||||
//
|
||||
HWREG(NVIC_MPU_ATTR) = ((ui32Flags & ~(NVIC_MPU_ATTR_TEX_M |
|
||||
NVIC_MPU_ATTR_CACHEABLE)) |
|
||||
NVIC_MPU_ATTR_SHAREABLE | NVIC_MPU_ATTR_BUFFRABLE);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Gets the current settings for a specific region.
|
||||
//!
|
||||
//! \param ui32Region is the region number to get.
|
||||
//! \param pui32Addr points to storage for the base address of the region.
|
||||
//! \param pui32Flags points to the attribute flags for the region.
|
||||
//!
|
||||
//! This function retrieves the configuration of a specific region. The
|
||||
//! meanings and format of the parameters is the same as that of the
|
||||
//! MPURegionSet() function.
|
||||
//!
|
||||
//! This function can be used to save the configuration of a region for later
|
||||
//! use with the MPURegionSet() function. The region's enable state is
|
||||
//! preserved in the attributes that are saved.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
MPURegionGet(uint32_t ui32Region, uint32_t *pui32Addr, uint32_t *pui32Flags)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT(ui32Region < 8);
|
||||
ASSERT(pui32Addr);
|
||||
ASSERT(pui32Flags);
|
||||
|
||||
//
|
||||
// Select the region to get.
|
||||
//
|
||||
HWREG(NVIC_MPU_NUMBER) = ui32Region;
|
||||
|
||||
//
|
||||
// Read and store the base address for the region.
|
||||
//
|
||||
*pui32Addr = HWREG(NVIC_MPU_BASE) & NVIC_MPU_BASE_ADDR_M;
|
||||
|
||||
//
|
||||
// Read and store the region attributes.
|
||||
//
|
||||
*pui32Flags = HWREG(NVIC_MPU_ATTR);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Registers an interrupt handler for the memory management fault.
|
||||
//!
|
||||
//! \param pfnHandler is a pointer to the function to be called when the
|
||||
//! memory management fault occurs.
|
||||
//!
|
||||
//! This function sets and enables the handler to be called when the MPU
|
||||
//! generates a memory management fault due to a protection region access
|
||||
//! violation.
|
||||
//!
|
||||
//! \sa IntRegister() for important information about registering interrupt
|
||||
//! handlers.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
MPUIntRegister(void (*pfnHandler)(void))
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT(pfnHandler);
|
||||
|
||||
//
|
||||
// Register the interrupt handler.
|
||||
//
|
||||
IntRegister(FAULT_MPU, pfnHandler);
|
||||
|
||||
//
|
||||
// Enable the memory management fault.
|
||||
//
|
||||
IntEnable(FAULT_MPU);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Unregisters an interrupt handler for the memory management fault.
|
||||
//!
|
||||
//! This function disables and clears the handler to be called when a
|
||||
//! memory management fault occurs.
|
||||
//!
|
||||
//! \sa IntRegister() for important information about registering interrupt
|
||||
//! handlers.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
MPUIntUnregister(void)
|
||||
{
|
||||
//
|
||||
// Disable the interrupt.
|
||||
//
|
||||
IntDisable(FAULT_MPU);
|
||||
|
||||
//
|
||||
// Unregister the interrupt handler.
|
||||
//
|
||||
IntUnregister(FAULT_MPU);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Close the Doxygen group.
|
||||
//! @}
|
||||
//
|
||||
//*****************************************************************************
|
|
@ -0,0 +1,162 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// mpu.h - Defines and Macros for the memory protection unit.
|
||||
//
|
||||
// Copyright (c) 2005-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __DRIVERLIB_MPU_H__
|
||||
#define __DRIVERLIB_MPU_H__
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// If building with a C++ compiler, make all of the definitions in this header
|
||||
// have a C binding.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Flags that can be passed to MPUEnable.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define MPU_CONFIG_PRIV_DEFAULT 4
|
||||
#define MPU_CONFIG_HARDFLT_NMI 2
|
||||
#define MPU_CONFIG_NONE 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Flags for the region size to be passed to MPURegionSet.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define MPU_RGN_SIZE_32B (4 << 1)
|
||||
#define MPU_RGN_SIZE_64B (5 << 1)
|
||||
#define MPU_RGN_SIZE_128B (6 << 1)
|
||||
#define MPU_RGN_SIZE_256B (7 << 1)
|
||||
#define MPU_RGN_SIZE_512B (8 << 1)
|
||||
|
||||
#define MPU_RGN_SIZE_1K (9 << 1)
|
||||
#define MPU_RGN_SIZE_2K (10 << 1)
|
||||
#define MPU_RGN_SIZE_4K (11 << 1)
|
||||
#define MPU_RGN_SIZE_8K (12 << 1)
|
||||
#define MPU_RGN_SIZE_16K (13 << 1)
|
||||
#define MPU_RGN_SIZE_32K (14 << 1)
|
||||
#define MPU_RGN_SIZE_64K (15 << 1)
|
||||
#define MPU_RGN_SIZE_128K (16 << 1)
|
||||
#define MPU_RGN_SIZE_256K (17 << 1)
|
||||
#define MPU_RGN_SIZE_512K (18 << 1)
|
||||
|
||||
#define MPU_RGN_SIZE_1M (19 << 1)
|
||||
#define MPU_RGN_SIZE_2M (20 << 1)
|
||||
#define MPU_RGN_SIZE_4M (21 << 1)
|
||||
#define MPU_RGN_SIZE_8M (22 << 1)
|
||||
#define MPU_RGN_SIZE_16M (23 << 1)
|
||||
#define MPU_RGN_SIZE_32M (24 << 1)
|
||||
#define MPU_RGN_SIZE_64M (25 << 1)
|
||||
#define MPU_RGN_SIZE_128M (26 << 1)
|
||||
#define MPU_RGN_SIZE_256M (27 << 1)
|
||||
#define MPU_RGN_SIZE_512M (28 << 1)
|
||||
|
||||
#define MPU_RGN_SIZE_1G (29 << 1)
|
||||
#define MPU_RGN_SIZE_2G (30 << 1)
|
||||
#define MPU_RGN_SIZE_4G (31 << 1)
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Flags for the permissions to be passed to MPURegionSet.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define MPU_RGN_PERM_EXEC 0x00000000
|
||||
#define MPU_RGN_PERM_NOEXEC 0x10000000
|
||||
#define MPU_RGN_PERM_PRV_NO_USR_NO 0x00000000
|
||||
#define MPU_RGN_PERM_PRV_RW_USR_NO 0x01000000
|
||||
#define MPU_RGN_PERM_PRV_RW_USR_RO 0x02000000
|
||||
#define MPU_RGN_PERM_PRV_RW_USR_RW 0x03000000
|
||||
#define MPU_RGN_PERM_PRV_RO_USR_NO 0x05000000
|
||||
#define MPU_RGN_PERM_PRV_RO_USR_RO 0x06000000
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Flags for the sub-region to be passed to MPURegionSet.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define MPU_SUB_RGN_DISABLE_0 0x00000100
|
||||
#define MPU_SUB_RGN_DISABLE_1 0x00000200
|
||||
#define MPU_SUB_RGN_DISABLE_2 0x00000400
|
||||
#define MPU_SUB_RGN_DISABLE_3 0x00000800
|
||||
#define MPU_SUB_RGN_DISABLE_4 0x00001000
|
||||
#define MPU_SUB_RGN_DISABLE_5 0x00002000
|
||||
#define MPU_SUB_RGN_DISABLE_6 0x00004000
|
||||
#define MPU_SUB_RGN_DISABLE_7 0x00008000
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Flags to enable or disable a region, to be passed to MPURegionSet.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define MPU_RGN_ENABLE 1
|
||||
#define MPU_RGN_DISABLE 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// API Function prototypes
|
||||
//
|
||||
//*****************************************************************************
|
||||
extern void MPUEnable(uint32_t ui32MPUConfig);
|
||||
extern void MPUDisable(void);
|
||||
extern uint32_t MPURegionCountGet(void);
|
||||
extern void MPURegionEnable(uint32_t ui32Region);
|
||||
extern void MPURegionDisable(uint32_t ui32Region);
|
||||
extern void MPURegionSet(uint32_t ui32Region, uint32_t ui32Addr,
|
||||
uint32_t ui32Flags);
|
||||
extern void MPURegionGet(uint32_t ui32Region, uint32_t *pui32Addr,
|
||||
uint32_t *pui32Flags);
|
||||
extern void MPUIntRegister(void (*pfnHandler)(void));
|
||||
extern void MPUIntUnregister(void);
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Mark the end of the C bindings section for C++ compilers.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // __DRIVERLIB_MPU_H__
|
|
@ -0,0 +1,771 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// onewire.c - Driver for OneWire master module.
|
||||
//
|
||||
// Copyright (c) 2012-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! \addtogroup onewire_api
|
||||
//! @{
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include "inc/hw_ints.h"
|
||||
#include "inc/hw_memmap.h"
|
||||
#include "inc/hw_onewire.h"
|
||||
#include "inc/hw_sysctl.h"
|
||||
#include "inc/hw_types.h"
|
||||
#include "driverlib/debug.h"
|
||||
#include "driverlib/interrupt.h"
|
||||
#include "driverlib/onewire.h"
|
||||
#include "driverlib/sysctl.h"
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// A bit mask for all transaction related fields in the 1-Wire control
|
||||
// register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define ONEWIRE_TXN_MASK (ONEWIRE_CS_OP_M | ONEWIRE_CS_SZ_M | \
|
||||
ONEWIRE_CS_BSIZE_M)
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Left-shift value for the control register's transaction size.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define ONEWIRE_TXN_SIZE_LSHIFT 3
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Left-shift value for the control register's last byte bit size.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define ONEWIRE_TXN_BSIZE_LSHIFT \
|
||||
16
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Initializes the 1-Wire module.
|
||||
//!
|
||||
//! \param ui32Base specifies the base address of the 1-Wire module.
|
||||
//! \param ui32InitFlags provides the initialization flags.
|
||||
//!
|
||||
//! This function configures and initializes the 1-Wire interface for use.
|
||||
//!
|
||||
//! The \e ui32InitFlags parameter is a combination of the following:
|
||||
//!
|
||||
//! - \b ONEWIRE_INIT_SPD_STD - standard speed bus timings
|
||||
//! - \b ONEWIRE_INIT_SPD_OD - overdrive speed bus timings
|
||||
//! - \b ONEWIRE_INIT_READ_STD - standard read sampling timing
|
||||
//! - \b ONEWIRE_INIT_READ_LATE - late read sampling timing
|
||||
//! - \b ONEWIRE_INIT_ATR - standard answer-to-reset presence detect
|
||||
//! - \b ONEWIRE_INIT_NO_ATR - no answer-to-reset presence detect
|
||||
//! - \b ONEWIRE_INIT_STD_POL - normal signal polarity
|
||||
//! - \b ONEWIRE_INIT_ALT_POL - alternate (reverse) signal polarity
|
||||
//! - \b ONEWIRE_INIT_1_WIRE_CFG - standard 1-Wire (1 data pin) setup
|
||||
//! - \b ONEWIRE_INIT_2_WIRE_CFG - alternate 2-Wire (2 data pin) setup
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
OneWireInit(uint32_t ui32Base, uint32_t ui32InitFlags)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT(ui32Base == ONEWIRE0_BASE);
|
||||
|
||||
//
|
||||
// Initialize control register.
|
||||
//
|
||||
HWREG(ui32Base + ONEWIRE_O_CS) = ui32InitFlags;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Issues a reset on the 1-Wire bus.
|
||||
//!
|
||||
//! \param ui32Base specifies the base address of the 1-Wire module.
|
||||
//!
|
||||
//! This function causes the 1-Wire module to generate a reset signal on the
|
||||
//! 1-Wire bus.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
OneWireBusReset(uint32_t ui32Base)
|
||||
{
|
||||
//
|
||||
// Check the argument.
|
||||
//
|
||||
ASSERT(ui32Base == ONEWIRE0_BASE);
|
||||
|
||||
//
|
||||
// Issue a bus reset.
|
||||
//
|
||||
HWREG(ui32Base + ONEWIRE_O_CS) |= ONEWIRE_CS_RST;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Retrieves the 1-Wire bus condition status.
|
||||
//!
|
||||
//! \param ui32Base specifies the base address of the 1-Wire module.
|
||||
//!
|
||||
//! This function returns the 1-Wire bus conditions reported by the 1-Wire
|
||||
//! module. These conditions could be a logical OR of any of the following:
|
||||
//!
|
||||
//! - \b ONEWIRE_BUS_STATUS_BUSY - A read, write, or reset is active.
|
||||
//! - \b ONEWIRE_BUS_STATUS_NO_SLAVE - No slave presence pulses detected.
|
||||
//! - \b ONEWIRE_BUS_STATUS_STUCK - The bus is being held low by non-master.
|
||||
//!
|
||||
//! \return Returns the 1-Wire bus conditions if detected else zero.
|
||||
//
|
||||
//*****************************************************************************
|
||||
uint32_t
|
||||
OneWireBusStatus(uint32_t ui32Base)
|
||||
{
|
||||
//
|
||||
// Check the argument.
|
||||
//
|
||||
ASSERT(ui32Base == ONEWIRE0_BASE);
|
||||
|
||||
//
|
||||
// Return the status bits from control and status register.
|
||||
//
|
||||
return(HWREG(ui32Base + ONEWIRE_O_CS) & (ONEWIRE_CS_BUSY |
|
||||
ONEWIRE_CS_NOATR |
|
||||
ONEWIRE_CS_STUCK));
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Retrieves data from the 1-Wire interface.
|
||||
//!
|
||||
//! \param ui32Base specifies the base address of the 1-Wire module.
|
||||
//! \param pui32Data is a pointer to storage to hold the read data.
|
||||
//!
|
||||
//! This function reads data from the 1-Wire module once all active bus
|
||||
//! operations are completed. By protocol definition, bit data defaults to
|
||||
//! a 1. Thus if a slave did not signal any 0-bit data, this read returns
|
||||
//! 0xffffffff.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
OneWireDataGet(uint32_t ui32Base, uint32_t *pui32Data)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT(ui32Base == ONEWIRE0_BASE);
|
||||
ASSERT(pui32Data);
|
||||
|
||||
//
|
||||
// Wait for any active operations to complete.
|
||||
//
|
||||
while(HWREG(ui32Base + ONEWIRE_O_CS) & ONEWIRE_CS_BUSY)
|
||||
{
|
||||
}
|
||||
|
||||
//
|
||||
// Copy the data into the provided storage.
|
||||
//
|
||||
*pui32Data = HWREG(ui32Base + ONEWIRE_O_DATR);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Retrieves data from the 1-Wire interface.
|
||||
//!
|
||||
//! \param ui32Base specifies the base address of the 1-Wire module.
|
||||
//! \param pui32Data is a pointer to storage to hold the read data.
|
||||
//!
|
||||
//! This function reads data from the 1-Wire module if there are no active
|
||||
//! operations on the bus. Otherwise it returns without reading the data from
|
||||
//! the module.
|
||||
//!
|
||||
//! By protocol definition, bit data defaults to a 1. Thus if a slave did
|
||||
//! not signal any 0-bit data, this read returns 0xffffffff.
|
||||
//!
|
||||
//! \return Returns \b true if a data read was performed, or \b false if the
|
||||
//! bus was not idle and no data was read.
|
||||
//
|
||||
//*****************************************************************************
|
||||
bool
|
||||
OneWireDataGetNonBlocking(uint32_t ui32Base, uint32_t *pui32Data)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT(ui32Base == ONEWIRE0_BASE);
|
||||
ASSERT(pui32Data);
|
||||
|
||||
//
|
||||
// If the bus is busy, return without reading.
|
||||
//
|
||||
if(HWREG(ui32Base + ONEWIRE_O_CS) & ONEWIRE_CS_BUSY)
|
||||
{
|
||||
return(false);
|
||||
}
|
||||
|
||||
//
|
||||
// Copy the data into the provided storage.
|
||||
//
|
||||
*pui32Data = HWREG(ui32Base + ONEWIRE_O_DATR);
|
||||
|
||||
//
|
||||
// Notify the caller data was read from the read register.
|
||||
//
|
||||
return(true);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Clears the 1-Wire module interrupt sources.
|
||||
//!
|
||||
//! \param ui32Base specifies the base address of the 1-Wire module.
|
||||
//! \param ui32IntFlags is a bit mask of the interrupt sources to be cleared.
|
||||
//!
|
||||
//! This function clears the specified 1-Wire interrupt sources so that they no
|
||||
//! longer assert. This function must be called in the interrupt handler to
|
||||
//! keep the interrupts from being triggered again immediately upon exit. The
|
||||
//! \e ui32IntFlags parameter can be a logical OR of any of the following:
|
||||
//!
|
||||
//! - \b ONEWIRE_INT_RESET_DONE - Bus reset has just completed.
|
||||
//! - \b ONEWIRE_INT_OP_DONE - Read or write operation completed. If a
|
||||
//! combined write and read operation was set up, the interrupt signals the
|
||||
//! read is done.
|
||||
//! - \b ONEWIRE_INT_NO_SLAVE - No presence detect was signaled by a slave.
|
||||
//! - \b ONEWIRE_INT_STUCK - Bus is being held low by non-master.
|
||||
//! - \b ONEWIRE_INT_DMA_DONE - DMA operation has completed.
|
||||
//!
|
||||
//! \note Because there is a write buffer in the Cortex-M 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
|
||||
OneWireIntClear(uint32_t ui32Base, uint32_t ui32IntFlags)
|
||||
{
|
||||
//
|
||||
// Check the argument.
|
||||
//
|
||||
ASSERT(ui32Base == ONEWIRE0_BASE);
|
||||
ASSERT((ui32IntFlags & ~(ONEWIRE_IM_RST | ONEWIRE_IM_OPC | ONEWIRE_IM_DMA |
|
||||
ONEWIRE_IM_NOATR | ONEWIRE_IM_STUCK)) == 0);
|
||||
|
||||
//
|
||||
// Clear the requested interrupts.
|
||||
//
|
||||
HWREG(ui32Base + ONEWIRE_O_ICR) = ui32IntFlags;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Disables individual 1-Wire module interrupt sources.
|
||||
//!
|
||||
//! \param ui32Base specifies the base address of the 1-Wire module.
|
||||
//! \param ui32IntFlags is a bit mask of the interrupt sources to be disabled.
|
||||
//!
|
||||
//! This function disables the indicated 1-Wire interrupt sources. The
|
||||
//! \e ui32IntFlags parameter can be a logical OR of any of the following:
|
||||
//!
|
||||
//! - \b ONEWIRE_INT_RESET_DONE - Bus reset has just completed.
|
||||
//! - \b ONEWIRE_INT_OP_DONE - Read or write operation completed. If a
|
||||
//! combined write and read operation was set up, the interrupt signals the
|
||||
//! read is done.
|
||||
//! - \b ONEWIRE_INT_NO_SLAVE - No presence detect was signaled by a slave.
|
||||
//! - \b ONEWIRE_INT_STUCK - Bus is being held low by non-master.
|
||||
//! - \b ONEWIRE_INT_DMA_DONE - DMA operation has completed
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
OneWireIntDisable(uint32_t ui32Base, uint32_t ui32IntFlags)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT(ui32Base == ONEWIRE0_BASE);
|
||||
ASSERT((ui32IntFlags & ~(ONEWIRE_IM_RST | ONEWIRE_IM_OPC | ONEWIRE_IM_DMA |
|
||||
ONEWIRE_IM_NOATR | ONEWIRE_IM_STUCK)) == 0);
|
||||
|
||||
//
|
||||
// Disable the requested interrupts.
|
||||
//
|
||||
HWREG(ui32Base + ONEWIRE_O_IM) &= ~ui32IntFlags;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Enables individual 1-Wire module interrupt sources.
|
||||
//!
|
||||
//! \param ui32Base specifies the base address of the 1-Wire module.
|
||||
//! \param ui32IntFlags is a bit mask of the interrupt sources to be enabled.
|
||||
//!
|
||||
//! This function enables the indicated 1-Wire 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 ui32IntFlags
|
||||
//! parameter can be a logical OR of any of the following:
|
||||
//!
|
||||
//! - \b ONEWIRE_INT_RESET_DONE - Bus reset has just completed.
|
||||
//! - \b ONEWIRE_INT_OP_DONE - Read or write operation completed. If a
|
||||
//! combined write and read operation was set up, the interrupt signals the
|
||||
//! read is done.
|
||||
//! - \b ONEWIRE_INT_NO_SLAVE - No presence detect was signaled by a slave.
|
||||
//! - \b ONEWIRE_INT_STUCK - Bus is being held low by non-master.
|
||||
//! - \b ONEWIRE_INT_DMA_DONE - DMA operation has completed
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
OneWireIntEnable(uint32_t ui32Base, uint32_t ui32IntFlags)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT(ui32Base == ONEWIRE0_BASE);
|
||||
ASSERT((ui32IntFlags & ~(ONEWIRE_IM_RST | ONEWIRE_IM_OPC | ONEWIRE_IM_DMA |
|
||||
ONEWIRE_IM_NOATR | ONEWIRE_IM_STUCK)) == 0);
|
||||
|
||||
//
|
||||
// Enable the requested interrupts.
|
||||
//
|
||||
HWREG(ui32Base + ONEWIRE_O_IM) |= ui32IntFlags;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Gets the current 1-Wire interrupt status.
|
||||
//!
|
||||
//! \param ui32Base specifies the base address of the 1-Wire module.
|
||||
//! \param bMasked is \b false if the raw interrupt status is required or
|
||||
//! \b true if the masked interrupt status is required.
|
||||
//!
|
||||
//! This function returns the interrupt status for the 1-Wire module. Either
|
||||
//! the raw interrupt status or the status of interrupts that are allowed to
|
||||
//! reflect to the processor can be returned.
|
||||
//!
|
||||
//! \return Returns the masked or raw 1-Wire interrupt status, as a bit field
|
||||
//! of any of the following values:
|
||||
//!
|
||||
//! - \b ONEWIRE_INT_RESET_DONE - Bus reset has just completed.
|
||||
//! - \b ONEWIRE_INT_OP_DONE - Read or write operation completed.
|
||||
//! - \b ONEWIRE_INT_NO_SLAVE - No presence detect was signaled by a slave.
|
||||
//! - \b ONEWIRE_INT_STUCK - Bus is being held low by non-master.
|
||||
//! - \b ONEWIRE_INT_DMA_DONE - DMA operation has completed
|
||||
//
|
||||
//*****************************************************************************
|
||||
uint32_t
|
||||
OneWireIntStatus(uint32_t ui32Base, bool bMasked)
|
||||
{
|
||||
//
|
||||
// Check the argument.
|
||||
//
|
||||
ASSERT(ui32Base == ONEWIRE0_BASE);
|
||||
|
||||
//
|
||||
// Return either the interrupt status or the raw interrupt status as
|
||||
// requested.
|
||||
//
|
||||
if(bMasked)
|
||||
{
|
||||
return(HWREG(ui32Base + ONEWIRE_O_MIS));
|
||||
}
|
||||
else
|
||||
{
|
||||
return(HWREG(ui32Base + ONEWIRE_O_RIS));
|
||||
}
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Returns the 1-Wire controller interrupt number.
|
||||
//!
|
||||
//! \param ui32Base specifies the 1-Wire module base address.
|
||||
//!
|
||||
//! This function returns the interrupt number for the 1-Wire module with the
|
||||
//! base address passed in the \e ui32Base parameter.
|
||||
//!
|
||||
//! \return Returns a 1-Wire interrupt number or 0 if the interrupt does not
|
||||
//! exist.
|
||||
//
|
||||
//*****************************************************************************
|
||||
static uint32_t
|
||||
_OneWireIntNumberGet(uint32_t ui32Base)
|
||||
{
|
||||
uint32_t ui32Int;
|
||||
|
||||
ASSERT(ui32Base == ONEWIRE0_BASE);
|
||||
|
||||
ui32Int = 0;
|
||||
|
||||
//
|
||||
// Find the valid interrupt number for the 1-Wire module.
|
||||
//
|
||||
if(CLASS_IS_TM4E111)
|
||||
{
|
||||
ui32Int = INT_ONEWIRE0_TM4E111;
|
||||
}
|
||||
if(CLASS_IS_TM4C129)
|
||||
{
|
||||
ui32Int = INT_ONEWIRE0_TM4C129;
|
||||
}
|
||||
|
||||
return(ui32Int);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Registers an interrupt handler for the 1-Wire module.
|
||||
//!
|
||||
//! \param ui32Base is the base address of the 1-Wire module.
|
||||
//! \param pfnHandler is a pointer to the function to be called when the
|
||||
//! 1-Wire interrupt occurs.
|
||||
//!
|
||||
//! This function sets the handler to be called when a 1-Wire interrupt occurs.
|
||||
//! This function enables the global interrupt in the interrupt controller;
|
||||
//! specific 1-Wire interrupts must be enabled via OneWireIntEnable(). If
|
||||
//! necessary, it is the interrupt handler's responsibility to clear the
|
||||
//! interrupt source via OneWireIntClear().
|
||||
//!
|
||||
//! \sa IntRegister() for important information about registering interrupt
|
||||
//! handlers.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
OneWireIntRegister(uint32_t ui32Base, void (*pfnHandler)(void))
|
||||
{
|
||||
uint32_t ui32Int;
|
||||
|
||||
//
|
||||
// Check the argument.
|
||||
//
|
||||
ASSERT(ui32Base == ONEWIRE0_BASE);
|
||||
ASSERT(pfnHandler);
|
||||
|
||||
//
|
||||
// Get the actual interrupt number for the 1-Wire module.
|
||||
//
|
||||
ui32Int = _OneWireIntNumberGet(ui32Base);
|
||||
|
||||
ASSERT(ui32Int != 0);
|
||||
|
||||
//
|
||||
// Register the interrupt handler.
|
||||
//
|
||||
IntRegister(ui32Int, pfnHandler);
|
||||
|
||||
//
|
||||
// Enable the 1-Wire peripheral interrupt.
|
||||
//
|
||||
IntEnable(ui32Int);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Unregisters an interrupt handler for the 1-Wire module.
|
||||
//!
|
||||
//! \param ui32Base is the base address of the 1-Wire module.
|
||||
//!
|
||||
//! This function clears the handler to be called when an 1-Wire 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
|
||||
OneWireIntUnregister(uint32_t ui32Base)
|
||||
{
|
||||
uint32_t ui32Int;
|
||||
|
||||
//
|
||||
// Check the argument.
|
||||
//
|
||||
ASSERT(ui32Base == ONEWIRE0_BASE);
|
||||
|
||||
//
|
||||
// Get the actual interrupt number for the 1-Wire module.
|
||||
//
|
||||
ui32Int = _OneWireIntNumberGet(ui32Base);
|
||||
ASSERT(ui32Int != 0);
|
||||
|
||||
//
|
||||
// Disable the 1-Wire peripheral interrupt.
|
||||
//
|
||||
IntDisable(ui32Int);
|
||||
|
||||
//
|
||||
// Unregister the interrupt handler.
|
||||
//
|
||||
IntUnregister(ui32Int);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Disables 1-Wire DMA operations.
|
||||
//!
|
||||
//! \param ui32Base is the base address of the 1-Wire module.
|
||||
//! \param ui32DMAFlags is a bit mask of the DMA features to disable.
|
||||
//!
|
||||
//! This function is used to disable 1-Wire DMA features that were enabled
|
||||
//! by OneWireDMAEnable(). The specified 1-Wire DMA features are disabled.
|
||||
//! The \e ui32DMAFlags parameter is a combination of the following:
|
||||
//!
|
||||
//! - \b ONEWIRE_DMA_BUS_RESET - Issue a 1-Wire bus reset before starting
|
||||
//! - \b ONEWIRE_DMA_OP_READ - Read after each module transaction
|
||||
//! - \b ONEWIRE_DMA_OP_MULTI_WRITE - Write after each previous write
|
||||
//! - \b ONEWIRE_DMA_OP_MULTI_READ - Read after each previous read
|
||||
//! - \b ONEWIRE_DMA_MODE_SG - Start DMA on enable then repeat on each
|
||||
//! completion
|
||||
//! - \b ONEWIRE_DMA_OP_SZ_8 - Bus read/write of 8 bits
|
||||
//! - \b ONEWIRE_DMA_OP_SZ_16 - Bus read/write of 16 bits
|
||||
//! - \b ONEWIRE_DMA_OP_SZ_32 - Bus read/write of 32 bits
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
OneWireDMADisable(uint32_t ui32Base, uint32_t ui32DMAFlags)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT(ui32Base == ONEWIRE0_BASE);
|
||||
ASSERT(ui32DMAFlags > 0);
|
||||
|
||||
//
|
||||
// Clear the transaction size bits
|
||||
//
|
||||
HWREG(ui32Base + ONEWIRE_O_CS) = (HWREG(ui32Base + ONEWIRE_O_CS) &
|
||||
~(ONEWIRE_TXN_MASK));
|
||||
|
||||
//
|
||||
// Disable the DMA features as requested.
|
||||
//
|
||||
HWREG(ui32Base + ONEWIRE_O_DMA) &= ~(ui32DMAFlags & 0xff);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Enables 1-Wire DMA operations.
|
||||
//!
|
||||
//! \param ui32Base is the base address of the 1-Wire module.
|
||||
//! \param ui32DMAFlags is a bit mask of the DMA features to enable.
|
||||
//!
|
||||
//! This function enables the specified 1-Wire DMA features. The 1-Wire module
|
||||
//! can be configured for write operations, read operations, small write and
|
||||
//! read operations, and scatter-gather support of mixed operations.
|
||||
//!
|
||||
//! The \e ui32DMAFlags parameter is a combination of the following:
|
||||
//!
|
||||
//! - \b ONEWIRE_DMA_BUS_RESET - Issue a 1-Wire bus reset before starting
|
||||
//! - \b ONEWIRE_DMA_OP_READ - Read after each module transaction
|
||||
//! - \b ONEWIRE_DMA_OP_MULTI_WRITE - Write after each previous write
|
||||
//! - \b ONEWIRE_DMA_OP_MULTI_READ - Read after each previous read
|
||||
//! - \b ONEWIRE_DMA_MODE_SG - Start DMA on enable then repeat on each
|
||||
//! completion
|
||||
//! - \b ONEWIRE_DMA_OP_SZ_8 - Bus read/write of 8 bits
|
||||
//! - \b ONEWIRE_DMA_OP_SZ_16 - Bus read/write of 16 bits
|
||||
//! - \b ONEWIRE_DMA_OP_SZ_32 - Bus read/write of 32 bits
|
||||
//!
|
||||
//! \note The uDMA controller must be properly configured before DMA can be
|
||||
//! used with the 1-Wire module.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
OneWireDMAEnable(uint32_t ui32Base, uint32_t ui32DMAFlags)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT(ui32Base == ONEWIRE0_BASE);
|
||||
ASSERT(ui32DMAFlags > 0);
|
||||
|
||||
//
|
||||
// set up the transaction size.
|
||||
//
|
||||
HWREG(ui32Base + ONEWIRE_O_CS) = ((HWREG(ui32Base + ONEWIRE_O_CS) &
|
||||
~(ONEWIRE_TXN_MASK)) |
|
||||
(ui32DMAFlags >> 8));
|
||||
|
||||
//
|
||||
// Enable DMA with the parameters provided.
|
||||
//
|
||||
HWREG(ui32Base + ONEWIRE_O_DMA) = (ui32DMAFlags & 0xf);
|
||||
|
||||
//
|
||||
// If a read transaction was requested, seed the write data register. This
|
||||
// will trigger the DMA reads to start. This should not be done for
|
||||
// scatter-gather operations.
|
||||
//
|
||||
if((ui32DMAFlags & (ONEWIRE_DMA_DMAOP_RDSNG | ONEWIRE_DMA_DMAOP_RDMUL)) &&
|
||||
!(ui32DMAFlags & ONEWIRE_DMA_SG))
|
||||
{
|
||||
//
|
||||
// Workaround for Snowflake DMA receive trigger errata.
|
||||
//
|
||||
if(CLASS_IS_TM4C129)
|
||||
{
|
||||
SysCtlDelay(9);
|
||||
}
|
||||
|
||||
//
|
||||
// Write DATW to trigger DMA receive start.
|
||||
//
|
||||
HWREG(ui32Base + ONEWIRE_O_DATW) = 0xffffffff;
|
||||
}
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Performs a 1-Wire protocol transaction on the bus.
|
||||
//!
|
||||
//! \param ui32Base specifies the base address of the 1-Wire module.
|
||||
//! \param ui32OpMode sets the transaction type.
|
||||
//! \param ui32Data is the data for a write operation.
|
||||
//! \param ui32BitCnt specifies the number of valid bits (1-32) for the
|
||||
//! operation.
|
||||
//!
|
||||
//! This function performs a 1-Wire protocol transaction, read and/or write, on
|
||||
//! the bus. The application should confirm the bus is idle before starting a
|
||||
//! read or write transaction.
|
||||
//!
|
||||
//! The \e ui32OpMode defines the activity for the bus operations and is a
|
||||
//! logical OR of the following:
|
||||
//!
|
||||
//! - \b ONEWIRE_OP_RESET - Indicates the operation should be started with
|
||||
//! a bus reset.
|
||||
//! - \b ONEWIRE_OP_WRITE - A write operation
|
||||
//! - \b ONEWIRE_OP_READ - A read operation
|
||||
//!
|
||||
//! \note If both a read and write operation are requested, the write will be
|
||||
//! performed prior to the read.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
OneWireTransaction(uint32_t ui32Base, uint32_t ui32OpMode, uint32_t ui32Data,
|
||||
uint32_t ui32BitCnt)
|
||||
{
|
||||
uint32_t ui32Transaction;
|
||||
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT(ui32Base == ONEWIRE0_BASE);
|
||||
ASSERT((ui32OpMode & (ONEWIRE_OP_RESET | ONEWIRE_OP_WRITE |
|
||||
ONEWIRE_OP_READ)) > 0);
|
||||
ASSERT((ui32BitCnt >= 1) && (ui32BitCnt <= 32));
|
||||
|
||||
//
|
||||
// Read the control register and clear any transaction related
|
||||
// bit fields.
|
||||
//
|
||||
ui32Transaction = HWREG(ui32Base + ONEWIRE_O_CS) & ~(ONEWIRE_TXN_MASK);
|
||||
|
||||
//
|
||||
// Add the user specified operation flags.
|
||||
//
|
||||
ui32Transaction |= (ui32OpMode & (ONEWIRE_OP_RESET | ONEWIRE_OP_WRITE |
|
||||
ONEWIRE_OP_READ));
|
||||
|
||||
//
|
||||
// set up for a read or write transaction.
|
||||
//
|
||||
if(ui32Transaction & (ONEWIRE_CS_OP_WR | ONEWIRE_CS_OP_RD))
|
||||
{
|
||||
//
|
||||
// Configure the 1-Wire module for the transaction size. This is
|
||||
// specified as 1-4 bytes and the specific bit size for the last
|
||||
// byte therein.
|
||||
//
|
||||
ui32Transaction |= ((((ui32BitCnt % 8) ? (ui32BitCnt / 8) + 1 :
|
||||
(ui32BitCnt / 8)) - 1) <<
|
||||
ONEWIRE_TXN_SIZE_LSHIFT);
|
||||
ui32Transaction |= ((ui32BitCnt % 8) << ONEWIRE_TXN_BSIZE_LSHIFT);
|
||||
|
||||
//
|
||||
// Write specific setup.
|
||||
//
|
||||
if(ui32Transaction & ONEWIRE_CS_OP_WR)
|
||||
{
|
||||
//
|
||||
// Load the data into the write register.
|
||||
//
|
||||
HWREG(ui32Base + ONEWIRE_O_DATW) = ui32Data;
|
||||
}
|
||||
}
|
||||
|
||||
//
|
||||
// Start the transaction.
|
||||
//
|
||||
HWREG(ui32Base + ONEWIRE_O_CS) = ui32Transaction;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Close the Doxygen group.
|
||||
//! @}
|
||||
//
|
||||
//*****************************************************************************
|
|
@ -0,0 +1,307 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// onewire.h - Prototypes for the OneWire Driver.
|
||||
//
|
||||
// Copyright (c) 2012-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __DRIVERLIB_ONEWIRE_H__
|
||||
#define __DRIVERLIB_ONEWIRE_H__
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! \addtogroup onewire_api
|
||||
//! @{
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// If building with a C++ compiler, make all of the definitions in this header
|
||||
// have a C binding.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Defines used in the OneWireInit() function call.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
//
|
||||
// This define is used in initialization to request standard speed bus
|
||||
// timings. This is the default.
|
||||
//
|
||||
#define ONEWIRE_INIT_SPD_STD 0x00000000
|
||||
|
||||
//
|
||||
// This define is used in initialization to request overdrive speed bus
|
||||
// timings.
|
||||
//
|
||||
#define ONEWIRE_INIT_SPD_OD 0x00000020
|
||||
|
||||
//
|
||||
// This define is used in initialization to request standard read sampling
|
||||
// timing (2us for ONEWIRE_INIT_SPD_OD and 16us for ONEWIRE_INIT_SPD_STD).
|
||||
// This is the default.
|
||||
//
|
||||
#define ONEWIRE_INIT_READ_STD 0x00000000
|
||||
|
||||
//
|
||||
// This define is used in initialization to request late read sampling
|
||||
// timing (7us for ONEWIRE_INIT_SPD_OD and 50us for ONEWIRE_INIT_SPD_STD).
|
||||
//
|
||||
#define ONEWIRE_INIT_READ_LATE 0x00000040
|
||||
|
||||
//
|
||||
// This define is used in initialization to request a standard
|
||||
// Answer-to-Reset (presence detect) monitor. This is the default.
|
||||
//
|
||||
#define ONEWIRE_INIT_ATR 0x00000000
|
||||
|
||||
//
|
||||
// This define is used in initialization to request no Answer-to-Reset
|
||||
// (presence detect) monitor. The module will delay operations after a bus
|
||||
// reset for the expected presence detect period in this case.
|
||||
//
|
||||
#define ONEWIRE_INIT_NO_ATR 0x00000080
|
||||
|
||||
//
|
||||
// This define is used in initialization to request standard signal polarity
|
||||
// on the 1-Wire bus (pin is driven low to drive bus low). This is the
|
||||
// default.
|
||||
//
|
||||
#define ONEWIRE_INIT_STD_POL 0x00000000
|
||||
|
||||
//
|
||||
// This define is used in initialization to request alternate signal polarity
|
||||
// on the 1-Wire bus (pin is driven high to drive bus low).
|
||||
//
|
||||
#define ONEWIRE_INIT_ALT_POL 0x40000000
|
||||
|
||||
//
|
||||
// This define is used in initialization to request normal 1-Wire operational
|
||||
// mode. This is the default.
|
||||
//
|
||||
#define ONEWIRE_INIT_1_WIRE_CFG 0x00000000
|
||||
|
||||
//
|
||||
// This define is used in initialization to request a 2 pin operational
|
||||
// mode where one pin is used exclusively for TX operations and the other
|
||||
// for RX.
|
||||
//
|
||||
#define ONEWIRE_INIT_2_WIRE_CFG 0x80000000
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Defines for bus status conditions. These values can be returned by
|
||||
// OneWireBusStatus().
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
//
|
||||
// This will be set if the bus is busy handling a Read, Write or
|
||||
// Reset activity.
|
||||
//
|
||||
#define ONEWIRE_BUS_STATUS_BUSY 0x00000100
|
||||
|
||||
//
|
||||
// This will be set if the module did not detect any slave presence pulses
|
||||
// after a bus reset.
|
||||
//
|
||||
#define ONEWIRE_BUS_STATUS_NO_SLAVE \
|
||||
0x00000200
|
||||
|
||||
//
|
||||
// This will be set if the bus is being held low outside of a normal Read,
|
||||
// Write or Reset activity.
|
||||
//
|
||||
#define ONEWIRE_BUS_STATUS_STUCK \
|
||||
0x00000400
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// OneWire operation modes used with OneWireTransaction().
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
//
|
||||
// This mode flag indicates a single reset should be issued prior to a write
|
||||
// and/or read operation.
|
||||
//
|
||||
#define ONEWIRE_OP_RESET 0x00000001
|
||||
|
||||
//
|
||||
// This mode flag indicates a read operation.
|
||||
//
|
||||
#define ONEWIRE_OP_READ 0x00000002
|
||||
|
||||
//
|
||||
// This mode flag indicates a write operation.
|
||||
//
|
||||
#define ONEWIRE_OP_WRITE 0x00000004
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// OneWire DMA used with OneWireDMAEnable().
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
//
|
||||
// This indicates the DMA should issue a 1-Wire bus reset before starting.
|
||||
//
|
||||
#define ONEWIRE_DMA_BUS_RESET 0x00000001
|
||||
|
||||
//
|
||||
// The DMA operation will be a single Read after each module transaction.
|
||||
//
|
||||
#define ONEWIRE_DMA_OP_READ 0x00000002
|
||||
|
||||
//
|
||||
// The DMA will write values to the 1-Wire interface as each previous DMA
|
||||
// write operation completes.
|
||||
//
|
||||
#define ONEWIRE_DMA_OP_MULTI_WRITE \
|
||||
0x00000004
|
||||
|
||||
//
|
||||
// The DMA will read values from the 1-Wire interface as each previous DMA
|
||||
// read operation completes.
|
||||
//
|
||||
#define ONEWIRE_DMA_OP_MULTI_READ \
|
||||
0x00000006
|
||||
|
||||
//
|
||||
// This Scatter Gather DMA mode is paired with ONEWIRE_DMA_OP_READ to instruct
|
||||
// the 1-Wire DMA to initiate an operation at the start of and then on each
|
||||
// transition completion thereafter.
|
||||
//
|
||||
#define ONEWIRE_DMA_MODE_SG 0x00000008
|
||||
|
||||
//
|
||||
// DMA expects a Read/Write bus operation size of 8 bits. This should match
|
||||
// the uDMA channel setup.
|
||||
//
|
||||
#define ONEWIRE_DMA_OP_SZ_8 0x00000000
|
||||
|
||||
//
|
||||
// DMA expects a Read/Write bus operation size of 16 bits. This should match
|
||||
// the uDMA channel setup.
|
||||
//
|
||||
#define ONEWIRE_DMA_OP_SZ_16 0x00000800
|
||||
|
||||
//
|
||||
// DMA expects a Read/Write bus operation size of 32 bits. This should match
|
||||
// the uDMA channel setup.
|
||||
//
|
||||
#define ONEWIRE_DMA_OP_SZ_32 0x00001800
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// OneWire interrupt defines. Use in calls to OneWireIntEnable(),
|
||||
// OneWireIntDisable(), OneWireIntClear() and returned by OneWireIntStatus().
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
//
|
||||
// This interrupt indicates a bus reset has just completed.
|
||||
//
|
||||
#define ONEWIRE_INT_RESET_DONE 0x00000001
|
||||
|
||||
//
|
||||
// The interrupt indicates a Read or Write master initiated operation
|
||||
// has just completed.
|
||||
//
|
||||
#define ONEWIRE_INT_OP_DONE 0x00000002
|
||||
|
||||
//
|
||||
// This interrupt indicates that no presence detect was signaled by a slave
|
||||
// on the bus after a reset.
|
||||
//
|
||||
#define ONEWIRE_INT_NO_SLAVE 0x00000004
|
||||
|
||||
//
|
||||
// This interrupt indicates the bus is being held low outside of normal
|
||||
// operations.
|
||||
//
|
||||
#define ONEWIRE_INT_STUCK 0x00000008
|
||||
|
||||
//
|
||||
// This interrupt indicates a OneWire DMA operation has completed.
|
||||
//
|
||||
#define ONEWIRE_INT_DMA_DONE 0x00000010
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Close the Doxygen group.
|
||||
//! @}
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Prototypes for the APIs.
|
||||
//
|
||||
//*****************************************************************************
|
||||
extern void OneWireBusReset(uint32_t ui32Base);
|
||||
extern uint32_t OneWireBusStatus(uint32_t ui32Base);
|
||||
extern void OneWireDataGet(uint32_t u3i2Base, uint32_t *pui32Data);
|
||||
extern bool OneWireDataGetNonBlocking(uint32_t ui32Base, uint32_t *pui32Data);
|
||||
extern void OneWireDMADisable(uint32_t ui32Base, uint32_t ui32DMAFlags);
|
||||
extern void OneWireDMAEnable(uint32_t ui32Base, uint32_t ui32DMAFlags);
|
||||
extern void OneWireInit(uint32_t ui32Base, uint32_t ui32InitFlags);
|
||||
extern void OneWireIntClear(uint32_t ui32Base, uint32_t ui32IntFlags);
|
||||
extern void OneWireIntDisable(uint32_t ui32Base, uint32_t ui32IntFlags);
|
||||
extern void OneWireIntEnable(uint32_t ui32Base, uint32_t ui32IntFlags);
|
||||
extern void OneWireIntRegister(uint32_t ui32Base, void (*pfnHandler)(void));
|
||||
extern void OneWireIntUnregister(uint32_t ui32Base);
|
||||
extern uint32_t OneWireIntStatus(uint32_t ui32Base, bool bMasked);
|
||||
extern void OneWireTransaction(uint32_t ui32Base, uint32_t ui32OpFlags,
|
||||
uint32_t ui32Data, uint32_t ui32BitCnt);
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Mark the end of the C bindings section for C++ compilers.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // __DRIVERLIB_ONEWIRE_H__
|
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,326 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// pwm.h - API function protoypes for Pulse Width Modulation (PWM) ports
|
||||
//
|
||||
// Copyright (c) 2005-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __DRIVERLIB_PWM_H__
|
||||
#define __DRIVERLIB_PWM_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 passed to PWMGenConfigure() as the ui32Config
|
||||
// parameter and specify the configuration of the PWM generator.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define PWM_GEN_MODE_DOWN 0x00000000 // Down count mode
|
||||
#define PWM_GEN_MODE_UP_DOWN 0x00000002 // Up/Down count mode
|
||||
#define PWM_GEN_MODE_SYNC 0x00000038 // Synchronous updates
|
||||
#define PWM_GEN_MODE_NO_SYNC 0x00000000 // Immediate updates
|
||||
#define PWM_GEN_MODE_DBG_RUN 0x00000004 // Continue running in debug mode
|
||||
#define PWM_GEN_MODE_DBG_STOP 0x00000000 // Stop running in debug mode
|
||||
#define PWM_GEN_MODE_FAULT_LATCHED \
|
||||
0x00040000 // Fault is latched
|
||||
#define PWM_GEN_MODE_FAULT_UNLATCHED \
|
||||
0x00000000 // Fault is not latched
|
||||
#define PWM_GEN_MODE_FAULT_MINPER \
|
||||
0x00020000 // Enable min fault period
|
||||
#define PWM_GEN_MODE_FAULT_NO_MINPER \
|
||||
0x00000000 // Disable min fault period
|
||||
#define PWM_GEN_MODE_FAULT_EXT 0x00010000 // Enable extended fault support
|
||||
#define PWM_GEN_MODE_FAULT_LEGACY \
|
||||
0x00000000 // Disable extended fault support
|
||||
#define PWM_GEN_MODE_DB_NO_SYNC 0x00000000 // Deadband updates occur
|
||||
// immediately
|
||||
#define PWM_GEN_MODE_DB_SYNC_LOCAL \
|
||||
0x0000A800 // Deadband updates locally
|
||||
// synchronized
|
||||
#define PWM_GEN_MODE_DB_SYNC_GLOBAL \
|
||||
0x0000FC00 // Deadband updates globally
|
||||
// synchronized
|
||||
#define PWM_GEN_MODE_GEN_NO_SYNC \
|
||||
0x00000000 // Generator mode updates occur
|
||||
// immediately
|
||||
#define PWM_GEN_MODE_GEN_SYNC_LOCAL \
|
||||
0x00000280 // Generator mode updates locally
|
||||
// synchronized
|
||||
#define PWM_GEN_MODE_GEN_SYNC_GLOBAL \
|
||||
0x000003C0 // Generator mode updates globally
|
||||
// synchronized
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Defines for enabling, disabling, and clearing PWM generator interrupts and
|
||||
// triggers.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define PWM_INT_CNT_ZERO 0x00000001 // Int if COUNT = 0
|
||||
#define PWM_INT_CNT_LOAD 0x00000002 // Int if COUNT = LOAD
|
||||
#define PWM_INT_CNT_AU 0x00000004 // Int if COUNT = CMPA U
|
||||
#define PWM_INT_CNT_AD 0x00000008 // Int if COUNT = CMPA D
|
||||
#define PWM_INT_CNT_BU 0x00000010 // Int if COUNT = CMPA U
|
||||
#define PWM_INT_CNT_BD 0x00000020 // Int if COUNT = CMPA D
|
||||
#define PWM_TR_CNT_ZERO 0x00000100 // Trig if COUNT = 0
|
||||
#define PWM_TR_CNT_LOAD 0x00000200 // Trig if COUNT = LOAD
|
||||
#define PWM_TR_CNT_AU 0x00000400 // Trig if COUNT = CMPA U
|
||||
#define PWM_TR_CNT_AD 0x00000800 // Trig if COUNT = CMPA D
|
||||
#define PWM_TR_CNT_BU 0x00001000 // Trig if COUNT = CMPA U
|
||||
#define PWM_TR_CNT_BD 0x00002000 // Trig if COUNT = CMPA D
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Defines for enabling, disabling, and clearing PWM interrupts.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define PWM_INT_GEN_0 0x00000001 // Generator 0 interrupt
|
||||
#define PWM_INT_GEN_1 0x00000002 // Generator 1 interrupt
|
||||
#define PWM_INT_GEN_2 0x00000004 // Generator 2 interrupt
|
||||
#define PWM_INT_GEN_3 0x00000008 // Generator 3 interrupt
|
||||
#define PWM_INT_FAULT0 0x00010000 // Fault0 interrupt
|
||||
#define PWM_INT_FAULT1 0x00020000 // Fault1 interrupt
|
||||
#define PWM_INT_FAULT2 0x00040000 // Fault2 interrupt
|
||||
#define PWM_INT_FAULT3 0x00080000 // Fault3 interrupt
|
||||
#define PWM_INT_FAULT_M 0x000F0000 // Fault interrupt source mask
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Defines to identify the generators within a module.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define PWM_GEN_0 0x00000040 // Offset address of Gen0
|
||||
#define PWM_GEN_1 0x00000080 // Offset address of Gen1
|
||||
#define PWM_GEN_2 0x000000C0 // Offset address of Gen2
|
||||
#define PWM_GEN_3 0x00000100 // Offset address of Gen3
|
||||
|
||||
#define PWM_GEN_0_BIT 0x00000001 // Bit-wise ID for Gen0
|
||||
#define PWM_GEN_1_BIT 0x00000002 // Bit-wise ID for Gen1
|
||||
#define PWM_GEN_2_BIT 0x00000004 // Bit-wise ID for Gen2
|
||||
#define PWM_GEN_3_BIT 0x00000008 // Bit-wise ID for Gen3
|
||||
|
||||
#define PWM_GEN_EXT_0 0x00000800 // Offset of Gen0 ext address range
|
||||
#define PWM_GEN_EXT_1 0x00000880 // Offset of Gen1 ext address range
|
||||
#define PWM_GEN_EXT_2 0x00000900 // Offset of Gen2 ext address range
|
||||
#define PWM_GEN_EXT_3 0x00000980 // Offset of Gen3 ext address range
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Defines to identify the outputs within a module.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define PWM_OUT_0 0x00000040 // Encoded offset address of PWM0
|
||||
#define PWM_OUT_1 0x00000041 // Encoded offset address of PWM1
|
||||
#define PWM_OUT_2 0x00000082 // Encoded offset address of PWM2
|
||||
#define PWM_OUT_3 0x00000083 // Encoded offset address of PWM3
|
||||
#define PWM_OUT_4 0x000000C4 // Encoded offset address of PWM4
|
||||
#define PWM_OUT_5 0x000000C5 // Encoded offset address of PWM5
|
||||
#define PWM_OUT_6 0x00000106 // Encoded offset address of PWM6
|
||||
#define PWM_OUT_7 0x00000107 // Encoded offset address of PWM7
|
||||
|
||||
#define PWM_OUT_0_BIT 0x00000001 // Bit-wise ID for PWM0
|
||||
#define PWM_OUT_1_BIT 0x00000002 // Bit-wise ID for PWM1
|
||||
#define PWM_OUT_2_BIT 0x00000004 // Bit-wise ID for PWM2
|
||||
#define PWM_OUT_3_BIT 0x00000008 // Bit-wise ID for PWM3
|
||||
#define PWM_OUT_4_BIT 0x00000010 // Bit-wise ID for PWM4
|
||||
#define PWM_OUT_5_BIT 0x00000020 // Bit-wise ID for PWM5
|
||||
#define PWM_OUT_6_BIT 0x00000040 // Bit-wise ID for PWM6
|
||||
#define PWM_OUT_7_BIT 0x00000080 // Bit-wise ID for PWM7
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Defines to identify each of the possible fault trigger conditions in
|
||||
// PWM_FAULT_GROUP_0.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define PWM_FAULT_GROUP_0 0
|
||||
|
||||
#define PWM_FAULT_FAULT0 0x00000001
|
||||
#define PWM_FAULT_FAULT1 0x00000002
|
||||
#define PWM_FAULT_FAULT2 0x00000004
|
||||
#define PWM_FAULT_FAULT3 0x00000008
|
||||
#define PWM_FAULT_ACMP0 0x00010000
|
||||
#define PWM_FAULT_ACMP1 0x00020000
|
||||
#define PWM_FAULT_ACMP2 0x00040000
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Defines to identify each of the possible fault trigger conditions in
|
||||
// PWM_FAULT_GROUP_1.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define PWM_FAULT_GROUP_1 1
|
||||
|
||||
#define PWM_FAULT_DCMP0 0x00000001
|
||||
#define PWM_FAULT_DCMP1 0x00000002
|
||||
#define PWM_FAULT_DCMP2 0x00000004
|
||||
#define PWM_FAULT_DCMP3 0x00000008
|
||||
#define PWM_FAULT_DCMP4 0x00000010
|
||||
#define PWM_FAULT_DCMP5 0x00000020
|
||||
#define PWM_FAULT_DCMP6 0x00000040
|
||||
#define PWM_FAULT_DCMP7 0x00000080
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Defines to identify the sense of each of the external FAULTn signals
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define PWM_FAULT0_SENSE_HIGH 0x00000000
|
||||
#define PWM_FAULT0_SENSE_LOW 0x00000001
|
||||
#define PWM_FAULT1_SENSE_HIGH 0x00000000
|
||||
#define PWM_FAULT1_SENSE_LOW 0x00000002
|
||||
#define PWM_FAULT2_SENSE_HIGH 0x00000000
|
||||
#define PWM_FAULT2_SENSE_LOW 0x00000004
|
||||
#define PWM_FAULT3_SENSE_HIGH 0x00000000
|
||||
#define PWM_FAULT3_SENSE_LOW 0x00000008
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Defines that can be passed to the PWMClockSet() API as the ui32Config
|
||||
// parameter, and can be returned by the PWMClockGet() API.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define PWM_SYSCLK_DIV_1 0x00000000 // PWM clock is system clock
|
||||
#define PWM_SYSCLK_DIV_2 0x00000100 // PWM clock is system clock /2
|
||||
#define PWM_SYSCLK_DIV_4 0x00000101 // PWM clock is system clock /4
|
||||
#define PWM_SYSCLK_DIV_8 0x00000102 // PWM clock is system clock /8
|
||||
#define PWM_SYSCLK_DIV_16 0x00000103 // PWM clock is system clock /16
|
||||
#define PWM_SYSCLK_DIV_32 0x00000104 // PWM clock is system clock /32
|
||||
#define PWM_SYSCLK_DIV_64 0x00000105 // PWM clock is system clock /64
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Defines passed to PWMOutputUpdateMode() to identify the synchronization mode
|
||||
// to use when enabling or disabling outputs using PWMOutputState().
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define PWM_OUTPUT_MODE_NO_SYNC 0x00000000 // Updates to occur immediately
|
||||
#define PWM_OUTPUT_MODE_SYNC_LOCAL \
|
||||
0x00000002 // Updates are locally synchronized
|
||||
#define PWM_OUTPUT_MODE_SYNC_GLOBAL \
|
||||
0x00000003 // Updates are globally synchronized
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// API Function prototypes
|
||||
//
|
||||
//*****************************************************************************
|
||||
extern void PWMGenConfigure(uint32_t ui32Base, uint32_t ui32Gen,
|
||||
uint32_t ui32Config);
|
||||
extern void PWMGenPeriodSet(uint32_t ui32Base, uint32_t ui32Gen,
|
||||
uint32_t ui32Period);
|
||||
extern uint32_t PWMGenPeriodGet(uint32_t ui32Base,
|
||||
uint32_t ui32Gen);
|
||||
extern void PWMGenEnable(uint32_t ui32Base, uint32_t ui32Gen);
|
||||
extern void PWMGenDisable(uint32_t ui32Base, uint32_t ui32Gen);
|
||||
extern void PWMPulseWidthSet(uint32_t ui32Base, uint32_t ui32PWMOut,
|
||||
uint32_t ui32Width);
|
||||
extern uint32_t PWMPulseWidthGet(uint32_t ui32Base,
|
||||
uint32_t ui32PWMOut);
|
||||
extern void PWMDeadBandEnable(uint32_t ui32Base, uint32_t ui32Gen,
|
||||
uint16_t ui16Rise, uint16_t ui16Fall);
|
||||
extern void PWMDeadBandDisable(uint32_t ui32Base, uint32_t ui32Gen);
|
||||
extern void PWMSyncUpdate(uint32_t ui32Base, uint32_t ui32GenBits);
|
||||
extern void PWMSyncTimeBase(uint32_t ui32Base, uint32_t ui32GenBits);
|
||||
extern void PWMOutputState(uint32_t ui32Base, uint32_t ui32PWMOutBits,
|
||||
bool bEnable);
|
||||
extern void PWMOutputInvert(uint32_t ui32Base, uint32_t ui32PWMOutBits,
|
||||
bool bInvert);
|
||||
extern void PWMOutputFaultLevel(uint32_t ui32Base,
|
||||
uint32_t ui32PWMOutBits,
|
||||
bool bDriveHigh);
|
||||
extern void PWMOutputFault(uint32_t ui32Base, uint32_t ui32PWMOutBits,
|
||||
bool bFaultSuppress);
|
||||
extern void PWMGenIntRegister(uint32_t ui32Base, uint32_t ui32Gen,
|
||||
void (*pfnIntHandler)(void));
|
||||
extern void PWMGenIntUnregister(uint32_t ui32Base, uint32_t ui32Gen);
|
||||
extern void PWMFaultIntRegister(uint32_t ui32Base,
|
||||
void (*pfnIntHandler)(void));
|
||||
extern void PWMFaultIntUnregister(uint32_t ui32Base);
|
||||
extern void PWMGenIntTrigEnable(uint32_t ui32Base, uint32_t ui32Gen,
|
||||
uint32_t ui32IntTrig);
|
||||
extern void PWMGenIntTrigDisable(uint32_t ui32Base, uint32_t ui32Gen,
|
||||
uint32_t ui32IntTrig);
|
||||
extern uint32_t PWMGenIntStatus(uint32_t ui32Base, uint32_t ui32Gen,
|
||||
bool bMasked);
|
||||
extern void PWMGenIntClear(uint32_t ui32Base, uint32_t ui32Gen,
|
||||
uint32_t ui32Ints);
|
||||
extern void PWMIntEnable(uint32_t ui32Base, uint32_t ui32GenFault);
|
||||
extern void PWMIntDisable(uint32_t ui32Base, uint32_t ui32GenFault);
|
||||
extern void PWMFaultIntClear(uint32_t ui32Base);
|
||||
extern uint32_t PWMIntStatus(uint32_t ui32Base, bool bMasked);
|
||||
extern void PWMFaultIntClearExt(uint32_t ui32Base,
|
||||
uint32_t ui32FaultInts);
|
||||
extern void PWMGenFaultConfigure(uint32_t ui32Base, uint32_t ui32Gen,
|
||||
uint32_t ui32MinFaultPeriod,
|
||||
uint32_t ui32FaultSenses);
|
||||
extern void PWMGenFaultTriggerSet(uint32_t ui32Base, uint32_t ui32Gen,
|
||||
uint32_t ui32Group,
|
||||
uint32_t ui32FaultTriggers);
|
||||
extern uint32_t PWMGenFaultTriggerGet(uint32_t ui32Base,
|
||||
uint32_t ui32Gen,
|
||||
uint32_t ui32Group);
|
||||
extern uint32_t PWMGenFaultStatus(uint32_t ui32Base,
|
||||
uint32_t ui32Gen,
|
||||
uint32_t ui32Group);
|
||||
extern void PWMGenFaultClear(uint32_t ui32Base, uint32_t ui32Gen,
|
||||
uint32_t ui32Group,
|
||||
uint32_t ui32FaultTriggers);
|
||||
extern void PWMClockSet(uint32_t ui32Base, uint32_t ui32Config);
|
||||
extern uint32_t PWMClockGet(uint32_t ui32Base);
|
||||
extern void PWMOutputUpdateMode(uint32_t ui32Base,
|
||||
uint32_t ui32PWMOutBits,
|
||||
uint32_t ui32Mode);
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Mark the end of the C bindings section for C++ compilers.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // __DRIVERLIB_PWM_H__
|
|
@ -0,0 +1,693 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// qei.c - Driver for the Quadrature Encoder with Index.
|
||||
//
|
||||
// Copyright (c) 2005-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! \addtogroup qei_api
|
||||
//! @{
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include "inc/hw_ints.h"
|
||||
#include "inc/hw_memmap.h"
|
||||
#include "inc/hw_qei.h"
|
||||
#include "inc/hw_types.h"
|
||||
#include "inc/hw_sysctl.h"
|
||||
#include "driverlib/debug.h"
|
||||
#include "driverlib/interrupt.h"
|
||||
#include "driverlib/qei.h"
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Enables the quadrature encoder.
|
||||
//!
|
||||
//! \param ui32Base is the base address of the quadrature encoder module.
|
||||
//!
|
||||
//! This function enables operation of the quadrature encoder module. The
|
||||
//! module must be configured before it is enabled.
|
||||
//!
|
||||
//! \sa QEIConfigure()
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
QEIEnable(uint32_t ui32Base)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT((ui32Base == QEI0_BASE) || (ui32Base == QEI1_BASE));
|
||||
|
||||
//
|
||||
// Enable the QEI module.
|
||||
//
|
||||
HWREG(ui32Base + QEI_O_CTL) |= QEI_CTL_ENABLE;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Disables the quadrature encoder.
|
||||
//!
|
||||
//! \param ui32Base is the base address of the quadrature encoder module.
|
||||
//!
|
||||
//! This function disables operation of the quadrature encoder module.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
QEIDisable(uint32_t ui32Base)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT((ui32Base == QEI0_BASE) || (ui32Base == QEI1_BASE));
|
||||
|
||||
//
|
||||
// Disable the QEI module.
|
||||
//
|
||||
HWREG(ui32Base + QEI_O_CTL) &= ~(QEI_CTL_ENABLE);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Configures the quadrature encoder.
|
||||
//!
|
||||
//! \param ui32Base is the base address of the quadrature encoder module.
|
||||
//! \param ui32Config is the configuration for the quadrature encoder. See
|
||||
//! below for a description of this parameter.
|
||||
//! \param ui32MaxPosition specifies the maximum position value.
|
||||
//!
|
||||
//! This function configures the operation of the quadrature encoder. The
|
||||
//! \e ui32Config parameter provides the configuration of the encoder and is
|
||||
//! the logical OR of several values:
|
||||
//!
|
||||
//! - \b QEI_CONFIG_CAPTURE_A or \b QEI_CONFIG_CAPTURE_A_B specify if edges
|
||||
//! on channel A or on both channels A and B should be counted by the
|
||||
//! position integrator and velocity accumulator.
|
||||
//! - \b QEI_CONFIG_NO_RESET or \b QEI_CONFIG_RESET_IDX specify if the
|
||||
//! position integrator should be reset when the index pulse is detected.
|
||||
//! - \b QEI_CONFIG_QUADRATURE or \b QEI_CONFIG_CLOCK_DIR specify if
|
||||
//! quadrature signals are being provided on ChA and ChB, or if a direction
|
||||
//! signal and a clock are being provided instead.
|
||||
//! - \b QEI_CONFIG_NO_SWAP or \b QEI_CONFIG_SWAP to specify if the signals
|
||||
//! provided on ChA and ChB should be swapped before being processed.
|
||||
//!
|
||||
//! \e ui32MaxPosition is the maximum value of the position integrator and is
|
||||
//! the value used to reset the position capture when in index reset mode and
|
||||
//! moving in the reverse (negative) direction.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
QEIConfigure(uint32_t ui32Base, uint32_t ui32Config,
|
||||
uint32_t ui32MaxPosition)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT((ui32Base == QEI0_BASE) || (ui32Base == QEI1_BASE));
|
||||
|
||||
//
|
||||
// Write the new configuration to the hardware.
|
||||
//
|
||||
HWREG(ui32Base + QEI_O_CTL) = ((HWREG(ui32Base + QEI_O_CTL) &
|
||||
~(QEI_CTL_CAPMODE | QEI_CTL_RESMODE |
|
||||
QEI_CTL_SIGMODE | QEI_CTL_SWAP)) |
|
||||
ui32Config);
|
||||
|
||||
//
|
||||
// Set the maximum position.
|
||||
//
|
||||
HWREG(ui32Base + QEI_O_MAXPOS) = ui32MaxPosition;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Gets the current encoder position.
|
||||
//!
|
||||
//! \param ui32Base is the base address of the quadrature encoder module.
|
||||
//!
|
||||
//! This function returns the current position of the encoder. Depending upon
|
||||
//! the configuration of the encoder, and the incident of an index pulse, this
|
||||
//! value may or may not contain the expected data (that is, if in reset on
|
||||
//! index mode, if an index pulse has not been encountered, the position
|
||||
//! counter is not yet aligned with the index pulse).
|
||||
//!
|
||||
//! \return The current position of the encoder.
|
||||
//
|
||||
//*****************************************************************************
|
||||
uint32_t
|
||||
QEIPositionGet(uint32_t ui32Base)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT((ui32Base == QEI0_BASE) || (ui32Base == QEI1_BASE));
|
||||
|
||||
//
|
||||
// Return the current position counter.
|
||||
//
|
||||
return(HWREG(ui32Base + QEI_O_POS));
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Sets the current encoder position.
|
||||
//!
|
||||
//! \param ui32Base is the base address of the quadrature encoder module.
|
||||
//! \param ui32Position is the new position for the encoder.
|
||||
//!
|
||||
//! This function sets the current position of the encoder; the encoder
|
||||
//! position is then measured relative to this value.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
QEIPositionSet(uint32_t ui32Base, uint32_t ui32Position)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT((ui32Base == QEI0_BASE) || (ui32Base == QEI1_BASE));
|
||||
|
||||
//
|
||||
// Set the position counter.
|
||||
//
|
||||
HWREG(ui32Base + QEI_O_POS) = ui32Position;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Gets the current direction of rotation.
|
||||
//!
|
||||
//! \param ui32Base is the base address of the quadrature encoder module.
|
||||
//!
|
||||
//! This function returns the current direction of rotation. In this case,
|
||||
//! current means the most recently detected direction of the encoder; it may
|
||||
//! not be presently moving but this is the direction it last moved before it
|
||||
//! stopped.
|
||||
//!
|
||||
//! \return Returns 1 if moving in the forward direction or -1 if moving in the
|
||||
//! reverse direction.
|
||||
//
|
||||
//*****************************************************************************
|
||||
int32_t
|
||||
QEIDirectionGet(uint32_t ui32Base)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT((ui32Base == QEI0_BASE) || (ui32Base == QEI1_BASE));
|
||||
|
||||
//
|
||||
// Return the direction of rotation.
|
||||
//
|
||||
return((HWREG(ui32Base + QEI_O_STAT) & QEI_STAT_DIRECTION) ? -1 : 1);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Gets the encoder error indicator.
|
||||
//!
|
||||
//! \param ui32Base is the base address of the quadrature encoder module.
|
||||
//!
|
||||
//! This function returns the error indicator for the quadrature encoder. It
|
||||
//! is an error for both of the signals of the quadrature input to change at
|
||||
//! the same time.
|
||||
//!
|
||||
//! \return Returns \b true if an error has occurred and \b false otherwise.
|
||||
//
|
||||
//*****************************************************************************
|
||||
bool
|
||||
QEIErrorGet(uint32_t ui32Base)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT((ui32Base == QEI0_BASE) || (ui32Base == QEI1_BASE));
|
||||
|
||||
//
|
||||
// Return the error indicator.
|
||||
//
|
||||
return((HWREG(ui32Base + QEI_O_STAT) & QEI_STAT_ERROR) ? true : false);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Enables the velocity capture.
|
||||
//!
|
||||
//! \param ui32Base is the base address of the quadrature encoder module.
|
||||
//!
|
||||
//! This function enables operation of the velocity capture in the quadrature
|
||||
//! encoder module. The module must be configured before velocity capture is
|
||||
//! enabled.
|
||||
//!
|
||||
//! \sa QEIVelocityConfigure() and QEIEnable()
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
QEIVelocityEnable(uint32_t ui32Base)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT((ui32Base == QEI0_BASE) || (ui32Base == QEI1_BASE));
|
||||
|
||||
//
|
||||
// Enable the velocity capture.
|
||||
//
|
||||
HWREG(ui32Base + QEI_O_CTL) |= QEI_CTL_VELEN;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Disables the velocity capture.
|
||||
//!
|
||||
//! \param ui32Base is the base address of the quadrature encoder module.
|
||||
//!
|
||||
//! This function disables operation of the velocity capture in the quadrature
|
||||
//! encoder module.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
QEIVelocityDisable(uint32_t ui32Base)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT((ui32Base == QEI0_BASE) || (ui32Base == QEI1_BASE));
|
||||
|
||||
//
|
||||
// Disable the velocity capture.
|
||||
//
|
||||
HWREG(ui32Base + QEI_O_CTL) &= ~(QEI_CTL_VELEN);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Configures the velocity capture.
|
||||
//!
|
||||
//! \param ui32Base is the base address of the quadrature encoder module.
|
||||
//! \param ui32PreDiv specifies the predivider applied to the input quadrature
|
||||
//! signal before it is counted; can be one of \b QEI_VELDIV_1,
|
||||
//! \b QEI_VELDIV_2, \b QEI_VELDIV_4, \b QEI_VELDIV_8, \b QEI_VELDIV_16,
|
||||
//! \b QEI_VELDIV_32, \b QEI_VELDIV_64, or \b QEI_VELDIV_128.
|
||||
//! \param ui32Period specifies the number of clock ticks over which to measure
|
||||
//! the velocity; must be non-zero.
|
||||
//!
|
||||
//! This function configures the operation of the velocity capture portion of
|
||||
//! the quadrature encoder. The position increment signal is predivided as
|
||||
//! specified by \e ui32PreDiv before being accumulated by the velocity
|
||||
//! capture. The divided signal is accumulated over \e ui32Period system clock
|
||||
//! before being saved and resetting the accumulator.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
QEIVelocityConfigure(uint32_t ui32Base, uint32_t ui32PreDiv,
|
||||
uint32_t ui32Period)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT((ui32Base == QEI0_BASE) || (ui32Base == QEI1_BASE));
|
||||
ASSERT(!(ui32PreDiv & ~(QEI_CTL_VELDIV_M)));
|
||||
ASSERT(ui32Period != 0);
|
||||
|
||||
//
|
||||
// Set the velocity predivider.
|
||||
//
|
||||
HWREG(ui32Base + QEI_O_CTL) = ((HWREG(ui32Base + QEI_O_CTL) &
|
||||
~(QEI_CTL_VELDIV_M)) | ui32PreDiv);
|
||||
|
||||
//
|
||||
// Set the timer period.
|
||||
//
|
||||
HWREG(ui32Base + QEI_O_LOAD) = ui32Period - 1;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Gets the current encoder speed.
|
||||
//!
|
||||
//! \param ui32Base is the base address of the quadrature encoder module.
|
||||
//!
|
||||
//! This function returns the current speed of the encoder. The value returned
|
||||
//! is the number of pulses detected in the specified time period; this number
|
||||
//! can be multiplied by the number of time periods per second and divided by
|
||||
//! the number of pulses per revolution to obtain the number of revolutions per
|
||||
//! second.
|
||||
//!
|
||||
//! \return Returns the number of pulses captured in the given time period.
|
||||
//
|
||||
//*****************************************************************************
|
||||
uint32_t
|
||||
QEIVelocityGet(uint32_t ui32Base)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT((ui32Base == QEI0_BASE) || (ui32Base == QEI1_BASE));
|
||||
|
||||
//
|
||||
// Return the speed capture value.
|
||||
//
|
||||
return(HWREG(ui32Base + QEI_O_SPEED));
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Returns the quadrature encoder interrupt number.
|
||||
//!
|
||||
//! \param ui32Base is the base address of the selected quadrature encoder
|
||||
//!
|
||||
//! This function returns the interrupt number for the quadrature encoder with
|
||||
//! the base address passed in the \e ui32Base parameter.
|
||||
//!
|
||||
//! \return Returns a quadrature encoder interrupt number or 0 if the interrupt
|
||||
//! does not exist.
|
||||
//
|
||||
//*****************************************************************************
|
||||
static uint32_t
|
||||
_QEIIntNumberGet(uint32_t ui32Base)
|
||||
{
|
||||
uint32_t ui32Int;
|
||||
|
||||
ASSERT((ui32Base == QEI0_BASE) || (ui32Base == QEI1_BASE));
|
||||
|
||||
//
|
||||
// Find the valid interrupt number for this quadrature encoder.
|
||||
//
|
||||
if(CLASS_IS_TM4C123)
|
||||
{
|
||||
if(ui32Base == QEI0_BASE)
|
||||
{
|
||||
ui32Int = INT_QEI0_TM4C123;
|
||||
}
|
||||
else
|
||||
{
|
||||
ui32Int = INT_QEI1_TM4C123;
|
||||
}
|
||||
}
|
||||
else if(CLASS_IS_TM4C129)
|
||||
{
|
||||
if(ui32Base == QEI0_BASE)
|
||||
{
|
||||
ui32Int = INT_QEI0_TM4C129;
|
||||
}
|
||||
else
|
||||
{
|
||||
ui32Int = 0;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
ui32Int = 0;
|
||||
}
|
||||
|
||||
return(ui32Int);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Registers an interrupt handler for the quadrature encoder interrupt.
|
||||
//!
|
||||
//! \param ui32Base is the base address of the quadrature encoder module.
|
||||
//! \param pfnHandler is a pointer to the function to be called when the
|
||||
//! quadrature encoder interrupt occurs.
|
||||
//!
|
||||
//! This function registers the handler to be called when a quadrature encoder
|
||||
//! interrupt occurs. This function enables the global interrupt in the
|
||||
//! interrupt controller; specific quadrature encoder interrupts must be
|
||||
//! enabled via QEIIntEnable(). It is the interrupt handler's responsibility
|
||||
//! to clear the interrupt source via QEIIntClear().
|
||||
//!
|
||||
//! \sa IntRegister() for important information about registering interrupt
|
||||
//! handlers.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
QEIIntRegister(uint32_t ui32Base, void (*pfnHandler)(void))
|
||||
{
|
||||
uint32_t ui32Int;
|
||||
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT((ui32Base == QEI0_BASE) || (ui32Base == QEI1_BASE));
|
||||
|
||||
//
|
||||
// Determine the interrupt number based on the QEI module.
|
||||
//
|
||||
ui32Int = _QEIIntNumberGet(ui32Base);
|
||||
|
||||
ASSERT(ui32Int != 0);
|
||||
|
||||
//
|
||||
// Register the interrupt handler, returning an error if an error occurs.
|
||||
//
|
||||
IntRegister(ui32Int, pfnHandler);
|
||||
|
||||
//
|
||||
// Enable the quadrature encoder interrupt.
|
||||
//
|
||||
IntEnable(ui32Int);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Unregisters an interrupt handler for the quadrature encoder interrupt.
|
||||
//!
|
||||
//! \param ui32Base is the base address of the quadrature encoder module.
|
||||
//!
|
||||
//! This function unregisters the handler to be called when a quadrature
|
||||
//! encoder 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
|
||||
QEIIntUnregister(uint32_t ui32Base)
|
||||
{
|
||||
uint32_t ui32Int;
|
||||
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT((ui32Base == QEI0_BASE) || (ui32Base == QEI1_BASE));
|
||||
|
||||
//
|
||||
// Determine the interrupt number based on the QEI module.
|
||||
//
|
||||
ui32Int = _QEIIntNumberGet(ui32Base);
|
||||
|
||||
ASSERT(ui32Int != 0);
|
||||
|
||||
//
|
||||
// Disable the interrupt.
|
||||
//
|
||||
IntDisable(ui32Int);
|
||||
|
||||
//
|
||||
// Unregister the interrupt handler.
|
||||
//
|
||||
IntUnregister(ui32Int);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Enables individual quadrature encoder interrupt sources.
|
||||
//!
|
||||
//! \param ui32Base is the base address of the quadrature encoder module.
|
||||
//! \param ui32IntFlags is a bit mask of the interrupt sources to be enabled.
|
||||
//! Can be any of the \b QEI_INTERROR, \b QEI_INTDIR, \b QEI_INTTIMER, or
|
||||
//! \b QEI_INTINDEX values.
|
||||
//!
|
||||
//! This function enables the indicated quadrature encoder 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
|
||||
QEIIntEnable(uint32_t ui32Base, uint32_t ui32IntFlags)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT((ui32Base == QEI0_BASE) || (ui32Base == QEI1_BASE));
|
||||
|
||||
//
|
||||
// Enable the specified interrupts.
|
||||
//
|
||||
HWREG(ui32Base + QEI_O_INTEN) |= ui32IntFlags;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Disables individual quadrature encoder interrupt sources.
|
||||
//!
|
||||
//! \param ui32Base is the base address of the quadrature encoder module.
|
||||
//! \param ui32IntFlags is a bit mask of the interrupt sources to be disabled.
|
||||
//! This parameter can be any of the \b QEI_INTERROR, \b QEI_INTDIR,
|
||||
//! \b QEI_INTTIMER, or \b QEI_INTINDEX values.
|
||||
//!
|
||||
//! This function disables the indicated quadrature encoder 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
|
||||
QEIIntDisable(uint32_t ui32Base, uint32_t ui32IntFlags)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT((ui32Base == QEI0_BASE) || (ui32Base == QEI1_BASE));
|
||||
|
||||
//
|
||||
// Disable the specified interrupts.
|
||||
//
|
||||
HWREG(ui32Base + QEI_O_INTEN) &= ~(ui32IntFlags);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Gets the current interrupt status.
|
||||
//!
|
||||
//! \param ui32Base is the base address of the quadrature encoder module.
|
||||
//! \param bMasked is false if the raw interrupt status is required and true if
|
||||
//! the masked interrupt status is required.
|
||||
//!
|
||||
//! This function returns the interrupt status for the quadrature encoder
|
||||
//! module. Either the raw interrupt status or the status of interrupts that
|
||||
//! are allowed to reflect to the processor can be returned.
|
||||
//!
|
||||
//! \return Returns the current interrupt status, enumerated as a bit field of
|
||||
//! \b QEI_INTERROR, \b QEI_INTDIR, \b QEI_INTTIMER, and \b QEI_INTINDEX.
|
||||
//
|
||||
//*****************************************************************************
|
||||
uint32_t
|
||||
QEIIntStatus(uint32_t ui32Base, bool bMasked)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT((ui32Base == QEI0_BASE) || (ui32Base == QEI1_BASE));
|
||||
|
||||
//
|
||||
// Return either the interrupt status or the raw interrupt status as
|
||||
// requested.
|
||||
//
|
||||
if(bMasked)
|
||||
{
|
||||
return(HWREG(ui32Base + QEI_O_ISC));
|
||||
}
|
||||
else
|
||||
{
|
||||
return(HWREG(ui32Base + QEI_O_RIS));
|
||||
}
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Clears quadrature encoder interrupt sources.
|
||||
//!
|
||||
//! \param ui32Base is the base address of the quadrature encoder module.
|
||||
//! \param ui32IntFlags is a bit mask of the interrupt sources to be cleared.
|
||||
//! This parameter can be any of the \b QEI_INTERROR, \b QEI_INTDIR,
|
||||
//! \b QEI_INTTIMER, or \b QEI_INTINDEX values.
|
||||
//!
|
||||
//! The specified quadrature encoder 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 triggered again immediately upon
|
||||
//! exit.
|
||||
//!
|
||||
//! \note Because there is a write buffer in the Cortex-M 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
|
||||
QEIIntClear(uint32_t ui32Base, uint32_t ui32IntFlags)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT((ui32Base == QEI0_BASE) || (ui32Base == QEI1_BASE));
|
||||
|
||||
//
|
||||
// Clear the requested interrupt sources.
|
||||
//
|
||||
HWREG(ui32Base + QEI_O_ISC) = ui32IntFlags;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Close the Doxygen group.
|
||||
//! @}
|
||||
//
|
||||
//*****************************************************************************
|
|
@ -0,0 +1,128 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// qei.h - Prototypes for the Quadrature Encoder Driver.
|
||||
//
|
||||
// Copyright (c) 2005-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __DRIVERLIB_QEI_H__
|
||||
#define __DRIVERLIB_QEI_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 QEIConfigure as the ui32Config paramater.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define QEI_CONFIG_CAPTURE_A 0x00000000 // Count on ChA edges only
|
||||
#define QEI_CONFIG_CAPTURE_A_B 0x00000008 // Count on ChA and ChB edges
|
||||
#define QEI_CONFIG_NO_RESET 0x00000000 // Do not reset on index pulse
|
||||
#define QEI_CONFIG_RESET_IDX 0x00000010 // Reset position on index pulse
|
||||
#define QEI_CONFIG_QUADRATURE 0x00000000 // ChA and ChB are quadrature
|
||||
#define QEI_CONFIG_CLOCK_DIR 0x00000004 // ChA and ChB are clock and dir
|
||||
#define QEI_CONFIG_NO_SWAP 0x00000000 // Do not swap ChA and ChB
|
||||
#define QEI_CONFIG_SWAP 0x00000002 // Swap ChA and ChB
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to QEIVelocityConfigure as the ui32PreDiv
|
||||
// parameter.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define QEI_VELDIV_1 0x00000000 // Predivide by 1
|
||||
#define QEI_VELDIV_2 0x00000040 // Predivide by 2
|
||||
#define QEI_VELDIV_4 0x00000080 // Predivide by 4
|
||||
#define QEI_VELDIV_8 0x000000C0 // Predivide by 8
|
||||
#define QEI_VELDIV_16 0x00000100 // Predivide by 16
|
||||
#define QEI_VELDIV_32 0x00000140 // Predivide by 32
|
||||
#define QEI_VELDIV_64 0x00000180 // Predivide by 64
|
||||
#define QEI_VELDIV_128 0x000001C0 // Predivide by 128
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to QEIEnableInts, QEIDisableInts, and QEIClearInts
|
||||
// as the ui32IntFlags parameter, and returned by QEIGetIntStatus.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define QEI_INTERROR 0x00000008 // Phase error detected
|
||||
#define QEI_INTDIR 0x00000004 // Direction change
|
||||
#define QEI_INTTIMER 0x00000002 // Velocity timer expired
|
||||
#define QEI_INTINDEX 0x00000001 // Index pulse detected
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Prototypes for the APIs.
|
||||
//
|
||||
//*****************************************************************************
|
||||
extern void QEIEnable(uint32_t ui32Base);
|
||||
extern void QEIDisable(uint32_t ui32Base);
|
||||
extern void QEIConfigure(uint32_t ui32Base, uint32_t ui32Config,
|
||||
uint32_t ui32MaxPosition);
|
||||
extern uint32_t QEIPositionGet(uint32_t ui32Base);
|
||||
extern void QEIPositionSet(uint32_t ui32Base, uint32_t ui32Position);
|
||||
extern int32_t QEIDirectionGet(uint32_t ui32Base);
|
||||
extern bool QEIErrorGet(uint32_t ui32Base);
|
||||
extern void QEIVelocityEnable(uint32_t ui32Base);
|
||||
extern void QEIVelocityDisable(uint32_t ui32Base);
|
||||
extern void QEIVelocityConfigure(uint32_t ui32Base, uint32_t ui32PreDiv,
|
||||
uint32_t ui32Period);
|
||||
extern uint32_t QEIVelocityGet(uint32_t ui32Base);
|
||||
extern void QEIIntRegister(uint32_t ui32Base, void (*pfnHandler)(void));
|
||||
extern void QEIIntUnregister(uint32_t ui32Base);
|
||||
extern void QEIIntEnable(uint32_t ui32Base, uint32_t ui32IntFlags);
|
||||
extern void QEIIntDisable(uint32_t ui32Base, uint32_t ui32IntFlags);
|
||||
extern uint32_t QEIIntStatus(uint32_t ui32Base, bool bMasked);
|
||||
extern void QEIIntClear(uint32_t ui32Base, uint32_t ui32IntFlags);
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Mark the end of the C bindings section for C++ compilers.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // __DRIVERLIB_QEI_H__
|
|
@ -0,0 +1,36 @@
|
|||
This project will build the TivaWare Peripheral Driver Library.
|
||||
|
||||
-------------------------------------------------------------------------------
|
||||
|
||||
Copyright (c) 2006-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
Software License Agreement
|
||||
|
||||
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.
|
||||
|
||||
This is part of revision 2.1.0.12573 of the Tiva Peripheral Driver Library.
|
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,108 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// rtos_bindings.h - Macros intended to aid porting of TivaWare modules
|
||||
// for use with an RTOS.
|
||||
//
|
||||
// Copyright (c) 2012-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __DRIVERLIB_RTOS_BINDINGS_H__
|
||||
#define __DRIVERLIB_RTOS_BINDINGS_H__
|
||||
|
||||
#ifdef USE_RTOS
|
||||
//*****************************************************************************
|
||||
//
|
||||
// If an RTOS is in use, implement a header file called "tiva_rtos.h"
|
||||
// which contains RTOS-specific versions of each of the macros defined below
|
||||
// and make sure it appears on the include path set when you build your
|
||||
// project.
|
||||
//
|
||||
// Note that there is no default implementation of this header file included
|
||||
// in TivaWare - it is your responsibility to create it specifically for
|
||||
// your RTOS.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#include "tiva_rtos.h"
|
||||
|
||||
#else
|
||||
//*****************************************************************************
|
||||
//
|
||||
// When no RTOS is in use, the follow macros compile to either nothing or a
|
||||
// minimal implementation that works in a bare-metal environment.
|
||||
//
|
||||
// Each of these macros must be redefined in tiva_rtos.h if you are using
|
||||
// TivaWare under an RTOS.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// A simple macro used to yield within polling loops. In the default, non-RTOS
|
||||
// implementation, this compiles to nothing.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define OS_YIELD()
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// A simple macro around the SysCtlDelay function. The parameter is the number
|
||||
// of 3 cycle loops to wait before returning (as for SysCtlDelay). In an RTOS
|
||||
// implementation, this could be replaced with an OS delay call with
|
||||
// appropriate parameter scaling.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define OS_DELAY(ul3Cycles) MAP_SysCtlDelay(ul3Cycles)
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Wrappers around low level interrupt control functions. For information
|
||||
// on each of these functions, please see the appropriate API documentation
|
||||
// for the DriverLib Interrupt driver.
|
||||
//
|
||||
// The macros defined here represent interrupt-control functions that may be
|
||||
// called from within TivaWare code. It is expected that application
|
||||
// code will use RTOS-specific functions to control interrupt priority, to
|
||||
// pend interrupts and to perform runtime vector manipulation. As a result,
|
||||
// no macros are defined to wrap any of these functions from interrupt.c.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define OS_INT_MASTER_ENABLE() MAP_IntMasterEnable()
|
||||
#define OS_INT_MASTER_DISABLE() MAP_IntMasterDisable()
|
||||
#define OS_INT_DISABLE(ui32IntID) MAP_IntDisable(ui32IntID)
|
||||
#define OS_INT_ENABLE(ui32IntID) MAP_IntEnable(ui32IntID)
|
||||
|
||||
#endif // USE_RTOS
|
||||
|
||||
#endif // __DRIVERLIB_RTOS_BINDINGS_H__
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,127 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// shamd5.h - Defines and Macros for the SHA/MD5.
|
||||
//
|
||||
// Copyright (c) 2012-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#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
|
||||
#define SHAMD5_ALGO_SHA1 0x0000001a
|
||||
#define SHAMD5_ALGO_SHA224 0x0000001c
|
||||
#define SHAMD5_ALGO_SHA256 0x0000001e
|
||||
#define SHAMD5_ALGO_HMAC_MD5 0x00000000
|
||||
#define SHAMD5_ALGO_HMAC_SHA1 0x00000002
|
||||
#define SHAMD5_ALGO_HMAC_SHA224 0x00000004
|
||||
#define SHAMD5_ALGO_HMAC_SHA256 0x00000006
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// 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 \
|
||||
0x00080000
|
||||
#define SHAMD5_INT_DMA_DATA_IN 0x00020000
|
||||
#define SHAMD5_INT_DMA_CONTEXT_OUT \
|
||||
0x00010000
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Function prototypes
|
||||
//
|
||||
//*****************************************************************************
|
||||
extern void SHAMD5ConfigSet(uint32_t ui32Base, uint32_t ui32Mode);
|
||||
extern void SHAMD5DataProcess(uint32_t ui32Base, uint32_t *pui32DataSrc,
|
||||
uint32_t ui32DataLength,
|
||||
uint32_t *pui32HashResult);
|
||||
extern void SHAMD5DataWrite(uint32_t ui32Base, uint32_t *pui32Src);
|
||||
extern bool SHAMD5DataWriteNonBlocking(uint32_t ui32Base, uint32_t *pui32Src);
|
||||
extern void SHAMD5DMADisable(uint32_t ui32Base);
|
||||
extern void SHAMD5DMAEnable(uint32_t ui32Base);
|
||||
extern void SHAMD5HashLengthSet(uint32_t ui32Base, uint32_t ui32Length);
|
||||
extern void SHAMD5HMACKeySet(uint32_t ui32Base, uint32_t *pui32Src);
|
||||
extern void SHAMD5HMACPPKeyGenerate(uint32_t ui32Base, uint32_t *pui32Key,
|
||||
uint32_t *pui32PPKey);
|
||||
extern void SHAMD5HMACPPKeySet(uint32_t ui32Base, uint32_t *pui32Src);
|
||||
extern void SHAMD5HMACProcess(uint32_t ui32Base, uint32_t *pui32DataSrc,
|
||||
uint32_t ui32DataLength,
|
||||
uint32_t *pui32HashResult);
|
||||
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 SHAMD5Reset(uint32_t ui32Base);
|
||||
extern void SHAMD5ResultRead(uint32_t ui32Base, uint32_t *pui32Dest);
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Mark the end of the C bindings section for C++ compilers.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // __DRIVERLIB_SHAMD5_H__
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,157 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// ssi.h - Prototypes for the Synchronous Serial Interface Driver.
|
||||
//
|
||||
// Copyright (c) 2005-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __DRIVERLIB_SSI_H__
|
||||
#define __DRIVERLIB_SSI_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 SSIIntEnable, SSIIntDisable, and SSIIntClear
|
||||
// as the ui32IntFlags parameter, and returned by SSIIntStatus.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define SSI_TXEOT 0x00000040 // Transmit FIFO is empty
|
||||
#define SSI_DMATX 0x00000020 // DMA Transmit complete
|
||||
#define SSI_DMARX 0x00000010 // DMA Receive complete
|
||||
#define SSI_TXFF 0x00000008 // TX FIFO half full or less
|
||||
#define SSI_RXFF 0x00000004 // RX FIFO half full or more
|
||||
#define SSI_RXTO 0x00000002 // RX timeout
|
||||
#define SSI_RXOR 0x00000001 // RX overrun
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to SSIConfigSetExpClk.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define SSI_FRF_MOTO_MODE_0 0x00000000 // Moto fmt, polarity 0, phase 0
|
||||
#define SSI_FRF_MOTO_MODE_1 0x00000002 // Moto fmt, polarity 0, phase 1
|
||||
#define SSI_FRF_MOTO_MODE_2 0x00000001 // Moto fmt, polarity 1, phase 0
|
||||
#define SSI_FRF_MOTO_MODE_3 0x00000003 // Moto fmt, polarity 1, phase 1
|
||||
#define SSI_FRF_TI 0x00000010 // TI frame format
|
||||
#define SSI_FRF_NMW 0x00000020 // National MicroWire frame format
|
||||
|
||||
#define SSI_MODE_MASTER 0x00000000 // SSI master
|
||||
#define SSI_MODE_SLAVE 0x00000001 // SSI slave
|
||||
#define SSI_MODE_SLAVE_OD 0x00000002 // SSI slave with output disabled
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to SSIDMAEnable() and SSIDMADisable().
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define SSI_DMA_TX 0x00000002 // Enable DMA for transmit
|
||||
#define SSI_DMA_RX 0x00000001 // Enable DMA for receive
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to SSIClockSourceSet() or returned from
|
||||
// SSIClockSourceGet().
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define SSI_CLOCK_SYSTEM 0x00000000
|
||||
#define SSI_CLOCK_PIOSC 0x00000005
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to SSIAdvModeSet().
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define SSI_ADV_MODE_LEGACY 0x00000000
|
||||
#define SSI_ADV_MODE_READ_WRITE 0x000001c0
|
||||
#define SSI_ADV_MODE_WRITE 0x000000c0
|
||||
#define SSI_ADV_MODE_BI_READ 0x00000140
|
||||
#define SSI_ADV_MODE_BI_WRITE 0x00000040
|
||||
#define SSI_ADV_MODE_QUAD_READ 0x00000180
|
||||
#define SSI_ADV_MODE_QUAD_WRITE 0x00000080
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Prototypes for the APIs.
|
||||
//
|
||||
//*****************************************************************************
|
||||
extern void SSIConfigSetExpClk(uint32_t ui32Base, uint32_t ui32SSIClk,
|
||||
uint32_t ui32Protocol, uint32_t ui32Mode,
|
||||
uint32_t ui32BitRate,
|
||||
uint32_t ui32DataWidth);
|
||||
extern void SSIDataGet(uint32_t ui32Base, uint32_t *pui32Data);
|
||||
extern int32_t SSIDataGetNonBlocking(uint32_t ui32Base,
|
||||
uint32_t *pui32Data);
|
||||
extern void SSIDataPut(uint32_t ui32Base, uint32_t ui32Data);
|
||||
extern int32_t SSIDataPutNonBlocking(uint32_t ui32Base, uint32_t ui32Data);
|
||||
extern void SSIDisable(uint32_t ui32Base);
|
||||
extern void SSIEnable(uint32_t ui32Base);
|
||||
extern void SSIIntClear(uint32_t ui32Base, uint32_t ui32IntFlags);
|
||||
extern void SSIIntDisable(uint32_t ui32Base, uint32_t ui32IntFlags);
|
||||
extern void SSIIntEnable(uint32_t ui32Base, uint32_t ui32IntFlags);
|
||||
extern void SSIIntRegister(uint32_t ui32Base, void (*pfnHandler)(void));
|
||||
extern uint32_t SSIIntStatus(uint32_t ui32Base, bool bMasked);
|
||||
extern void SSIIntUnregister(uint32_t ui32Base);
|
||||
extern void SSIDMAEnable(uint32_t ui32Base, uint32_t ui32DMAFlags);
|
||||
extern void SSIDMADisable(uint32_t ui32Base, uint32_t ui32DMAFlags);
|
||||
extern bool SSIBusy(uint32_t ui32Base);
|
||||
extern void SSIClockSourceSet(uint32_t ui32Base, uint32_t ui32Source);
|
||||
extern uint32_t SSIClockSourceGet(uint32_t ui32Base);
|
||||
extern void SSIAdvModeSet(uint32_t ui32Base, uint32_t ui32Mode);
|
||||
extern void SSIAdvDataPutFrameEnd(uint32_t ui32Base, uint32_t ui32Data);
|
||||
extern int32_t SSIAdvDataPutFrameEndNonBlocking(uint32_t ui32Base,
|
||||
uint32_t ui32Data);
|
||||
extern void SSIAdvFrameHoldEnable(uint32_t ui32Base);
|
||||
extern void SSIAdvFrameHoldDisable(uint32_t ui32Base);
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Mark the end of the C bindings section for C++ compilers.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // __DRIVERLIB_SSI_H__
|
|
@ -0,0 +1,770 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// sw_crc.c - Software CRC functions.
|
||||
//
|
||||
// Copyright (c) 2010-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! \addtogroup sw_crc_api
|
||||
//! @{
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#include <stdint.h>
|
||||
#include "driverlib/sw_crc.h"
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The CRC table for the polynomial C(x) = x^8 + x^2 + x + 1 (CRC-8-CCITT).
|
||||
//
|
||||
//*****************************************************************************
|
||||
static const uint8_t g_pui8Crc8CCITT[256] =
|
||||
{
|
||||
0x00, 0x07, 0x0E, 0x09, 0x1C, 0x1B, 0x12, 0x15,
|
||||
0x38, 0x3F, 0x36, 0x31, 0x24, 0x23, 0x2A, 0x2D,
|
||||
0x70, 0x77, 0x7E, 0x79, 0x6C, 0x6B, 0x62, 0x65,
|
||||
0x48, 0x4F, 0x46, 0x41, 0x54, 0x53, 0x5A, 0x5D,
|
||||
0xE0, 0xE7, 0xEE, 0xE9, 0xFC, 0xFB, 0xF2, 0xF5,
|
||||
0xD8, 0xDF, 0xD6, 0xD1, 0xC4, 0xC3, 0xCA, 0xCD,
|
||||
0x90, 0x97, 0x9E, 0x99, 0x8C, 0x8B, 0x82, 0x85,
|
||||
0xA8, 0xAF, 0xA6, 0xA1, 0xB4, 0xB3, 0xBA, 0xBD,
|
||||
0xC7, 0xC0, 0xC9, 0xCE, 0xDB, 0xDC, 0xD5, 0xD2,
|
||||
0xFF, 0xF8, 0xF1, 0xF6, 0xE3, 0xE4, 0xED, 0xEA,
|
||||
0xB7, 0xB0, 0xB9, 0xBE, 0xAB, 0xAC, 0xA5, 0xA2,
|
||||
0x8F, 0x88, 0x81, 0x86, 0x93, 0x94, 0x9D, 0x9A,
|
||||
0x27, 0x20, 0x29, 0x2E, 0x3B, 0x3C, 0x35, 0x32,
|
||||
0x1F, 0x18, 0x11, 0x16, 0x03, 0x04, 0x0D, 0x0A,
|
||||
0x57, 0x50, 0x59, 0x5E, 0x4B, 0x4C, 0x45, 0x42,
|
||||
0x6F, 0x68, 0x61, 0x66, 0x73, 0x74, 0x7D, 0x7A,
|
||||
0x89, 0x8E, 0x87, 0x80, 0x95, 0x92, 0x9B, 0x9C,
|
||||
0xB1, 0xB6, 0xBF, 0xB8, 0xAD, 0xAA, 0xA3, 0xA4,
|
||||
0xF9, 0xFE, 0xF7, 0xF0, 0xE5, 0xE2, 0xEB, 0xEC,
|
||||
0xC1, 0xC6, 0xCF, 0xC8, 0xDD, 0xDA, 0xD3, 0xD4,
|
||||
0x69, 0x6E, 0x67, 0x60, 0x75, 0x72, 0x7B, 0x7C,
|
||||
0x51, 0x56, 0x5F, 0x58, 0x4D, 0x4A, 0x43, 0x44,
|
||||
0x19, 0x1E, 0x17, 0x10, 0x05, 0x02, 0x0B, 0x0C,
|
||||
0x21, 0x26, 0x2F, 0x28, 0x3D, 0x3A, 0x33, 0x34,
|
||||
0x4E, 0x49, 0x40, 0x47, 0x52, 0x55, 0x5C, 0x5B,
|
||||
0x76, 0x71, 0x78, 0x7F, 0x6A, 0x6D, 0x64, 0x63,
|
||||
0x3E, 0x39, 0x30, 0x37, 0x22, 0x25, 0x2C, 0x2B,
|
||||
0x06, 0x01, 0x08, 0x0F, 0x1A, 0x1D, 0x14, 0x13,
|
||||
0xAE, 0xA9, 0xA0, 0xA7, 0xB2, 0xB5, 0xBC, 0xBB,
|
||||
0x96, 0x91, 0x98, 0x9F, 0x8A, 0x8D, 0x84, 0x83,
|
||||
0xDE, 0xD9, 0xD0, 0xD7, 0xC2, 0xC5, 0xCC, 0xCB,
|
||||
0xE6, 0xE1, 0xE8, 0xEF, 0xFA, 0xFD, 0xF4, 0xF3
|
||||
};
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The CRC-16 table for the polynomial C(x) = x^16 + x^15 + x^2 + 1 (standard
|
||||
// CRC-16, also known as CRC-16-IBM and CRC-16-ANSI).
|
||||
//
|
||||
//*****************************************************************************
|
||||
static const uint16_t g_pui16Crc16[256] =
|
||||
{
|
||||
0x0000, 0xC0C1, 0xC181, 0x0140, 0xC301, 0x03C0, 0x0280, 0xC241,
|
||||
0xC601, 0x06C0, 0x0780, 0xC741, 0x0500, 0xC5C1, 0xC481, 0x0440,
|
||||
0xCC01, 0x0CC0, 0x0D80, 0xCD41, 0x0F00, 0xCFC1, 0xCE81, 0x0E40,
|
||||
0x0A00, 0xCAC1, 0xCB81, 0x0B40, 0xC901, 0x09C0, 0x0880, 0xC841,
|
||||
0xD801, 0x18C0, 0x1980, 0xD941, 0x1B00, 0xDBC1, 0xDA81, 0x1A40,
|
||||
0x1E00, 0xDEC1, 0xDF81, 0x1F40, 0xDD01, 0x1DC0, 0x1C80, 0xDC41,
|
||||
0x1400, 0xD4C1, 0xD581, 0x1540, 0xD701, 0x17C0, 0x1680, 0xD641,
|
||||
0xD201, 0x12C0, 0x1380, 0xD341, 0x1100, 0xD1C1, 0xD081, 0x1040,
|
||||
0xF001, 0x30C0, 0x3180, 0xF141, 0x3300, 0xF3C1, 0xF281, 0x3240,
|
||||
0x3600, 0xF6C1, 0xF781, 0x3740, 0xF501, 0x35C0, 0x3480, 0xF441,
|
||||
0x3C00, 0xFCC1, 0xFD81, 0x3D40, 0xFF01, 0x3FC0, 0x3E80, 0xFE41,
|
||||
0xFA01, 0x3AC0, 0x3B80, 0xFB41, 0x3900, 0xF9C1, 0xF881, 0x3840,
|
||||
0x2800, 0xE8C1, 0xE981, 0x2940, 0xEB01, 0x2BC0, 0x2A80, 0xEA41,
|
||||
0xEE01, 0x2EC0, 0x2F80, 0xEF41, 0x2D00, 0xEDC1, 0xEC81, 0x2C40,
|
||||
0xE401, 0x24C0, 0x2580, 0xE541, 0x2700, 0xE7C1, 0xE681, 0x2640,
|
||||
0x2200, 0xE2C1, 0xE381, 0x2340, 0xE101, 0x21C0, 0x2080, 0xE041,
|
||||
0xA001, 0x60C0, 0x6180, 0xA141, 0x6300, 0xA3C1, 0xA281, 0x6240,
|
||||
0x6600, 0xA6C1, 0xA781, 0x6740, 0xA501, 0x65C0, 0x6480, 0xA441,
|
||||
0x6C00, 0xACC1, 0xAD81, 0x6D40, 0xAF01, 0x6FC0, 0x6E80, 0xAE41,
|
||||
0xAA01, 0x6AC0, 0x6B80, 0xAB41, 0x6900, 0xA9C1, 0xA881, 0x6840,
|
||||
0x7800, 0xB8C1, 0xB981, 0x7940, 0xBB01, 0x7BC0, 0x7A80, 0xBA41,
|
||||
0xBE01, 0x7EC0, 0x7F80, 0xBF41, 0x7D00, 0xBDC1, 0xBC81, 0x7C40,
|
||||
0xB401, 0x74C0, 0x7580, 0xB541, 0x7700, 0xB7C1, 0xB681, 0x7640,
|
||||
0x7200, 0xB2C1, 0xB381, 0x7340, 0xB101, 0x71C0, 0x7080, 0xB041,
|
||||
0x5000, 0x90C1, 0x9181, 0x5140, 0x9301, 0x53C0, 0x5280, 0x9241,
|
||||
0x9601, 0x56C0, 0x5780, 0x9741, 0x5500, 0x95C1, 0x9481, 0x5440,
|
||||
0x9C01, 0x5CC0, 0x5D80, 0x9D41, 0x5F00, 0x9FC1, 0x9E81, 0x5E40,
|
||||
0x5A00, 0x9AC1, 0x9B81, 0x5B40, 0x9901, 0x59C0, 0x5880, 0x9841,
|
||||
0x8801, 0x48C0, 0x4980, 0x8941, 0x4B00, 0x8BC1, 0x8A81, 0x4A40,
|
||||
0x4E00, 0x8EC1, 0x8F81, 0x4F40, 0x8D01, 0x4DC0, 0x4C80, 0x8C41,
|
||||
0x4400, 0x84C1, 0x8581, 0x4540, 0x8701, 0x47C0, 0x4680, 0x8641,
|
||||
0x8201, 0x42C0, 0x4380, 0x8341, 0x4100, 0x81C1, 0x8081, 0x4040
|
||||
};
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The CRC-32 table for the polynomial C(x) = x^32 + x^26 + x^23 + x^22 +
|
||||
// x^16 + x^12 + x^11 + x^10 + x^8 + x^7 + x^5 + x^4 + x^2 + x + 1 (standard
|
||||
// CRC32 as used in Ethernet, MPEG-2, PNG, etc.).
|
||||
//
|
||||
//*****************************************************************************
|
||||
static const uint32_t g_pui32Crc32[] =
|
||||
{
|
||||
0x00000000, 0x77073096, 0xee0e612c, 0x990951ba,
|
||||
0x076dc419, 0x706af48f, 0xe963a535, 0x9e6495a3,
|
||||
0x0edb8832, 0x79dcb8a4, 0xe0d5e91e, 0x97d2d988,
|
||||
0x09b64c2b, 0x7eb17cbd, 0xe7b82d07, 0x90bf1d91,
|
||||
0x1db71064, 0x6ab020f2, 0xf3b97148, 0x84be41de,
|
||||
0x1adad47d, 0x6ddde4eb, 0xf4d4b551, 0x83d385c7,
|
||||
0x136c9856, 0x646ba8c0, 0xfd62f97a, 0x8a65c9ec,
|
||||
0x14015c4f, 0x63066cd9, 0xfa0f3d63, 0x8d080df5,
|
||||
0x3b6e20c8, 0x4c69105e, 0xd56041e4, 0xa2677172,
|
||||
0x3c03e4d1, 0x4b04d447, 0xd20d85fd, 0xa50ab56b,
|
||||
0x35b5a8fa, 0x42b2986c, 0xdbbbc9d6, 0xacbcf940,
|
||||
0x32d86ce3, 0x45df5c75, 0xdcd60dcf, 0xabd13d59,
|
||||
0x26d930ac, 0x51de003a, 0xc8d75180, 0xbfd06116,
|
||||
0x21b4f4b5, 0x56b3c423, 0xcfba9599, 0xb8bda50f,
|
||||
0x2802b89e, 0x5f058808, 0xc60cd9b2, 0xb10be924,
|
||||
0x2f6f7c87, 0x58684c11, 0xc1611dab, 0xb6662d3d,
|
||||
0x76dc4190, 0x01db7106, 0x98d220bc, 0xefd5102a,
|
||||
0x71b18589, 0x06b6b51f, 0x9fbfe4a5, 0xe8b8d433,
|
||||
0x7807c9a2, 0x0f00f934, 0x9609a88e, 0xe10e9818,
|
||||
0x7f6a0dbb, 0x086d3d2d, 0x91646c97, 0xe6635c01,
|
||||
0x6b6b51f4, 0x1c6c6162, 0x856530d8, 0xf262004e,
|
||||
0x6c0695ed, 0x1b01a57b, 0x8208f4c1, 0xf50fc457,
|
||||
0x65b0d9c6, 0x12b7e950, 0x8bbeb8ea, 0xfcb9887c,
|
||||
0x62dd1ddf, 0x15da2d49, 0x8cd37cf3, 0xfbd44c65,
|
||||
0x4db26158, 0x3ab551ce, 0xa3bc0074, 0xd4bb30e2,
|
||||
0x4adfa541, 0x3dd895d7, 0xa4d1c46d, 0xd3d6f4fb,
|
||||
0x4369e96a, 0x346ed9fc, 0xad678846, 0xda60b8d0,
|
||||
0x44042d73, 0x33031de5, 0xaa0a4c5f, 0xdd0d7cc9,
|
||||
0x5005713c, 0x270241aa, 0xbe0b1010, 0xc90c2086,
|
||||
0x5768b525, 0x206f85b3, 0xb966d409, 0xce61e49f,
|
||||
0x5edef90e, 0x29d9c998, 0xb0d09822, 0xc7d7a8b4,
|
||||
0x59b33d17, 0x2eb40d81, 0xb7bd5c3b, 0xc0ba6cad,
|
||||
0xedb88320, 0x9abfb3b6, 0x03b6e20c, 0x74b1d29a,
|
||||
0xead54739, 0x9dd277af, 0x04db2615, 0x73dc1683,
|
||||
0xe3630b12, 0x94643b84, 0x0d6d6a3e, 0x7a6a5aa8,
|
||||
0xe40ecf0b, 0x9309ff9d, 0x0a00ae27, 0x7d079eb1,
|
||||
0xf00f9344, 0x8708a3d2, 0x1e01f268, 0x6906c2fe,
|
||||
0xf762575d, 0x806567cb, 0x196c3671, 0x6e6b06e7,
|
||||
0xfed41b76, 0x89d32be0, 0x10da7a5a, 0x67dd4acc,
|
||||
0xf9b9df6f, 0x8ebeeff9, 0x17b7be43, 0x60b08ed5,
|
||||
0xd6d6a3e8, 0xa1d1937e, 0x38d8c2c4, 0x4fdff252,
|
||||
0xd1bb67f1, 0xa6bc5767, 0x3fb506dd, 0x48b2364b,
|
||||
0xd80d2bda, 0xaf0a1b4c, 0x36034af6, 0x41047a60,
|
||||
0xdf60efc3, 0xa867df55, 0x316e8eef, 0x4669be79,
|
||||
0xcb61b38c, 0xbc66831a, 0x256fd2a0, 0x5268e236,
|
||||
0xcc0c7795, 0xbb0b4703, 0x220216b9, 0x5505262f,
|
||||
0xc5ba3bbe, 0xb2bd0b28, 0x2bb45a92, 0x5cb36a04,
|
||||
0xc2d7ffa7, 0xb5d0cf31, 0x2cd99e8b, 0x5bdeae1d,
|
||||
0x9b64c2b0, 0xec63f226, 0x756aa39c, 0x026d930a,
|
||||
0x9c0906a9, 0xeb0e363f, 0x72076785, 0x05005713,
|
||||
0x95bf4a82, 0xe2b87a14, 0x7bb12bae, 0x0cb61b38,
|
||||
0x92d28e9b, 0xe5d5be0d, 0x7cdcefb7, 0x0bdbdf21,
|
||||
0x86d3d2d4, 0xf1d4e242, 0x68ddb3f8, 0x1fda836e,
|
||||
0x81be16cd, 0xf6b9265b, 0x6fb077e1, 0x18b74777,
|
||||
0x88085ae6, 0xff0f6a70, 0x66063bca, 0x11010b5c,
|
||||
0x8f659eff, 0xf862ae69, 0x616bffd3, 0x166ccf45,
|
||||
0xa00ae278, 0xd70dd2ee, 0x4e048354, 0x3903b3c2,
|
||||
0xa7672661, 0xd06016f7, 0x4969474d, 0x3e6e77db,
|
||||
0xaed16a4a, 0xd9d65adc, 0x40df0b66, 0x37d83bf0,
|
||||
0xa9bcae53, 0xdebb9ec5, 0x47b2cf7f, 0x30b5ffe9,
|
||||
0xbdbdf21c, 0xcabac28a, 0x53b39330, 0x24b4a3a6,
|
||||
0xbad03605, 0xcdd70693, 0x54de5729, 0x23d967bf,
|
||||
0xb3667a2e, 0xc4614ab8, 0x5d681b02, 0x2a6f2b94,
|
||||
0xb40bbe37, 0xc30c8ea1, 0x5a05df1b, 0x2d02ef8d,
|
||||
};
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// This macro executes one iteration of the CRC-8-CCITT.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CRC8_ITER(crc, data) g_pui8Crc8CCITT[(uint8_t)((crc) ^ (data))]
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// This macro executes one iteration of the CRC-16.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CRC16_ITER(crc, data) (((crc) >> 8) ^ \
|
||||
g_pui16Crc16[(uint8_t)((crc) ^ (data))])
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// This macro executes one iteration of the CRC-32.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CRC32_ITER(crc, data) (((crc) >> 8) ^ \
|
||||
g_pui32Crc32[(uint8_t)((crc & 0xFF) ^ \
|
||||
(data))])
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Calculates the CRC-8-CCITT of an array of bytes.
|
||||
//!
|
||||
//! \param ui8Crc is the starting CRC-8-CCITT value.
|
||||
//! \param pui8Data is a pointer to the data buffer.
|
||||
//! \param ui32Count is the number of bytes in the data buffer.
|
||||
//!
|
||||
//! This function is used to calculate the CRC-8-CCITT of the input buffer.
|
||||
//! The CRC-8-CCITT is computed in a running fashion, meaning that the entire
|
||||
//! data block that is to have its CRC-8-CCITT computed does not need to be
|
||||
//! supplied all at once. If the input buffer contains the entire block of
|
||||
//! data, then \b ui8Crc should be set to 0. If, however, the entire block of
|
||||
//! data is not available, then \b ui8Crc should be set to 0 for the first
|
||||
//! portion of the data, and then the returned value should be passed back in
|
||||
//! as \b ui8Crc for the next portion of the data.
|
||||
//!
|
||||
//! For example, to compute the CRC-8-CCITT of a block that has been split into
|
||||
//! three pieces, use the following:
|
||||
//!
|
||||
//! \verbatim
|
||||
//! ui8Crc = Crc8CCITT(0, pui8Data1, ui32Len1);
|
||||
//! ui8Crc = Crc8CCITT(ui8Crc, pui8Data2, ui32Len2);
|
||||
//! ui8Crc = Crc8CCITT(ui8Crc, pui8Data3, ui32Len3);
|
||||
//! \endverbatim
|
||||
//!
|
||||
//! Computing a CRC-8-CCITT in a running fashion is useful in cases where the
|
||||
//! data is arriving via a serial link (for example) and is therefore not all
|
||||
//! available at one time.
|
||||
//!
|
||||
//! \return The CRC-8-CCITT of the input data.
|
||||
//
|
||||
//*****************************************************************************
|
||||
uint8_t
|
||||
Crc8CCITT(uint8_t ui8Crc, const uint8_t *pui8Data, uint32_t ui32Count)
|
||||
{
|
||||
uint32_t ui32Temp;
|
||||
|
||||
//
|
||||
// If the data buffer is not 16 bit-aligned, then perform a single step of
|
||||
// the CRC to make it 16 bit-aligned.
|
||||
//
|
||||
if((uint32_t)pui8Data & 1)
|
||||
{
|
||||
//
|
||||
// Perform the CRC on this input byte.
|
||||
//
|
||||
ui8Crc = CRC8_ITER(ui8Crc, *pui8Data);
|
||||
|
||||
//
|
||||
// Skip this input byte.
|
||||
//
|
||||
pui8Data++;
|
||||
ui32Count--;
|
||||
}
|
||||
|
||||
//
|
||||
// If the data buffer is not word-aligned and there are at least two bytes
|
||||
// of data left, then perform two steps of the CRC to make it word-aligned.
|
||||
//
|
||||
if(((uint32_t)pui8Data & 2) && (ui32Count > 1))
|
||||
{
|
||||
//
|
||||
// Read the next 16 bits.
|
||||
//
|
||||
ui32Temp = *(uint16_t *)pui8Data;
|
||||
|
||||
//
|
||||
// Perform the CRC on these two bytes.
|
||||
//
|
||||
ui8Crc = CRC8_ITER(ui8Crc, ui32Temp);
|
||||
ui8Crc = CRC8_ITER(ui8Crc, ui32Temp >> 8);
|
||||
|
||||
//
|
||||
// Skip these input bytes.
|
||||
//
|
||||
pui8Data += 2;
|
||||
ui32Count -= 2;
|
||||
}
|
||||
|
||||
//
|
||||
// While there is at least a word remaining in the data buffer, perform
|
||||
// four steps of the CRC to consume a word.
|
||||
//
|
||||
while(ui32Count > 3)
|
||||
{
|
||||
//
|
||||
// Read the next word.
|
||||
//
|
||||
ui32Temp = *(uint32_t *)pui8Data;
|
||||
|
||||
//
|
||||
// Perform the CRC on these four bytes.
|
||||
//
|
||||
ui8Crc = CRC8_ITER(ui8Crc, ui32Temp);
|
||||
ui8Crc = CRC8_ITER(ui8Crc, ui32Temp >> 8);
|
||||
ui8Crc = CRC8_ITER(ui8Crc, ui32Temp >> 16);
|
||||
ui8Crc = CRC8_ITER(ui8Crc, ui32Temp >> 24);
|
||||
|
||||
//
|
||||
// Skip these input bytes.
|
||||
//
|
||||
pui8Data += 4;
|
||||
ui32Count -= 4;
|
||||
}
|
||||
|
||||
//
|
||||
// If there are 16 bits left in the input buffer, then perform two steps of
|
||||
// the CRC.
|
||||
//
|
||||
if(ui32Count > 1)
|
||||
{
|
||||
//
|
||||
// Read the 16 bits.
|
||||
//
|
||||
ui32Temp = *(uint16_t *)pui8Data;
|
||||
|
||||
//
|
||||
// Perform the CRC on these two bytes.
|
||||
//
|
||||
ui8Crc = CRC8_ITER(ui8Crc, ui32Temp);
|
||||
ui8Crc = CRC8_ITER(ui8Crc, ui32Temp >> 8);
|
||||
|
||||
//
|
||||
// Skip these input bytes.
|
||||
//
|
||||
pui8Data += 2;
|
||||
ui32Count -= 2;
|
||||
}
|
||||
|
||||
//
|
||||
// If there is a final byte remaining in the input buffer, then perform a
|
||||
// single step of the CRC.
|
||||
//
|
||||
if(ui32Count != 0)
|
||||
{
|
||||
ui8Crc = CRC8_ITER(ui8Crc, *pui8Data);
|
||||
}
|
||||
|
||||
//
|
||||
// Return the resulting CRC-8-CCITT value.
|
||||
//
|
||||
return(ui8Crc);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Calculates the CRC-16 of an array of bytes.
|
||||
//!
|
||||
//! \param ui16Crc is the starting CRC-16 value.
|
||||
//! \param pui8Data is a pointer to the data buffer.
|
||||
//! \param ui32Count is the number of bytes in the data buffer.
|
||||
//!
|
||||
//! This function is used to calculate the CRC-16 of the input buffer. The
|
||||
//! CRC-16 is computed in a running fashion, meaning that the entire data block
|
||||
//! that is to have its CRC-16 computed does not need to be supplied all at
|
||||
//! once. If the input buffer contains the entire block of data, then
|
||||
//! \b ui16Crc should be set to 0. If, however, the entire block of data is
|
||||
//! not available, then \b ui16Crc should be set to 0 for the first portion of
|
||||
//! the data, and then the returned value should be passed back in as
|
||||
//! \b ui16Crc for the next portion of the data.
|
||||
//!
|
||||
//! For example, to compute the CRC-16 of a block that has been split into
|
||||
//! three pieces, use the following:
|
||||
//!
|
||||
//! \verbatim
|
||||
//! ui16Crc = Crc16(0, pui8Data1, ui32Len1);
|
||||
//! ui16Crc = Crc16(ui16Crc, pui8Data2, ui32Len2);
|
||||
//! ui16Crc = Crc16(ui16Crc, pui8Data3, ui32Len3);
|
||||
//! \endverbatim
|
||||
//!
|
||||
//! Computing a CRC-16 in a running fashion is useful in cases where the data
|
||||
//! is arriving via a serial link (for example) and is therefore not all
|
||||
//! available at one time.
|
||||
//!
|
||||
//! \return The CRC-16 of the input data.
|
||||
//
|
||||
//*****************************************************************************
|
||||
uint16_t
|
||||
Crc16(uint16_t ui16Crc, const uint8_t *pui8Data, uint32_t ui32Count)
|
||||
{
|
||||
uint32_t ui32Temp;
|
||||
|
||||
//
|
||||
// If the data buffer is not 16 bit-aligned, then perform a single step of
|
||||
// the CRC to make it 16 bit-aligned.
|
||||
//
|
||||
if((uint32_t)pui8Data & 1)
|
||||
{
|
||||
//
|
||||
// Perform the CRC on this input byte.
|
||||
//
|
||||
ui16Crc = CRC16_ITER(ui16Crc, *pui8Data);
|
||||
|
||||
//
|
||||
// Skip this input byte.
|
||||
//
|
||||
pui8Data++;
|
||||
ui32Count--;
|
||||
}
|
||||
|
||||
//
|
||||
// If the data buffer is not word-aligned and there are at least two bytes
|
||||
// of data left, then perform two steps of the CRC to make it word-aligned.
|
||||
//
|
||||
if(((uint32_t)pui8Data & 2) && (ui32Count > 1))
|
||||
{
|
||||
//
|
||||
// Read the next 16 bits.
|
||||
//
|
||||
ui32Temp = *(uint16_t *)pui8Data;
|
||||
|
||||
//
|
||||
// Perform the CRC on these two bytes.
|
||||
//
|
||||
ui16Crc = CRC16_ITER(ui16Crc, ui32Temp);
|
||||
ui16Crc = CRC16_ITER(ui16Crc, ui32Temp >> 8);
|
||||
|
||||
//
|
||||
// Skip these input bytes.
|
||||
//
|
||||
pui8Data += 2;
|
||||
ui32Count -= 2;
|
||||
}
|
||||
|
||||
//
|
||||
// While there is at least a word remaining in the data buffer, perform
|
||||
// four steps of the CRC to consume a word.
|
||||
//
|
||||
while(ui32Count > 3)
|
||||
{
|
||||
//
|
||||
// Read the next word.
|
||||
//
|
||||
ui32Temp = *(uint32_t *)pui8Data;
|
||||
|
||||
//
|
||||
// Perform the CRC on these four bytes.
|
||||
//
|
||||
ui16Crc = CRC16_ITER(ui16Crc, ui32Temp);
|
||||
ui16Crc = CRC16_ITER(ui16Crc, ui32Temp >> 8);
|
||||
ui16Crc = CRC16_ITER(ui16Crc, ui32Temp >> 16);
|
||||
ui16Crc = CRC16_ITER(ui16Crc, ui32Temp >> 24);
|
||||
|
||||
//
|
||||
// Skip these input bytes.
|
||||
//
|
||||
pui8Data += 4;
|
||||
ui32Count -= 4;
|
||||
}
|
||||
|
||||
//
|
||||
// If there are two bytes left in the input buffer, then perform two steps
|
||||
// of the CRC.
|
||||
//
|
||||
if(ui32Count > 1)
|
||||
{
|
||||
//
|
||||
// Read the two bytes.
|
||||
//
|
||||
ui32Temp = *(uint16_t *)pui8Data;
|
||||
|
||||
//
|
||||
// Perform the CRC on these two bytes.
|
||||
//
|
||||
ui16Crc = CRC16_ITER(ui16Crc, ui32Temp);
|
||||
ui16Crc = CRC16_ITER(ui16Crc, ui32Temp >> 8);
|
||||
|
||||
//
|
||||
// Skip these input bytes.
|
||||
//
|
||||
pui8Data += 2;
|
||||
ui32Count -= 2;
|
||||
}
|
||||
|
||||
//
|
||||
// If there is a final byte remaining in the input buffer, then perform a
|
||||
// single step of the CRC.
|
||||
//
|
||||
if(ui32Count != 0)
|
||||
{
|
||||
ui16Crc = CRC16_ITER(ui16Crc, *pui8Data);
|
||||
}
|
||||
|
||||
//
|
||||
// Return the resulting CRC-16 value.
|
||||
//
|
||||
return(ui16Crc);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Calculates the CRC-16 of an array of words.
|
||||
//!
|
||||
//! \param ui32WordLen is the length of the array in words (the number of bytes
|
||||
//! divided by 4).
|
||||
//! \param pui32Data is a pointer to the data buffer.
|
||||
//!
|
||||
//! This function is a wrapper around the running CRC-16 function, providing
|
||||
//! the CRC-16 for a single block of data.
|
||||
//!
|
||||
//! \return The CRC-16 of the input data.
|
||||
//
|
||||
//*****************************************************************************
|
||||
uint16_t
|
||||
Crc16Array(uint32_t ui32WordLen, const uint32_t *pui32Data)
|
||||
{
|
||||
//
|
||||
// Calculate and return the CRC-16 of this array of words.
|
||||
//
|
||||
return(Crc16(0, (const uint8_t *)pui32Data, ui32WordLen * 4));
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Calculates three CRC-16s of an array of words.
|
||||
//!
|
||||
//! \param ui32WordLen is the length of the array in words (the number of bytes
|
||||
//! divided by 4).
|
||||
//! \param pui32Data is a pointer to the data buffer.
|
||||
//! \param pui16Crc3 is a pointer to an array in which to place the three
|
||||
//! CRC-16 values.
|
||||
//!
|
||||
//! This function is used to calculate three CRC-16s of the input buffer; the
|
||||
//! first uses every byte from the array, the second uses only the even-index
|
||||
//! bytes from the array (in other words, bytes 0, 2, 4, etc.), and the third
|
||||
//! uses only the odd-index bytes from the array (in other words, bytes 1, 3,
|
||||
//! 5, etc.).
|
||||
//!
|
||||
//! \return None
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
Crc16Array3(uint32_t ui32WordLen, const uint32_t *pui32Data,
|
||||
uint16_t *pui16Crc3)
|
||||
{
|
||||
uint16_t ui16Crc, ui16Cri8Odd, ui16Cri8Even;
|
||||
uint32_t ui32Temp;
|
||||
|
||||
//
|
||||
// Initialize the CRC values to zero.
|
||||
//
|
||||
ui16Crc = 0;
|
||||
ui16Cri8Odd = 0;
|
||||
ui16Cri8Even = 0;
|
||||
|
||||
//
|
||||
// Loop while there are more words in the data buffer.
|
||||
//
|
||||
while(ui32WordLen--)
|
||||
{
|
||||
//
|
||||
// Read the next word.
|
||||
//
|
||||
ui32Temp = *pui32Data++;
|
||||
|
||||
//
|
||||
// Perform the first CRC on all four data bytes.
|
||||
//
|
||||
ui16Crc = CRC16_ITER(ui16Crc, ui32Temp);
|
||||
ui16Crc = CRC16_ITER(ui16Crc, ui32Temp >> 8);
|
||||
ui16Crc = CRC16_ITER(ui16Crc, ui32Temp >> 16);
|
||||
ui16Crc = CRC16_ITER(ui16Crc, ui32Temp >> 24);
|
||||
|
||||
//
|
||||
// Perform the second CRC on only the even-index data bytes.
|
||||
//
|
||||
ui16Cri8Even = CRC16_ITER(ui16Cri8Even, ui32Temp);
|
||||
ui16Cri8Even = CRC16_ITER(ui16Cri8Even, ui32Temp >> 16);
|
||||
|
||||
//
|
||||
// Perform the third CRC on only the odd-index data bytes.
|
||||
//
|
||||
ui16Cri8Odd = CRC16_ITER(ui16Cri8Odd, ui32Temp >> 8);
|
||||
ui16Cri8Odd = CRC16_ITER(ui16Cri8Odd, ui32Temp >> 24);
|
||||
}
|
||||
|
||||
//
|
||||
// Return the resulting CRC-16 values.
|
||||
//
|
||||
pui16Crc3[0] = ui16Crc;
|
||||
pui16Crc3[1] = ui16Cri8Even;
|
||||
pui16Crc3[2] = ui16Cri8Odd;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Calculates the CRC-32 of an array of bytes.
|
||||
//!
|
||||
//! \param ui32Crc is the starting CRC-32 value.
|
||||
//! \param pui8Data is a pointer to the data buffer.
|
||||
//! \param ui32Count is the number of bytes in the data buffer.
|
||||
//!
|
||||
//! This function is used to calculate the CRC-32 of the input buffer. The
|
||||
//! CRC-32 is computed in a running fashion, meaning that the entire data block
|
||||
//! that is to have its CRC-32 computed does not need to be supplied all at
|
||||
//! once. If the input buffer contains the entire block of data, then
|
||||
//! \b ui32Crc should be set to 0xFFFFFFFF. If, however, the entire block of
|
||||
//! data is not available, then \b ui32Crc should be set to 0xFFFFFFFF for the
|
||||
//! first portion of the data, and then the returned value should be passed
|
||||
//! back in as \b ui32Crc for the next portion of the data. Once all data has
|
||||
//! been passed to the function, the final CRC-32 can be obtained by inverting
|
||||
//! the last returned value.
|
||||
//!
|
||||
//! For example, to compute the CRC-32 of a block that has been split into
|
||||
//! three pieces, use the following:
|
||||
//!
|
||||
//! \verbatim
|
||||
//! ui32Crc = Crc32(0xFFFFFFFF, pui8Data1, ui32Len1);
|
||||
//! ui32Crc = Crc32(ui32Crc, pui8Data2, ui32Len2);
|
||||
//! ui32Crc = Crc32(ui32Crc, pui8Data3, ui32Len3);
|
||||
//! ui32Crc ^= 0xFFFFFFFF;
|
||||
//! \endverbatim
|
||||
//!
|
||||
//! Computing a CRC-32 in a running fashion is useful in cases where the data
|
||||
//! is arriving via a serial link (for example) and is therefore not all
|
||||
//! available at one time.
|
||||
//!
|
||||
//! \return The accumulated CRC-32 of the input data.
|
||||
//
|
||||
//*****************************************************************************
|
||||
uint32_t
|
||||
Crc32(uint32_t ui32Crc, const uint8_t *pui8Data, uint32_t ui32Count)
|
||||
{
|
||||
uint32_t ui32Temp;
|
||||
|
||||
//
|
||||
// If the data buffer is not 16 bit-aligned, then perform a single step
|
||||
// of the CRC to make it 16 bit-aligned.
|
||||
//
|
||||
if((uint32_t)pui8Data & 1)
|
||||
{
|
||||
//
|
||||
// Perform the CRC on this input byte.
|
||||
//
|
||||
ui32Crc = CRC32_ITER(ui32Crc, *pui8Data);
|
||||
|
||||
//
|
||||
// Skip this input byte.
|
||||
//
|
||||
pui8Data++;
|
||||
ui32Count--;
|
||||
}
|
||||
|
||||
//
|
||||
// If the data buffer is not word-aligned and there are at least two bytes
|
||||
// of data left, then perform two steps of the CRC to make it word-aligned.
|
||||
//
|
||||
if(((uint32_t)pui8Data & 2) && (ui32Count > 1))
|
||||
{
|
||||
//
|
||||
// Read the next int16_t.
|
||||
//
|
||||
ui32Temp = *(uint16_t *)pui8Data;
|
||||
|
||||
//
|
||||
// Perform the CRC on these two bytes.
|
||||
//
|
||||
ui32Crc = CRC32_ITER(ui32Crc, ui32Temp);
|
||||
ui32Crc = CRC32_ITER(ui32Crc, ui32Temp >> 8);
|
||||
|
||||
//
|
||||
// Skip these input bytes.
|
||||
//
|
||||
pui8Data += 2;
|
||||
ui32Count -= 2;
|
||||
}
|
||||
|
||||
//
|
||||
// While there is at least a word remaining in the data buffer, perform
|
||||
// four steps of the CRC to consume a word.
|
||||
//
|
||||
while(ui32Count > 3)
|
||||
{
|
||||
//
|
||||
// Read the next word.
|
||||
//
|
||||
ui32Temp = *(uint32_t *)pui8Data;
|
||||
|
||||
//
|
||||
// Perform the CRC on these four bytes.
|
||||
//
|
||||
ui32Crc = CRC32_ITER(ui32Crc, ui32Temp);
|
||||
ui32Crc = CRC32_ITER(ui32Crc, ui32Temp >> 8);
|
||||
ui32Crc = CRC32_ITER(ui32Crc, ui32Temp >> 16);
|
||||
ui32Crc = CRC32_ITER(ui32Crc, ui32Temp >> 24);
|
||||
|
||||
//
|
||||
// Skip these input bytes.
|
||||
//
|
||||
pui8Data += 4;
|
||||
ui32Count -= 4;
|
||||
}
|
||||
|
||||
//
|
||||
// If there are 16 bits left in the input buffer, then perform two steps of
|
||||
// the CRC.
|
||||
//
|
||||
if(ui32Count > 1)
|
||||
{
|
||||
//
|
||||
// Read the two bytes.
|
||||
//
|
||||
ui32Temp = *(uint16_t *)pui8Data;
|
||||
|
||||
//
|
||||
// Perform the CRC on these two bytes.
|
||||
//
|
||||
ui32Crc = CRC32_ITER(ui32Crc, ui32Temp);
|
||||
ui32Crc = CRC32_ITER(ui32Crc, ui32Temp >> 8);
|
||||
|
||||
//
|
||||
// Skip these input bytes.
|
||||
//
|
||||
pui8Data += 2;
|
||||
ui32Count -= 2;
|
||||
}
|
||||
|
||||
//
|
||||
// If there is a final byte remaining in the input buffer, then perform a
|
||||
// single step of the CRC.
|
||||
//
|
||||
if(ui32Count != 0)
|
||||
{
|
||||
ui32Crc = CRC32_ITER(ui32Crc, *pui8Data);
|
||||
}
|
||||
|
||||
//
|
||||
// Return the resulting CRC-32 value.
|
||||
//
|
||||
return(ui32Crc);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Close the Doxygen group.
|
||||
//! @}
|
||||
//
|
||||
//*****************************************************************************
|
|
@ -0,0 +1,78 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// sw_crc.h - Prototypes for the software CRC functions.
|
||||
//
|
||||
// Copyright (c) 2010-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __DRIVERLIB_SW_CRC_H__
|
||||
#define __DRIVERLIB_SW_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
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Prototypes for the functions.
|
||||
//
|
||||
//*****************************************************************************
|
||||
extern uint8_t Crc8CCITT(uint8_t ui8Crc, const uint8_t *pui8Data,
|
||||
uint32_t ui32Count);
|
||||
extern uint16_t Crc16(uint16_t ui16Crc, const uint8_t *pui8Data,
|
||||
uint32_t ui32Count);
|
||||
extern uint16_t Crc16Array(uint32_t ui32WordLen, const uint32_t *pui32Data);
|
||||
extern void Crc16Array3(uint32_t ui32WordLen, const uint32_t *pui32Data,
|
||||
uint16_t *pui16Crc3);
|
||||
extern uint32_t Crc32(uint32_t ui32Crc, const uint8_t *pui8Data,
|
||||
uint32_t ui32Count);
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Mark the end of the C bindings section for C++ compilers.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // __DRIVERLIB_SW_CRC_H__
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,655 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// sysctl.h - Prototypes for the system control driver.
|
||||
//
|
||||
// Copyright (c) 2005-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __DRIVERLIB_SYSCTL_H__
|
||||
#define __DRIVERLIB_SYSCTL_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 are values that can be passed to the
|
||||
// SysCtlPeripheralPresent(), SysCtlPeripheralEnable(),
|
||||
// SysCtlPeripheralDisable(), and SysCtlPeripheralReset() APIs as the
|
||||
// ui32Peripheral parameter. The peripherals in the fourth group (upper nibble
|
||||
// is 3) can only be used with the SysCtlPeripheralPresent() API.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define SYSCTL_PERIPH_ADC0 0xf0003800 // ADC 0
|
||||
#define SYSCTL_PERIPH_ADC1 0xf0003801 // ADC 1
|
||||
#define SYSCTL_PERIPH_CAN0 0xf0003400 // CAN 0
|
||||
#define SYSCTL_PERIPH_CAN1 0xf0003401 // CAN 1
|
||||
#define SYSCTL_PERIPH_COMP0 0xf0003c00 // Analog Comparator Module 0
|
||||
#define SYSCTL_PERIPH_EMAC0 0xf0009c00 // Ethernet MAC0
|
||||
#define SYSCTL_PERIPH_EPHY0 0xf0003000 // Ethernet PHY0
|
||||
#define SYSCTL_PERIPH_EPI0 0xf0001000 // EPI0
|
||||
#define SYSCTL_PERIPH_GPIOA 0xf0000800 // GPIO A
|
||||
#define SYSCTL_PERIPH_GPIOB 0xf0000801 // GPIO B
|
||||
#define SYSCTL_PERIPH_GPIOC 0xf0000802 // GPIO C
|
||||
#define SYSCTL_PERIPH_GPIOD 0xf0000803 // GPIO D
|
||||
#define SYSCTL_PERIPH_GPIOE 0xf0000804 // GPIO E
|
||||
#define SYSCTL_PERIPH_GPIOF 0xf0000805 // GPIO F
|
||||
#define SYSCTL_PERIPH_GPIOG 0xf0000806 // GPIO G
|
||||
#define SYSCTL_PERIPH_GPIOH 0xf0000807 // GPIO H
|
||||
#define SYSCTL_PERIPH_GPIOJ 0xf0000808 // GPIO J
|
||||
#define SYSCTL_PERIPH_HIBERNATE 0xf0001400 // Hibernation module
|
||||
#define SYSCTL_PERIPH_CCM0 0xf0007400 // CCM 0
|
||||
#define SYSCTL_PERIPH_EEPROM0 0xf0005800 // EEPROM 0
|
||||
#define SYSCTL_PERIPH_FAN0 0xf0005400 // FAN 0
|
||||
#define SYSCTL_PERIPH_FAN1 0xf0005401 // FAN 1
|
||||
#define SYSCTL_PERIPH_GPIOK 0xf0000809 // GPIO K
|
||||
#define SYSCTL_PERIPH_GPIOL 0xf000080a // GPIO L
|
||||
#define SYSCTL_PERIPH_GPIOM 0xf000080b // GPIO M
|
||||
#define SYSCTL_PERIPH_GPION 0xf000080c // GPIO N
|
||||
#define SYSCTL_PERIPH_GPIOP 0xf000080d // GPIO P
|
||||
#define SYSCTL_PERIPH_GPIOQ 0xf000080e // GPIO Q
|
||||
#define SYSCTL_PERIPH_GPIOR 0xf000080f // GPIO R
|
||||
#define SYSCTL_PERIPH_GPIOS 0xf0000810 // GPIO S
|
||||
#define SYSCTL_PERIPH_GPIOT 0xf0000811 // GPIO T
|
||||
#define SYSCTL_PERIPH_I2C0 0xf0002000 // I2C 0
|
||||
#define SYSCTL_PERIPH_I2C1 0xf0002001 // I2C 1
|
||||
#define SYSCTL_PERIPH_I2C2 0xf0002002 // I2C 2
|
||||
#define SYSCTL_PERIPH_I2C3 0xf0002003 // I2C 3
|
||||
#define SYSCTL_PERIPH_I2C4 0xf0002004 // I2C 4
|
||||
#define SYSCTL_PERIPH_I2C5 0xf0002005 // I2C 5
|
||||
#define SYSCTL_PERIPH_I2C6 0xf0002006 // I2C 6
|
||||
#define SYSCTL_PERIPH_I2C7 0xf0002007 // I2C 7
|
||||
#define SYSCTL_PERIPH_I2C8 0xf0002008 // I2C 8
|
||||
#define SYSCTL_PERIPH_I2C9 0xf0002009 // I2C 9
|
||||
#define SYSCTL_PERIPH_LCD0 0xf0009000 // LCD 0
|
||||
#define SYSCTL_PERIPH_ONEWIRE0 0xf0009800 // One Wire 0
|
||||
#define SYSCTL_PERIPH_PWM0 0xf0004000 // PWM 0
|
||||
#define SYSCTL_PERIPH_PWM1 0xf0004001 // PWM 1
|
||||
#define SYSCTL_PERIPH_QEI0 0xf0004400 // QEI 0
|
||||
#define SYSCTL_PERIPH_QEI1 0xf0004401 // QEI 1
|
||||
#define SYSCTL_PERIPH_SSI0 0xf0001c00 // SSI 0
|
||||
#define SYSCTL_PERIPH_SSI1 0xf0001c01 // SSI 1
|
||||
#define SYSCTL_PERIPH_SSI2 0xf0001c02 // SSI 2
|
||||
#define SYSCTL_PERIPH_SSI3 0xf0001c03 // SSI 3
|
||||
#define SYSCTL_PERIPH_TIMER0 0xf0000400 // Timer 0
|
||||
#define SYSCTL_PERIPH_TIMER1 0xf0000401 // Timer 1
|
||||
#define SYSCTL_PERIPH_TIMER2 0xf0000402 // Timer 2
|
||||
#define SYSCTL_PERIPH_TIMER3 0xf0000403 // Timer 3
|
||||
#define SYSCTL_PERIPH_TIMER4 0xf0000404 // Timer 4
|
||||
#define SYSCTL_PERIPH_TIMER5 0xf0000405 // Timer 5
|
||||
#define SYSCTL_PERIPH_TIMER6 0xf0000406 // Timer 6
|
||||
#define SYSCTL_PERIPH_TIMER7 0xf0000407 // Timer 7
|
||||
#define SYSCTL_PERIPH_UART0 0xf0001800 // UART 0
|
||||
#define SYSCTL_PERIPH_UART1 0xf0001801 // UART 1
|
||||
#define SYSCTL_PERIPH_UART2 0xf0001802 // UART 2
|
||||
#define SYSCTL_PERIPH_UART3 0xf0001803 // UART 3
|
||||
#define SYSCTL_PERIPH_UART4 0xf0001804 // UART 4
|
||||
#define SYSCTL_PERIPH_UART5 0xf0001805 // UART 5
|
||||
#define SYSCTL_PERIPH_UART6 0xf0001806 // UART 6
|
||||
#define SYSCTL_PERIPH_UART7 0xf0001807 // UART 7
|
||||
#define SYSCTL_PERIPH_UDMA 0xf0000c00 // uDMA
|
||||
#define SYSCTL_PERIPH_USB0 0xf0002800 // USB 0
|
||||
#define SYSCTL_PERIPH_WDOG0 0xf0000000 // Watchdog 0
|
||||
#define SYSCTL_PERIPH_WDOG1 0xf0000001 // Watchdog 1
|
||||
#define SYSCTL_PERIPH_WTIMER0 0xf0005c00 // Wide Timer 0
|
||||
#define SYSCTL_PERIPH_WTIMER1 0xf0005c01 // Wide Timer 1
|
||||
#define SYSCTL_PERIPH_WTIMER2 0xf0005c02 // Wide Timer 2
|
||||
#define SYSCTL_PERIPH_WTIMER3 0xf0005c03 // Wide Timer 3
|
||||
#define SYSCTL_PERIPH_WTIMER4 0xf0005c04 // Wide Timer 4
|
||||
#define SYSCTL_PERIPH_WTIMER5 0xf0005c05 // Wide Timer 5
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are values that can be passed to the SysCtlLDOSleepSet() and
|
||||
// SysCtlLDODeepSleepSet() APIs as the ui32Voltage value, or returned by the
|
||||
// SysCtlLDOSleepGet() and SysCtlLDODeepSleepGet() APIs.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define SYSCTL_LDO_0_90V 0x80000012 // LDO output of 0.90V
|
||||
#define SYSCTL_LDO_0_95V 0x80000013 // LDO output of 0.95V
|
||||
#define SYSCTL_LDO_1_00V 0x80000014 // LDO output of 1.00V
|
||||
#define SYSCTL_LDO_1_05V 0x80000015 // LDO output of 1.05V
|
||||
#define SYSCTL_LDO_1_10V 0x80000016 // LDO output of 1.10V
|
||||
#define SYSCTL_LDO_1_15V 0x80000017 // LDO output of 1.15V
|
||||
#define SYSCTL_LDO_1_20V 0x80000018 // LDO output of 1.20V
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are values that can be passed to the SysCtlIntEnable(),
|
||||
// SysCtlIntDisable(), and SysCtlIntClear() APIs, or returned in the bit mask
|
||||
// by the SysCtlIntStatus() API.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define SYSCTL_INT_BOR0 0x00000800 // VDD under BOR0
|
||||
#define SYSCTL_INT_VDDA_OK 0x00000400 // VDDA Power OK
|
||||
#define SYSCTL_INT_MOSC_PUP 0x00000100 // MOSC power-up interrupt
|
||||
#define SYSCTL_INT_USBPLL_LOCK 0x00000080 // USB PLL lock interrupt
|
||||
#define SYSCTL_INT_PLL_LOCK 0x00000040 // PLL lock interrupt
|
||||
#define SYSCTL_INT_MOSC_FAIL 0x00000008 // Main oscillator failure int
|
||||
#define SYSCTL_INT_BOR1 0x00000002 // VDD under BOR1
|
||||
#define SYSCTL_INT_BOR 0x00000002 // Brown out interrupt
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are values that can be passed to the SysCtlResetCauseClear()
|
||||
// API or returned by the SysCtlResetCauseGet() API.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define SYSCTL_CAUSE_HSRVREQ 0x00001000 // Hardware System Service Request
|
||||
#define SYSCTL_CAUSE_HIB 0x00000040 // Hibernate reset
|
||||
#define SYSCTL_CAUSE_WDOG1 0x00000020 // Watchdog 1 reset
|
||||
#define SYSCTL_CAUSE_SW 0x00000010 // Software reset
|
||||
#define SYSCTL_CAUSE_WDOG0 0x00000008 // Watchdog 0 reset
|
||||
#ifndef DEPRECATED
|
||||
#define SYSCTL_CAUSE_WDOG SYSCTL_CAUSE_WDOG0
|
||||
// Watchdog reset(Deprecated)
|
||||
#endif
|
||||
#define SYSCTL_CAUSE_BOR 0x00000004 // Brown-out reset
|
||||
#define SYSCTL_CAUSE_POR 0x00000002 // Power on reset
|
||||
#define SYSCTL_CAUSE_EXT 0x00000001 // External reset
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are values that can be passed to the SysCtlBrownOutConfigSet()
|
||||
// API as the ui32Config parameter.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define SYSCTL_BOR_RESET 0x00000002 // Reset instead of interrupting
|
||||
#define SYSCTL_BOR_RESAMPLE 0x00000001 // Resample BOR before asserting
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are values that can be passed to the SysCtlPWMClockSet() API
|
||||
// as the ui32Config parameter, and can be returned by the SysCtlPWMClockGet()
|
||||
// API.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define SYSCTL_PWMDIV_1 0x00000000 // PWM clock is processor clock /1
|
||||
#define SYSCTL_PWMDIV_2 0x00100000 // PWM clock is processor clock /2
|
||||
#define SYSCTL_PWMDIV_4 0x00120000 // PWM clock is processor clock /4
|
||||
#define SYSCTL_PWMDIV_8 0x00140000 // PWM clock is processor clock /8
|
||||
#define SYSCTL_PWMDIV_16 0x00160000 // PWM clock is processor clock /16
|
||||
#define SYSCTL_PWMDIV_32 0x00180000 // PWM clock is processor clock /32
|
||||
#define SYSCTL_PWMDIV_64 0x001A0000 // PWM clock is processor clock /64
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are values that can be passed to the SysCtlClockSet() API as
|
||||
// the ui32Config parameter.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define SYSCTL_SYSDIV_1 0x07800000 // Processor clock is osc/pll /1
|
||||
#define SYSCTL_SYSDIV_2 0x00C00000 // Processor clock is osc/pll /2
|
||||
#define SYSCTL_SYSDIV_3 0x01400000 // Processor clock is osc/pll /3
|
||||
#define SYSCTL_SYSDIV_4 0x01C00000 // Processor clock is osc/pll /4
|
||||
#define SYSCTL_SYSDIV_5 0x02400000 // Processor clock is osc/pll /5
|
||||
#define SYSCTL_SYSDIV_6 0x02C00000 // Processor clock is osc/pll /6
|
||||
#define SYSCTL_SYSDIV_7 0x03400000 // Processor clock is osc/pll /7
|
||||
#define SYSCTL_SYSDIV_8 0x03C00000 // Processor clock is osc/pll /8
|
||||
#define SYSCTL_SYSDIV_9 0x04400000 // Processor clock is osc/pll /9
|
||||
#define SYSCTL_SYSDIV_10 0x04C00000 // Processor clock is osc/pll /10
|
||||
#define SYSCTL_SYSDIV_11 0x05400000 // Processor clock is osc/pll /11
|
||||
#define SYSCTL_SYSDIV_12 0x05C00000 // Processor clock is osc/pll /12
|
||||
#define SYSCTL_SYSDIV_13 0x06400000 // Processor clock is osc/pll /13
|
||||
#define SYSCTL_SYSDIV_14 0x06C00000 // Processor clock is osc/pll /14
|
||||
#define SYSCTL_SYSDIV_15 0x07400000 // Processor clock is osc/pll /15
|
||||
#define SYSCTL_SYSDIV_16 0x07C00000 // Processor clock is osc/pll /16
|
||||
#define SYSCTL_SYSDIV_17 0x88400000 // Processor clock is osc/pll /17
|
||||
#define SYSCTL_SYSDIV_18 0x88C00000 // Processor clock is osc/pll /18
|
||||
#define SYSCTL_SYSDIV_19 0x89400000 // Processor clock is osc/pll /19
|
||||
#define SYSCTL_SYSDIV_20 0x89C00000 // Processor clock is osc/pll /20
|
||||
#define SYSCTL_SYSDIV_21 0x8A400000 // Processor clock is osc/pll /21
|
||||
#define SYSCTL_SYSDIV_22 0x8AC00000 // Processor clock is osc/pll /22
|
||||
#define SYSCTL_SYSDIV_23 0x8B400000 // Processor clock is osc/pll /23
|
||||
#define SYSCTL_SYSDIV_24 0x8BC00000 // Processor clock is osc/pll /24
|
||||
#define SYSCTL_SYSDIV_25 0x8C400000 // Processor clock is osc/pll /25
|
||||
#define SYSCTL_SYSDIV_26 0x8CC00000 // Processor clock is osc/pll /26
|
||||
#define SYSCTL_SYSDIV_27 0x8D400000 // Processor clock is osc/pll /27
|
||||
#define SYSCTL_SYSDIV_28 0x8DC00000 // Processor clock is osc/pll /28
|
||||
#define SYSCTL_SYSDIV_29 0x8E400000 // Processor clock is osc/pll /29
|
||||
#define SYSCTL_SYSDIV_30 0x8EC00000 // Processor clock is osc/pll /30
|
||||
#define SYSCTL_SYSDIV_31 0x8F400000 // Processor clock is osc/pll /31
|
||||
#define SYSCTL_SYSDIV_32 0x8FC00000 // Processor clock is osc/pll /32
|
||||
#define SYSCTL_SYSDIV_33 0x90400000 // Processor clock is osc/pll /33
|
||||
#define SYSCTL_SYSDIV_34 0x90C00000 // Processor clock is osc/pll /34
|
||||
#define SYSCTL_SYSDIV_35 0x91400000 // Processor clock is osc/pll /35
|
||||
#define SYSCTL_SYSDIV_36 0x91C00000 // Processor clock is osc/pll /36
|
||||
#define SYSCTL_SYSDIV_37 0x92400000 // Processor clock is osc/pll /37
|
||||
#define SYSCTL_SYSDIV_38 0x92C00000 // Processor clock is osc/pll /38
|
||||
#define SYSCTL_SYSDIV_39 0x93400000 // Processor clock is osc/pll /39
|
||||
#define SYSCTL_SYSDIV_40 0x93C00000 // Processor clock is osc/pll /40
|
||||
#define SYSCTL_SYSDIV_41 0x94400000 // Processor clock is osc/pll /41
|
||||
#define SYSCTL_SYSDIV_42 0x94C00000 // Processor clock is osc/pll /42
|
||||
#define SYSCTL_SYSDIV_43 0x95400000 // Processor clock is osc/pll /43
|
||||
#define SYSCTL_SYSDIV_44 0x95C00000 // Processor clock is osc/pll /44
|
||||
#define SYSCTL_SYSDIV_45 0x96400000 // Processor clock is osc/pll /45
|
||||
#define SYSCTL_SYSDIV_46 0x96C00000 // Processor clock is osc/pll /46
|
||||
#define SYSCTL_SYSDIV_47 0x97400000 // Processor clock is osc/pll /47
|
||||
#define SYSCTL_SYSDIV_48 0x97C00000 // Processor clock is osc/pll /48
|
||||
#define SYSCTL_SYSDIV_49 0x98400000 // Processor clock is osc/pll /49
|
||||
#define SYSCTL_SYSDIV_50 0x98C00000 // Processor clock is osc/pll /50
|
||||
#define SYSCTL_SYSDIV_51 0x99400000 // Processor clock is osc/pll /51
|
||||
#define SYSCTL_SYSDIV_52 0x99C00000 // Processor clock is osc/pll /52
|
||||
#define SYSCTL_SYSDIV_53 0x9A400000 // Processor clock is osc/pll /53
|
||||
#define SYSCTL_SYSDIV_54 0x9AC00000 // Processor clock is osc/pll /54
|
||||
#define SYSCTL_SYSDIV_55 0x9B400000 // Processor clock is osc/pll /55
|
||||
#define SYSCTL_SYSDIV_56 0x9BC00000 // Processor clock is osc/pll /56
|
||||
#define SYSCTL_SYSDIV_57 0x9C400000 // Processor clock is osc/pll /57
|
||||
#define SYSCTL_SYSDIV_58 0x9CC00000 // Processor clock is osc/pll /58
|
||||
#define SYSCTL_SYSDIV_59 0x9D400000 // Processor clock is osc/pll /59
|
||||
#define SYSCTL_SYSDIV_60 0x9DC00000 // Processor clock is osc/pll /60
|
||||
#define SYSCTL_SYSDIV_61 0x9E400000 // Processor clock is osc/pll /61
|
||||
#define SYSCTL_SYSDIV_62 0x9EC00000 // Processor clock is osc/pll /62
|
||||
#define SYSCTL_SYSDIV_63 0x9F400000 // Processor clock is osc/pll /63
|
||||
#define SYSCTL_SYSDIV_64 0x9FC00000 // Processor clock is osc/pll /64
|
||||
#define SYSCTL_SYSDIV_2_5 0xC1000000 // Processor clock is pll / 2.5
|
||||
#define SYSCTL_SYSDIV_3_5 0xC1800000 // Processor clock is pll / 3.5
|
||||
#define SYSCTL_SYSDIV_4_5 0xC2000000 // Processor clock is pll / 4.5
|
||||
#define SYSCTL_SYSDIV_5_5 0xC2800000 // Processor clock is pll / 5.5
|
||||
#define SYSCTL_SYSDIV_6_5 0xC3000000 // Processor clock is pll / 6.5
|
||||
#define SYSCTL_SYSDIV_7_5 0xC3800000 // Processor clock is pll / 7.5
|
||||
#define SYSCTL_SYSDIV_8_5 0xC4000000 // Processor clock is pll / 8.5
|
||||
#define SYSCTL_SYSDIV_9_5 0xC4800000 // Processor clock is pll / 9.5
|
||||
#define SYSCTL_SYSDIV_10_5 0xC5000000 // Processor clock is pll / 10.5
|
||||
#define SYSCTL_SYSDIV_11_5 0xC5800000 // Processor clock is pll / 11.5
|
||||
#define SYSCTL_SYSDIV_12_5 0xC6000000 // Processor clock is pll / 12.5
|
||||
#define SYSCTL_SYSDIV_13_5 0xC6800000 // Processor clock is pll / 13.5
|
||||
#define SYSCTL_SYSDIV_14_5 0xC7000000 // Processor clock is pll / 14.5
|
||||
#define SYSCTL_SYSDIV_15_5 0xC7800000 // Processor clock is pll / 15.5
|
||||
#define SYSCTL_SYSDIV_16_5 0xC8000000 // Processor clock is pll / 16.5
|
||||
#define SYSCTL_SYSDIV_17_5 0xC8800000 // Processor clock is pll / 17.5
|
||||
#define SYSCTL_SYSDIV_18_5 0xC9000000 // Processor clock is pll / 18.5
|
||||
#define SYSCTL_SYSDIV_19_5 0xC9800000 // Processor clock is pll / 19.5
|
||||
#define SYSCTL_SYSDIV_20_5 0xCA000000 // Processor clock is pll / 20.5
|
||||
#define SYSCTL_SYSDIV_21_5 0xCA800000 // Processor clock is pll / 21.5
|
||||
#define SYSCTL_SYSDIV_22_5 0xCB000000 // Processor clock is pll / 22.5
|
||||
#define SYSCTL_SYSDIV_23_5 0xCB800000 // Processor clock is pll / 23.5
|
||||
#define SYSCTL_SYSDIV_24_5 0xCC000000 // Processor clock is pll / 24.5
|
||||
#define SYSCTL_SYSDIV_25_5 0xCC800000 // Processor clock is pll / 25.5
|
||||
#define SYSCTL_SYSDIV_26_5 0xCD000000 // Processor clock is pll / 26.5
|
||||
#define SYSCTL_SYSDIV_27_5 0xCD800000 // Processor clock is pll / 27.5
|
||||
#define SYSCTL_SYSDIV_28_5 0xCE000000 // Processor clock is pll / 28.5
|
||||
#define SYSCTL_SYSDIV_29_5 0xCE800000 // Processor clock is pll / 29.5
|
||||
#define SYSCTL_SYSDIV_30_5 0xCF000000 // Processor clock is pll / 30.5
|
||||
#define SYSCTL_SYSDIV_31_5 0xCF800000 // Processor clock is pll / 31.5
|
||||
#define SYSCTL_SYSDIV_32_5 0xD0000000 // Processor clock is pll / 32.5
|
||||
#define SYSCTL_SYSDIV_33_5 0xD0800000 // Processor clock is pll / 33.5
|
||||
#define SYSCTL_SYSDIV_34_5 0xD1000000 // Processor clock is pll / 34.5
|
||||
#define SYSCTL_SYSDIV_35_5 0xD1800000 // Processor clock is pll / 35.5
|
||||
#define SYSCTL_SYSDIV_36_5 0xD2000000 // Processor clock is pll / 36.5
|
||||
#define SYSCTL_SYSDIV_37_5 0xD2800000 // Processor clock is pll / 37.5
|
||||
#define SYSCTL_SYSDIV_38_5 0xD3000000 // Processor clock is pll / 38.5
|
||||
#define SYSCTL_SYSDIV_39_5 0xD3800000 // Processor clock is pll / 39.5
|
||||
#define SYSCTL_SYSDIV_40_5 0xD4000000 // Processor clock is pll / 40.5
|
||||
#define SYSCTL_SYSDIV_41_5 0xD4800000 // Processor clock is pll / 41.5
|
||||
#define SYSCTL_SYSDIV_42_5 0xD5000000 // Processor clock is pll / 42.5
|
||||
#define SYSCTL_SYSDIV_43_5 0xD5800000 // Processor clock is pll / 43.5
|
||||
#define SYSCTL_SYSDIV_44_5 0xD6000000 // Processor clock is pll / 44.5
|
||||
#define SYSCTL_SYSDIV_45_5 0xD6800000 // Processor clock is pll / 45.5
|
||||
#define SYSCTL_SYSDIV_46_5 0xD7000000 // Processor clock is pll / 46.5
|
||||
#define SYSCTL_SYSDIV_47_5 0xD7800000 // Processor clock is pll / 47.5
|
||||
#define SYSCTL_SYSDIV_48_5 0xD8000000 // Processor clock is pll / 48.5
|
||||
#define SYSCTL_SYSDIV_49_5 0xD8800000 // Processor clock is pll / 49.5
|
||||
#define SYSCTL_SYSDIV_50_5 0xD9000000 // Processor clock is pll / 50.5
|
||||
#define SYSCTL_SYSDIV_51_5 0xD9800000 // Processor clock is pll / 51.5
|
||||
#define SYSCTL_SYSDIV_52_5 0xDA000000 // Processor clock is pll / 52.5
|
||||
#define SYSCTL_SYSDIV_53_5 0xDA800000 // Processor clock is pll / 53.5
|
||||
#define SYSCTL_SYSDIV_54_5 0xDB000000 // Processor clock is pll / 54.5
|
||||
#define SYSCTL_SYSDIV_55_5 0xDB800000 // Processor clock is pll / 55.5
|
||||
#define SYSCTL_SYSDIV_56_5 0xDC000000 // Processor clock is pll / 56.5
|
||||
#define SYSCTL_SYSDIV_57_5 0xDC800000 // Processor clock is pll / 57.5
|
||||
#define SYSCTL_SYSDIV_58_5 0xDD000000 // Processor clock is pll / 58.5
|
||||
#define SYSCTL_SYSDIV_59_5 0xDD800000 // Processor clock is pll / 59.5
|
||||
#define SYSCTL_SYSDIV_60_5 0xDE000000 // Processor clock is pll / 60.5
|
||||
#define SYSCTL_SYSDIV_61_5 0xDE800000 // Processor clock is pll / 61.5
|
||||
#define SYSCTL_SYSDIV_62_5 0xDF000000 // Processor clock is pll / 62.5
|
||||
#define SYSCTL_SYSDIV_63_5 0xDF800000 // Processor clock is pll / 63.5
|
||||
#define SYSCTL_CFG_VCO_480 0xF1000000 // VCO is 480 MHz
|
||||
#define SYSCTL_CFG_VCO_320 0xF0000000 // VCO is 320 MHz
|
||||
#define SYSCTL_USE_PLL 0x00000000 // System clock is the PLL clock
|
||||
#define SYSCTL_USE_OSC 0x00003800 // System clock is the osc clock
|
||||
#define SYSCTL_XTAL_1MHZ 0x00000000 // External crystal is 1MHz
|
||||
#define SYSCTL_XTAL_1_84MHZ 0x00000040 // External crystal is 1.8432MHz
|
||||
#define SYSCTL_XTAL_2MHZ 0x00000080 // External crystal is 2MHz
|
||||
#define SYSCTL_XTAL_2_45MHZ 0x000000C0 // External crystal is 2.4576MHz
|
||||
#define SYSCTL_XTAL_3_57MHZ 0x00000100 // External crystal is 3.579545MHz
|
||||
#define SYSCTL_XTAL_3_68MHZ 0x00000140 // External crystal is 3.6864MHz
|
||||
#define SYSCTL_XTAL_4MHZ 0x00000180 // External crystal is 4MHz
|
||||
#define SYSCTL_XTAL_4_09MHZ 0x000001C0 // External crystal is 4.096MHz
|
||||
#define SYSCTL_XTAL_4_91MHZ 0x00000200 // External crystal is 4.9152MHz
|
||||
#define SYSCTL_XTAL_5MHZ 0x00000240 // External crystal is 5MHz
|
||||
#define SYSCTL_XTAL_5_12MHZ 0x00000280 // External crystal is 5.12MHz
|
||||
#define SYSCTL_XTAL_6MHZ 0x000002C0 // External crystal is 6MHz
|
||||
#define SYSCTL_XTAL_6_14MHZ 0x00000300 // External crystal is 6.144MHz
|
||||
#define SYSCTL_XTAL_7_37MHZ 0x00000340 // External crystal is 7.3728MHz
|
||||
#define SYSCTL_XTAL_8MHZ 0x00000380 // External crystal is 8MHz
|
||||
#define SYSCTL_XTAL_8_19MHZ 0x000003C0 // External crystal is 8.192MHz
|
||||
#define SYSCTL_XTAL_10MHZ 0x00000400 // External crystal is 10 MHz
|
||||
#define SYSCTL_XTAL_12MHZ 0x00000440 // External crystal is 12 MHz
|
||||
#define SYSCTL_XTAL_12_2MHZ 0x00000480 // External crystal is 12.288 MHz
|
||||
#define SYSCTL_XTAL_13_5MHZ 0x000004C0 // External crystal is 13.56 MHz
|
||||
#define SYSCTL_XTAL_14_3MHZ 0x00000500 // External crystal is 14.31818 MHz
|
||||
#define SYSCTL_XTAL_16MHZ 0x00000540 // External crystal is 16 MHz
|
||||
#define SYSCTL_XTAL_16_3MHZ 0x00000580 // External crystal is 16.384 MHz
|
||||
#define SYSCTL_XTAL_18MHZ 0x000005C0 // External crystal is 18.0 MHz
|
||||
#define SYSCTL_XTAL_20MHZ 0x00000600 // External crystal is 20.0 MHz
|
||||
#define SYSCTL_XTAL_24MHZ 0x00000640 // External crystal is 24.0 MHz
|
||||
#define SYSCTL_XTAL_25MHZ 0x00000680 // External crystal is 25.0 MHz
|
||||
#define SYSCTL_OSC_MAIN 0x00000000 // Osc source is main osc
|
||||
#define SYSCTL_OSC_INT 0x00000010 // Osc source is int. osc
|
||||
#define SYSCTL_OSC_INT4 0x00000020 // Osc source is int. osc /4
|
||||
#define SYSCTL_OSC_INT30 0x00000030 // Osc source is int. 30 KHz
|
||||
#define SYSCTL_OSC_EXT32 0x80000038 // Osc source is ext. 32 KHz
|
||||
#define SYSCTL_INT_OSC_DIS 0x00000002 // Disable internal oscillator
|
||||
#define SYSCTL_MAIN_OSC_DIS 0x00000001 // Disable main oscillator
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are values that can be passed to the SysCtlDeepSleepClockSet()
|
||||
// API as the ui32Config parameter.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define SYSCTL_DSLP_DIV_1 0x00000000 // Deep-sleep clock is osc /1
|
||||
#define SYSCTL_DSLP_DIV_2 0x00800000 // Deep-sleep clock is osc /2
|
||||
#define SYSCTL_DSLP_DIV_3 0x01000000 // Deep-sleep clock is osc /3
|
||||
#define SYSCTL_DSLP_DIV_4 0x01800000 // Deep-sleep clock is osc /4
|
||||
#define SYSCTL_DSLP_DIV_5 0x02000000 // Deep-sleep clock is osc /5
|
||||
#define SYSCTL_DSLP_DIV_6 0x02800000 // Deep-sleep clock is osc /6
|
||||
#define SYSCTL_DSLP_DIV_7 0x03000000 // Deep-sleep clock is osc /7
|
||||
#define SYSCTL_DSLP_DIV_8 0x03800000 // Deep-sleep clock is osc /8
|
||||
#define SYSCTL_DSLP_DIV_9 0x04000000 // Deep-sleep clock is osc /9
|
||||
#define SYSCTL_DSLP_DIV_10 0x04800000 // Deep-sleep clock is osc /10
|
||||
#define SYSCTL_DSLP_DIV_11 0x05000000 // Deep-sleep clock is osc /11
|
||||
#define SYSCTL_DSLP_DIV_12 0x05800000 // Deep-sleep clock is osc /12
|
||||
#define SYSCTL_DSLP_DIV_13 0x06000000 // Deep-sleep clock is osc /13
|
||||
#define SYSCTL_DSLP_DIV_14 0x06800000 // Deep-sleep clock is osc /14
|
||||
#define SYSCTL_DSLP_DIV_15 0x07000000 // Deep-sleep clock is osc /15
|
||||
#define SYSCTL_DSLP_DIV_16 0x07800000 // Deep-sleep clock is osc /16
|
||||
#define SYSCTL_DSLP_DIV_17 0x08000000 // Deep-sleep clock is osc /17
|
||||
#define SYSCTL_DSLP_DIV_18 0x08800000 // Deep-sleep clock is osc /18
|
||||
#define SYSCTL_DSLP_DIV_19 0x09000000 // Deep-sleep clock is osc /19
|
||||
#define SYSCTL_DSLP_DIV_20 0x09800000 // Deep-sleep clock is osc /20
|
||||
#define SYSCTL_DSLP_DIV_21 0x0A000000 // Deep-sleep clock is osc /21
|
||||
#define SYSCTL_DSLP_DIV_22 0x0A800000 // Deep-sleep clock is osc /22
|
||||
#define SYSCTL_DSLP_DIV_23 0x0B000000 // Deep-sleep clock is osc /23
|
||||
#define SYSCTL_DSLP_DIV_24 0x0B800000 // Deep-sleep clock is osc /24
|
||||
#define SYSCTL_DSLP_DIV_25 0x0C000000 // Deep-sleep clock is osc /25
|
||||
#define SYSCTL_DSLP_DIV_26 0x0C800000 // Deep-sleep clock is osc /26
|
||||
#define SYSCTL_DSLP_DIV_27 0x0D000000 // Deep-sleep clock is osc /27
|
||||
#define SYSCTL_DSLP_DIV_28 0x0D800000 // Deep-sleep clock is osc /28
|
||||
#define SYSCTL_DSLP_DIV_29 0x0E000000 // Deep-sleep clock is osc /29
|
||||
#define SYSCTL_DSLP_DIV_30 0x0E800000 // Deep-sleep clock is osc /30
|
||||
#define SYSCTL_DSLP_DIV_31 0x0F000000 // Deep-sleep clock is osc /31
|
||||
#define SYSCTL_DSLP_DIV_32 0x0F800000 // Deep-sleep clock is osc /32
|
||||
#define SYSCTL_DSLP_DIV_33 0x10000000 // Deep-sleep clock is osc /33
|
||||
#define SYSCTL_DSLP_DIV_34 0x10800000 // Deep-sleep clock is osc /34
|
||||
#define SYSCTL_DSLP_DIV_35 0x11000000 // Deep-sleep clock is osc /35
|
||||
#define SYSCTL_DSLP_DIV_36 0x11800000 // Deep-sleep clock is osc /36
|
||||
#define SYSCTL_DSLP_DIV_37 0x12000000 // Deep-sleep clock is osc /37
|
||||
#define SYSCTL_DSLP_DIV_38 0x12800000 // Deep-sleep clock is osc /38
|
||||
#define SYSCTL_DSLP_DIV_39 0x13000000 // Deep-sleep clock is osc /39
|
||||
#define SYSCTL_DSLP_DIV_40 0x13800000 // Deep-sleep clock is osc /40
|
||||
#define SYSCTL_DSLP_DIV_41 0x14000000 // Deep-sleep clock is osc /41
|
||||
#define SYSCTL_DSLP_DIV_42 0x14800000 // Deep-sleep clock is osc /42
|
||||
#define SYSCTL_DSLP_DIV_43 0x15000000 // Deep-sleep clock is osc /43
|
||||
#define SYSCTL_DSLP_DIV_44 0x15800000 // Deep-sleep clock is osc /44
|
||||
#define SYSCTL_DSLP_DIV_45 0x16000000 // Deep-sleep clock is osc /45
|
||||
#define SYSCTL_DSLP_DIV_46 0x16800000 // Deep-sleep clock is osc /46
|
||||
#define SYSCTL_DSLP_DIV_47 0x17000000 // Deep-sleep clock is osc /47
|
||||
#define SYSCTL_DSLP_DIV_48 0x17800000 // Deep-sleep clock is osc /48
|
||||
#define SYSCTL_DSLP_DIV_49 0x18000000 // Deep-sleep clock is osc /49
|
||||
#define SYSCTL_DSLP_DIV_50 0x18800000 // Deep-sleep clock is osc /50
|
||||
#define SYSCTL_DSLP_DIV_51 0x19000000 // Deep-sleep clock is osc /51
|
||||
#define SYSCTL_DSLP_DIV_52 0x19800000 // Deep-sleep clock is osc /52
|
||||
#define SYSCTL_DSLP_DIV_53 0x1A000000 // Deep-sleep clock is osc /53
|
||||
#define SYSCTL_DSLP_DIV_54 0x1A800000 // Deep-sleep clock is osc /54
|
||||
#define SYSCTL_DSLP_DIV_55 0x1B000000 // Deep-sleep clock is osc /55
|
||||
#define SYSCTL_DSLP_DIV_56 0x1B800000 // Deep-sleep clock is osc /56
|
||||
#define SYSCTL_DSLP_DIV_57 0x1C000000 // Deep-sleep clock is osc /57
|
||||
#define SYSCTL_DSLP_DIV_58 0x1C800000 // Deep-sleep clock is osc /58
|
||||
#define SYSCTL_DSLP_DIV_59 0x1D000000 // Deep-sleep clock is osc /59
|
||||
#define SYSCTL_DSLP_DIV_60 0x1D800000 // Deep-sleep clock is osc /60
|
||||
#define SYSCTL_DSLP_DIV_61 0x1E000000 // Deep-sleep clock is osc /61
|
||||
#define SYSCTL_DSLP_DIV_62 0x1E800000 // Deep-sleep clock is osc /62
|
||||
#define SYSCTL_DSLP_DIV_63 0x1F000000 // Deep-sleep clock is osc /63
|
||||
#define SYSCTL_DSLP_DIV_64 0x1F800000 // Deep-sleep clock is osc /64
|
||||
#define SYSCTL_DSLP_OSC_MAIN 0x00000000 // Osc source is main osc
|
||||
#define SYSCTL_DSLP_OSC_INT 0x00000010 // Osc source is int. osc
|
||||
#define SYSCTL_DSLP_OSC_INT30 0x00000030 // Osc source is int. 30 KHz
|
||||
#define SYSCTL_DSLP_OSC_EXT32 0x00000070 // Osc source is ext. 32 KHz
|
||||
#define SYSCTL_DSLP_PIOSC_PD 0x00000002 // Power down PIOSC in deep-sleep
|
||||
#define SYSCTL_DSLP_MOSC_PD 0x40000000 // Power down MOSC in deep-sleep
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are values that can be passed to the SysCtlPIOSCCalibrate()
|
||||
// API as the ui32Type parameter.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define SYSCTL_PIOSC_CAL_AUTO 0x00000200 // Automatic calibration
|
||||
#define SYSCTL_PIOSC_CAL_FACT 0x00000100 // Factory calibration
|
||||
#define SYSCTL_PIOSC_CAL_USER 0x80000100 // User-supplied calibration
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are values that can be passed to the SysCtlMOSCConfigSet() API
|
||||
// as the ui32Config parameter.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define SYSCTL_MOSC_VALIDATE 0x00000001 // Enable MOSC validation
|
||||
#define SYSCTL_MOSC_INTERRUPT 0x00000002 // Generate interrupt on MOSC fail
|
||||
#define SYSCTL_MOSC_NO_XTAL 0x00000004 // No crystal is attached to MOSC
|
||||
#define SYSCTL_MOSC_PWR_DIS 0x00000008 // Power down the MOSC.
|
||||
#define SYSCTL_MOSC_LOWFREQ 0x00000000 // MOSC is less than 10MHz
|
||||
#define SYSCTL_MOSC_HIGHFREQ 0x00000010 // MOSC is greater than 10MHz
|
||||
#define SYSCTL_MOSC_SESRC 0x00000020 // Singled ended oscillator source.
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are values that can be passed to the SysCtlSleepPowerSet() and
|
||||
// SysCtlDeepSleepPowerSet() APIs as the ui32Config parameter.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define SYSCTL_LDO_SLEEP 0x00000200 // LDO in sleep mode
|
||||
// (Deep Sleep Only)
|
||||
#define SYSCTL_TEMP_LOW_POWER 0x00000100 // Temp sensor in low power mode
|
||||
// (Deep Sleep Only)
|
||||
#define SYSCTL_FLASH_NORMAL 0x00000000 // Flash in normal mode
|
||||
#define SYSCTL_FLASH_LOW_POWER 0x00000020 // Flash in low power mode
|
||||
#define SYSCTL_SRAM_NORMAL 0x00000000 // SRAM in normal mode
|
||||
#define SYSCTL_SRAM_STANDBY 0x00000001 // SRAM in standby mode
|
||||
#define SYSCTL_SRAM_LOW_POWER 0x00000003 // SRAM in low power mode
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Defines for the SysCtlResetBehaviorSet() and SysCtlResetBehaviorGet() APIs.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define SYSCTL_ONRST_WDOG0_POR 0x00000030
|
||||
#define SYSCTL_ONRST_WDOG0_SYS 0x00000020
|
||||
#define SYSCTL_ONRST_WDOG1_POR 0x000000C0
|
||||
#define SYSCTL_ONRST_WDOG1_SYS 0x00000080
|
||||
#define SYSCTL_ONRST_BOR_POR 0x0000000C
|
||||
#define SYSCTL_ONRST_BOR_SYS 0x00000008
|
||||
#define SYSCTL_ONRST_EXT_POR 0x00000003
|
||||
#define SYSCTL_ONRST_EXT_SYS 0x00000002
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values used with the SysCtlVoltageEventConfig() API.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define SYSCTL_VEVENT_VDDABO_NONE \
|
||||
0x00000000
|
||||
#define SYSCTL_VEVENT_VDDABO_INT \
|
||||
0x00000100
|
||||
#define SYSCTL_VEVENT_VDDABO_NMI \
|
||||
0x00000200
|
||||
#define SYSCTL_VEVENT_VDDABO_RST \
|
||||
0x00000300
|
||||
#define SYSCTL_VEVENT_VDDBO_NONE \
|
||||
0x00000000
|
||||
#define SYSCTL_VEVENT_VDDBO_INT 0x00000001
|
||||
#define SYSCTL_VEVENT_VDDBO_NMI 0x00000002
|
||||
#define SYSCTL_VEVENT_VDDBO_RST 0x00000003
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values used with the SysCtlVoltageEventStatus() and
|
||||
// SysCtlVoltageEventClear() APIs.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define SYSCTL_VESTAT_VDDBOR 0x00000040
|
||||
#define SYSCTL_VESTAT_VDDABOR 0x00000010
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values used with the SysCtlNMIStatus() API.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define SYSCTL_NMI_MOSCFAIL 0x00010000
|
||||
#define SYSCTL_NMI_TAMPER 0x00000200
|
||||
#define SYSCTL_NMI_WDT1 0x00000020
|
||||
#define SYSCTL_NMI_WDT0 0x00000008
|
||||
#define SYSCTL_NMI_POWER 0x00000004
|
||||
#define SYSCTL_NMI_EXTERNAL 0x00000001
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The defines for the SysCtlClockOutConfig() API.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define SYSCTL_CLKOUT_EN 0x80000000
|
||||
#define SYSCTL_CLKOUT_DIS 0x00000000
|
||||
#define SYSCTL_CLKOUT_SYSCLK 0x00000000
|
||||
#define SYSCTL_CLKOUT_PIOSC 0x00010000
|
||||
#define SYSCTL_CLKOUT_MOSC 0x00020000
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following defines are used with the SysCtlAltClkConfig() function.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define SYSCTL_ALTCLK_PIOSC 0x00000000
|
||||
#define SYSCTL_ALTCLK_RTCOSC 0x00000003
|
||||
#define SYSCTL_ALTCLK_LFIOSC 0x00000004
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Prototypes for the APIs.
|
||||
//
|
||||
//*****************************************************************************
|
||||
extern uint32_t SysCtlSRAMSizeGet(void);
|
||||
extern uint32_t SysCtlFlashSizeGet(void);
|
||||
extern uint32_t SysCtlFlashSectorSizeGet(void);
|
||||
extern bool SysCtlPeripheralPresent(uint32_t ui32Peripheral);
|
||||
extern bool SysCtlPeripheralReady(uint32_t ui32Peripheral);
|
||||
extern void SysCtlPeripheralPowerOn(uint32_t ui32Peripheral);
|
||||
extern void SysCtlPeripheralPowerOff(uint32_t ui32Peripheral);
|
||||
extern void SysCtlPeripheralReset(uint32_t ui32Peripheral);
|
||||
extern void SysCtlPeripheralEnable(uint32_t ui32Peripheral);
|
||||
extern void SysCtlPeripheralDisable(uint32_t ui32Peripheral);
|
||||
extern void SysCtlPeripheralSleepEnable(uint32_t ui32Peripheral);
|
||||
extern void SysCtlPeripheralSleepDisable(uint32_t ui32Peripheral);
|
||||
extern void SysCtlPeripheralDeepSleepEnable(uint32_t ui32Peripheral);
|
||||
extern void SysCtlPeripheralDeepSleepDisable(uint32_t ui32Peripheral);
|
||||
extern void SysCtlPeripheralClockGating(bool bEnable);
|
||||
extern void SysCtlIntRegister(void (*pfnHandler)(void));
|
||||
extern void SysCtlIntUnregister(void);
|
||||
extern void SysCtlIntEnable(uint32_t ui32Ints);
|
||||
extern void SysCtlIntDisable(uint32_t ui32Ints);
|
||||
extern void SysCtlIntClear(uint32_t ui32Ints);
|
||||
extern uint32_t SysCtlIntStatus(bool bMasked);
|
||||
extern void SysCtlLDOSleepSet(uint32_t ui32Voltage);
|
||||
extern uint32_t SysCtlLDOSleepGet(void);
|
||||
extern void SysCtlLDODeepSleepSet(uint32_t ui32Voltage);
|
||||
extern uint32_t SysCtlLDODeepSleepGet(void);
|
||||
extern void SysCtlSleepPowerSet(uint32_t ui32Config);
|
||||
extern void SysCtlDeepSleepPowerSet(uint32_t ui32Config);
|
||||
extern void SysCtlReset(void);
|
||||
extern void SysCtlSleep(void);
|
||||
extern void SysCtlDeepSleep(void);
|
||||
extern uint32_t SysCtlResetCauseGet(void);
|
||||
extern void SysCtlResetCauseClear(uint32_t ui32Causes);
|
||||
extern void SysCtlBrownOutConfigSet(uint32_t ui32Config,
|
||||
uint32_t ui32Delay);
|
||||
extern void SysCtlDelay(uint32_t ui32Count);
|
||||
extern void SysCtlMOSCConfigSet(uint32_t ui32Config);
|
||||
extern uint32_t SysCtlPIOSCCalibrate(uint32_t ui32Type);
|
||||
extern void SysCtlClockSet(uint32_t ui32Config);
|
||||
extern uint32_t SysCtlClockGet(void);
|
||||
extern void SysCtlDeepSleepClockSet(uint32_t ui32Config);
|
||||
extern void SysCtlDeepSleepClockConfigSet(uint32_t ui32Div,
|
||||
uint32_t ui32Config);
|
||||
extern void SysCtlPWMClockSet(uint32_t ui32Config);
|
||||
extern uint32_t SysCtlPWMClockGet(void);
|
||||
extern void SysCtlIOSCVerificationSet(bool bEnable);
|
||||
extern void SysCtlMOSCVerificationSet(bool bEnable);
|
||||
extern void SysCtlPLLVerificationSet(bool bEnable);
|
||||
extern void SysCtlClkVerificationClear(void);
|
||||
extern void SysCtlGPIOAHBEnable(uint32_t ui32GPIOPeripheral);
|
||||
extern void SysCtlGPIOAHBDisable(uint32_t ui32GPIOPeripheral);
|
||||
extern void SysCtlUSBPLLEnable(void);
|
||||
extern void SysCtlUSBPLLDisable(void);
|
||||
extern uint32_t SysCtlClockFreqSet(uint32_t ui32Config,
|
||||
uint32_t ui32SysClock);
|
||||
extern void SysCtlResetBehaviorSet(uint32_t ui32Behavior);
|
||||
extern uint32_t SysCtlResetBehaviorGet(void);
|
||||
extern void SysCtlClockOutConfig(uint32_t ui32Config, uint32_t ui32Div);
|
||||
extern void SysCtlAltClkConfig(uint32_t ui32Config);
|
||||
extern uint32_t SysCtlNMIStatus(void);
|
||||
extern void SysCtlNMIClear(uint32_t ui32Status);
|
||||
extern void SysCtlVoltageEventConfig(uint32_t ui32Config);
|
||||
extern uint32_t SysCtlVoltageEventStatus(void);
|
||||
extern void SysCtlVoltageEventClear(uint32_t ui32Status);
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Mark the end of the C bindings section for C++ compilers.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // __DRIVERLIB_SYSCTL_H__
|
|
@ -0,0 +1,311 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// sysexc.c - Routines for the System Exception Module.
|
||||
//
|
||||
// Copyright (c) 2011-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! \addtogroup sysexc_api
|
||||
//! @{
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include "inc/hw_ints.h"
|
||||
#include "inc/hw_sysctl.h"
|
||||
#include "inc/hw_sysexc.h"
|
||||
#include "inc/hw_types.h"
|
||||
#include "driverlib/debug.h"
|
||||
#include "driverlib/interrupt.h"
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Returns the interrupt number for a system exception.
|
||||
//!
|
||||
//! This function returns the interrupt number for a system exception.
|
||||
//!
|
||||
//! \return Returns the system exception interrupt number.
|
||||
//
|
||||
//*****************************************************************************
|
||||
static uint32_t
|
||||
_SysExcIntNumberGet(void)
|
||||
{
|
||||
uint32_t ui32Int;
|
||||
|
||||
//
|
||||
// Get the interrupt number based on the class.
|
||||
//
|
||||
if(CLASS_IS_TM4C123)
|
||||
{
|
||||
ui32Int = INT_SYSEXC_TM4C123;
|
||||
}
|
||||
else if(CLASS_IS_TM4C129)
|
||||
{
|
||||
ui32Int = INT_SYSEXC_TM4C129;
|
||||
}
|
||||
else
|
||||
{
|
||||
ui32Int = 0;
|
||||
}
|
||||
return(ui32Int);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Registers an interrupt handler for the system exception interrupt.
|
||||
//!
|
||||
//! \param pfnHandler is a pointer to the function to be called when the system
|
||||
//! exception interrupt occurs.
|
||||
//!
|
||||
//! This function places the address of the system exception interrupt handler
|
||||
//! into the interrupt vector table in SRAM. This function also enables the
|
||||
//! global interrupt in the interrupt controller; specific system exception
|
||||
//! interrupts must be enabled via SysExcIntEnable(). It is the interrupt
|
||||
//! handler's responsibility to clear the interrupt source.
|
||||
//!
|
||||
//! \sa IntRegister() for important information about registering interrupt
|
||||
//! handlers.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
SysExcIntRegister(void (*pfnHandler)(void))
|
||||
{
|
||||
uint32_t ui32Int;
|
||||
|
||||
//
|
||||
// Get the system exception interrupt number.
|
||||
//
|
||||
ui32Int = _SysExcIntNumberGet();
|
||||
|
||||
ASSERT(ui32Int != 0);
|
||||
|
||||
//
|
||||
// Register the interrupt handler.
|
||||
//
|
||||
IntRegister(ui32Int, pfnHandler);
|
||||
|
||||
//
|
||||
// Enable the system exception interrupt.
|
||||
//
|
||||
IntEnable(ui32Int);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Unregisters the system exception interrupt handler.
|
||||
//!
|
||||
//! This function removes the system exception interrupt handler from the
|
||||
//! vector table in SRAM. This function also masks off the system exception
|
||||
//! 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
|
||||
SysExcIntUnregister(void)
|
||||
{
|
||||
uint32_t ui32Int;
|
||||
|
||||
//
|
||||
// Get the system exception interrupt number.
|
||||
//
|
||||
ui32Int = _SysExcIntNumberGet();
|
||||
|
||||
ASSERT(ui32Int != 0);
|
||||
|
||||
//
|
||||
// Disable the system exception interrupt.
|
||||
//
|
||||
IntDisable(ui32Int);
|
||||
|
||||
//
|
||||
// Unregister the system exception interrupt handler.
|
||||
//
|
||||
IntUnregister(ui32Int);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Enables individual system exception interrupt sources.
|
||||
//!
|
||||
//! \param ui32IntFlags is the bit mask of the interrupt sources to be enabled.
|
||||
//!
|
||||
//! This function enables the indicated system exception 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 ui32IntFlags parameter is the logical OR of any of the following:
|
||||
//!
|
||||
//! - \b SYSEXC_INT_FP_IXC - Floating-point inexact exception interrupt
|
||||
//! - \b SYSEXC_INT_FP_OFC - Floating-point overflow exception interrupt
|
||||
//! - \b SYSEXC_INT_FP_UFC - Floating-point underflow exception interrupt
|
||||
//! - \b SYSEXC_INT_FP_IOC - Floating-point invalid operation interrupt
|
||||
//! - \b SYSEXC_INT_FP_DZC - Floating-point divide by zero exception interrupt
|
||||
//! - \b SYSEXC_INT_FP_IDC - Floating-point input denormal exception interrupt
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
SysExcIntEnable(uint32_t ui32IntFlags)
|
||||
{
|
||||
//
|
||||
// Enable the specified interrupts.
|
||||
//
|
||||
HWREG(SYSEXC_IM) |= ui32IntFlags;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Disables individual system exception interrupt sources.
|
||||
//!
|
||||
//! \param ui32IntFlags is the bit mask of the interrupt sources to be
|
||||
//! disabled.
|
||||
//!
|
||||
//! This function disables the indicated system exception interrupt sources.
|
||||
//! Only sources that are enabled can be reflected to the processor interrupt;
|
||||
//! disabled sources have no effect on the processor.
|
||||
//!
|
||||
//! The \e ui32IntFlags parameter is the logical OR of any of the following:
|
||||
//!
|
||||
//! - \b SYSEXC_INT_FP_IXC - Floating-point inexact exception interrupt
|
||||
//! - \b SYSEXC_INT_FP_OFC - Floating-point overflow exception interrupt
|
||||
//! - \b SYSEXC_INT_FP_UFC - Floating-point underflow exception interrupt
|
||||
//! - \b SYSEXC_INT_FP_IOC - Floating-point invalid operation interrupt
|
||||
//! - \b SYSEXC_INT_FP_DZC - Floating-point divide by zero exception interrupt
|
||||
//! - \b SYSEXC_INT_FP_IDC - Floating-point input denormal exception interrupt
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
SysExcIntDisable(uint32_t ui32IntFlags)
|
||||
{
|
||||
//
|
||||
// Disable the specified interrupts.
|
||||
//
|
||||
HWREG(SYSEXC_IM) &= ~(ui32IntFlags);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Gets the current system exception interrupt status.
|
||||
//!
|
||||
//! \param bMasked is \b false if the raw interrupt status is required and
|
||||
//! \b true if the masked interrupt status is required.
|
||||
//!
|
||||
//! This function returns the system exception interrupt status. Either the
|
||||
//! raw interrupt status or the status of interrupts that are allowed to
|
||||
//! reflect to the processor can be returned.
|
||||
//!
|
||||
//! \return Returns the current system exception interrupt status, enumerated
|
||||
//! as the logical OR of \b SYSEXC_INT_FP_IXC, \b SYSEXC_INT_FP_OFC,
|
||||
//! \b SYSEXC_INT_FP_UFC, \b SYSEXC_INT_FP_IOC, \b SYSEXC_INT_FP_DZC, and
|
||||
//! \b SYSEXC_INT_FP_IDC.
|
||||
//
|
||||
//*****************************************************************************
|
||||
uint32_t
|
||||
SysExcIntStatus(bool bMasked)
|
||||
{
|
||||
//
|
||||
// Return either the interrupt status or the raw interrupt status as
|
||||
// requested.
|
||||
//
|
||||
if(bMasked)
|
||||
{
|
||||
return(HWREG(SYSEXC_MIS));
|
||||
}
|
||||
else
|
||||
{
|
||||
return(HWREG(SYSEXC_RIS));
|
||||
}
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Clears system exception interrupt sources.
|
||||
//!
|
||||
//! \param ui32IntFlags is a bit mask of the interrupt sources to be cleared.
|
||||
//!
|
||||
//! This function clears the specified system exception interrupt sources, 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 ui32IntFlags parameter is the logical OR of any of the following:
|
||||
//!
|
||||
//! - \b SYSEXC_INT_FP_IXC - Floating-point inexact exception interrupt
|
||||
//! - \b SYSEXC_INT_FP_OFC - Floating-point overflow exception interrupt
|
||||
//! - \b SYSEXC_INT_FP_UFC - Floating-point underflow exception interrupt
|
||||
//! - \b SYSEXC_INT_FP_IOC - Floating-point invalid operation interrupt
|
||||
//! - \b SYSEXC_INT_FP_DZC - Floating-point divide by zero exception interrupt
|
||||
//! - \b SYSEXC_INT_FP_IDC - Floating-point input denormal exception interrupt
|
||||
//!
|
||||
//! \note Because there is a write buffer in the Cortex-M 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
|
||||
SysExcIntClear(uint32_t ui32IntFlags)
|
||||
{
|
||||
//
|
||||
// Clear the requested interrupt sources.
|
||||
//
|
||||
HWREG(SYSEXC_IC) = ui32IntFlags;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Close the Doxygen group.
|
||||
//! @}
|
||||
//
|
||||
//*****************************************************************************
|
|
@ -0,0 +1,89 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// sysexc.h - Prototypes for the System Exception Module routines.
|
||||
//
|
||||
// Copyright (c) 2011-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __DRIVERLIB_SYSEXC_H__
|
||||
#define __DRIVERLIB_SYSEXC_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 SysExcIntEnable, SysExcIntDisable, and
|
||||
// SysExcIntClear as the ui32IntFlags parameter, and returned from
|
||||
// SysExcIntStatus.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define SYSEXC_INT_FP_IXC 0x00000020 // FP Inexact exception interrupt
|
||||
#define SYSEXC_INT_FP_OFC 0x00000010 // FP Overflow exception interrupt
|
||||
#define SYSEXC_INT_FP_UFC 0x00000008 // FP Underflow exception interrupt
|
||||
#define SYSEXC_INT_FP_IOC 0x00000004 // FP Invalid operation interrupt
|
||||
#define SYSEXC_INT_FP_DZC 0x00000002 // FP Divide by zero exception int
|
||||
#define SYSEXC_INT_FP_IDC 0x00000001 // FP Input denormal exception int
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Prototypes.
|
||||
//
|
||||
//*****************************************************************************
|
||||
extern void SysExcIntRegister(void (*pfnHandler)(void));
|
||||
extern void SysExcIntUnregister(void);
|
||||
extern void SysExcIntEnable(uint32_t ui32IntFlags);
|
||||
extern void SysExcIntDisable(uint32_t ui32IntFlags);
|
||||
extern uint32_t SysExcIntStatus(bool bMasked);
|
||||
extern void SysExcIntClear(uint32_t ui32IntFlags);
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Mark the end of the C bindings section for C++ compilers.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // __DRIVERLIB_SYSEXC_H__
|
|
@ -0,0 +1,277 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// systick.c - Driver for the SysTick timer in NVIC.
|
||||
//
|
||||
// Copyright (c) 2005-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! \addtogroup systick_api
|
||||
//! @{
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include "inc/hw_ints.h"
|
||||
#include "inc/hw_nvic.h"
|
||||
#include "inc/hw_types.h"
|
||||
#include "driverlib/debug.h"
|
||||
#include "driverlib/interrupt.h"
|
||||
#include "driverlib/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 ui32Period 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 ui32Period supplied here on
|
||||
//! the next clock after SysTick is enabled.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
SysTickPeriodSet(uint32_t ui32Period)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT((ui32Period > 0) && (ui32Period <= 16777216));
|
||||
|
||||
//
|
||||
// Set the period of the SysTick counter.
|
||||
//
|
||||
HWREG(NVIC_ST_RELOAD) = ui32Period - 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.
|
||||
//
|
||||
//*****************************************************************************
|
||||
uint32_t
|
||||
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.
|
||||
//
|
||||
//*****************************************************************************
|
||||
uint32_t
|
||||
SysTickValueGet(void)
|
||||
{
|
||||
//
|
||||
// Return the current value of the SysTick counter.
|
||||
//
|
||||
return(HWREG(NVIC_ST_CURRENT));
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Close the Doxygen group.
|
||||
//! @}
|
||||
//
|
||||
//*****************************************************************************
|
|
@ -0,0 +1,78 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// systick.h - Prototypes for the SysTick driver.
|
||||
//
|
||||
// Copyright (c) 2005-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __DRIVERLIB_SYSTICK_H__
|
||||
#define __DRIVERLIB_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(uint32_t ui32Period);
|
||||
extern uint32_t SysTickPeriodGet(void);
|
||||
extern uint32_t SysTickValueGet(void);
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Mark the end of the C bindings section for C++ compilers.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // __DRIVERLIB_SYSTICK_H__
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,301 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// timer.h - Prototypes for the timer module
|
||||
//
|
||||
// Copyright (c) 2005-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __DRIVERLIB_TIVA_TIMER_H__
|
||||
#define __DRIVERLIB_TIVA_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 ui32Config 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_RTC 0x01000000 // Full-width RTC 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
|
||||
#define TIMER_CFG_A_ACT_TOINTD 0x00010000 // Timer A compare action disable
|
||||
// time-out interrupt.
|
||||
#define TIMER_CFG_A_ACT_NONE 0x00000000 // Timer A compare action none.
|
||||
#define TIMER_CFG_A_ACT_TOGGLE 0x00020000 // Timer A compare action toggle.
|
||||
#define TIMER_CFG_A_ACT_CLRTO 0x00040000 // Timer A compare action CCP
|
||||
// clear on time-out.
|
||||
#define TIMER_CFG_A_ACT_SETTO 0x00060000 // Timer A compare action CCP set
|
||||
// on time-out.
|
||||
#define TIMER_CFG_A_ACT_SETTOGTO 0x00080000 // Timer A compare action set CCP
|
||||
// toggle on time-out.
|
||||
#define TIMER_CFG_A_ACT_CLRTOGTO 0x000A0000 // Timer A compare action clear
|
||||
// CCP toggle on time-out.
|
||||
#define TIMER_CFG_A_ACT_SETCLRTO 0x000C0000 // Timer A compare action set CCP
|
||||
// clear on time-out.
|
||||
#define TIMER_CFG_A_ACT_CLRSETTO 0x000E0000 // Timer A compare action clear
|
||||
// CCP set on time-out.
|
||||
#define TIMER_CFG_B_ACT_TOINTD 0x00100000 // Timer B compare action disable
|
||||
// time-out interrupt.
|
||||
#define TIMER_CFG_B_ACT_NONE 0x00000000 // Timer A compare action none.
|
||||
#define TIMER_CFG_B_ACT_TOGGLE 0x00200000 // Timer A compare action toggle.
|
||||
#define TIMER_CFG_B_ACT_CLRTO 0x00400000 // Timer A compare action CCP
|
||||
// clear on time-out.
|
||||
#define TIMER_CFG_B_ACT_SETTO 0x00600000 // Timer A compare action CCP set
|
||||
// on time-out.
|
||||
#define TIMER_CFG_B_ACT_SETTOGTO 0x00800000 // Timer A compare action set CCP
|
||||
// toggle on time-out.
|
||||
#define TIMER_CFG_B_ACT_CLRTOGTO 0x00A00000 // Timer A compare action clear
|
||||
// CCP toggle on time-out.
|
||||
#define TIMER_CFG_B_ACT_SETCLRTO 0x00C00000 // Timer A compare action set CCP
|
||||
// clear on time-out.
|
||||
#define TIMER_CFG_B_ACT_CLRSETTO 0x0000E000 // Timer A compare action clear
|
||||
// CCP set on time-out.
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to TimerIntEnable, TimerIntDisable, and
|
||||
// TimerIntClear as the ui32IntFlags parameter, and returned from
|
||||
// TimerIntStatus.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define TIMER_TIMB_DMA 0x00002000 // TimerB DMA Complete 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 Complete Interrupt.
|
||||
#define TIMER_TIMA_MATCH 0x00000010 // TimerA match interrupt
|
||||
#define TIMER_RTC_MATCH 0x00000008 // RTC interrupt mask
|
||||
#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 ui32Event 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 ui32Timer
|
||||
// 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 ui32Timers 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
|
||||
#define TIMER_4A_SYNC 0x00000100 // Synchronize Timer 4A
|
||||
#define TIMER_4B_SYNC 0x00000200 // Synchronize Timer 4B
|
||||
#define TIMER_5A_SYNC 0x00000400 // Synchronize Timer 5A
|
||||
#define TIMER_5B_SYNC 0x00000800 // Synchronize Timer 5B
|
||||
#define WTIMER_0A_SYNC 0x00001000 // Synchronize Wide Timer 0A
|
||||
#define WTIMER_0B_SYNC 0x00002000 // Synchronize Wide Timer 0B
|
||||
#define WTIMER_1A_SYNC 0x00004000 // Synchronize Wide Timer 1A
|
||||
#define WTIMER_1B_SYNC 0x00008000 // Synchronize Wide Timer 1B
|
||||
#define WTIMER_2A_SYNC 0x00010000 // Synchronize Wide Timer 2A
|
||||
#define WTIMER_2B_SYNC 0x00020000 // Synchronize Wide Timer 2B
|
||||
#define WTIMER_3A_SYNC 0x00040000 // Synchronize Wide Timer 3A
|
||||
#define WTIMER_3B_SYNC 0x00080000 // Synchronize Wide Timer 3B
|
||||
#define WTIMER_4A_SYNC 0x00100000 // Synchronize Wide Timer 4A
|
||||
#define WTIMER_4B_SYNC 0x00200000 // Synchronize Wide Timer 4B
|
||||
#define WTIMER_5A_SYNC 0x00400000 // Synchronize Wide Timer 5A
|
||||
#define WTIMER_5B_SYNC 0x00800000 // Synchronize Wide Timer 5B
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to TimerClockSourceSet() or returned from
|
||||
// TimerClockSourceGet().
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define TIMER_CLOCK_SYSTEM 0x00000000
|
||||
#define TIMER_CLOCK_PIOSC 0x00000001
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// 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_RTC_A 0x00000008
|
||||
#define TIMER_DMA_CAPEVENT_A 0x00000004
|
||||
#define TIMER_DMA_CAPMATCH_A 0x00000002
|
||||
#define TIMER_DMA_TIMEOUT_A 0x00000001
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to TimerADCEventSet() or returned from
|
||||
// TimerADCEventGet().
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define TIMER_ADC_MODEMATCH_B 0x00000800
|
||||
#define TIMER_ADC_CAPEVENT_B 0x00000400
|
||||
#define TIMER_ADC_CAPMATCH_B 0x00000200
|
||||
#define TIMER_ADC_TIMEOUT_B 0x00000100
|
||||
#define TIMER_ADC_MODEMATCH_A 0x00000010
|
||||
#define TIMER_ADC_RTC_A 0x00000008
|
||||
#define TIMER_ADC_CAPEVENT_A 0x00000004
|
||||
#define TIMER_ADC_CAPMATCH_A 0x00000002
|
||||
#define TIMER_ADC_TIMEOUT_A 0x00000001
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to TimerUpdateMode().
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define TIMER_UP_LOAD_IMMEDIATE 0x00000000
|
||||
#define TIMER_UP_LOAD_TIMEOUT 0x00000100
|
||||
#define TIMER_UP_MATCH_IMMEDIATE \
|
||||
0x00000000
|
||||
#define TIMER_UP_MATCH_TIMEOUT 0x00000400
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Prototypes for the APIs.
|
||||
//
|
||||
//*****************************************************************************
|
||||
extern void TimerEnable(uint32_t ui32Base, uint32_t ui32Timer);
|
||||
extern void TimerDisable(uint32_t ui32Base, uint32_t ui32Timer);
|
||||
extern void TimerConfigure(uint32_t ui32Base, uint32_t ui32Config);
|
||||
extern void TimerControlLevel(uint32_t ui32Base, uint32_t ui32Timer,
|
||||
bool bInvert);
|
||||
extern void TimerControlTrigger(uint32_t ui32Base, uint32_t ui32Timer,
|
||||
bool bEnable);
|
||||
extern void TimerControlEvent(uint32_t ui32Base, uint32_t ui32Timer,
|
||||
uint32_t ui32Event);
|
||||
extern void TimerControlStall(uint32_t ui32Base, uint32_t ui32Timer,
|
||||
bool bStall);
|
||||
extern void TimerControlWaitOnTrigger(uint32_t ui32Base, uint32_t ui32Timer,
|
||||
bool bWait);
|
||||
extern void TimerRTCEnable(uint32_t ui32Base);
|
||||
extern void TimerRTCDisable(uint32_t ui32Base);
|
||||
extern void TimerPrescaleSet(uint32_t ui32Base, uint32_t ui32Timer,
|
||||
uint32_t ui32Value);
|
||||
extern uint32_t TimerPrescaleGet(uint32_t ui32Base, uint32_t ui32Timer);
|
||||
extern void TimerPrescaleMatchSet(uint32_t ui32Base, uint32_t ui32Timer,
|
||||
uint32_t ui32Value);
|
||||
extern uint32_t TimerPrescaleMatchGet(uint32_t ui32Base, uint32_t ui32Timer);
|
||||
extern void TimerLoadSet(uint32_t ui32Base, uint32_t ui32Timer,
|
||||
uint32_t ui32Value);
|
||||
extern uint32_t TimerLoadGet(uint32_t ui32Base, uint32_t ui32Timer);
|
||||
extern void TimerLoadSet64(uint32_t ui32Base, uint64_t ui64Value);
|
||||
extern uint64_t TimerLoadGet64(uint32_t ui32Base);
|
||||
extern uint32_t TimerValueGet(uint32_t ui32Base, uint32_t ui32Timer);
|
||||
extern uint64_t TimerValueGet64(uint32_t ui32Base);
|
||||
extern void TimerMatchSet(uint32_t ui32Base, uint32_t ui32Timer,
|
||||
uint32_t ui32Value);
|
||||
extern uint32_t TimerMatchGet(uint32_t ui32Base, uint32_t ui32Timer);
|
||||
extern void TimerMatchSet64(uint32_t ui32Base, uint64_t ui64Value);
|
||||
extern uint64_t TimerMatchGet64(uint32_t ui32Base);
|
||||
extern void TimerIntRegister(uint32_t ui32Base, uint32_t ui32Timer,
|
||||
void (*pfnHandler)(void));
|
||||
extern void TimerIntUnregister(uint32_t ui32Base, uint32_t ui32Timer);
|
||||
extern void TimerIntEnable(uint32_t ui32Base, uint32_t ui32IntFlags);
|
||||
extern void TimerIntDisable(uint32_t ui32Base, uint32_t ui32IntFlags);
|
||||
extern uint32_t TimerIntStatus(uint32_t ui32Base, bool bMasked);
|
||||
extern void TimerIntClear(uint32_t ui32Base, uint32_t ui32IntFlags);
|
||||
extern void TimerSynchronize(uint32_t ui32Base, uint32_t ui32Timers);
|
||||
extern uint32_t TimerClockSourceGet(uint32_t ui32Base);
|
||||
extern void TimerClockSourceSet(uint32_t ui32Base, uint32_t ui32Source);
|
||||
extern uint32_t TimerADCEventGet(uint32_t ui32Base);
|
||||
extern void TimerADCEventSet(uint32_t ui32Base, uint32_t ui32ADCEvent);
|
||||
extern uint32_t TimerDMAEventGet(uint32_t ui32Base);
|
||||
extern void TimerDMAEventSet(uint32_t ui32Base, uint32_t ui32DMAEvent);
|
||||
extern void TimerUpdateMode(uint32_t ui32Base, uint32_t ui32Timer,
|
||||
uint32_t ui32Config);
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Mark the end of the C bindings section for C++ compilers.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // __DRIVERLIB_TIMER_H__
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,255 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// uart.h - Defines and Macros for the UART.
|
||||
//
|
||||
// Copyright (c) 2005-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __DRIVERLIB_UART_H__
|
||||
#define __DRIVERLIB_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 ui32IntFlags parameter, and returned from UARTIntStatus.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UART_INT_DMATX 0x20000 // DMA TX interrupt
|
||||
#define UART_INT_DMARX 0x10000 // DMA RX interrupt
|
||||
#define UART_INT_9BIT 0x1000 // 9-bit address match interrupt
|
||||
#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_DSR 0x008 // DSR Modem Interrupt Mask
|
||||
#define UART_INT_DCD 0x004 // DCD Modem Interrupt Mask
|
||||
#define UART_INT_CTS 0x002 // CTS Modem Interrupt Mask
|
||||
#define UART_INT_RI 0x001 // RI Modem Interrupt Mask
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to UARTConfigSetExpClk as the ui32Config parameter
|
||||
// and returned by UARTConfigGetExpClk in the pui32Config parameter.
|
||||
// Additionally, the UART_CONFIG_PAR_* subset can be passed to
|
||||
// UARTParityModeSet as the ui32Parity 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 ui32TxLevel parameter
|
||||
// and returned by UARTFIFOLevelGet in the pui32TxLevel.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#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 ui32RxLevel parameter
|
||||
// and returned by UARTFIFOLevelGet in the pui32RxLevel.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#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 UARTHandshakeOutputsSet() or returned from
|
||||
// UARTHandshakeOutputGet().
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UART_OUTPUT_RTS 0x00000800
|
||||
#define UART_OUTPUT_DTR 0x00000400
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be returned from UARTHandshakeInputsGet().
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UART_INPUT_RI 0x00000100
|
||||
#define UART_INPUT_DCD 0x00000004
|
||||
#define UART_INPUT_DSR 0x00000002
|
||||
#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
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to UARTClockSourceSet() or returned from
|
||||
// UARTClockSourceGet().
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UART_CLOCK_SYSTEM 0x00000000
|
||||
#define UART_CLOCK_PIOSC 0x00000005
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// API Function prototypes
|
||||
//
|
||||
//*****************************************************************************
|
||||
extern void UARTParityModeSet(uint32_t ui32Base, uint32_t ui32Parity);
|
||||
extern uint32_t UARTParityModeGet(uint32_t ui32Base);
|
||||
extern void UARTFIFOLevelSet(uint32_t ui32Base, uint32_t ui32TxLevel,
|
||||
uint32_t ui32RxLevel);
|
||||
extern void UARTFIFOLevelGet(uint32_t ui32Base, uint32_t *pui32TxLevel,
|
||||
uint32_t *pui32RxLevel);
|
||||
extern void UARTConfigSetExpClk(uint32_t ui32Base, uint32_t ui32UARTClk,
|
||||
uint32_t ui32Baud, uint32_t ui32Config);
|
||||
extern void UARTConfigGetExpClk(uint32_t ui32Base, uint32_t ui32UARTClk,
|
||||
uint32_t *pui32Baud, uint32_t *pui32Config);
|
||||
extern void UARTEnable(uint32_t ui32Base);
|
||||
extern void UARTDisable(uint32_t ui32Base);
|
||||
extern void UARTFIFOEnable(uint32_t ui32Base);
|
||||
extern void UARTFIFODisable(uint32_t ui32Base);
|
||||
extern void UARTEnableSIR(uint32_t ui32Base, bool bLowPower);
|
||||
extern void UARTDisableSIR(uint32_t ui32Base);
|
||||
extern bool UARTCharsAvail(uint32_t ui32Base);
|
||||
extern bool UARTSpaceAvail(uint32_t ui32Base);
|
||||
extern int32_t UARTCharGetNonBlocking(uint32_t ui32Base);
|
||||
extern int32_t UARTCharGet(uint32_t ui32Base);
|
||||
extern bool UARTCharPutNonBlocking(uint32_t ui32Base, unsigned char ucData);
|
||||
extern void UARTCharPut(uint32_t ui32Base, unsigned char ucData);
|
||||
extern void UARTBreakCtl(uint32_t ui32Base, bool bBreakState);
|
||||
extern bool UARTBusy(uint32_t ui32Base);
|
||||
extern void UARTIntRegister(uint32_t ui32Base, void (*pfnHandler)(void));
|
||||
extern void UARTIntUnregister(uint32_t ui32Base);
|
||||
extern void UARTIntEnable(uint32_t ui32Base, uint32_t ui32IntFlags);
|
||||
extern void UARTIntDisable(uint32_t ui32Base, uint32_t ui32IntFlags);
|
||||
extern uint32_t UARTIntStatus(uint32_t ui32Base, bool bMasked);
|
||||
extern void UARTIntClear(uint32_t ui32Base, uint32_t ui32IntFlags);
|
||||
extern void UARTDMAEnable(uint32_t ui32Base, uint32_t ui32DMAFlags);
|
||||
extern void UARTDMADisable(uint32_t ui32Base, uint32_t ui32DMAFlags);
|
||||
extern uint32_t UARTRxErrorGet(uint32_t ui32Base);
|
||||
extern void UARTRxErrorClear(uint32_t ui32Base);
|
||||
extern void UARTSmartCardEnable(uint32_t ui32Base);
|
||||
extern void UARTSmartCardDisable(uint32_t ui32Base);
|
||||
extern void UARTModemControlSet(uint32_t ui32Base, uint32_t ui32Control);
|
||||
extern void UARTModemControlClear(uint32_t ui32Base, uint32_t ui32Control);
|
||||
extern uint32_t UARTModemControlGet(uint32_t ui32Base);
|
||||
extern uint32_t UARTModemStatusGet(uint32_t ui32Base);
|
||||
extern void UARTFlowControlSet(uint32_t ui32Base, uint32_t ui32Mode);
|
||||
extern uint32_t UARTFlowControlGet(uint32_t ui32Base);
|
||||
extern void UARTTxIntModeSet(uint32_t ui32Base, uint32_t ui32Mode);
|
||||
extern uint32_t UARTTxIntModeGet(uint32_t ui32Base);
|
||||
extern void UARTClockSourceSet(uint32_t ui32Base, uint32_t ui32Source);
|
||||
extern uint32_t UARTClockSourceGet(uint32_t ui32Base);
|
||||
extern void UART9BitEnable(uint32_t ui32Base);
|
||||
extern void UART9BitDisable(uint32_t ui32Base);
|
||||
extern void UART9BitAddrSet(uint32_t ui32Base, uint8_t ui8Addr,
|
||||
uint8_t ui8Mask);
|
||||
extern void UART9BitAddrSend(uint32_t ui32Base, uint8_t ui8Addr);
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Mark the end of the C bindings section for C++ compilers.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // __DRIVERLIB_UART_H__
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,899 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// udma.h - Prototypes and macros for the uDMA controller.
|
||||
//
|
||||
// Copyright (c) 2007-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __DRIVERLIB_UDMA_H__
|
||||
#define __DRIVERLIB_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_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 uint32_t ui32Control;
|
||||
|
||||
//
|
||||
// An unused location.
|
||||
//
|
||||
volatile uint32_t ui32Spare;
|
||||
}
|
||||
tDMAControlTable;
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! A helper macro for building scatter-gather task table entries.
|
||||
//!
|
||||
//! \param ui32TransferCount is the count of items to transfer for this task.
|
||||
//! \param ui32ItemSize is the bit size of the items to transfer for this task.
|
||||
//! \param ui32SrcIncrement is the bit size increment for source data.
|
||||
//! \param pvSrcAddr is the starting address of the data to transfer.
|
||||
//! \param ui32DstIncrement is the bit size increment for destination data.
|
||||
//! \param pvDstAddr is the starting address of the destination data.
|
||||
//! \param ui32ArbSize is the arbitration size to use for the transfer task.
|
||||
//! \param ui32Mode 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 ui32TransferCount parameter is the number of items that will be
|
||||
//! transferred by this task. It must be in the range 1-1024.
|
||||
//!
|
||||
//! The \e ui32ItemSize 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 ui32SrcIncrement 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 ui32DstIncrement 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 ui32ArbSize 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 ui32Mode 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(ui32TransferCount, \
|
||||
ui32ItemSize, \
|
||||
ui32SrcIncrement, \
|
||||
pvSrcAddr, \
|
||||
ui32DstIncrement, \
|
||||
pvDstAddr, \
|
||||
ui32ArbSize, \
|
||||
ui32Mode) \
|
||||
{ \
|
||||
(((ui32SrcIncrement) == UDMA_SRC_INC_NONE) ? (void *)(pvSrcAddr) : \
|
||||
((void *)(&((uint8_t *)(pvSrcAddr))[((ui32TransferCount) << \
|
||||
((ui32SrcIncrement) >> 26)) - 1]))), \
|
||||
(((ui32DstIncrement) == UDMA_DST_INC_NONE) ? (void *)(pvDstAddr) :\
|
||||
((void *)(&((uint8_t *)(pvDstAddr))[((ui32TransferCount) << \
|
||||
((ui32DstIncrement) >> 30)) - 1]))), \
|
||||
(ui32SrcIncrement) | (ui32DstIncrement) | (ui32ItemSize) | \
|
||||
(ui32ArbSize) | \
|
||||
(((ui32TransferCount) - 1) << 4) | \
|
||||
((((ui32Mode) == UDMA_MODE_MEM_SCATTER_GATHER) || \
|
||||
((ui32Mode) == UDMA_MODE_PER_SCATTER_GATHER)) ? \
|
||||
(ui32Mode) | UDMA_MODE_ALT_SELECT : (ui32Mode)), 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
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// 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_DST_PROT_PRIV 0x00200000
|
||||
#define UDMA_SRC_PROT_PRIV 0x00040000
|
||||
#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
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Channel numbers to be passed to API functions that require a channel number
|
||||
// ID.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UDMA_CHANNEL_USBEP1RX 0
|
||||
#define UDMA_CHANNEL_USBEP1TX 1
|
||||
#define UDMA_CHANNEL_USBEP2RX 2
|
||||
#define UDMA_CHANNEL_USBEP2TX 3
|
||||
#define UDMA_CHANNEL_USBEP3RX 4
|
||||
#define UDMA_CHANNEL_USBEP3TX 5
|
||||
#define UDMA_CHANNEL_ETH0RX 6
|
||||
#define UDMA_CHANNEL_ETH0TX 7
|
||||
#define UDMA_CHANNEL_UART0RX 8
|
||||
#define UDMA_CHANNEL_UART0TX 9
|
||||
#define UDMA_CHANNEL_SSI0RX 10
|
||||
#define UDMA_CHANNEL_SSI0TX 11
|
||||
#define UDMA_CHANNEL_ADC0 14
|
||||
#define UDMA_CHANNEL_ADC1 15
|
||||
#define UDMA_CHANNEL_ADC2 16
|
||||
#define UDMA_CHANNEL_ADC3 17
|
||||
#define UDMA_CHANNEL_TMR0A 18
|
||||
#define UDMA_CHANNEL_TMR0B 19
|
||||
#define UDMA_CHANNEL_TMR1A 20
|
||||
#define UDMA_CHANNEL_TMR1B 21
|
||||
#define UDMA_CHANNEL_UART1RX 22
|
||||
#define UDMA_CHANNEL_UART1TX 23
|
||||
#define UDMA_CHANNEL_SSI1RX 24
|
||||
#define UDMA_CHANNEL_SSI1TX 25
|
||||
#define UDMA_CHANNEL_I2S0RX 28
|
||||
#define UDMA_CHANNEL_I2S0TX 29
|
||||
#define UDMA_CHANNEL_SW 30
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// 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 62
|
||||
#define UDMA_INT_ERR 63
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Channel numbers to be passed to API functions that require a channel number
|
||||
// ID. These are for secondary peripheral assignments.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UDMA_SEC_CHANNEL_UART2RX_0 \
|
||||
0
|
||||
#define UDMA_SEC_CHANNEL_UART2TX_1 \
|
||||
1
|
||||
#define UDMA_SEC_CHANNEL_TMR3A 2
|
||||
#define UDMA_SEC_CHANNEL_TMR3B 3
|
||||
#define UDMA_SEC_CHANNEL_TMR2A_4 \
|
||||
4
|
||||
#define UDMA_SEC_CHANNEL_TMR2B_5 \
|
||||
5
|
||||
#define UDMA_SEC_CHANNEL_TMR2A_6 \
|
||||
6
|
||||
#define UDMA_SEC_CHANNEL_TMR2B_7 \
|
||||
7
|
||||
#define UDMA_SEC_CHANNEL_UART1RX \
|
||||
8
|
||||
#define UDMA_SEC_CHANNEL_UART1TX \
|
||||
9
|
||||
#define UDMA_SEC_CHANNEL_SSI1RX 10
|
||||
#define UDMA_SEC_CHANNEL_SSI1TX 11
|
||||
#define UDMA_SEC_CHANNEL_UART2RX_12 \
|
||||
12
|
||||
#define UDMA_SEC_CHANNEL_UART2TX_13 \
|
||||
13
|
||||
#define UDMA_SEC_CHANNEL_TMR2A_14 \
|
||||
14
|
||||
#define UDMA_SEC_CHANNEL_TMR2B_15 \
|
||||
15
|
||||
#define UDMA_SEC_CHANNEL_TMR1A 18
|
||||
#define UDMA_SEC_CHANNEL_TMR1B 19
|
||||
#define UDMA_SEC_CHANNEL_EPI0RX 20
|
||||
#define UDMA_SEC_CHANNEL_EPI0TX 21
|
||||
#define UDMA_SEC_CHANNEL_ADC10 24
|
||||
#define UDMA_SEC_CHANNEL_ADC11 25
|
||||
#define UDMA_SEC_CHANNEL_ADC12 26
|
||||
#define UDMA_SEC_CHANNEL_ADC13 27
|
||||
#define UDMA_SEC_CHANNEL_SW 30
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// 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_USB0EP1RX 0x00000000
|
||||
#define UDMA_CH0_UART2RX 0x00010000
|
||||
#define UDMA_CH0_RESERVED2 0x00020000
|
||||
#define UDMA_CH0_TIMER4A 0x00030000
|
||||
#define UDMA_CH0_RESERVED4 0x00040000
|
||||
#define UDMA_CH0_RESERVED5 0x00050000
|
||||
#define UDMA_CH0_I2C0RX 0x00060000
|
||||
#define UDMA_CH0_RESERVED7 0x00070000
|
||||
#define UDMA_CH0_RESERVED8 0x00080000
|
||||
|
||||
//
|
||||
// Channel 1
|
||||
//
|
||||
#define UDMA_CH1_USB0EP1TX 0x00000001
|
||||
#define UDMA_CH1_UART2TX 0x00010001
|
||||
#define UDMA_CH1_RESERVED2 0x00020001
|
||||
#define UDMA_CH1_TIMER4B 0x00030001
|
||||
#define UDMA_CH1_RESERVED4 0x00040001
|
||||
#define UDMA_CH1_RESERVED5 0x00050001
|
||||
#define UDMA_CH1_I2C0TX 0x00060001
|
||||
#define UDMA_CH1_RESERVED7 0x00070001
|
||||
#define UDMA_CH1_RESERVED8 0x00080001
|
||||
|
||||
//
|
||||
// Channel 2
|
||||
//
|
||||
#define UDMA_CH2_USB0EP2RX 0x00000002
|
||||
#define UDMA_CH2_TIMER3A 0x00010002
|
||||
#define UDMA_CH2_RESERVED2 0x00020002
|
||||
#define UDMA_CH2_RESERVED3 0x00030002
|
||||
#define UDMA_CH2_RESERVED4 0x00040002
|
||||
#define UDMA_CH2_RESERVED5 0x00050002
|
||||
#define UDMA_CH2_I2C1RX 0x00060002
|
||||
#define UDMA_CH2_RESERVED7 0x00070002
|
||||
#define UDMA_CH2_RESERVED8 0x00080002
|
||||
|
||||
//
|
||||
// Channel 3
|
||||
//
|
||||
#define UDMA_CH3_USB0EP2TX 0x00000003
|
||||
#define UDMA_CH3_TIMER3B 0x00010003
|
||||
#define UDMA_CH3_RESERVED2 0x00020003
|
||||
#define UDMA_CH3_LPC0_3 0x00030003
|
||||
#define UDMA_CH3_RESERVED4 0x00040003
|
||||
#define UDMA_CH3_RESERVED5 0x00050003
|
||||
#define UDMA_CH3_I2C1TX 0x00060003
|
||||
#define UDMA_CH3_RESERVED7 0x00070003
|
||||
#define UDMA_CH3_RESERVED8 0x00080003
|
||||
|
||||
//
|
||||
// Channel 4
|
||||
//
|
||||
#define UDMA_CH4_USB0EP3RX 0x00000004
|
||||
#define UDMA_CH4_TIMER2A 0x00010004
|
||||
#define UDMA_CH4_RESERVED2 0x00020004
|
||||
#define UDMA_CH4_GPIOA 0x00030004
|
||||
#define UDMA_CH4_RESERVED4 0x00040004
|
||||
#define UDMA_CH4_SHAMD50CIN 0x00050004
|
||||
#define UDMA_CH4_I2C2RX 0x00060004
|
||||
#define UDMA_CH4_RESERVED7 0x00070004
|
||||
#define UDMA_CH4_RESERVED8 0x00080004
|
||||
|
||||
//
|
||||
// Channel 5
|
||||
//
|
||||
#define UDMA_CH5_USB0EP3TX 0x00000005
|
||||
#define UDMA_CH5_TIMER2B 0x00010005
|
||||
#define UDMA_CH5_RESERVED2 0x00020005
|
||||
#define UDMA_CH5_GPIOB 0x00030005
|
||||
#define UDMA_CH5_RESERVED4 0x00040005
|
||||
#define UDMA_CH5_SHAMD50DIN 0x00050005
|
||||
#define UDMA_CH5_I2C2TX 0x00060005
|
||||
#define UDMA_CH5_RESERVED7 0x00070005
|
||||
#define UDMA_CH5_RESERVED8 0x00080005
|
||||
|
||||
//
|
||||
// Channel 6
|
||||
//
|
||||
#define UDMA_CH6_RESERVED0 0x00000006
|
||||
#define UDMA_CH6_ETH0RX 0x00000006
|
||||
#define UDMA_CH6_TIMER2A 0x00010006
|
||||
#define UDMA_CH6_UART5RX 0x00020006
|
||||
#define UDMA_CH6_GPIOC 0x00030006
|
||||
#define UDMA_CH6_I2C0RX 0x00040006
|
||||
#define UDMA_CH6_SHAMD50COUT 0x00050006
|
||||
#define UDMA_CH6_RESERVED6 0x00060006
|
||||
#define UDMA_CH6_RESERVED7 0x00070006
|
||||
#define UDMA_CH6_RESERVED8 0x00080006
|
||||
|
||||
//
|
||||
// Channel 7
|
||||
//
|
||||
#define UDMA_CH7_RESERVED0 0x00000007
|
||||
#define UDMA_CH7_ETH0TX 0x00000007
|
||||
#define UDMA_CH7_TIMER2B 0x00010007
|
||||
#define UDMA_CH7_UART5TX 0x00020007
|
||||
#define UDMA_CH7_GPIOD 0x00030007
|
||||
#define UDMA_CH7_I2C0TX 0x00040007
|
||||
#define UDMA_CH7_RESERVED5 0x00050007
|
||||
#define UDMA_CH7_RESERVED6 0x00060007
|
||||
#define UDMA_CH7_RESERVED7 0x00070007
|
||||
#define UDMA_CH7_RESERVED8 0x00080007
|
||||
|
||||
//
|
||||
// Channel 8
|
||||
//
|
||||
#define UDMA_CH8_UART0RX 0x00000008
|
||||
#define UDMA_CH8_UART1RX 0x00010008
|
||||
#define UDMA_CH8_RESERVED2 0x00020008
|
||||
#define UDMA_CH8_TIMER5A 0x00030008
|
||||
#define UDMA_CH8_I2C1RX 0x00040008
|
||||
#define UDMA_CH8_RESERVED5 0x00050008
|
||||
#define UDMA_CH8_RESERVED6 0x00060008
|
||||
#define UDMA_CH8_RESERVED7 0x00070008
|
||||
#define UDMA_CH8_RESERVED8 0x00080008
|
||||
|
||||
//
|
||||
// Channel 9
|
||||
//
|
||||
#define UDMA_CH9_UART0TX 0x00000009
|
||||
#define UDMA_CH9_UART1TX 0x00010009
|
||||
#define UDMA_CH9_RESERVED2 0x00020009
|
||||
#define UDMA_CH9_TIMER5B 0x00030009
|
||||
#define UDMA_CH9_I2C1TX 0x00040009
|
||||
#define UDMA_CH9_RESERVED5 0x00050009
|
||||
#define UDMA_CH9_RESERVED6 0x00060009
|
||||
#define UDMA_CH9_RESERVED7 0x00070009
|
||||
#define UDMA_CH9_RESERVED8 0x00080009
|
||||
|
||||
//
|
||||
// Channel 10
|
||||
//
|
||||
#define UDMA_CH10_SSI0RX 0x0000000A
|
||||
#define UDMA_CH10_SSI1RX 0x0001000A
|
||||
#define UDMA_CH10_UART6RX 0x0002000A
|
||||
#define UDMA_CH10_WTIMER0A 0x0003000A
|
||||
#define UDMA_CH10_I2C2RX 0x0004000A
|
||||
#define UDMA_CH10_RESERVED5 0x0005000A
|
||||
#define UDMA_CH10_RESERVED6 0x0006000A
|
||||
#define UDMA_CH10_TIMER6A 0x0007000A
|
||||
#define UDMA_CH10_RESERVED8 0x0008000A
|
||||
|
||||
//
|
||||
// Channel 11
|
||||
//
|
||||
#define UDMA_CH11_SSI0TX 0x0000000B
|
||||
#define UDMA_CH11_SSI1TX 0x0001000B
|
||||
#define UDMA_CH11_UART6TX 0x0002000B
|
||||
#define UDMA_CH11_WTIMER0B 0x0003000B
|
||||
#define UDMA_CH11_I2C2TX 0x0004000B
|
||||
#define UDMA_CH11_RESERVED5 0x0005000B
|
||||
#define UDMA_CH11_RESERVED6 0x0006000B
|
||||
#define UDMA_CH11_TIMER6B 0x0007000B
|
||||
#define UDMA_CH11_RESERVED8 0x0008000B
|
||||
|
||||
//
|
||||
// Channel 12
|
||||
//
|
||||
#define UDMA_CH12_RESERVED0 0x0000000C
|
||||
#define UDMA_CH12_UART2RX 0x0001000C
|
||||
#define UDMA_CH12_SSI2RX 0x0002000C
|
||||
#define UDMA_CH12_WTIMER1A 0x0003000C
|
||||
#define UDMA_CH12_GPIOK 0x0004000C
|
||||
#define UDMA_CH12_AES0CIN 0x0005000C
|
||||
#define UDMA_CH12_RESERVED6 0x0006000C
|
||||
#define UDMA_CH12_TIMER7A 0x0007000C
|
||||
#define UDMA_CH12_RESERVED8 0x0008000C
|
||||
|
||||
//
|
||||
// Channel 13
|
||||
//
|
||||
#define UDMA_CH13_RESERVED0 0x0000000D
|
||||
#define UDMA_CH13_UART2TX 0x0001000D
|
||||
#define UDMA_CH13_SSI2TX 0x0002000D
|
||||
#define UDMA_CH13_WTIMER1B 0x0003000D
|
||||
#define UDMA_CH13_GPIOL 0x0004000D
|
||||
#define UDMA_CH13_AES0COUT 0x0005000D
|
||||
#define UDMA_CH13_RESERVED6 0x0006000D
|
||||
#define UDMA_CH13_TIMER7B 0x0007000D
|
||||
#define UDMA_CH13_RESERVED8 0x0008000D
|
||||
|
||||
//
|
||||
// Channel 14
|
||||
//
|
||||
#define UDMA_CH14_ADC0_0 0x0000000E
|
||||
#define UDMA_CH14_TIMER2A 0x0001000E
|
||||
#define UDMA_CH14_SSI3RX 0x0002000E
|
||||
#define UDMA_CH14_GPIOE 0x0003000E
|
||||
#define UDMA_CH14_GPIOM 0x0004000E
|
||||
#define UDMA_CH14_AES0DIN 0x0005000E
|
||||
#define UDMA_CH14_RESERVED6 0x0006000E
|
||||
#define UDMA_CH14_RESERVED7 0x0007000E
|
||||
#define UDMA_CH14_RESERVED8 0x0008000E
|
||||
|
||||
//
|
||||
// Channel 15
|
||||
//
|
||||
#define UDMA_CH15_ADC0_1 0x0000000F
|
||||
#define UDMA_CH15_TIMER2B 0x0001000F
|
||||
#define UDMA_CH15_SSI3TX 0x0002000F
|
||||
#define UDMA_CH15_GPIOF 0x0003000F
|
||||
#define UDMA_CH15_GPION 0x0004000F
|
||||
#define UDMA_CH15_AES0DOUT 0x0005000F
|
||||
#define UDMA_CH15_RESERVED6 0x0006000F
|
||||
#define UDMA_CH15_RESERVED7 0x0007000F
|
||||
#define UDMA_CH15_RESERVED8 0x0008000F
|
||||
|
||||
//
|
||||
// Channel 16
|
||||
//
|
||||
#define UDMA_CH16_ADC0_2 0x00000010
|
||||
#define UDMA_CH16_RESERVED1 0x00010010
|
||||
#define UDMA_CH16_UART3RX 0x00020010
|
||||
#define UDMA_CH16_WTIMER2A 0x00030010
|
||||
#define UDMA_CH16_GPIOP 0x00040010
|
||||
#define UDMA_CH16_RESERVED5 0x00050010
|
||||
#define UDMA_CH16_RESERVED6 0x00060010
|
||||
#define UDMA_CH16_RESERVED7 0x00070010
|
||||
#define UDMA_CH16_RESERVED8 0x00080010
|
||||
|
||||
//
|
||||
// Channel 17
|
||||
//
|
||||
#define UDMA_CH17_ADC0_3 0x00000011
|
||||
#define UDMA_CH17_RESERVED1 0x00010011
|
||||
#define UDMA_CH17_UART3TX 0x00020011
|
||||
#define UDMA_CH17_WTIMER2B 0x00030011
|
||||
#define UDMA_CH17_RESERVED4 0x00040011
|
||||
#define UDMA_CH17_RESERVED5 0x00050011
|
||||
#define UDMA_CH17_RESERVED6 0x00060011
|
||||
#define UDMA_CH17_RESERVED7 0x00070011
|
||||
#define UDMA_CH17_RESERVED8 0x00080011
|
||||
|
||||
//
|
||||
// Channel 18
|
||||
//
|
||||
#define UDMA_CH18_TIMER0A 0x00000012
|
||||
#define UDMA_CH18_TIMER1A 0x00010012
|
||||
#define UDMA_CH18_UART4RX 0x00020012
|
||||
#define UDMA_CH18_GPIOB 0x00030012
|
||||
#define UDMA_CH18_I2C3RX 0x00040012
|
||||
#define UDMA_CH18_RESERVED5 0x00050012
|
||||
#define UDMA_CH18_RESERVED6 0x00060012
|
||||
#define UDMA_CH18_RESERVED7 0x00070012
|
||||
#define UDMA_CH18_RESERVED8 0x00080012
|
||||
|
||||
//
|
||||
// Channel 19
|
||||
//
|
||||
#define UDMA_CH19_TIMER0B 0x00000013
|
||||
#define UDMA_CH19_TIMER1B 0x00010013
|
||||
#define UDMA_CH19_UART4TX 0x00020013
|
||||
#define UDMA_CH19_GPIOG 0x00030013
|
||||
#define UDMA_CH19_I2C3TX 0x00040013
|
||||
#define UDMA_CH19_RESERVED5 0x00050013
|
||||
#define UDMA_CH19_RESERVED6 0x00060013
|
||||
#define UDMA_CH19_RESERVED7 0x00070013
|
||||
#define UDMA_CH19_RESERVED8 0x00080013
|
||||
|
||||
//
|
||||
// Channel 20
|
||||
//
|
||||
#define UDMA_CH20_TIMER1A 0x00000014
|
||||
#define UDMA_CH20_RESERVED1 0x00010014
|
||||
#define UDMA_CH20_EPI0RX 0x00010014
|
||||
#define UDMA_CH20_UART7RX 0x00020014
|
||||
#define UDMA_CH20_GPIOH 0x00030014
|
||||
#define UDMA_CH20_I2C4RX 0x00040014
|
||||
#define UDMA_CH20_DES0CIN 0x00050014
|
||||
#define UDMA_CH20_RESERVED6 0x00060014
|
||||
#define UDMA_CH20_RESERVED7 0x00070014
|
||||
#define UDMA_CH20_RESERVED8 0x00080014
|
||||
|
||||
//
|
||||
// Channel 21
|
||||
//
|
||||
#define UDMA_CH21_TIMER1B 0x00000015
|
||||
#define UDMA_CH21_RESERVED1 0x00010015
|
||||
#define UDMA_CH21_EPI0TX 0x00010015
|
||||
#define UDMA_CH21_UART7TX 0x00020015
|
||||
#define UDMA_CH21_GPIOJ 0x00030015
|
||||
#define UDMA_CH21_I2C4TX 0x00040015
|
||||
#define UDMA_CH21_DES0DIN 0x00050015
|
||||
#define UDMA_CH21_RESERVED6 0x00060015
|
||||
#define UDMA_CH21_RESERVED7 0x00070015
|
||||
#define UDMA_CH21_RESERVED8 0x00080015
|
||||
|
||||
//
|
||||
// Channel 22
|
||||
//
|
||||
#define UDMA_CH22_UART1RX 0x00000016
|
||||
#define UDMA_CH22_RESERVED1 0x00010016
|
||||
#define UDMA_CH22_RESERVED2 0x00020016
|
||||
#define UDMA_CH22_LPC0_2 0x00030016
|
||||
#define UDMA_CH22_I2C5RX 0x00040016
|
||||
#define UDMA_CH22_DES0DOUT 0x00050016
|
||||
#define UDMA_CH22_RESERVED6 0x00060016
|
||||
#define UDMA_CH22_RESERVED7 0x00070016
|
||||
#define UDMA_CH22_I2C8RX 0x00080016
|
||||
|
||||
//
|
||||
// Channel 23
|
||||
//
|
||||
#define UDMA_CH23_UART1TX 0x00000017
|
||||
#define UDMA_CH23_RESERVED1 0x00010017
|
||||
#define UDMA_CH23_RESERVED2 0x00020017
|
||||
#define UDMA_CH23_LPC0_1 0x00030017
|
||||
#define UDMA_CH23_I2C5TX 0x00040017
|
||||
#define UDMA_CH23_RESERVED5 0x00050017
|
||||
#define UDMA_CH23_RESERVED6 0x00060017
|
||||
#define UDMA_CH23_RESERVED7 0x00070017
|
||||
#define UDMA_CH23_I2C8TX 0x00080017
|
||||
|
||||
//
|
||||
// Channel 24
|
||||
//
|
||||
#define UDMA_CH24_SSI1RX 0x00000018
|
||||
#define UDMA_CH24_ADC1_0 0x00010018
|
||||
#define UDMA_CH24_RESERVED2 0x00020018
|
||||
#define UDMA_CH24_WTIMER3A 0x00030018
|
||||
#define UDMA_CH24_GPIOQ 0x00040018
|
||||
#define UDMA_CH24_RESERVED5 0x00050018
|
||||
#define UDMA_CH24_RESERVED6 0x00060018
|
||||
#define UDMA_CH24_RESERVED7 0x00070018
|
||||
#define UDMA_CH24_I2C9RX 0x00080018
|
||||
|
||||
//
|
||||
// Channel 25
|
||||
//
|
||||
#define UDMA_CH25_SSI1TX 0x00000019
|
||||
#define UDMA_CH25_ADC1_1 0x00010019
|
||||
#define UDMA_CH25_RESERVED2 0x00020019
|
||||
#define UDMA_CH25_WTIMER3B 0x00030019
|
||||
#define UDMA_CH25_RESERVED4 0x00040019
|
||||
#define UDMA_CH25_RESERVED5 0x00050019
|
||||
#define UDMA_CH25_RESERVED6 0x00060019
|
||||
#define UDMA_CH25_RESERVED7 0x00070019
|
||||
#define UDMA_CH25_I2C9TX 0x00080019
|
||||
|
||||
//
|
||||
// Channel 26
|
||||
//
|
||||
#define UDMA_CH26_RESERVED0 0x0000001A
|
||||
#define UDMA_CH26_ADC1_2 0x0001001A
|
||||
#define UDMA_CH26_RESERVED2 0x0002001A
|
||||
#define UDMA_CH26_WTIMER4A 0x0003001A
|
||||
#define UDMA_CH26_RESERVED4 0x0004001A
|
||||
#define UDMA_CH26_RESERVED5 0x0005001A
|
||||
#define UDMA_CH26_RESERVED6 0x0006001A
|
||||
#define UDMA_CH26_RESERVED7 0x0007001A
|
||||
#define UDMA_CH26_I2C6RX 0x0008001A
|
||||
|
||||
//
|
||||
// Channel 27
|
||||
//
|
||||
#define UDMA_CH27_RESERVED0 0x0000001B
|
||||
#define UDMA_CH27_ADC1_3 0x0001001B
|
||||
#define UDMA_CH27_RESERVED2 0x0002001B
|
||||
#define UDMA_CH27_WTIMER4B 0x0003001B
|
||||
#define UDMA_CH27_RESERVED4 0x0004001B
|
||||
#define UDMA_CH27_RESERVED5 0x0005001B
|
||||
#define UDMA_CH27_RESERVED6 0x0006001B
|
||||
#define UDMA_CH27_RESERVED7 0x0007001B
|
||||
#define UDMA_CH27_I2C6TX 0x0008001B
|
||||
|
||||
//
|
||||
// Channel 28
|
||||
//
|
||||
#define UDMA_CH28_RESERVED0 0x0000001C
|
||||
#define UDMA_CH28_RESERVED1 0x0001001C
|
||||
#define UDMA_CH28_RESERVED2 0x0002001C
|
||||
#define UDMA_CH28_WTIMER5A 0x0003001C
|
||||
#define UDMA_CH28_RESERVED4 0x0004001C
|
||||
#define UDMA_CH28_RESERVED5 0x0005001C
|
||||
#define UDMA_CH28_RESERVED6 0x0006001C
|
||||
#define UDMA_CH28_RESERVED7 0x0007001C
|
||||
#define UDMA_CH28_I2C7RX 0x0008001C
|
||||
|
||||
//
|
||||
// Channel 29
|
||||
//
|
||||
#define UDMA_CH29_RESERVED0 0x0000001D
|
||||
#define UDMA_CH29_RESERVED1 0x0001001D
|
||||
#define UDMA_CH29_RESERVED2 0x0002001D
|
||||
#define UDMA_CH29_WTIMER5B 0x0003001D
|
||||
#define UDMA_CH29_RESERVED4 0x0004001D
|
||||
#define UDMA_CH29_RESERVED5 0x0005001D
|
||||
#define UDMA_CH29_RESERVED6 0x0006001D
|
||||
#define UDMA_CH29_RESERVED7 0x0007001D
|
||||
#define UDMA_CH29_I2C7TX 0x0008001D
|
||||
|
||||
//
|
||||
// Channel 30
|
||||
//
|
||||
#define UDMA_CH30_SW 0x0000001E
|
||||
#define UDMA_CH30_RESERVED1 0x0001001E
|
||||
#define UDMA_CH30_RESERVED2 0x0002001E
|
||||
#define UDMA_CH30_RESERVED3 0x0003001E
|
||||
#define UDMA_CH30_RESERVED4 0x0004001E
|
||||
#define UDMA_CH30_RESERVED5 0x0005001E
|
||||
#define UDMA_CH30_RESERVED6 0x0006001E
|
||||
#define UDMA_CH30_EPI0RX 0x0007001E
|
||||
#define UDMA_CH30_1WIRE0 0x0008001E
|
||||
|
||||
//
|
||||
// Channel 31
|
||||
//
|
||||
#define UDMA_CH31_RESERVED0 0x0000001F
|
||||
#define UDMA_CH31_RESERVED1 0x0001001F
|
||||
#define UDMA_CH31_RESERVED2 0x0002001F
|
||||
#define UDMA_CH31_LPC0_0 0x0003001F
|
||||
#define UDMA_CH31_RESERVED4 0x0004001F
|
||||
#define UDMA_CH31_RESERVED5 0x0005001F
|
||||
#define UDMA_CH31_RESERVED6 0x0006001F
|
||||
#define UDMA_CH31_EPI0RX 0x0007001F
|
||||
#define UDMA_CH31_RESERVED8 0x0008001F
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// API Function prototypes
|
||||
//
|
||||
//*****************************************************************************
|
||||
extern void uDMAEnable(void);
|
||||
extern void uDMADisable(void);
|
||||
extern uint32_t uDMAErrorStatusGet(void);
|
||||
extern void uDMAErrorStatusClear(void);
|
||||
extern void uDMAChannelEnable(uint32_t ui32ChannelNum);
|
||||
extern void uDMAChannelDisable(uint32_t ui32ChannelNum);
|
||||
extern bool uDMAChannelIsEnabled(uint32_t ui32ChannelNum);
|
||||
extern void uDMAControlBaseSet(void *pControlTable);
|
||||
extern void *uDMAControlBaseGet(void);
|
||||
extern void *uDMAControlAlternateBaseGet(void);
|
||||
extern void uDMAChannelRequest(uint32_t ui32ChannelNum);
|
||||
extern void uDMAChannelAttributeEnable(uint32_t ui32ChannelNum,
|
||||
uint32_t ui32Attr);
|
||||
extern void uDMAChannelAttributeDisable(uint32_t ui32ChannelNum,
|
||||
uint32_t ui32Attr);
|
||||
extern uint32_t uDMAChannelAttributeGet(uint32_t ui32ChannelNum);
|
||||
extern void uDMAChannelControlSet(uint32_t ui32ChannelStructIndex,
|
||||
uint32_t ui32Control);
|
||||
extern void uDMAChannelTransferSet(uint32_t ui32ChannelStructIndex,
|
||||
uint32_t ui32Mode, void *pvSrcAddr,
|
||||
void *pvDstAddr, uint32_t ui32TransferSize);
|
||||
extern void uDMAChannelScatterGatherSet(uint32_t ui32ChannelNum,
|
||||
uint32_t ui32TaskCount,
|
||||
void *pvTaskList,
|
||||
uint32_t ui32IsPeriphSG);
|
||||
extern uint32_t uDMAChannelSizeGet(uint32_t ui32ChannelStructIndex);
|
||||
extern uint32_t uDMAChannelModeGet(uint32_t ui32ChannelStructIndex);
|
||||
extern void uDMAIntRegister(uint32_t ui32IntChannel, void (*pfnHandler)(void));
|
||||
extern void uDMAIntUnregister(uint32_t ui32IntChannel);
|
||||
extern uint32_t uDMAIntStatus(void);
|
||||
extern void uDMAIntClear(uint32_t ui32ChanMask);
|
||||
extern void uDMAChannelAssign(uint32_t ui32Mapping);
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following functions and definitions are deprecated and will be removed
|
||||
// from the API in the future. Use uDMAChannelAssign() instead to accomplish
|
||||
// the same end.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifndef DEPRECATED
|
||||
//*****************************************************************************
|
||||
//
|
||||
// uDMA default/secondary peripheral selections, to be passed to
|
||||
// uDMAChannelSelectSecondary() and uDMAChannelSelectDefault().
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UDMA_DEF_USBEP1RX_SEC_UART2RX \
|
||||
0x00000001
|
||||
#define UDMA_DEF_USBEP1TX_SEC_UART2TX \
|
||||
0x00000002
|
||||
#define UDMA_DEF_USBEP2RX_SEC_TMR3A \
|
||||
0x00000004
|
||||
#define UDMA_DEF_USBEP2TX_SEC_TMR3B \
|
||||
0x00000008
|
||||
#define UDMA_DEF_USBEP3RX_SEC_TMR2A \
|
||||
0x00000010
|
||||
#define UDMA_DEF_USBEP3TX_SEC_TMR2B \
|
||||
0x00000020
|
||||
#define UDMA_DEF_ETH0RX_SEC_TMR2A \
|
||||
0x00000040
|
||||
#define UDMA_DEF_ETH0TX_SEC_TMR2B \
|
||||
0x00000080
|
||||
#define UDMA_DEF_UART0RX_SEC_UART1RX \
|
||||
0x00000100
|
||||
#define UDMA_DEF_UART0TX_SEC_UART1TX \
|
||||
0x00000200
|
||||
#define UDMA_DEF_SSI0RX_SEC_SSI1RX \
|
||||
0x00000400
|
||||
#define UDMA_DEF_SSI0TX_SEC_SSI1TX \
|
||||
0x00000800
|
||||
#define UDMA_DEF_RESERVED_SEC_UART2RX \
|
||||
0x00001000
|
||||
#define UDMA_DEF_RESERVED_SEC_UART2TX \
|
||||
0x00002000
|
||||
#define UDMA_DEF_ADC00_SEC_TMR2A \
|
||||
0x00004000
|
||||
#define UDMA_DEF_ADC01_SEC_TMR2B \
|
||||
0x00008000
|
||||
#define UDMA_DEF_ADC02_SEC_RESERVED \
|
||||
0x00010000
|
||||
#define UDMA_DEF_ADC03_SEC_RESERVED \
|
||||
0x00020000
|
||||
#define UDMA_DEF_TMR0A_SEC_TMR1A \
|
||||
0x00040000
|
||||
#define UDMA_DEF_TMR0B_SEC_TMR1B \
|
||||
0x00080000
|
||||
#define UDMA_DEF_TMR1A_SEC_EPI0RX \
|
||||
0x00100000
|
||||
#define UDMA_DEF_TMR1B_SEC_EPI0TX \
|
||||
0x00200000
|
||||
#define UDMA_DEF_UART1RX_SEC_RESERVED \
|
||||
0x00400000
|
||||
#define UDMA_DEF_UART1TX_SEC_RESERVED \
|
||||
0x00800000
|
||||
#define UDMA_DEF_SSI1RX_SEC_ADC10 \
|
||||
0x01000000
|
||||
#define UDMA_DEF_SSI1TX_SEC_ADC11 \
|
||||
0x02000000
|
||||
#define UDMA_DEF_RESERVED_SEC_ADC12 \
|
||||
0x04000000
|
||||
#define UDMA_DEF_RESERVED_SEC_ADC13 \
|
||||
0x08000000
|
||||
#define UDMA_DEF_I2S0RX_SEC_RESERVED \
|
||||
0x10000000
|
||||
#define UDMA_DEF_I2S0TX_SEC_RESERVED \
|
||||
0x20000000
|
||||
|
||||
extern void uDMAChannelSelectDefault(uint32_t ui32DefPeriphs);
|
||||
extern void uDMAChannelSelectSecondary(uint32_t ui32SecPeriphs);
|
||||
|
||||
#endif
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Mark the end of the C bindings section for C++ compilers.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // __DRIVERLIB_UDMA_H__
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,658 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// usb.h - Prototypes for the USB Interface Driver.
|
||||
//
|
||||
// Copyright (c) 2007-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __DRIVERLIB_USB_H__
|
||||
#define __DRIVERLIB_USB_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 are values that can be passed to USBIntEnableControl() and
|
||||
// USBIntDisableControl() as the ui32Flags parameter, and are returned from
|
||||
// USBIntStatusControl().
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define USB_INTCTRL_ALL 0x000003FF // All control interrupt sources
|
||||
#define USB_INTCTRL_STATUS 0x000000FF // Status Interrupts
|
||||
#define USB_INTCTRL_VBUS_ERR 0x00000080 // VBUS Error
|
||||
#define USB_INTCTRL_SESSION 0x00000040 // Session Start Detected
|
||||
#define USB_INTCTRL_SESSION_END 0x00000040 // Session End Detected
|
||||
#define USB_INTCTRL_DISCONNECT 0x00000020 // Disconnect Detected
|
||||
#define USB_INTCTRL_CONNECT 0x00000010 // Device Connect Detected
|
||||
#define USB_INTCTRL_SOF 0x00000008 // Start of Frame Detected
|
||||
#define USB_INTCTRL_BABBLE 0x00000004 // Babble signaled
|
||||
#define USB_INTCTRL_RESET 0x00000004 // Reset signaled
|
||||
#define USB_INTCTRL_RESUME 0x00000002 // Resume detected
|
||||
#define USB_INTCTRL_SUSPEND 0x00000001 // Suspend detected
|
||||
#define USB_INTCTRL_MODE_DETECT 0x00000200 // Mode value valid
|
||||
#define USB_INTCTRL_POWER_FAULT 0x00000100 // Power Fault detected
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are values that can be passed to USBIntEnableEndpoint() and
|
||||
// USBIntDisableEndpoint() as the ui32Flags parameter, and are returned from
|
||||
// USBIntStatusEndpoint().
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define USB_INTEP_ALL 0xFFFFFFFF // Host IN Interrupts
|
||||
#define USB_INTEP_HOST_IN 0xFFFE0000 // Host IN Interrupts
|
||||
#define USB_INTEP_HOST_IN_15 0x80000000 // Endpoint 15 Host IN Interrupt
|
||||
#define USB_INTEP_HOST_IN_14 0x40000000 // Endpoint 14 Host IN Interrupt
|
||||
#define USB_INTEP_HOST_IN_13 0x20000000 // Endpoint 13 Host IN Interrupt
|
||||
#define USB_INTEP_HOST_IN_12 0x10000000 // Endpoint 12 Host IN Interrupt
|
||||
#define USB_INTEP_HOST_IN_11 0x08000000 // Endpoint 11 Host IN Interrupt
|
||||
#define USB_INTEP_HOST_IN_10 0x04000000 // Endpoint 10 Host IN Interrupt
|
||||
#define USB_INTEP_HOST_IN_9 0x02000000 // Endpoint 9 Host IN Interrupt
|
||||
#define USB_INTEP_HOST_IN_8 0x01000000 // Endpoint 8 Host IN Interrupt
|
||||
#define USB_INTEP_HOST_IN_7 0x00800000 // Endpoint 7 Host IN Interrupt
|
||||
#define USB_INTEP_HOST_IN_6 0x00400000 // Endpoint 6 Host IN Interrupt
|
||||
#define USB_INTEP_HOST_IN_5 0x00200000 // Endpoint 5 Host IN Interrupt
|
||||
#define USB_INTEP_HOST_IN_4 0x00100000 // Endpoint 4 Host IN Interrupt
|
||||
#define USB_INTEP_HOST_IN_3 0x00080000 // Endpoint 3 Host IN Interrupt
|
||||
#define USB_INTEP_HOST_IN_2 0x00040000 // Endpoint 2 Host IN Interrupt
|
||||
#define USB_INTEP_HOST_IN_1 0x00020000 // Endpoint 1 Host IN Interrupt
|
||||
|
||||
#define USB_INTEP_DEV_OUT 0xFFFE0000 // Device OUT Interrupts
|
||||
#define USB_INTEP_DEV_OUT_15 0x80000000 // Endpoint 15 Device OUT Interrupt
|
||||
#define USB_INTEP_DEV_OUT_14 0x40000000 // Endpoint 14 Device OUT Interrupt
|
||||
#define USB_INTEP_DEV_OUT_13 0x20000000 // Endpoint 13 Device OUT Interrupt
|
||||
#define USB_INTEP_DEV_OUT_12 0x10000000 // Endpoint 12 Device OUT Interrupt
|
||||
#define USB_INTEP_DEV_OUT_11 0x08000000 // Endpoint 11 Device OUT Interrupt
|
||||
#define USB_INTEP_DEV_OUT_10 0x04000000 // Endpoint 10 Device OUT Interrupt
|
||||
#define USB_INTEP_DEV_OUT_9 0x02000000 // Endpoint 9 Device OUT Interrupt
|
||||
#define USB_INTEP_DEV_OUT_8 0x01000000 // Endpoint 8 Device OUT Interrupt
|
||||
#define USB_INTEP_DEV_OUT_7 0x00800000 // Endpoint 7 Device OUT Interrupt
|
||||
#define USB_INTEP_DEV_OUT_6 0x00400000 // Endpoint 6 Device OUT Interrupt
|
||||
#define USB_INTEP_DEV_OUT_5 0x00200000 // Endpoint 5 Device OUT Interrupt
|
||||
#define USB_INTEP_DEV_OUT_4 0x00100000 // Endpoint 4 Device OUT Interrupt
|
||||
#define USB_INTEP_DEV_OUT_3 0x00080000 // Endpoint 3 Device OUT Interrupt
|
||||
#define USB_INTEP_DEV_OUT_2 0x00040000 // Endpoint 2 Device OUT Interrupt
|
||||
#define USB_INTEP_DEV_OUT_1 0x00020000 // Endpoint 1 Device OUT Interrupt
|
||||
|
||||
#define USB_INTEP_HOST_OUT 0x0000FFFE // Host OUT Interrupts
|
||||
#define USB_INTEP_HOST_OUT_15 0x00008000 // Endpoint 15 Host OUT Interrupt
|
||||
#define USB_INTEP_HOST_OUT_14 0x00004000 // Endpoint 14 Host OUT Interrupt
|
||||
#define USB_INTEP_HOST_OUT_13 0x00002000 // Endpoint 13 Host OUT Interrupt
|
||||
#define USB_INTEP_HOST_OUT_12 0x00001000 // Endpoint 12 Host OUT Interrupt
|
||||
#define USB_INTEP_HOST_OUT_11 0x00000800 // Endpoint 11 Host OUT Interrupt
|
||||
#define USB_INTEP_HOST_OUT_10 0x00000400 // Endpoint 10 Host OUT Interrupt
|
||||
#define USB_INTEP_HOST_OUT_9 0x00000200 // Endpoint 9 Host OUT Interrupt
|
||||
#define USB_INTEP_HOST_OUT_8 0x00000100 // Endpoint 8 Host OUT Interrupt
|
||||
#define USB_INTEP_HOST_OUT_7 0x00000080 // Endpoint 7 Host OUT Interrupt
|
||||
#define USB_INTEP_HOST_OUT_6 0x00000040 // Endpoint 6 Host OUT Interrupt
|
||||
#define USB_INTEP_HOST_OUT_5 0x00000020 // Endpoint 5 Host OUT Interrupt
|
||||
#define USB_INTEP_HOST_OUT_4 0x00000010 // Endpoint 4 Host OUT Interrupt
|
||||
#define USB_INTEP_HOST_OUT_3 0x00000008 // Endpoint 3 Host OUT Interrupt
|
||||
#define USB_INTEP_HOST_OUT_2 0x00000004 // Endpoint 2 Host OUT Interrupt
|
||||
#define USB_INTEP_HOST_OUT_1 0x00000002 // Endpoint 1 Host OUT Interrupt
|
||||
|
||||
#define USB_INTEP_DEV_IN 0x0000FFFE // Device IN Interrupts
|
||||
#define USB_INTEP_DEV_IN_15 0x00008000 // Endpoint 15 Device IN Interrupt
|
||||
#define USB_INTEP_DEV_IN_14 0x00004000 // Endpoint 14 Device IN Interrupt
|
||||
#define USB_INTEP_DEV_IN_13 0x00002000 // Endpoint 13 Device IN Interrupt
|
||||
#define USB_INTEP_DEV_IN_12 0x00001000 // Endpoint 12 Device IN Interrupt
|
||||
#define USB_INTEP_DEV_IN_11 0x00000800 // Endpoint 11 Device IN Interrupt
|
||||
#define USB_INTEP_DEV_IN_10 0x00000400 // Endpoint 10 Device IN Interrupt
|
||||
#define USB_INTEP_DEV_IN_9 0x00000200 // Endpoint 9 Device IN Interrupt
|
||||
#define USB_INTEP_DEV_IN_8 0x00000100 // Endpoint 8 Device IN Interrupt
|
||||
#define USB_INTEP_DEV_IN_7 0x00000080 // Endpoint 7 Device IN Interrupt
|
||||
#define USB_INTEP_DEV_IN_6 0x00000040 // Endpoint 6 Device IN Interrupt
|
||||
#define USB_INTEP_DEV_IN_5 0x00000020 // Endpoint 5 Device IN Interrupt
|
||||
#define USB_INTEP_DEV_IN_4 0x00000010 // Endpoint 4 Device IN Interrupt
|
||||
#define USB_INTEP_DEV_IN_3 0x00000008 // Endpoint 3 Device IN Interrupt
|
||||
#define USB_INTEP_DEV_IN_2 0x00000004 // Endpoint 2 Device IN Interrupt
|
||||
#define USB_INTEP_DEV_IN_1 0x00000002 // Endpoint 1 Device IN Interrupt
|
||||
|
||||
#define USB_INTEP_0 0x00000001 // Endpoint 0 Interrupt
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are values that are returned from USBSpeedGet().
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define USB_UNDEF_SPEED 0x80000000 // Current speed is undefined
|
||||
#define USB_HIGH_SPEED 0x00000002 // Current speed is High Speed
|
||||
#define USB_FULL_SPEED 0x00000001 // Current speed is Full Speed
|
||||
#define USB_LOW_SPEED 0x00000000 // Current speed is Low Speed
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are values that are returned from USBEndpointStatus(). The
|
||||
// USB_HOST_* values are used when the USB controller is in host mode and the
|
||||
// USB_DEV_* values are used when the USB controller is in device mode.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define USB_HOST_IN_STATUS 0x114F0000 // Mask of all host IN interrupts
|
||||
#define USB_HOST_IN_PID_ERROR 0x10000000 // Stall on this endpoint received
|
||||
#define USB_HOST_IN_NOT_COMP 0x01000000 // Device failed to respond
|
||||
#define USB_HOST_IN_STALL 0x00400000 // Stall on this endpoint received
|
||||
#define USB_HOST_IN_DATA_ERROR 0x00080000 // CRC or bit-stuff error
|
||||
// (ISOC Mode)
|
||||
#define USB_HOST_IN_NAK_TO 0x00080000 // NAK received for more than the
|
||||
// specified timeout period
|
||||
#define USB_HOST_IN_ERROR 0x00040000 // Failed to communicate with a
|
||||
// device
|
||||
#define USB_HOST_IN_FIFO_FULL 0x00020000 // RX FIFO full
|
||||
#define USB_HOST_IN_PKTRDY 0x00010000 // Data packet ready
|
||||
#define USB_HOST_OUT_STATUS 0x000000A7 // Mask of all host OUT interrupts
|
||||
#define USB_HOST_OUT_NAK_TO 0x00000080 // NAK received for more than the
|
||||
// specified timeout period
|
||||
#define USB_HOST_OUT_NOT_COMP 0x00000080 // No response from device
|
||||
// (ISOC mode)
|
||||
#define USB_HOST_OUT_STALL 0x00000020 // Stall on this endpoint received
|
||||
#define USB_HOST_OUT_ERROR 0x00000004 // Failed to communicate with a
|
||||
// device
|
||||
#define USB_HOST_OUT_FIFO_NE 0x00000002 // TX FIFO is not empty
|
||||
#define USB_HOST_OUT_PKTPEND 0x00000001 // Transmit still being transmitted
|
||||
#define USB_HOST_EP0_NAK_TO 0x00000080 // NAK received for more than the
|
||||
// specified timeout period
|
||||
#define USB_HOST_EP0_STATUS 0x00000040 // This was a status packet
|
||||
#define USB_HOST_EP0_ERROR 0x00000010 // Failed to communicate with a
|
||||
// device
|
||||
#define USB_HOST_EP0_RX_STALL 0x00000004 // Stall on this endpoint received
|
||||
#define USB_HOST_EP0_RXPKTRDY 0x00000001 // Receive data packet ready
|
||||
#define USB_DEV_RX_PID_ERROR 0x01000000 // PID error in isochronous
|
||||
// transfer
|
||||
#define USB_DEV_RX_SENT_STALL 0x00400000 // Stall was sent on this endpoint
|
||||
#define USB_DEV_RX_DATA_ERROR 0x00080000 // CRC error on the data
|
||||
#define USB_DEV_RX_OVERRUN 0x00040000 // OUT packet was not loaded due to
|
||||
// a full FIFO
|
||||
#define USB_DEV_RX_FIFO_FULL 0x00020000 // RX FIFO full
|
||||
#define USB_DEV_RX_PKT_RDY 0x00010000 // Data packet ready
|
||||
#define USB_DEV_TX_NOT_COMP 0x00000080 // Large packet split up, more data
|
||||
// to come
|
||||
#define USB_DEV_TX_SENT_STALL 0x00000020 // Stall was sent on this endpoint
|
||||
#define USB_DEV_TX_UNDERRUN 0x00000004 // IN received with no data ready
|
||||
#define USB_DEV_TX_FIFO_NE 0x00000002 // The TX FIFO is not empty
|
||||
#define USB_DEV_TX_TXPKTRDY 0x00000001 // Transmit still being transmitted
|
||||
#define USB_DEV_EP0_SETUP_END 0x00000010 // Control transaction ended before
|
||||
// Data End seen
|
||||
#define USB_DEV_EP0_SENT_STALL 0x00000004 // Stall was sent on this endpoint
|
||||
#define USB_DEV_EP0_IN_PKTPEND 0x00000002 // Transmit data packet pending
|
||||
#define USB_DEV_EP0_OUT_PKTRDY 0x00000001 // Receive data packet ready
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are values that can be passed to USBHostEndpointConfig() and
|
||||
// USBDevEndpointConfigSet() as the ui32Flags parameter.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define USB_EP_AUTO_SET 0x00000001 // Auto set feature enabled
|
||||
#define USB_EP_AUTO_REQUEST 0x00000002 // Auto request feature enabled
|
||||
#define USB_EP_AUTO_CLEAR 0x00000004 // Auto clear feature enabled
|
||||
#define USB_EP_DMA_MODE_0 0x00000008 // Enable DMA access using mode 0
|
||||
#define USB_EP_DMA_MODE_1 0x00000010 // Enable DMA access using mode 1
|
||||
#define USB_EP_DIS_NYET 0x00000020 // Disable NYET response for
|
||||
// high-speed Bulk and Interrupt
|
||||
// endpoints in device mode.
|
||||
#define USB_EP_MODE_ISOC 0x00000000 // Isochronous endpoint
|
||||
#define USB_EP_MODE_BULK 0x00000100 // Bulk endpoint
|
||||
#define USB_EP_MODE_INT 0x00000200 // Interrupt endpoint
|
||||
#define USB_EP_MODE_CTRL 0x00000300 // Control endpoint
|
||||
#define USB_EP_MODE_MASK 0x00000300 // Mode Mask
|
||||
#define USB_EP_SPEED_LOW 0x00000000 // Low Speed
|
||||
#define USB_EP_SPEED_FULL 0x00001000 // Full Speed
|
||||
#define USB_EP_SPEED_HIGH 0x00004000 // High Speed
|
||||
#define USB_EP_HOST_IN 0x00000000 // Host IN endpoint
|
||||
#define USB_EP_HOST_OUT 0x00002000 // Host OUT endpoint
|
||||
#define USB_EP_DEV_IN 0x00002000 // Device IN endpoint
|
||||
#define USB_EP_DEV_OUT 0x00000000 // Device OUT endpoint
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are values that can be passed to USBHostPwrConfig() as the
|
||||
// ui32Flags parameter.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define USB_HOST_PWRFLT_LOW 0x00000010
|
||||
#define USB_HOST_PWRFLT_HIGH 0x00000030
|
||||
#define USB_HOST_PWRFLT_EP_NONE 0x00000000
|
||||
#define USB_HOST_PWRFLT_EP_TRI 0x00000140
|
||||
#define USB_HOST_PWRFLT_EP_LOW 0x00000240
|
||||
#define USB_HOST_PWRFLT_EP_HIGH 0x00000340
|
||||
#define USB_HOST_PWREN_MAN_LOW 0x00000000
|
||||
#define USB_HOST_PWREN_MAN_HIGH 0x00000001
|
||||
#define USB_HOST_PWREN_AUTOLOW 0x00000002
|
||||
#define USB_HOST_PWREN_AUTOHIGH 0x00000003
|
||||
#define USB_HOST_PWREN_FILTER 0x00010000
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are the valid values that can be passed to the
|
||||
// USBHostLPMConfig() function in the ui32Config parameter.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define USB_HOST_LPM_RMTWAKE 0x00000100
|
||||
#define USB_HOST_LPM_L1 0x00000001
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are the valid values that can be passed to the
|
||||
// USBDevLPMConfig() function in the ui32Config parameter.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define USB_DEV_LPM_NAK 0x00000010
|
||||
#define USB_DEV_LPM_NONE 0x00000000
|
||||
#define USB_DEV_LPM_EN 0x0000000c
|
||||
#define USB_DEV_LPM_EXTONLY 0x00000004
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are the valid values that are returned from the
|
||||
// USBLPMLinkStateGet() function.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define USB_DEV_LPM_LS_RMTWAKE 0x00000100
|
||||
#define USB_DEV_LPM_LS_L1 0x00000001
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are the valid values that are passed to the USBLPMIntEnable()
|
||||
// or USBLPMIntDisable() functions or are returned from the USBLPMIntStatus()
|
||||
// function.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define USB_INTLPM_ERROR 0x00000020
|
||||
#define USB_INTLPM_RESUME 0x00000010
|
||||
#define USB_INTLPM_INCOMPLETE 0x00000008
|
||||
#define USB_INTLPM_ACK 0x00000004
|
||||
#define USB_INTLPM_NYET 0x00000002
|
||||
#define USB_INTLPM_STALL 0x00000001
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are the valid values that are passed to the USBClockEnable()
|
||||
// functions.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define USB_CLOCK_INTERNAL 0x00000200
|
||||
#define USB_CLOCK_EXTERNAL 0x00000300
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The configuration options used with the USBULPIConfig() API.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define USB_ULPI_EXTVBUS 0x00000001
|
||||
#define USB_ULPI_EXTVBUS_IND 0x00000002
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are special values that can be passed to
|
||||
// USBHostEndpointConfig() as the ui32NAKPollInterval parameter.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define MAX_NAK_LIMIT 31 // Maximum NAK interval
|
||||
#define DISABLE_NAK_LIMIT 0 // No NAK timeouts
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// This value specifies the maximum size of transfers on endpoint 0 as 64
|
||||
// bytes. This value is fixed in hardware as the FIFO size for endpoint 0.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define MAX_PACKET_SIZE_EP0 64
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// These values are used to indicate which endpoint to access.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define USB_EP_0 0x00000000 // Endpoint 0
|
||||
#define USB_EP_1 0x00000010 // Endpoint 1
|
||||
#define USB_EP_2 0x00000020 // Endpoint 2
|
||||
#define USB_EP_3 0x00000030 // Endpoint 3
|
||||
#define USB_EP_4 0x00000040 // Endpoint 4
|
||||
#define USB_EP_5 0x00000050 // Endpoint 5
|
||||
#define USB_EP_6 0x00000060 // Endpoint 6
|
||||
#define USB_EP_7 0x00000070 // Endpoint 7
|
||||
#define NUM_USB_EP 8 // Number of supported endpoints
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// These macros allow conversion between 0-based endpoint indices and the
|
||||
// USB_EP_x values required when calling various USB APIs.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define IndexToUSBEP(x) ((x) << 4)
|
||||
#define USBEPToIndex(x) ((x) >> 4)
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are values that can be passed to USBFIFOConfigSet() as the
|
||||
// ui32FIFOSize parameter.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define USB_FIFO_SZ_8 0x00000000 // 8 byte FIFO
|
||||
#define USB_FIFO_SZ_16 0x00000001 // 16 byte FIFO
|
||||
#define USB_FIFO_SZ_32 0x00000002 // 32 byte FIFO
|
||||
#define USB_FIFO_SZ_64 0x00000003 // 64 byte FIFO
|
||||
#define USB_FIFO_SZ_128 0x00000004 // 128 byte FIFO
|
||||
#define USB_FIFO_SZ_256 0x00000005 // 256 byte FIFO
|
||||
#define USB_FIFO_SZ_512 0x00000006 // 512 byte FIFO
|
||||
#define USB_FIFO_SZ_1024 0x00000007 // 1024 byte FIFO
|
||||
#define USB_FIFO_SZ_2048 0x00000008 // 2048 byte FIFO
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// This macro allow conversion from a FIFO size label as defined above to
|
||||
// a number of bytes
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define USBFIFOSizeToBytes(x) (8 << (x))
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are values that can be passed to USBEndpointDataSend() as the
|
||||
// ui32TransType parameter.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define USB_TRANS_OUT 0x00000102 // Normal OUT transaction
|
||||
#define USB_TRANS_IN 0x00000102 // Normal IN transaction
|
||||
#define USB_TRANS_IN_LAST 0x0000010a // Final IN transaction (for
|
||||
// endpoint 0 in device mode)
|
||||
#define USB_TRANS_SETUP 0x0000110a // Setup transaction (for endpoint
|
||||
// 0)
|
||||
#define USB_TRANS_STATUS 0x00000142 // Status transaction (for endpoint
|
||||
// 0)
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are values are returned by the USBModeGet function.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define USB_DUAL_MODE_HOST 0x00000001 // Dual mode controller is in Host
|
||||
// mode.
|
||||
#define USB_DUAL_MODE_DEVICE 0x00000081 // Dual mode controller is in
|
||||
// Device mode.
|
||||
#define USB_DUAL_MODE_NONE 0x00000080 // Dual mode controller mode is not
|
||||
// set.
|
||||
#define USB_OTG_MODE_ASIDE_HOST 0x0000001d // OTG controller on the A side of
|
||||
// the cable.
|
||||
#define USB_OTG_MODE_ASIDE_NPWR 0x00000001 // OTG controller on the A side of
|
||||
// the cable.
|
||||
#define USB_OTG_MODE_ASIDE_SESS 0x00000009 // OTG controller on the A side of
|
||||
// the cable Session Valid.
|
||||
#define USB_OTG_MODE_ASIDE_AVAL 0x00000011 // OTG controller on the A side of
|
||||
// the cable A valid.
|
||||
#define USB_OTG_MODE_ASIDE_DEV 0x00000019 // OTG controller on the A side of
|
||||
// the cable.
|
||||
#define USB_OTG_MODE_BSIDE_HOST 0x0000009d // OTG controller on the B side of
|
||||
// the cable.
|
||||
#define USB_OTG_MODE_BSIDE_DEV 0x00000099 // OTG controller on the B side of
|
||||
// the cable.
|
||||
#define USB_OTG_MODE_BSIDE_NPWR 0x00000081 // OTG controller on the B side of
|
||||
// the cable.
|
||||
#define USB_OTG_MODE_NONE 0x00000080 // OTG controller mode is not set.
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The values for the USBDMAChannelIntEnable() and USBDMAChannelIntStatus()
|
||||
// APIs.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define USB_DMA_INT_CH8 0x00000080
|
||||
#define USB_DMA_INT_CH7 0x00000040
|
||||
#define USB_DMA_INT_CH6 0x00000020
|
||||
#define USB_DMA_INT_CH5 0x00000010
|
||||
#define USB_DMA_INT_CH4 0x00000008
|
||||
#define USB_DMA_INT_CH3 0x00000004
|
||||
#define USB_DMA_INT_CH2 0x00000002
|
||||
#define USB_DMA_INT_CH1 0x00000001
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The values for the USBDMAChannelStatus() API.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define USB_DMA_STATUS_ERROR 0x00000100
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The valid return values for the USBControllerVersion() API.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define USB_CONTROLLER_VER_0 0x00000000 // This is for Blizzard class
|
||||
// devices.
|
||||
#define USB_CONTROLLER_VER_1 0x00000001 // This is for Snowflake class
|
||||
// devices.
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The valid return values for the USBDMAModeSet() and USBDMAModeGet() APIs or
|
||||
// USBDMAChannelConfig().
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define USB_DMA_CFG_BURST_NONE 0x00000000
|
||||
#define USB_DMA_CFG_BURST_4 0x00000200
|
||||
#define USB_DMA_CFG_BURST_8 0x00000400
|
||||
#define USB_DMA_CFG_BURST_16 0x00000600
|
||||
#define USB_DMA_CFG_INT_EN 0x00000008
|
||||
#define USB_DMA_CFG_MODE_0 0x00000000
|
||||
#define USB_DMA_CFG_MODE_1 0x00000004
|
||||
#define USB_DMA_CFG_DIR_RX 0x00000000
|
||||
#define USB_DMA_CFG_DIR_TX 0x00000002
|
||||
#define USB_DMA_CFG_EN 0x00000001
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are values that can be passed to USBModeConfig() as the
|
||||
// ui3Mode parameter.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define USB_MODE_HOST_VBUS 0x00000004
|
||||
#define USB_MODE_HOST 0x00000002
|
||||
#define USB_MODE_DEV_VBUS 0x00000005
|
||||
#define USB_MODE_DEV 0x00000003
|
||||
#define USB_MODE_OTG 0x00000000
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Prototypes for the APIs.
|
||||
//
|
||||
//*****************************************************************************
|
||||
extern uint32_t USBDevAddrGet(uint32_t ui32Base);
|
||||
extern void USBDevAddrSet(uint32_t ui32Base, uint32_t ui32Address);
|
||||
extern void USBDevConnect(uint32_t ui32Base);
|
||||
extern void USBDevDisconnect(uint32_t ui32Base);
|
||||
extern void USBDevEndpointConfigSet(uint32_t ui32Base, uint32_t ui32Endpoint,
|
||||
uint32_t ui32MaxPacketSize,
|
||||
uint32_t ui32Flags);
|
||||
extern void USBDevEndpointConfigGet(uint32_t ui32Base, uint32_t ui32Endpoint,
|
||||
uint32_t *pui32MaxPacketSize,
|
||||
uint32_t *pui32Flags);
|
||||
extern void USBDevEndpointDataAck(uint32_t ui32Base, uint32_t ui32Endpoint,
|
||||
bool bIsLastPacket);
|
||||
extern void USBDevEndpointStall(uint32_t ui32Base, uint32_t ui32Endpoint,
|
||||
uint32_t ui32Flags);
|
||||
extern void USBDevEndpointStallClear(uint32_t ui32Base, uint32_t ui32Endpoint,
|
||||
uint32_t ui32Flags);
|
||||
extern void USBDevEndpointStatusClear(uint32_t ui32Base, uint32_t ui32Endpoint,
|
||||
uint32_t ui32Flags);
|
||||
extern uint32_t USBEndpointDataAvail(uint32_t ui32Base, uint32_t ui32Endpoint);
|
||||
extern void USBEndpointDMAEnable(uint32_t ui32Base, uint32_t ui32Endpoint,
|
||||
uint32_t ui32Flags);
|
||||
extern void USBEndpointDMADisable(uint32_t ui32Base, uint32_t ui32Endpoint,
|
||||
uint32_t ui32Flags);
|
||||
extern void USBEndpointDMAConfigSet(uint32_t ui32Base, uint32_t ui32Endpoint,
|
||||
uint32_t ui32Config);
|
||||
extern int32_t USBEndpointDataGet(uint32_t ui32Base, uint32_t ui32Endpoint,
|
||||
uint8_t *pui8Data, uint32_t *pui32Size);
|
||||
extern int32_t USBEndpointDataPut(uint32_t ui32Base, uint32_t ui32Endpoint,
|
||||
uint8_t *pui8Data, uint32_t ui32Size);
|
||||
extern int32_t USBEndpointDataSend(uint32_t ui32Base, uint32_t ui32Endpoint,
|
||||
uint32_t ui32TransType);
|
||||
extern void USBEndpointDataToggleClear(uint32_t ui32Base,
|
||||
uint32_t ui32Endpoint,
|
||||
uint32_t ui32Flags);
|
||||
extern void USBEndpointPacketCountSet(uint32_t ui32Base, uint32_t ui32Endpoint,
|
||||
uint32_t ui32Count);
|
||||
extern uint32_t USBEndpointStatus(uint32_t ui32Base, uint32_t ui32Endpoint);
|
||||
extern uint32_t USBFIFOAddrGet(uint32_t ui32Base, uint32_t ui32Endpoint);
|
||||
extern void USBFIFOConfigGet(uint32_t ui32Base, uint32_t ui32Endpoint,
|
||||
uint32_t *pui32FIFOAddress,
|
||||
uint32_t *pui32FIFOSize, uint32_t ui32Flags);
|
||||
extern void USBFIFOConfigSet(uint32_t ui32Base, uint32_t ui32Endpoint,
|
||||
uint32_t ui32FIFOAddress, uint32_t ui32FIFOSize,
|
||||
uint32_t ui32Flags);
|
||||
extern void USBFIFOFlush(uint32_t ui32Base, uint32_t ui32Endpoint,
|
||||
uint32_t ui32Flags);
|
||||
extern uint32_t USBFrameNumberGet(uint32_t ui32Base);
|
||||
extern uint32_t USBHostAddrGet(uint32_t ui32Base, uint32_t ui32Endpoint,
|
||||
uint32_t ui32Flags);
|
||||
extern void USBHostAddrSet(uint32_t ui32Base, uint32_t ui32Endpoint,
|
||||
uint32_t ui32Addr, uint32_t ui32Flags);
|
||||
extern void USBHostEndpointConfig(uint32_t ui32Base, uint32_t ui32Endpoint,
|
||||
uint32_t ui32MaxPacketSize,
|
||||
uint32_t ui32NAKPollInterval,
|
||||
uint32_t ui32TargetEndpoint,
|
||||
uint32_t ui32Flags);
|
||||
extern void USBHostEndpointDataAck(uint32_t ui32Base,
|
||||
uint32_t ui32Endpoint);
|
||||
extern void USBHostEndpointDataToggle(uint32_t ui32Base, uint32_t ui32Endpoint,
|
||||
bool bDataToggle, uint32_t ui32Flags);
|
||||
extern void USBHostEndpointStatusClear(uint32_t ui32Base,
|
||||
uint32_t ui32Endpoint,
|
||||
uint32_t ui32Flags);
|
||||
extern uint32_t USBHostHubAddrGet(uint32_t ui32Base, uint32_t ui32Endpoint,
|
||||
uint32_t ui32Flags);
|
||||
extern void USBHostHubAddrSet(uint32_t ui32Base, uint32_t ui32Endpoint,
|
||||
uint32_t ui32Addr, uint32_t ui32Flags);
|
||||
extern void USBHostPwrDisable(uint32_t ui32Base);
|
||||
extern void USBHostPwrEnable(uint32_t ui32Base);
|
||||
extern void USBHostPwrConfig(uint32_t ui32Base, uint32_t ui32Flags);
|
||||
extern void USBHostPwrFaultDisable(uint32_t ui32Base);
|
||||
extern void USBHostPwrFaultEnable(uint32_t ui32Base);
|
||||
extern void USBHostRequestIN(uint32_t ui32Base, uint32_t ui32Endpoint);
|
||||
extern void USBHostRequestINClear(uint32_t ui32Base, uint32_t ui32Endpoint);
|
||||
extern void USBHostRequestStatus(uint32_t ui32Base);
|
||||
extern void USBHostReset(uint32_t ui32Base, bool bStart);
|
||||
extern void USBHostResume(uint32_t ui32Base, bool bStart);
|
||||
extern uint32_t USBHostSpeedGet(uint32_t ui32Base);
|
||||
extern void USBHostSuspend(uint32_t ui32Base);
|
||||
extern void USBIntDisableControl(uint32_t ui32Base, uint32_t ui32IntFlags);
|
||||
extern void USBIntEnableControl(uint32_t ui32Base, uint32_t ui32IntFlags);
|
||||
extern uint32_t USBIntStatusControl(uint32_t ui32Base);
|
||||
extern void USBIntDisableEndpoint(uint32_t ui32Base, uint32_t ui32IntFlags);
|
||||
extern void USBIntEnableEndpoint(uint32_t ui32Base, uint32_t ui32IntFlags);
|
||||
extern uint32_t USBIntStatusEndpoint(uint32_t ui32Base);
|
||||
extern void USBIntRegister(uint32_t ui32Base, void (*pfnHandler)(void));
|
||||
extern void USBIntUnregister(uint32_t ui32Base);
|
||||
extern void USBOTGSessionRequest(uint32_t ui32Base, bool bStart);
|
||||
extern uint32_t USBModeGet(uint32_t ui32Base);
|
||||
extern void USBEndpointDMAChannel(uint32_t ui32Base, uint32_t ui32Endpoint,
|
||||
uint32_t ui32Channel);
|
||||
extern uint32_t USBControllerVersion(uint32_t ui32Base);
|
||||
extern uint32_t USBDMAChannelIntStatus(uint32_t ui32Base);
|
||||
extern void USBDMAChannelConfigSet(uint32_t ui32Base, uint32_t ui32Channel,
|
||||
uint32_t ui32Endpoint, uint32_t ui32Config);
|
||||
extern void USBDMAChannelAddressSet(uint32_t ui32Base, uint32_t ui32Channel,
|
||||
void *pvAddress);
|
||||
extern void *USBDMAChannelAddressGet(uint32_t ui32Base, uint32_t ui32Channel);
|
||||
extern void USBDMAChannelCountSet(uint32_t ui32Base, uint32_t ui32Count,
|
||||
uint32_t ui32Channel);
|
||||
extern uint32_t USBDMAChannelCountGet(uint32_t ui32Base, uint32_t ui32Channel);
|
||||
extern uint32_t USBDMANumChannels(uint32_t ui32Base);
|
||||
extern void USBDMAChannelAssign(uint32_t ui32Base, uint32_t ui32Endpoint,
|
||||
uint32_t ui32Channel, uint32_t ui32Flags);
|
||||
extern void USBDMAChannelIntEnable(uint32_t ui32Base, uint32_t ui32Channel);
|
||||
extern void USBDMAChannelIntDisable(uint32_t ui32Base, uint32_t ui32Channel);
|
||||
extern void USBDMAChannelEnable(uint32_t ui32Base, uint32_t ui32Channel);
|
||||
extern void USBDMAChannelDisable(uint32_t ui32Base, uint32_t ui32Channel);
|
||||
extern uint32_t USBDMAChannelStatus(uint32_t ui32Base, uint32_t ui32Channel);
|
||||
extern void USBDMAChannelStatusClear(uint32_t ui32Base, uint32_t ui32Channel,
|
||||
uint32_t ui32Status);
|
||||
extern void USBHostEndpointSpeed(uint32_t ui32Base, uint32_t ui32Endpoint,
|
||||
uint32_t ui32Flags);
|
||||
extern void USBHostEndpointPing(uint32_t ui32Base, uint32_t ui32Endpoint,
|
||||
bool bEnable);
|
||||
extern void USBHostLPMSend(uint32_t ui32Base, uint32_t ui32Address,
|
||||
uint32_t uiEndpoint);
|
||||
extern void USBHostLPMConfig(uint32_t ui32Base, uint32_t ui32ResumeTime,
|
||||
uint32_t ui32Config);
|
||||
extern bool USBLPMRemoteWakeEnabled(uint32_t ui32Base);
|
||||
extern void USBHostLPMResume(uint32_t ui32Base);
|
||||
extern void USBDevLPMRemoteWake(uint32_t ui32Base);
|
||||
extern void USBDevLPMConfig(uint32_t ui32Base, uint32_t ui32Config);
|
||||
extern void USBDevLPMEnable(uint32_t ui32Base);
|
||||
extern void USBDevLPMDisable(uint32_t ui32Base);
|
||||
extern uint32_t USBLPMLinkStateGet(uint32_t ui32Base);
|
||||
extern uint32_t USBLPMEndpointGet(uint32_t ui32Base);
|
||||
extern uint32_t USBLPMIntStatus(uint32_t ui32Base);
|
||||
extern void USBLPMIntDisable(uint32_t ui32Base, uint32_t ui32Ints);
|
||||
extern void USBLPMIntEnable(uint32_t ui32Base, uint32_t ui32Ints);
|
||||
extern void USBHighSpeed(uint32_t ui32Base, bool bEnable);
|
||||
extern uint32_t USBDevSpeedGet(uint32_t ui32Base);
|
||||
extern void USBClockEnable(uint32_t ui32Base, uint32_t ui32Div,
|
||||
uint32_t ui32Flags);
|
||||
extern void USBClockDisable(uint32_t ui32Base);
|
||||
extern void USBULPIConfig(uint32_t ui32Base, uint32_t ui32Config);
|
||||
extern void USBULPIEnable(uint32_t ui32Base);
|
||||
extern void USBULPIDisable(uint32_t ui32Base);
|
||||
extern uint8_t USBULPIRegRead(uint32_t ui32Base, uint8_t ui8Reg);
|
||||
extern void USBULPIRegWrite(uint32_t ui32Base, uint8_t ui8Reg,
|
||||
uint8_t ui8Data);
|
||||
extern void USBHostMode(uint32_t ui32Base);
|
||||
extern void USBDevMode(uint32_t ui32Base);
|
||||
extern void USBOTGMode(uint32_t ui32Base);
|
||||
extern void USBModeConfig(uint32_t ui32Base, uint32_t ui32Mode);
|
||||
extern void USBPHYPowerOff(uint32_t ui32Base);
|
||||
extern void USBPHYPowerOn(uint32_t ui32Base);
|
||||
extern uint32_t USBNumEndpointsGet(uint32_t ui32Base);
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Mark the end of the C bindings section for C++ compilers.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // __DRIVERLIB_USB_H__
|
|
@ -0,0 +1,622 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// watchdog.c - Driver for the Watchdog Timer Module.
|
||||
//
|
||||
// Copyright (c) 2005-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! \addtogroup watchdog_api
|
||||
//! @{
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include "inc/hw_ints.h"
|
||||
#include "inc/hw_memmap.h"
|
||||
#include "inc/hw_types.h"
|
||||
#include "inc/hw_watchdog.h"
|
||||
#include "driverlib/debug.h"
|
||||
#include "driverlib/interrupt.h"
|
||||
#include "driverlib/watchdog.h"
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Determines if the watchdog timer is enabled.
|
||||
//!
|
||||
//! \param ui32Base is the base address of the watchdog timer module.
|
||||
//!
|
||||
//! This function checks 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.
|
||||
//
|
||||
//*****************************************************************************
|
||||
bool
|
||||
WatchdogRunning(uint32_t ui32Base)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT((ui32Base == WATCHDOG0_BASE) || (ui32Base == WATCHDOG1_BASE));
|
||||
|
||||
//
|
||||
// See if the watchdog timer module is enabled, and return.
|
||||
//
|
||||
return(HWREG(ui32Base + WDT_O_CTL) & WDT_CTL_INTEN);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Enables the watchdog timer.
|
||||
//!
|
||||
//! \param ui32Base is the base address of the watchdog timer module.
|
||||
//!
|
||||
//! This function enables the watchdog timer counter and interrupt.
|
||||
//!
|
||||
//! \note This function has no effect if the watchdog timer has been locked.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
WatchdogEnable(uint32_t ui32Base)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT((ui32Base == WATCHDOG0_BASE) || (ui32Base == WATCHDOG1_BASE));
|
||||
|
||||
//
|
||||
// Enable the watchdog timer module.
|
||||
//
|
||||
HWREG(ui32Base + WDT_O_CTL) |= WDT_CTL_INTEN;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Enables the watchdog timer reset.
|
||||
//!
|
||||
//! \param ui32Base is the base address of the watchdog timer module.
|
||||
//!
|
||||
//! This function enables the capability of the watchdog timer to issue a reset
|
||||
//! to the processor after a second timeout condition.
|
||||
//!
|
||||
//! \note This function has no effect if the watchdog timer has been locked.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
WatchdogResetEnable(uint32_t ui32Base)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT((ui32Base == WATCHDOG0_BASE) || (ui32Base == WATCHDOG1_BASE));
|
||||
|
||||
//
|
||||
// Enable the watchdog reset.
|
||||
//
|
||||
HWREG(ui32Base + WDT_O_CTL) |= WDT_CTL_RESEN;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Disables the watchdog timer reset.
|
||||
//!
|
||||
//! \param ui32Base is the base address of the watchdog timer module.
|
||||
//!
|
||||
//! This function disables the capability of the watchdog timer to issue a
|
||||
//! reset to the processor after a second timeout condition.
|
||||
//!
|
||||
//! \note This function has no effect if the watchdog timer has been locked.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
WatchdogResetDisable(uint32_t ui32Base)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT((ui32Base == WATCHDOG0_BASE) || (ui32Base == WATCHDOG1_BASE));
|
||||
|
||||
//
|
||||
// Disable the watchdog reset.
|
||||
//
|
||||
HWREG(ui32Base + WDT_O_CTL) &= ~(WDT_CTL_RESEN);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Enables the watchdog timer lock mechanism.
|
||||
//!
|
||||
//! \param ui32Base is the base address of the watchdog timer module.
|
||||
//!
|
||||
//! This function locks out write access to the watchdog timer registers.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
WatchdogLock(uint32_t ui32Base)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT((ui32Base == WATCHDOG0_BASE) || (ui32Base == WATCHDOG1_BASE));
|
||||
|
||||
//
|
||||
// Lock out watchdog register writes. Writing anything to the WDT_O_LOCK
|
||||
// register causes the lock to go into effect.
|
||||
//
|
||||
HWREG(ui32Base + WDT_O_LOCK) = WDT_LOCK_LOCKED;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Disables the watchdog timer lock mechanism.
|
||||
//!
|
||||
//! \param ui32Base is the base address of the watchdog timer module.
|
||||
//!
|
||||
//! This function enables write access to the watchdog timer registers.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
WatchdogUnlock(uint32_t ui32Base)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT((ui32Base == WATCHDOG0_BASE) || (ui32Base == WATCHDOG1_BASE));
|
||||
|
||||
//
|
||||
// Unlock watchdog register writes.
|
||||
//
|
||||
HWREG(ui32Base + WDT_O_LOCK) = WDT_LOCK_UNLOCK;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Gets the state of the watchdog timer lock mechanism.
|
||||
//!
|
||||
//! \param ui32Base is the base address of the watchdog timer module.
|
||||
//!
|
||||
//! This function 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.
|
||||
//
|
||||
//*****************************************************************************
|
||||
bool
|
||||
WatchdogLockState(uint32_t ui32Base)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT((ui32Base == WATCHDOG0_BASE) || (ui32Base == WATCHDOG1_BASE));
|
||||
|
||||
//
|
||||
// Get the lock state.
|
||||
//
|
||||
return((HWREG(ui32Base + WDT_O_LOCK) == WDT_LOCK_LOCKED) ? true : false);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Sets the watchdog timer reload value.
|
||||
//!
|
||||
//! \param ui32Base is the base address of the watchdog timer module.
|
||||
//! \param ui32LoadVal is the load value for the watchdog timer.
|
||||
//!
|
||||
//! This function configures 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 is immediately loaded into the
|
||||
//! watchdog timer counter. If the \e ui32LoadVal parameter is 0, then an
|
||||
//! interrupt is immediately generated.
|
||||
//!
|
||||
//! \note This function has no effect if the watchdog timer has been locked.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
WatchdogReloadSet(uint32_t ui32Base, uint32_t ui32LoadVal)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT((ui32Base == WATCHDOG0_BASE) || (ui32Base == WATCHDOG1_BASE));
|
||||
|
||||
//
|
||||
// Set the load register.
|
||||
//
|
||||
HWREG(ui32Base + WDT_O_LOAD) = ui32LoadVal;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Gets the watchdog timer reload value.
|
||||
//!
|
||||
//! \param ui32Base 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.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
uint32_t
|
||||
WatchdogReloadGet(uint32_t ui32Base)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT((ui32Base == WATCHDOG0_BASE) || (ui32Base == WATCHDOG1_BASE));
|
||||
|
||||
//
|
||||
// Get the load register.
|
||||
//
|
||||
return(HWREG(ui32Base + WDT_O_LOAD));
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Gets the current watchdog timer value.
|
||||
//!
|
||||
//! \param ui32Base 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.
|
||||
//
|
||||
//*****************************************************************************
|
||||
uint32_t
|
||||
WatchdogValueGet(uint32_t ui32Base)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT((ui32Base == WATCHDOG0_BASE) || (ui32Base == WATCHDOG1_BASE));
|
||||
|
||||
//
|
||||
// Get the current watchdog timer register value.
|
||||
//
|
||||
return(HWREG(ui32Base + WDT_O_VALUE));
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Registers an interrupt handler for the watchdog timer interrupt.
|
||||
//!
|
||||
//! \param ui32Base 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
|
||||
//! function also enables 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 For parts with a watchdog timer module that has the ability to
|
||||
//! generate an NMI instead of a standard interrupt, this function registers
|
||||
//! 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(uint32_t ui32Base, void (*pfnHandler)(void))
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT((ui32Base == WATCHDOG0_BASE) || (ui32Base == WATCHDOG1_BASE));
|
||||
|
||||
//
|
||||
// Register the interrupt handler.
|
||||
//
|
||||
IntRegister(INT_WATCHDOG_TM4C123, pfnHandler);
|
||||
|
||||
//
|
||||
// Enable the watchdog timer interrupt.
|
||||
//
|
||||
IntEnable(INT_WATCHDOG_TM4C123);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Unregisters an interrupt handler for the watchdog timer interrupt.
|
||||
//!
|
||||
//! \param ui32Base is the base address of the watchdog timer module.
|
||||
//!
|
||||
//! This function does the actual unregistering of the interrupt handler. This
|
||||
//! function clears the handler to be called when a watchdog timer 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.
|
||||
//!
|
||||
//! \note For parts with a watchdog timer module that has the ability to
|
||||
//! generate an NMI instead of a standard interrupt, this function unregisters
|
||||
//! 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(uint32_t ui32Base)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT((ui32Base == WATCHDOG0_BASE) || (ui32Base == WATCHDOG1_BASE));
|
||||
|
||||
//
|
||||
// Disable the interrupt.
|
||||
//
|
||||
IntDisable(INT_WATCHDOG_TM4C123);
|
||||
|
||||
//
|
||||
// Unregister the interrupt handler.
|
||||
//
|
||||
IntUnregister(INT_WATCHDOG_TM4C123);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Enables the watchdog timer interrupt.
|
||||
//!
|
||||
//! \param ui32Base is the base address of the watchdog timer module.
|
||||
//!
|
||||
//! This function enables the watchdog timer interrupt.
|
||||
//!
|
||||
//! \note This function has no effect if the watchdog timer has been locked.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
WatchdogIntEnable(uint32_t ui32Base)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT((ui32Base == WATCHDOG0_BASE) || (ui32Base == WATCHDOG1_BASE));
|
||||
|
||||
//
|
||||
// Enable the watchdog interrupt.
|
||||
//
|
||||
HWREG(ui32Base + WDT_O_CTL) |= WDT_CTL_INTEN;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Gets the current watchdog timer interrupt status.
|
||||
//!
|
||||
//! \param ui32Base 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 function 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.
|
||||
//
|
||||
//*****************************************************************************
|
||||
uint32_t
|
||||
WatchdogIntStatus(uint32_t ui32Base, bool bMasked)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT((ui32Base == WATCHDOG0_BASE) || (ui32Base == WATCHDOG1_BASE));
|
||||
|
||||
//
|
||||
// Return either the interrupt status or the raw interrupt status as
|
||||
// requested.
|
||||
//
|
||||
if(bMasked)
|
||||
{
|
||||
return(HWREG(ui32Base + WDT_O_MIS));
|
||||
}
|
||||
else
|
||||
{
|
||||
return(HWREG(ui32Base + WDT_O_RIS));
|
||||
}
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Clears the watchdog timer interrupt.
|
||||
//!
|
||||
//! \param ui32Base 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-M 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). This function has no effect if the watchdog
|
||||
//! timer has been locked.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
WatchdogIntClear(uint32_t ui32Base)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT((ui32Base == WATCHDOG0_BASE) || (ui32Base == WATCHDOG1_BASE));
|
||||
|
||||
//
|
||||
// Clear the interrupt source.
|
||||
//
|
||||
HWREG(ui32Base + WDT_O_ICR) = WDT_RIS_WDTRIS;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Sets the type of interrupt generated by the watchdog.
|
||||
//!
|
||||
//! \param ui32Base is the base address of the watchdog timer module.
|
||||
//! \param ui32Type is the type of interrupt to generate.
|
||||
//!
|
||||
//! This function sets the type of interrupt that is generated if the watchdog
|
||||
//! timer expires. \e ui32Type can be either \b WATCHDOG_INT_TYPE_INT to
|
||||
//! generate a standard interrupt (the default) or \b WATCHDOG_INT_TYPE_NMI to
|
||||
//! generate a non-maskable interrupt (NMI).
|
||||
//!
|
||||
//! When configured to generate an NMI, the watchdog interrupt must still be
|
||||
//! enabled with WatchdogIntEnable(), and it must still be cleared inside the
|
||||
//! NMI handler with WatchdogIntClear().
|
||||
//!
|
||||
//! \note The ability to select an NMI interrupt varies with the Tiva part
|
||||
//! in use. Please consult the datasheet for the part you are using to
|
||||
//! determine whether this support is available. This function has no effect if
|
||||
//! the watchdog timer has been locked.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
WatchdogIntTypeSet(uint32_t ui32Base, uint32_t ui32Type)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT((ui32Base == WATCHDOG0_BASE) || (ui32Base == WATCHDOG1_BASE));
|
||||
ASSERT((ui32Type == WATCHDOG_INT_TYPE_INT) ||
|
||||
(ui32Type == WATCHDOG_INT_TYPE_NMI));
|
||||
|
||||
//
|
||||
// Set the interrupt type.
|
||||
//
|
||||
HWREG(ui32Base + WDT_O_CTL) = (HWREG(ui32Base + WDT_O_CTL) &
|
||||
~WDT_CTL_INTTYPE) | ui32Type;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Enables stalling of the watchdog timer during debug events.
|
||||
//!
|
||||
//! \param ui32Base 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 instead expires
|
||||
//! after the appropriate number of processor cycles have been executed while
|
||||
//! debugging (or at the appropriate time after the processor has been
|
||||
//! restarted).
|
||||
//!
|
||||
//! \note This function has no effect if the watchdog timer has been locked.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
WatchdogStallEnable(uint32_t ui32Base)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT((ui32Base == WATCHDOG0_BASE) || (ui32Base == WATCHDOG1_BASE));
|
||||
|
||||
//
|
||||
// Enable timer stalling.
|
||||
//
|
||||
HWREG(ui32Base + WDT_O_TEST) |= WDT_TEST_STALL;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Disables stalling of the watchdog timer during debug events.
|
||||
//!
|
||||
//! \param ui32Base 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.
|
||||
//!
|
||||
//! \note This function has no effect if the watchdog timer has been locked.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
WatchdogStallDisable(uint32_t ui32Base)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT((ui32Base == WATCHDOG0_BASE) || (ui32Base == WATCHDOG1_BASE));
|
||||
|
||||
//
|
||||
// Disable timer stalling.
|
||||
//
|
||||
HWREG(ui32Base + WDT_O_TEST) &= ~(WDT_TEST_STALL);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Close the Doxygen group.
|
||||
//! @}
|
||||
//
|
||||
//*****************************************************************************
|
|
@ -0,0 +1,95 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// watchdog.h - Prototypes for the Watchdog Timer API
|
||||
//
|
||||
// Copyright (c) 2005-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __DRIVERLIB_WATCHDOG_H__
|
||||
#define __DRIVERLIB_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
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The type of interrupt that can be generated by the watchdog.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define WATCHDOG_INT_TYPE_INT 0x00000000
|
||||
#define WATCHDOG_INT_TYPE_NMI 0x00000004
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Prototypes for the APIs.
|
||||
//
|
||||
//*****************************************************************************
|
||||
extern bool WatchdogRunning(uint32_t ui32Base);
|
||||
extern void WatchdogEnable(uint32_t ui32Base);
|
||||
extern void WatchdogResetEnable(uint32_t ui32Base);
|
||||
extern void WatchdogResetDisable(uint32_t ui32Base);
|
||||
extern void WatchdogLock(uint32_t ui32Base);
|
||||
extern void WatchdogUnlock(uint32_t ui32Base);
|
||||
extern bool WatchdogLockState(uint32_t ui32Base);
|
||||
extern void WatchdogReloadSet(uint32_t ui32Base, uint32_t ui32LoadVal);
|
||||
extern uint32_t WatchdogReloadGet(uint32_t ui32Base);
|
||||
extern uint32_t WatchdogValueGet(uint32_t ui32Base);
|
||||
extern void WatchdogIntRegister(uint32_t ui32Base, void (*pfnHandler)(void));
|
||||
extern void WatchdogIntUnregister(uint32_t ui32Base);
|
||||
extern void WatchdogIntEnable(uint32_t ui32Base);
|
||||
extern uint32_t WatchdogIntStatus(uint32_t ui32Base, bool bMasked);
|
||||
extern void WatchdogIntClear(uint32_t ui32Base);
|
||||
extern void WatchdogIntTypeSet(uint32_t ui32Base, uint32_t ui32Type);
|
||||
extern void WatchdogStallEnable(uint32_t ui32Base);
|
||||
extern void WatchdogStallDisable(uint32_t ui32Base);
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Mark the end of the C bindings section for C++ compilers.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // __DRIVERLIB_WATCHDOG_H__
|
|
@ -0,0 +1,227 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// asmdefs.h - Macros to allow assembly code be portable among toolchains.
|
||||
//
|
||||
// Copyright (c) 2005-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Firmware Development Package.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#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__
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,545 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// hw_aes.h - Macros used when accessing the AES hardware.
|
||||
//
|
||||
// Copyright (c) 2012-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Firmware Development Package.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __HW_AES_H__
|
||||
#define __HW_AES_H__
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the AES register offsets.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define AES_O_KEY2_6 0x00000000 // AES Key 2_6
|
||||
#define AES_O_KEY2_7 0x00000004 // AES Key 2_7
|
||||
#define AES_O_KEY2_4 0x00000008 // AES Key 2_4
|
||||
#define AES_O_KEY2_5 0x0000000C // AES Key 2_5
|
||||
#define AES_O_KEY2_2 0x00000010 // AES Key 2_2
|
||||
#define AES_O_KEY2_3 0x00000014 // AES Key 2_3
|
||||
#define AES_O_KEY2_0 0x00000018 // AES Key 2_0
|
||||
#define AES_O_KEY2_1 0x0000001C // AES Key 2_1
|
||||
#define AES_O_KEY1_6 0x00000020 // AES Key 1_6
|
||||
#define AES_O_KEY1_7 0x00000024 // AES Key 1_7
|
||||
#define AES_O_KEY1_4 0x00000028 // AES Key 1_4
|
||||
#define AES_O_KEY1_5 0x0000002C // AES Key 1_5
|
||||
#define AES_O_KEY1_2 0x00000030 // AES Key 1_2
|
||||
#define AES_O_KEY1_3 0x00000034 // AES Key 1_3
|
||||
#define AES_O_KEY1_0 0x00000038 // AES Key 1_0
|
||||
#define AES_O_KEY1_1 0x0000003C // AES Key 1_1
|
||||
#define AES_O_IV_IN_0 0x00000040 // AES Initialization Vector Input
|
||||
// 0
|
||||
#define AES_O_IV_IN_1 0x00000044 // AES Initialization Vector Input
|
||||
// 1
|
||||
#define AES_O_IV_IN_2 0x00000048 // AES Initialization Vector Input
|
||||
// 2
|
||||
#define AES_O_IV_IN_3 0x0000004C // AES Initialization Vector Input
|
||||
// 3
|
||||
#define AES_O_CTRL 0x00000050 // AES Control
|
||||
#define AES_O_C_LENGTH_0 0x00000054 // AES Crypto Data Length 0
|
||||
#define AES_O_C_LENGTH_1 0x00000058 // AES Crypto Data Length 1
|
||||
#define AES_O_AUTH_LENGTH 0x0000005C // AES Authentication Data Length
|
||||
#define AES_O_DATA_IN_0 0x00000060 // AES Data RW Plaintext/Ciphertext
|
||||
// 0
|
||||
#define AES_O_DATA_IN_1 0x00000064 // AES Data RW Plaintext/Ciphertext
|
||||
// 1
|
||||
#define AES_O_DATA_IN_2 0x00000068 // AES Data RW Plaintext/Ciphertext
|
||||
// 2
|
||||
#define AES_O_DATA_IN_3 0x0000006C // AES Data RW Plaintext/Ciphertext
|
||||
// 3
|
||||
#define AES_O_TAG_OUT_0 0x00000070 // AES Hash Tag Out 0
|
||||
#define AES_O_TAG_OUT_1 0x00000074 // AES Hash Tag Out 1
|
||||
#define AES_O_TAG_OUT_2 0x00000078 // AES Hash Tag Out 2
|
||||
#define AES_O_TAG_OUT_3 0x0000007C // AES Hash Tag Out 3
|
||||
#define AES_O_REVISION 0x00000080 // AES IP Revision Identifier
|
||||
#define AES_O_SYSCONFIG 0x00000084 // AES System Configuration
|
||||
#define AES_O_SYSSTATUS 0x00000088 // AES System Status
|
||||
#define AES_O_IRQSTATUS 0x0000008C // AES Interrupt Status
|
||||
#define AES_O_IRQENABLE 0x00000090 // AES Interrupt Enable
|
||||
#define AES_O_DIRTYBITS 0x00000094 // AES Dirty Bits
|
||||
#define AES_O_DMAIM 0xFFFFA020 // AES DMA Interrupt Mask
|
||||
#define AES_O_DMARIS 0xFFFFA024 // AES DMA Raw Interrupt Status
|
||||
#define AES_O_DMAMIS 0xFFFFA028 // AES DMA Masked Interrupt Status
|
||||
#define AES_O_DMAIC 0xFFFFA02C // AES DMA Interrupt Clear
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// 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 // Initialization Vector Input
|
||||
#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 // Initialization Vector Input
|
||||
#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 // Initialization Vector Input
|
||||
#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 // Initialization Vector Input
|
||||
#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_CTXTRDY 0x80000000 // Context Data Registers Ready
|
||||
#define AES_CTRL_SVCTXTRDY 0x40000000 // AES TAG/IV Block(s) Ready
|
||||
#define AES_CTRL_SAVE_CONTEXT 0x20000000 // TAG or Result IV Save
|
||||
#define AES_CTRL_CCM_M_M 0x01C00000 // Counter with CBC-MAC (CCM)
|
||||
#define AES_CTRL_CCM_L_M 0x00380000 // L Value
|
||||
#define AES_CTRL_CCM_L_2 0x00080000 // width = 2
|
||||
#define AES_CTRL_CCM_L_4 0x00180000 // width = 4
|
||||
#define AES_CTRL_CCM_L_8 0x00380000 // width = 8
|
||||
#define AES_CTRL_CCM 0x00040000 // AES-CCM Mode Enable
|
||||
#define AES_CTRL_GCM_M 0x00030000 // AES-GCM Mode Enable
|
||||
#define AES_CTRL_GCM_NOP 0x00000000 // No operation
|
||||
#define AES_CTRL_GCM_HLY0ZERO 0x00010000 // GHASH with H loaded and
|
||||
// Y0-encrypted forced to zero
|
||||
#define AES_CTRL_GCM_HLY0CALC 0x00020000 // GHASH with H loaded and
|
||||
// Y0-encrypted calculated
|
||||
// internally
|
||||
#define AES_CTRL_GCM_HY0CALC 0x00030000 // Autonomous GHASH (both H and
|
||||
// Y0-encrypted calculated
|
||||
// internally)
|
||||
#define AES_CTRL_CBCMAC 0x00008000 // AES-CBC MAC Enable
|
||||
#define AES_CTRL_F9 0x00004000 // AES f9 Mode Enable
|
||||
#define AES_CTRL_F8 0x00002000 // AES f8 Mode Enable
|
||||
#define AES_CTRL_XTS_M 0x00001800 // AES-XTS Operation Enabled
|
||||
#define AES_CTRL_XTS_NOP 0x00000000 // No operation
|
||||
#define AES_CTRL_XTS_TWEAKJL 0x00000800 // Previous/intermediate tweak
|
||||
// value and j loaded (value is
|
||||
// loaded via IV, j is loaded via
|
||||
// the AAD length register)
|
||||
#define AES_CTRL_XTS_K2IJL 0x00001000 // Key2, n and j are loaded (n is
|
||||
// loaded via IV, j is loaded via
|
||||
// the AAD length register)
|
||||
#define AES_CTRL_XTS_K2ILJ0 0x00001800 // Key2 and n are loaded; j=0 (n is
|
||||
// loaded via IV)
|
||||
#define AES_CTRL_CFB 0x00000400 // Full block AES cipher feedback
|
||||
// mode (CFB128) Enable
|
||||
#define AES_CTRL_ICM 0x00000200 // AES Integer Counter Mode (ICM)
|
||||
// Enable
|
||||
#define AES_CTRL_CTR_WIDTH_M 0x00000180 // AES-CTR Mode Counter Width
|
||||
#define AES_CTRL_CTR_WIDTH_32 0x00000000 // Counter is 32 bits
|
||||
#define AES_CTRL_CTR_WIDTH_64 0x00000080 // Counter is 64 bits
|
||||
#define AES_CTRL_CTR_WIDTH_96 0x00000100 // Counter is 96 bits
|
||||
#define AES_CTRL_CTR_WIDTH_128 0x00000180 // Counter is 128 bits
|
||||
#define AES_CTRL_CTR 0x00000040 // Counter Mode
|
||||
#define AES_CTRL_MODE 0x00000020 // ECB/CBC Mode
|
||||
#define AES_CTRL_KEY_SIZE_M 0x00000018 // Key Size
|
||||
#define AES_CTRL_KEY_SIZE_128 0x00000008 // Key is 128 bits
|
||||
#define AES_CTRL_KEY_SIZE_192 0x00000010 // Key is 192 bits
|
||||
#define AES_CTRL_KEY_SIZE_256 0x00000018 // Key is 256 bits
|
||||
#define AES_CTRL_DIRECTION 0x00000004 // Encryption/Decryption Selection
|
||||
#define AES_CTRL_INPUT_READY 0x00000002 // Input Ready Status
|
||||
#define AES_CTRL_OUTPUT_READY 0x00000001 // Output Ready Status
|
||||
#define AES_CTRL_CCM_M_S 22
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the AES_O_C_LENGTH_0
|
||||
// register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define AES_C_LENGTH_0_LENGTH_M 0xFFFFFFFF // Data Length
|
||||
#define AES_C_LENGTH_0_LENGTH_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the AES_O_C_LENGTH_1
|
||||
// register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define AES_C_LENGTH_1_LENGTH_M 0xFFFFFFFF // Data Length
|
||||
#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 // Authentication Data Length
|
||||
#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 // Secure Data RW
|
||||
// Plaintext/Ciphertext
|
||||
#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 // Secure Data RW
|
||||
// Plaintext/Ciphertext
|
||||
#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 // Secure Data RW
|
||||
// Plaintext/Ciphertext
|
||||
#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 // Secure Data RW
|
||||
// Plaintext/Ciphertext
|
||||
#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
|
||||
#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
|
||||
#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
|
||||
#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
|
||||
#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_M 0xFFFFFFFF // Revision number
|
||||
#define AES_REVISION_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the AES_O_SYSCONFIG
|
||||
// register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define AES_SYSCONFIG_K3 0x00001000 // K3 Select
|
||||
#define AES_SYSCONFIG_KEYENC 0x00000800 // Key Encoding
|
||||
#define AES_SYSCONFIG_MAP_CONTEXT_OUT_ON_DATA_OUT \
|
||||
0x00000200 // Map Context Out on Data Out
|
||||
// Enable
|
||||
#define AES_SYSCONFIG_DMA_REQ_CONTEXT_OUT_EN \
|
||||
0x00000100 // DMA Request Context Out Enable
|
||||
#define AES_SYSCONFIG_DMA_REQ_CONTEXT_IN_EN \
|
||||
0x00000080 // DMA Request Context In Enable
|
||||
#define AES_SYSCONFIG_DMA_REQ_DATA_OUT_EN \
|
||||
0x00000040 // DMA Request Data Out Enable
|
||||
#define AES_SYSCONFIG_DMA_REQ_DATA_IN_EN \
|
||||
0x00000020 // DMA Request Data In Enable
|
||||
#define AES_SYSCONFIG_SOFTRESET 0x00000002 // Soft reset
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the AES_O_SYSSTATUS
|
||||
// register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define AES_SYSSTATUS_RESETDONE 0x00000001 // Reset Done
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the AES_O_IRQSTATUS
|
||||
// register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define AES_IRQSTATUS_CONTEXT_OUT \
|
||||
0x00000008 // Context Output Interrupt Status
|
||||
#define AES_IRQSTATUS_DATA_OUT 0x00000004 // Data Out Interrupt Status
|
||||
#define AES_IRQSTATUS_DATA_IN 0x00000002 // Data In Interrupt Status
|
||||
#define AES_IRQSTATUS_CONTEXT_IN \
|
||||
0x00000001 // Context In Interrupt Status
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the AES_O_IRQENABLE
|
||||
// register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define AES_IRQENABLE_CONTEXT_OUT \
|
||||
0x00000008 // Context Out Interrupt Enable
|
||||
#define AES_IRQENABLE_DATA_OUT 0x00000004 // Data Out Interrupt Enable
|
||||
#define AES_IRQENABLE_DATA_IN 0x00000002 // Data In Interrupt Enable
|
||||
#define AES_IRQENABLE_CONTEXT_IN \
|
||||
0x00000001 // Context In Interrupt Enable
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the AES_O_DIRTYBITS
|
||||
// register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define AES_DIRTYBITS_S_DIRTY 0x00000002 // AES Dirty Bit
|
||||
#define AES_DIRTYBITS_S_ACCESS 0x00000001 // AES Access Bit
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the AES_O_DMAIM register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define AES_DMAIM_DOUT 0x00000008 // Data Out DMA Done Interrupt Mask
|
||||
#define AES_DMAIM_DIN 0x00000004 // Data In DMA Done Interrupt Mask
|
||||
#define AES_DMAIM_COUT 0x00000002 // Context Out DMA Done Interrupt
|
||||
// Mask
|
||||
#define AES_DMAIM_CIN 0x00000001 // Context In DMA Done Interrupt
|
||||
// Mask
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the AES_O_DMARIS register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define AES_DMARIS_DOUT 0x00000008 // Data Out DMA Done Raw Interrupt
|
||||
// Status
|
||||
#define AES_DMARIS_DIN 0x00000004 // Data In DMA Done Raw Interrupt
|
||||
// Status
|
||||
#define AES_DMARIS_COUT 0x00000002 // Context Out DMA Done Raw
|
||||
// Interrupt Status
|
||||
#define AES_DMARIS_CIN 0x00000001 // Context In DMA Done Raw
|
||||
// Interrupt Status
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the AES_O_DMAMIS register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define AES_DMAMIS_DOUT 0x00000008 // Data Out DMA Done Masked
|
||||
// Interrupt Status
|
||||
#define AES_DMAMIS_DIN 0x00000004 // Data In DMA Done Masked
|
||||
// Interrupt Status
|
||||
#define AES_DMAMIS_COUT 0x00000002 // Context Out DMA Done Masked
|
||||
// Interrupt Status
|
||||
#define AES_DMAMIS_CIN 0x00000001 // Context In DMA Done Raw
|
||||
// Interrupt Status
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the AES_O_DMAIC register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define AES_DMAIC_DOUT 0x00000008 // Data Out DMA Done Interrupt
|
||||
// Clear
|
||||
#define AES_DMAIC_DIN 0x00000004 // Data In DMA Done Interrupt Clear
|
||||
#define AES_DMAIC_COUT 0x00000002 // Context Out DMA Done Masked
|
||||
// Interrupt Status
|
||||
#define AES_DMAIC_CIN 0x00000001 // Context In DMA Done Raw
|
||||
// Interrupt Status
|
||||
|
||||
#endif // __HW_AES_H__
|
|
@ -0,0 +1,462 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// hw_can.h - Defines and macros used when accessing the CAN controllers.
|
||||
//
|
||||
// Copyright (c) 2006-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Firmware Development Package.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __HW_CAN_H__
|
||||
#define __HW_CAN_H__
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the CAN register offsets.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CAN_O_CTL 0x00000000 // CAN Control
|
||||
#define CAN_O_STS 0x00000004 // CAN Status
|
||||
#define CAN_O_ERR 0x00000008 // CAN Error Counter
|
||||
#define CAN_O_BIT 0x0000000C // CAN Bit Timing
|
||||
#define CAN_O_INT 0x00000010 // CAN Interrupt
|
||||
#define CAN_O_TST 0x00000014 // CAN Test
|
||||
#define CAN_O_BRPE 0x00000018 // CAN Baud Rate Prescaler
|
||||
// Extension
|
||||
#define CAN_O_IF1CRQ 0x00000020 // CAN IF1 Command Request
|
||||
#define CAN_O_IF1CMSK 0x00000024 // CAN IF1 Command Mask
|
||||
#define CAN_O_IF1MSK1 0x00000028 // CAN IF1 Mask 1
|
||||
#define CAN_O_IF1MSK2 0x0000002C // CAN IF1 Mask 2
|
||||
#define CAN_O_IF1ARB1 0x00000030 // CAN IF1 Arbitration 1
|
||||
#define CAN_O_IF1ARB2 0x00000034 // CAN IF1 Arbitration 2
|
||||
#define CAN_O_IF1MCTL 0x00000038 // CAN IF1 Message Control
|
||||
#define CAN_O_IF1DA1 0x0000003C // CAN IF1 Data A1
|
||||
#define CAN_O_IF1DA2 0x00000040 // CAN IF1 Data A2
|
||||
#define CAN_O_IF1DB1 0x00000044 // CAN IF1 Data B1
|
||||
#define CAN_O_IF1DB2 0x00000048 // CAN IF1 Data B2
|
||||
#define CAN_O_IF2CRQ 0x00000080 // CAN IF2 Command Request
|
||||
#define CAN_O_IF2CMSK 0x00000084 // CAN IF2 Command Mask
|
||||
#define CAN_O_IF2MSK1 0x00000088 // CAN IF2 Mask 1
|
||||
#define CAN_O_IF2MSK2 0x0000008C // CAN IF2 Mask 2
|
||||
#define CAN_O_IF2ARB1 0x00000090 // CAN IF2 Arbitration 1
|
||||
#define CAN_O_IF2ARB2 0x00000094 // CAN IF2 Arbitration 2
|
||||
#define CAN_O_IF2MCTL 0x00000098 // CAN IF2 Message Control
|
||||
#define CAN_O_IF2DA1 0x0000009C // CAN IF2 Data A1
|
||||
#define CAN_O_IF2DA2 0x000000A0 // CAN IF2 Data A2
|
||||
#define CAN_O_IF2DB1 0x000000A4 // CAN IF2 Data B1
|
||||
#define CAN_O_IF2DB2 0x000000A8 // CAN IF2 Data B2
|
||||
#define CAN_O_TXRQ1 0x00000100 // CAN Transmission Request 1
|
||||
#define CAN_O_TXRQ2 0x00000104 // CAN Transmission Request 2
|
||||
#define CAN_O_NWDA1 0x00000120 // CAN New Data 1
|
||||
#define CAN_O_NWDA2 0x00000124 // CAN New Data 2
|
||||
#define CAN_O_MSG1INT 0x00000140 // CAN Message 1 Interrupt Pending
|
||||
#define CAN_O_MSG2INT 0x00000144 // CAN Message 2 Interrupt Pending
|
||||
#define CAN_O_MSG1VAL 0x00000160 // CAN Message 1 Valid
|
||||
#define CAN_O_MSG2VAL 0x00000164 // CAN Message 2 Valid
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the CAN_O_CTL register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CAN_CTL_TEST 0x00000080 // Test Mode Enable
|
||||
#define CAN_CTL_CCE 0x00000040 // Configuration Change Enable
|
||||
#define CAN_CTL_DAR 0x00000020 // Disable Automatic-Retransmission
|
||||
#define CAN_CTL_EIE 0x00000008 // Error Interrupt Enable
|
||||
#define CAN_CTL_SIE 0x00000004 // Status Interrupt Enable
|
||||
#define CAN_CTL_IE 0x00000002 // CAN Interrupt Enable
|
||||
#define CAN_CTL_INIT 0x00000001 // Initialization
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the CAN_O_STS register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CAN_STS_BOFF 0x00000080 // Bus-Off Status
|
||||
#define CAN_STS_EWARN 0x00000040 // Warning Status
|
||||
#define CAN_STS_EPASS 0x00000020 // Error Passive
|
||||
#define CAN_STS_RXOK 0x00000010 // Received a Message Successfully
|
||||
#define CAN_STS_TXOK 0x00000008 // Transmitted a Message
|
||||
// Successfully
|
||||
#define CAN_STS_LEC_M 0x00000007 // Last Error Code
|
||||
#define CAN_STS_LEC_NONE 0x00000000 // No Error
|
||||
#define CAN_STS_LEC_STUFF 0x00000001 // Stuff Error
|
||||
#define CAN_STS_LEC_FORM 0x00000002 // Format Error
|
||||
#define CAN_STS_LEC_ACK 0x00000003 // ACK Error
|
||||
#define CAN_STS_LEC_BIT1 0x00000004 // Bit 1 Error
|
||||
#define CAN_STS_LEC_BIT0 0x00000005 // Bit 0 Error
|
||||
#define CAN_STS_LEC_CRC 0x00000006 // CRC Error
|
||||
#define CAN_STS_LEC_NOEVENT 0x00000007 // No Event
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the CAN_O_ERR register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CAN_ERR_RP 0x00008000 // Received Error Passive
|
||||
#define CAN_ERR_REC_M 0x00007F00 // Receive Error Counter
|
||||
#define CAN_ERR_TEC_M 0x000000FF // Transmit Error Counter
|
||||
#define CAN_ERR_REC_S 8
|
||||
#define CAN_ERR_TEC_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the CAN_O_BIT register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CAN_BIT_TSEG2_M 0x00007000 // Time Segment after Sample Point
|
||||
#define CAN_BIT_TSEG1_M 0x00000F00 // Time Segment Before Sample Point
|
||||
#define CAN_BIT_SJW_M 0x000000C0 // (Re)Synchronization Jump Width
|
||||
#define CAN_BIT_BRP_M 0x0000003F // Baud Rate Prescaler
|
||||
#define CAN_BIT_TSEG2_S 12
|
||||
#define CAN_BIT_TSEG1_S 8
|
||||
#define CAN_BIT_SJW_S 6
|
||||
#define CAN_BIT_BRP_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the CAN_O_INT register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CAN_INT_INTID_M 0x0000FFFF // Interrupt Identifier
|
||||
#define CAN_INT_INTID_NONE 0x00000000 // No interrupt pending
|
||||
#define CAN_INT_INTID_STATUS 0x00008000 // Status Interrupt
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the CAN_O_TST register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CAN_TST_RX 0x00000080 // Receive Observation
|
||||
#define CAN_TST_TX_M 0x00000060 // Transmit Control
|
||||
#define CAN_TST_TX_CANCTL 0x00000000 // CAN Module Control
|
||||
#define CAN_TST_TX_SAMPLE 0x00000020 // Sample Point
|
||||
#define CAN_TST_TX_DOMINANT 0x00000040 // Driven Low
|
||||
#define CAN_TST_TX_RECESSIVE 0x00000060 // Driven High
|
||||
#define CAN_TST_LBACK 0x00000010 // Loopback Mode
|
||||
#define CAN_TST_SILENT 0x00000008 // Silent Mode
|
||||
#define CAN_TST_BASIC 0x00000004 // Basic Mode
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the CAN_O_BRPE register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CAN_BRPE_BRPE_M 0x0000000F // Baud Rate Prescaler Extension
|
||||
#define CAN_BRPE_BRPE_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the CAN_O_IF1CRQ register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CAN_IF1CRQ_BUSY 0x00008000 // Busy Flag
|
||||
#define CAN_IF1CRQ_MNUM_M 0x0000003F // Message Number
|
||||
#define CAN_IF1CRQ_MNUM_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the CAN_O_IF1CMSK register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CAN_IF1CMSK_WRNRD 0x00000080 // Write, Not Read
|
||||
#define CAN_IF1CMSK_MASK 0x00000040 // Access Mask Bits
|
||||
#define CAN_IF1CMSK_ARB 0x00000020 // Access Arbitration Bits
|
||||
#define CAN_IF1CMSK_CONTROL 0x00000010 // Access Control Bits
|
||||
#define CAN_IF1CMSK_CLRINTPND 0x00000008 // Clear Interrupt Pending Bit
|
||||
#define CAN_IF1CMSK_NEWDAT 0x00000004 // Access New Data
|
||||
#define CAN_IF1CMSK_TXRQST 0x00000004 // Access Transmission Request
|
||||
#define CAN_IF1CMSK_DATAA 0x00000002 // Access Data Byte 0 to 3
|
||||
#define CAN_IF1CMSK_DATAB 0x00000001 // Access Data Byte 4 to 7
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the CAN_O_IF1MSK1 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CAN_IF1MSK1_IDMSK_M 0x0000FFFF // Identifier Mask
|
||||
#define CAN_IF1MSK1_IDMSK_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the CAN_O_IF1MSK2 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CAN_IF1MSK2_MXTD 0x00008000 // Mask Extended Identifier
|
||||
#define CAN_IF1MSK2_MDIR 0x00004000 // Mask Message Direction
|
||||
#define CAN_IF1MSK2_IDMSK_M 0x00001FFF // Identifier Mask
|
||||
#define CAN_IF1MSK2_IDMSK_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the CAN_O_IF1ARB1 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CAN_IF1ARB1_ID_M 0x0000FFFF // Message Identifier
|
||||
#define CAN_IF1ARB1_ID_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the CAN_O_IF1ARB2 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CAN_IF1ARB2_MSGVAL 0x00008000 // Message Valid
|
||||
#define CAN_IF1ARB2_XTD 0x00004000 // Extended Identifier
|
||||
#define CAN_IF1ARB2_DIR 0x00002000 // Message Direction
|
||||
#define CAN_IF1ARB2_ID_M 0x00001FFF // Message Identifier
|
||||
#define CAN_IF1ARB2_ID_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the CAN_O_IF1MCTL register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CAN_IF1MCTL_NEWDAT 0x00008000 // New Data
|
||||
#define CAN_IF1MCTL_MSGLST 0x00004000 // Message Lost
|
||||
#define CAN_IF1MCTL_INTPND 0x00002000 // Interrupt Pending
|
||||
#define CAN_IF1MCTL_UMASK 0x00001000 // Use Acceptance Mask
|
||||
#define CAN_IF1MCTL_TXIE 0x00000800 // Transmit Interrupt Enable
|
||||
#define CAN_IF1MCTL_RXIE 0x00000400 // Receive Interrupt Enable
|
||||
#define CAN_IF1MCTL_RMTEN 0x00000200 // Remote Enable
|
||||
#define CAN_IF1MCTL_TXRQST 0x00000100 // Transmit Request
|
||||
#define CAN_IF1MCTL_EOB 0x00000080 // End of Buffer
|
||||
#define CAN_IF1MCTL_DLC_M 0x0000000F // Data Length Code
|
||||
#define CAN_IF1MCTL_DLC_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the CAN_O_IF1DA1 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CAN_IF1DA1_DATA_M 0x0000FFFF // Data
|
||||
#define CAN_IF1DA1_DATA_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the CAN_O_IF1DA2 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CAN_IF1DA2_DATA_M 0x0000FFFF // Data
|
||||
#define CAN_IF1DA2_DATA_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the CAN_O_IF1DB1 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CAN_IF1DB1_DATA_M 0x0000FFFF // Data
|
||||
#define CAN_IF1DB1_DATA_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the CAN_O_IF1DB2 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CAN_IF1DB2_DATA_M 0x0000FFFF // Data
|
||||
#define CAN_IF1DB2_DATA_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the CAN_O_IF2CRQ register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CAN_IF2CRQ_BUSY 0x00008000 // Busy Flag
|
||||
#define CAN_IF2CRQ_MNUM_M 0x0000003F // Message Number
|
||||
#define CAN_IF2CRQ_MNUM_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the CAN_O_IF2CMSK register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CAN_IF2CMSK_WRNRD 0x00000080 // Write, Not Read
|
||||
#define CAN_IF2CMSK_MASK 0x00000040 // Access Mask Bits
|
||||
#define CAN_IF2CMSK_ARB 0x00000020 // Access Arbitration Bits
|
||||
#define CAN_IF2CMSK_CONTROL 0x00000010 // Access Control Bits
|
||||
#define CAN_IF2CMSK_CLRINTPND 0x00000008 // Clear Interrupt Pending Bit
|
||||
#define CAN_IF2CMSK_NEWDAT 0x00000004 // Access New Data
|
||||
#define CAN_IF2CMSK_TXRQST 0x00000004 // Access Transmission Request
|
||||
#define CAN_IF2CMSK_DATAA 0x00000002 // Access Data Byte 0 to 3
|
||||
#define CAN_IF2CMSK_DATAB 0x00000001 // Access Data Byte 4 to 7
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the CAN_O_IF2MSK1 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CAN_IF2MSK1_IDMSK_M 0x0000FFFF // Identifier Mask
|
||||
#define CAN_IF2MSK1_IDMSK_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the CAN_O_IF2MSK2 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CAN_IF2MSK2_MXTD 0x00008000 // Mask Extended Identifier
|
||||
#define CAN_IF2MSK2_MDIR 0x00004000 // Mask Message Direction
|
||||
#define CAN_IF2MSK2_IDMSK_M 0x00001FFF // Identifier Mask
|
||||
#define CAN_IF2MSK2_IDMSK_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the CAN_O_IF2ARB1 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CAN_IF2ARB1_ID_M 0x0000FFFF // Message Identifier
|
||||
#define CAN_IF2ARB1_ID_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the CAN_O_IF2ARB2 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CAN_IF2ARB2_MSGVAL 0x00008000 // Message Valid
|
||||
#define CAN_IF2ARB2_XTD 0x00004000 // Extended Identifier
|
||||
#define CAN_IF2ARB2_DIR 0x00002000 // Message Direction
|
||||
#define CAN_IF2ARB2_ID_M 0x00001FFF // Message Identifier
|
||||
#define CAN_IF2ARB2_ID_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the CAN_O_IF2MCTL register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CAN_IF2MCTL_NEWDAT 0x00008000 // New Data
|
||||
#define CAN_IF2MCTL_MSGLST 0x00004000 // Message Lost
|
||||
#define CAN_IF2MCTL_INTPND 0x00002000 // Interrupt Pending
|
||||
#define CAN_IF2MCTL_UMASK 0x00001000 // Use Acceptance Mask
|
||||
#define CAN_IF2MCTL_TXIE 0x00000800 // Transmit Interrupt Enable
|
||||
#define CAN_IF2MCTL_RXIE 0x00000400 // Receive Interrupt Enable
|
||||
#define CAN_IF2MCTL_RMTEN 0x00000200 // Remote Enable
|
||||
#define CAN_IF2MCTL_TXRQST 0x00000100 // Transmit Request
|
||||
#define CAN_IF2MCTL_EOB 0x00000080 // End of Buffer
|
||||
#define CAN_IF2MCTL_DLC_M 0x0000000F // Data Length Code
|
||||
#define CAN_IF2MCTL_DLC_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the CAN_O_IF2DA1 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CAN_IF2DA1_DATA_M 0x0000FFFF // Data
|
||||
#define CAN_IF2DA1_DATA_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the CAN_O_IF2DA2 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CAN_IF2DA2_DATA_M 0x0000FFFF // Data
|
||||
#define CAN_IF2DA2_DATA_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the CAN_O_IF2DB1 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CAN_IF2DB1_DATA_M 0x0000FFFF // Data
|
||||
#define CAN_IF2DB1_DATA_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the CAN_O_IF2DB2 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CAN_IF2DB2_DATA_M 0x0000FFFF // Data
|
||||
#define CAN_IF2DB2_DATA_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the CAN_O_TXRQ1 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CAN_TXRQ1_TXRQST_M 0x0000FFFF // Transmission Request Bits
|
||||
#define CAN_TXRQ1_TXRQST_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the CAN_O_TXRQ2 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CAN_TXRQ2_TXRQST_M 0x0000FFFF // Transmission Request Bits
|
||||
#define CAN_TXRQ2_TXRQST_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the CAN_O_NWDA1 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CAN_NWDA1_NEWDAT_M 0x0000FFFF // New Data Bits
|
||||
#define CAN_NWDA1_NEWDAT_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the CAN_O_NWDA2 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CAN_NWDA2_NEWDAT_M 0x0000FFFF // New Data Bits
|
||||
#define CAN_NWDA2_NEWDAT_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the CAN_O_MSG1INT register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CAN_MSG1INT_INTPND_M 0x0000FFFF // Interrupt Pending Bits
|
||||
#define CAN_MSG1INT_INTPND_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the CAN_O_MSG2INT register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CAN_MSG2INT_INTPND_M 0x0000FFFF // Interrupt Pending Bits
|
||||
#define CAN_MSG2INT_INTPND_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the CAN_O_MSG1VAL register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CAN_MSG1VAL_MSGVAL_M 0x0000FFFF // Message Valid Bits
|
||||
#define CAN_MSG1VAL_MSGVAL_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the CAN_O_MSG2VAL register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CAN_MSG2VAL_MSGVAL_M 0x0000FFFF // Message Valid Bits
|
||||
#define CAN_MSG2VAL_MSGVAL_S 0
|
||||
|
||||
#endif // __HW_CAN_H__
|
|
@ -0,0 +1,115 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// hw_ccm.h - Macros used when accessing the CCM hardware.
|
||||
//
|
||||
// Copyright (c) 2012-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Firmware Development Package.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __HW_CCM_H__
|
||||
#define __HW_CCM_H__
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the EC register offsets.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CCM_O_CRCCTRL 0x00000400 // CRC Control
|
||||
#define CCM_O_CRCSEED 0x00000410 // CRC SEED/Context
|
||||
#define CCM_O_CRCDIN 0x00000414 // CRC Data Input
|
||||
#define CCM_O_CRCRSLTPP 0x00000418 // CRC Post Processing Result
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the CCM_O_CRCCTRL register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CCM_CRCCTRL_INIT_M 0x00006000 // CRC Initialization
|
||||
#define CCM_CRCCTRL_INIT_SEED 0x00000000 // Use the CRCSEED register context
|
||||
// as the starting value
|
||||
#define CCM_CRCCTRL_INIT_0 0x00004000 // Initialize to all '0s'
|
||||
#define CCM_CRCCTRL_INIT_1 0x00006000 // Initialize to all '1s'
|
||||
#define CCM_CRCCTRL_SIZE 0x00001000 // Input Data Size
|
||||
#define CCM_CRCCTRL_RESINV 0x00000200 // Result Inverse Enable
|
||||
#define CCM_CRCCTRL_OBR 0x00000100 // Output Reverse Enable
|
||||
#define CCM_CRCCTRL_BR 0x00000080 // Bit reverse enable
|
||||
#define CCM_CRCCTRL_ENDIAN_M 0x00000030 // Endian Control
|
||||
#define CCM_CRCCTRL_ENDIAN_SBHW 0x00000000 // Configuration unchanged. (B3,
|
||||
// B2, B1, B0)
|
||||
#define CCM_CRCCTRL_ENDIAN_SHW 0x00000010 // Bytes are swapped in half-words
|
||||
// but half-words are not swapped
|
||||
// (B2, B3, B0, B1)
|
||||
#define CCM_CRCCTRL_ENDIAN_SHWNB \
|
||||
0x00000020 // Half-words are swapped but bytes
|
||||
// are not swapped in half-word.
|
||||
// (B1, B0, B3, B2)
|
||||
#define CCM_CRCCTRL_ENDIAN_SBSW 0x00000030 // Bytes are swapped in half-words
|
||||
// and half-words are swapped. (B0,
|
||||
// B1, B2, B3)
|
||||
#define CCM_CRCCTRL_TYPE_M 0x0000000F // Operation Type
|
||||
#define CCM_CRCCTRL_TYPE_P8055 0x00000000 // Polynomial 0x8005
|
||||
#define CCM_CRCCTRL_TYPE_P1021 0x00000001 // Polynomial 0x1021
|
||||
#define CCM_CRCCTRL_TYPE_P4C11DB7 \
|
||||
0x00000002 // Polynomial 0x4C11DB7
|
||||
#define CCM_CRCCTRL_TYPE_P1EDC6F41 \
|
||||
0x00000003 // Polynomial 0x1EDC6F41
|
||||
#define CCM_CRCCTRL_TYPE_TCPCHKSUM \
|
||||
0x00000008 // TCP checksum
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the CCM_O_CRCSEED register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CCM_CRCSEED_SEED_M 0xFFFFFFFF // SEED/Context Value
|
||||
#define CCM_CRCSEED_SEED_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the CCM_O_CRCDIN register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CCM_CRCDIN_DATAIN_M 0xFFFFFFFF // Data Input
|
||||
#define CCM_CRCDIN_DATAIN_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the CCM_O_CRCRSLTPP
|
||||
// register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define CCM_CRCRSLTPP_RSLTPP_M 0xFFFFFFFF // Post Processing Result
|
||||
#define CCM_CRCRSLTPP_RSLTPP_S 0
|
||||
|
||||
#endif // __HW_CCM_H__
|
|
@ -0,0 +1,211 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// hw_comp.h - Macros used when accessing the comparator hardware.
|
||||
//
|
||||
// Copyright (c) 2005-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Firmware Development Package.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __HW_COMP_H__
|
||||
#define __HW_COMP_H__
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the Comparator register offsets.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define COMP_O_ACMIS 0x00000000 // Analog Comparator Masked
|
||||
// Interrupt Status
|
||||
#define COMP_O_ACRIS 0x00000004 // Analog Comparator Raw Interrupt
|
||||
// Status
|
||||
#define COMP_O_ACINTEN 0x00000008 // Analog Comparator Interrupt
|
||||
// Enable
|
||||
#define COMP_O_ACREFCTL 0x00000010 // Analog Comparator Reference
|
||||
// Voltage Control
|
||||
#define COMP_O_ACSTAT0 0x00000020 // Analog Comparator Status 0
|
||||
#define COMP_O_ACCTL0 0x00000024 // Analog Comparator Control 0
|
||||
#define COMP_O_ACSTAT1 0x00000040 // Analog Comparator Status 1
|
||||
#define COMP_O_ACCTL1 0x00000044 // Analog Comparator Control 1
|
||||
#define COMP_O_ACSTAT2 0x00000060 // Analog Comparator Status 2
|
||||
#define COMP_O_ACCTL2 0x00000064 // Analog Comparator Control 2
|
||||
#define COMP_O_PP 0x00000FC0 // Analog Comparator Peripheral
|
||||
// Properties
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the COMP_O_ACMIS register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define COMP_ACMIS_IN2 0x00000004 // Comparator 2 Masked Interrupt
|
||||
// Status
|
||||
#define COMP_ACMIS_IN1 0x00000002 // Comparator 1 Masked Interrupt
|
||||
// Status
|
||||
#define COMP_ACMIS_IN0 0x00000001 // Comparator 0 Masked Interrupt
|
||||
// Status
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the COMP_O_ACRIS register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define COMP_ACRIS_IN2 0x00000004 // Comparator 2 Interrupt Status
|
||||
#define COMP_ACRIS_IN1 0x00000002 // Comparator 1 Interrupt Status
|
||||
#define COMP_ACRIS_IN0 0x00000001 // Comparator 0 Interrupt Status
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the COMP_O_ACINTEN register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define COMP_ACINTEN_IN2 0x00000004 // Comparator 2 Interrupt Enable
|
||||
#define COMP_ACINTEN_IN1 0x00000002 // Comparator 1 Interrupt Enable
|
||||
#define COMP_ACINTEN_IN0 0x00000001 // Comparator 0 Interrupt Enable
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the COMP_O_ACREFCTL
|
||||
// register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define COMP_ACREFCTL_EN 0x00000200 // Resistor Ladder Enable
|
||||
#define COMP_ACREFCTL_RNG 0x00000100 // Resistor Ladder Range
|
||||
#define COMP_ACREFCTL_VREF_M 0x0000000F // Resistor Ladder Voltage Ref
|
||||
#define COMP_ACREFCTL_VREF_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the COMP_O_ACSTAT0 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define COMP_ACSTAT0_OVAL 0x00000002 // Comparator Output Value
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the COMP_O_ACCTL0 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define COMP_ACCTL0_TOEN 0x00000800 // Trigger Output Enable
|
||||
#define COMP_ACCTL0_ASRCP_M 0x00000600 // Analog Source Positive
|
||||
#define COMP_ACCTL0_ASRCP_PIN 0x00000000 // Pin value of Cn+
|
||||
#define COMP_ACCTL0_ASRCP_PIN0 0x00000200 // Pin value of C0+
|
||||
#define COMP_ACCTL0_ASRCP_REF 0x00000400 // Internal voltage reference
|
||||
#define COMP_ACCTL0_TSLVAL 0x00000080 // Trigger Sense Level Value
|
||||
#define COMP_ACCTL0_TSEN_M 0x00000060 // Trigger Sense
|
||||
#define COMP_ACCTL0_TSEN_LEVEL 0x00000000 // Level sense, see TSLVAL
|
||||
#define COMP_ACCTL0_TSEN_FALL 0x00000020 // Falling edge
|
||||
#define COMP_ACCTL0_TSEN_RISE 0x00000040 // Rising edge
|
||||
#define COMP_ACCTL0_TSEN_BOTH 0x00000060 // Either edge
|
||||
#define COMP_ACCTL0_ISLVAL 0x00000010 // Interrupt Sense Level Value
|
||||
#define COMP_ACCTL0_ISEN_M 0x0000000C // Interrupt Sense
|
||||
#define COMP_ACCTL0_ISEN_LEVEL 0x00000000 // Level sense, see ISLVAL
|
||||
#define COMP_ACCTL0_ISEN_FALL 0x00000004 // Falling edge
|
||||
#define COMP_ACCTL0_ISEN_RISE 0x00000008 // Rising edge
|
||||
#define COMP_ACCTL0_ISEN_BOTH 0x0000000C // Either edge
|
||||
#define COMP_ACCTL0_CINV 0x00000002 // Comparator Output Invert
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the COMP_O_ACSTAT1 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define COMP_ACSTAT1_OVAL 0x00000002 // Comparator Output Value
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the COMP_O_ACCTL1 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define COMP_ACCTL1_TOEN 0x00000800 // Trigger Output Enable
|
||||
#define COMP_ACCTL1_ASRCP_M 0x00000600 // Analog Source Positive
|
||||
#define COMP_ACCTL1_ASRCP_PIN 0x00000000 // Pin value of Cn+
|
||||
#define COMP_ACCTL1_ASRCP_PIN0 0x00000200 // Pin value of C0+
|
||||
#define COMP_ACCTL1_ASRCP_REF 0x00000400 // Internal voltage reference
|
||||
#define COMP_ACCTL1_TSLVAL 0x00000080 // Trigger Sense Level Value
|
||||
#define COMP_ACCTL1_TSEN_M 0x00000060 // Trigger Sense
|
||||
#define COMP_ACCTL1_TSEN_LEVEL 0x00000000 // Level sense, see TSLVAL
|
||||
#define COMP_ACCTL1_TSEN_FALL 0x00000020 // Falling edge
|
||||
#define COMP_ACCTL1_TSEN_RISE 0x00000040 // Rising edge
|
||||
#define COMP_ACCTL1_TSEN_BOTH 0x00000060 // Either edge
|
||||
#define COMP_ACCTL1_ISLVAL 0x00000010 // Interrupt Sense Level Value
|
||||
#define COMP_ACCTL1_ISEN_M 0x0000000C // Interrupt Sense
|
||||
#define COMP_ACCTL1_ISEN_LEVEL 0x00000000 // Level sense, see ISLVAL
|
||||
#define COMP_ACCTL1_ISEN_FALL 0x00000004 // Falling edge
|
||||
#define COMP_ACCTL1_ISEN_RISE 0x00000008 // Rising edge
|
||||
#define COMP_ACCTL1_ISEN_BOTH 0x0000000C // Either edge
|
||||
#define COMP_ACCTL1_CINV 0x00000002 // Comparator Output Invert
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the COMP_O_ACSTAT2 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define COMP_ACSTAT2_OVAL 0x00000002 // Comparator Output Value
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the COMP_O_ACCTL2 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define COMP_ACCTL2_TOEN 0x00000800 // Trigger Output Enable
|
||||
#define COMP_ACCTL2_ASRCP_M 0x00000600 // Analog Source Positive
|
||||
#define COMP_ACCTL2_ASRCP_PIN 0x00000000 // Pin value of Cn+
|
||||
#define COMP_ACCTL2_ASRCP_PIN0 0x00000200 // Pin value of C0+
|
||||
#define COMP_ACCTL2_ASRCP_REF 0x00000400 // Internal voltage reference
|
||||
#define COMP_ACCTL2_TSLVAL 0x00000080 // Trigger Sense Level Value
|
||||
#define COMP_ACCTL2_TSEN_M 0x00000060 // Trigger Sense
|
||||
#define COMP_ACCTL2_TSEN_LEVEL 0x00000000 // Level sense, see TSLVAL
|
||||
#define COMP_ACCTL2_TSEN_FALL 0x00000020 // Falling edge
|
||||
#define COMP_ACCTL2_TSEN_RISE 0x00000040 // Rising edge
|
||||
#define COMP_ACCTL2_TSEN_BOTH 0x00000060 // Either edge
|
||||
#define COMP_ACCTL2_ISLVAL 0x00000010 // Interrupt Sense Level Value
|
||||
#define COMP_ACCTL2_ISEN_M 0x0000000C // Interrupt Sense
|
||||
#define COMP_ACCTL2_ISEN_LEVEL 0x00000000 // Level sense, see ISLVAL
|
||||
#define COMP_ACCTL2_ISEN_FALL 0x00000004 // Falling edge
|
||||
#define COMP_ACCTL2_ISEN_RISE 0x00000008 // Rising edge
|
||||
#define COMP_ACCTL2_ISEN_BOTH 0x0000000C // Either edge
|
||||
#define COMP_ACCTL2_CINV 0x00000002 // Comparator Output Invert
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the COMP_O_PP register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define COMP_PP_C2O 0x00040000 // Comparator Output 2 Present
|
||||
#define COMP_PP_C1O 0x00020000 // Comparator Output 1 Present
|
||||
#define COMP_PP_C0O 0x00010000 // Comparator Output 0 Present
|
||||
#define COMP_PP_CMP2 0x00000004 // Comparator 2 Present
|
||||
#define COMP_PP_CMP1 0x00000002 // Comparator 1 Present
|
||||
#define COMP_PP_CMP0 0x00000001 // Comparator 0 Present
|
||||
|
||||
#endif // __HW_COMP_H__
|
|
@ -0,0 +1,310 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// hw_des.h - Macros used when accessing the DES hardware.
|
||||
//
|
||||
// Copyright (c) 2012-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Firmware Development Package.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __HW_DES_H__
|
||||
#define __HW_DES_H__
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the DES register offsets.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define DES_O_KEY3_L 0x00000000 // DES Key 3 LSW for 192-Bit Key
|
||||
#define DES_O_KEY3_H 0x00000004 // DES Key 3 MSW for 192-Bit Key
|
||||
#define DES_O_KEY2_L 0x00000008 // DES Key 2 LSW for 128-Bit Key
|
||||
#define DES_O_KEY2_H 0x0000000C // DES Key 2 MSW for 128-Bit Key
|
||||
#define DES_O_KEY1_L 0x00000010 // DES Key 1 LSW for 64-Bit Key
|
||||
#define DES_O_KEY1_H 0x00000014 // DES Key 1 MSW for 64-Bit Key
|
||||
#define DES_O_IV_L 0x00000018 // DES Initialization Vector
|
||||
#define DES_O_IV_H 0x0000001C // DES Initialization Vector
|
||||
#define DES_O_CTRL 0x00000020 // DES Control
|
||||
#define DES_O_LENGTH 0x00000024 // DES Cryptographic Data Length
|
||||
#define DES_O_DATA_L 0x00000028 // DES LSW Data RW
|
||||
#define DES_O_DATA_H 0x0000002C // DES MSW Data RW
|
||||
#define DES_O_REVISION 0x00000030 // DES Revision Number
|
||||
#define DES_O_SYSCONFIG 0x00000034 // DES System Configuration
|
||||
#define DES_O_SYSSTATUS 0x00000038 // DES System Status
|
||||
#define DES_O_IRQSTATUS 0x0000003C // DES Interrupt Status
|
||||
#define DES_O_IRQENABLE 0x00000040 // DES Interrupt Enable
|
||||
#define DES_O_DIRTYBITS 0x00000044 // DES Dirty Bits
|
||||
#define DES_O_DMAIM 0xFFFF8030 // DES DMA Interrupt Mask
|
||||
#define DES_O_DMARIS 0xFFFF8034 // DES DMA Raw Interrupt Status
|
||||
#define DES_O_DMAMIS 0xFFFF8038 // DES DMA Masked Interrupt Status
|
||||
#define DES_O_DMAIC 0xFFFF803C // DES DMA Interrupt Clear
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the DES_O_KEY3_L register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define DES_KEY3_L_KEY_M 0xFFFFFFFF // Key Data
|
||||
#define DES_KEY3_L_KEY_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the DES_O_KEY3_H register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define DES_KEY3_H_KEY_M 0xFFFFFFFF // Key Data
|
||||
#define DES_KEY3_H_KEY_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the DES_O_KEY2_L register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define DES_KEY2_L_KEY_M 0xFFFFFFFF // Key Data
|
||||
#define DES_KEY2_L_KEY_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the DES_O_KEY2_H register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define DES_KEY2_H_KEY_M 0xFFFFFFFF // Key Data
|
||||
#define DES_KEY2_H_KEY_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the DES_O_KEY1_L register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define DES_KEY1_L_KEY_M 0xFFFFFFFF // Key Data
|
||||
#define DES_KEY1_L_KEY_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the DES_O_KEY1_H register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define DES_KEY1_H_KEY_M 0xFFFFFFFF // Key Data
|
||||
#define DES_KEY1_H_KEY_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the DES_O_IV_L register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define DES_IV_L_M 0xFFFFFFFF // Initialization vector for CBC,
|
||||
// CFB modes (LSW)
|
||||
#define DES_IV_L_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the DES_O_IV_H register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define DES_IV_H_M 0xFFFFFFFF // Initialization vector for CBC,
|
||||
// CFB modes (MSW)
|
||||
#define DES_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 mode0x0:
|
||||
// ECB mode0x1: CBC mode0x2: CFB
|
||||
// mode0x3: reserved
|
||||
#define DES_CTRL_TDES 0x00000008 // Select DES or triple DES
|
||||
// encryption/decryption
|
||||
#define DES_CTRL_DIRECTION 0x00000004 // Select encryption/decryption
|
||||
// 0x0: decryption is selected0x1:
|
||||
// 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
|
||||
#define DES_CTRL_MODE_S 4
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the DES_O_LENGTH register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define DES_LENGTH_M 0xFFFFFFFF // Cryptographic data length in
|
||||
// bytes for all modes
|
||||
#define DES_LENGTH_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the DES_O_DATA_L register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define DES_DATA_L_M 0xFFFFFFFF // Data for encryption/decryption,
|
||||
// LSW
|
||||
#define DES_DATA_L_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the DES_O_DATA_H register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define DES_DATA_H_M 0xFFFFFFFF // Data for encryption/decryption,
|
||||
// MSW
|
||||
#define DES_DATA_H_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the DES_O_REVISION register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define DES_REVISION_M 0xFFFFFFFF // Revision number
|
||||
#define DES_REVISION_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 // DMA Request Context In Enable
|
||||
#define DES_SYSCONFIG_DMA_REQ_DATA_OUT_EN \
|
||||
0x00000040 // DMA Request Data Out Enable
|
||||
#define DES_SYSCONFIG_DMA_REQ_DATA_IN_EN \
|
||||
0x00000020 // DMA Request Data In Enable
|
||||
#define DES_SYSCONFIG_SIDLE_M 0x0000000C // Sidle mode
|
||||
#define DES_SYSCONFIG_SIDLE_FORCE \
|
||||
0x00000000 // Force-idle mode
|
||||
#define DES_SYSCONFIG_SOFTRESET 0x00000002 // Soft reset
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the DES_O_SYSSTATUS
|
||||
// register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define DES_SYSSTATUS_RESETDONE 0x00000001 // Reset Done
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// 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 data
|
||||
// output interrupt is enabled
|
||||
#define DES_IRQENABLE_M_DATA_IN 0x00000002 // If this bit is set to 1 the data
|
||||
// input interrupt is enabled
|
||||
#define DES_IRQENABLE_M_CONTEX_IN \
|
||||
0x00000001 // If this bit is set to 1 the
|
||||
// context interrupt is enabled
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the DES_O_DIRTYBITS
|
||||
// register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define DES_DIRTYBITS_S_DIRTY 0x00000002 // This bit is set to 1 by the
|
||||
// module if any of the DES_*
|
||||
// registers is written
|
||||
#define DES_DIRTYBITS_S_ACCESS 0x00000001 // This bit is set to 1 by the
|
||||
// module if any of the DES_*
|
||||
// registers is read
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the DES_O_DMAIM register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define DES_DMAIM_DOUT 0x00000004 // Data Out DMA Done Interrupt Mask
|
||||
#define DES_DMAIM_DIN 0x00000002 // Data In DMA Done Interrupt Mask
|
||||
#define DES_DMAIM_CIN 0x00000001 // Context In DMA Done Interrupt
|
||||
// Mask
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the DES_O_DMARIS register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define DES_DMARIS_DOUT 0x00000004 // Data Out DMA Done Raw Interrupt
|
||||
// Status
|
||||
#define DES_DMARIS_DIN 0x00000002 // Data In DMA Done Raw Interrupt
|
||||
// Status
|
||||
#define DES_DMARIS_CIN 0x00000001 // Context In DMA Done Raw
|
||||
// Interrupt Status
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the DES_O_DMAMIS register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define DES_DMAMIS_DOUT 0x00000004 // Data Out DMA Done Masked
|
||||
// Interrupt Status
|
||||
#define DES_DMAMIS_DIN 0x00000002 // Data In DMA Done Masked
|
||||
// Interrupt Status
|
||||
#define DES_DMAMIS_CIN 0x00000001 // Context In DMA Done Raw
|
||||
// Interrupt Status
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the DES_O_DMAIC register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define DES_DMAIC_DOUT 0x00000004 // Data Out DMA Done Interrupt
|
||||
// Clear
|
||||
#define DES_DMAIC_DIN 0x00000002 // Data In DMA Done Interrupt Clear
|
||||
#define DES_DMAIC_CIN 0x00000001 // Context In DMA Done Raw
|
||||
// Interrupt Status
|
||||
|
||||
#endif // __HW_DES_H__
|
|
@ -0,0 +1,251 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// hw_eeprom.h - Macros used when accessing the EEPROM controller.
|
||||
//
|
||||
// Copyright (c) 2011-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Firmware Development Package.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __HW_EEPROM_H__
|
||||
#define __HW_EEPROM_H__
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the EEPROM register offsets.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EEPROM_EESIZE 0x400AF000 // EEPROM Size Information
|
||||
#define EEPROM_EEBLOCK 0x400AF004 // EEPROM Current Block
|
||||
#define EEPROM_EEOFFSET 0x400AF008 // EEPROM Current Offset
|
||||
#define EEPROM_EERDWR 0x400AF010 // EEPROM Read-Write
|
||||
#define EEPROM_EERDWRINC 0x400AF014 // EEPROM Read-Write with Increment
|
||||
#define EEPROM_EEDONE 0x400AF018 // EEPROM Done Status
|
||||
#define EEPROM_EESUPP 0x400AF01C // EEPROM Support Control and
|
||||
// Status
|
||||
#define EEPROM_EEUNLOCK 0x400AF020 // EEPROM Unlock
|
||||
#define EEPROM_EEPROT 0x400AF030 // EEPROM Protection
|
||||
#define EEPROM_EEPASS0 0x400AF034 // EEPROM Password
|
||||
#define EEPROM_EEPASS1 0x400AF038 // EEPROM Password
|
||||
#define EEPROM_EEPASS2 0x400AF03C // EEPROM Password
|
||||
#define EEPROM_EEINT 0x400AF040 // EEPROM Interrupt
|
||||
#define EEPROM_EEHIDE0 0x400AF050 // EEPROM Block Hide 0
|
||||
#define EEPROM_EEHIDE 0x400AF050 // EEPROM Block Hide
|
||||
#define EEPROM_EEHIDE1 0x400AF054 // EEPROM Block Hide 1
|
||||
#define EEPROM_EEHIDE2 0x400AF058 // EEPROM Block Hide 2
|
||||
#define EEPROM_EEDBGME 0x400AF080 // EEPROM Debug Mass Erase
|
||||
#define EEPROM_PP 0x400AFFC0 // EEPROM Peripheral Properties
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EEPROM_EESIZE register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EEPROM_EESIZE_WORDCNT_M 0x0000FFFF // Number of 32-Bit Words
|
||||
#define EEPROM_EESIZE_BLKCNT_M 0x07FF0000 // Number of 16-Word Blocks
|
||||
#define EEPROM_EESIZE_WORDCNT_S 0
|
||||
#define EEPROM_EESIZE_BLKCNT_S 16
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EEPROM_EEBLOCK register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EEPROM_EEBLOCK_BLOCK_M 0x0000FFFF // Current Block
|
||||
#define EEPROM_EEBLOCK_BLOCK_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EEPROM_EEOFFSET
|
||||
// register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EEPROM_EEOFFSET_OFFSET_M \
|
||||
0x0000000F // Current Address Offset
|
||||
#define EEPROM_EEOFFSET_OFFSET_S \
|
||||
0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EEPROM_EERDWR register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EEPROM_EERDWR_VALUE_M 0xFFFFFFFF // EEPROM Read or Write Data
|
||||
#define EEPROM_EERDWR_VALUE_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EEPROM_EERDWRINC
|
||||
// register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EEPROM_EERDWRINC_VALUE_M \
|
||||
0xFFFFFFFF // EEPROM Read or Write Data with
|
||||
// Increment
|
||||
#define EEPROM_EERDWRINC_VALUE_S \
|
||||
0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EEPROM_EEDONE register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EEPROM_EEDONE_WORKING 0x00000001 // EEPROM Working
|
||||
#define EEPROM_EEDONE_WKERASE 0x00000004 // Working on an Erase
|
||||
#define EEPROM_EEDONE_WKCOPY 0x00000008 // Working on a Copy
|
||||
#define EEPROM_EEDONE_NOPERM 0x00000010 // Write Without Permission
|
||||
#define EEPROM_EEDONE_WRBUSY 0x00000020 // Write Busy
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EEPROM_EESUPP register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EEPROM_EESUPP_ERETRY 0x00000004 // Erase Must Be Retried
|
||||
#define EEPROM_EESUPP_PRETRY 0x00000008 // Programming Must Be Retried
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EEPROM_EEUNLOCK
|
||||
// register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EEPROM_EEUNLOCK_UNLOCK_M \
|
||||
0xFFFFFFFF // EEPROM Unlock
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EEPROM_EEPROT register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EEPROM_EEPROT_PROT_M 0x00000007 // Protection Control
|
||||
#define EEPROM_EEPROT_PROT_RWNPW \
|
||||
0x00000000 // This setting is the default. If
|
||||
// there is no password, the block
|
||||
// is not protected and is readable
|
||||
// and writable
|
||||
#define EEPROM_EEPROT_PROT_RWPW 0x00000001 // If there is a password, the
|
||||
// block is readable or writable
|
||||
// only when unlocked
|
||||
#define EEPROM_EEPROT_PROT_RONPW \
|
||||
0x00000002 // If there is no password, the
|
||||
// block is readable, not writable
|
||||
#define EEPROM_EEPROT_ACC 0x00000008 // Access Control
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EEPROM_EEPASS0 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EEPROM_EEPASS0_PASS_M 0xFFFFFFFF // Password
|
||||
#define EEPROM_EEPASS0_PASS_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EEPROM_EEPASS1 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EEPROM_EEPASS1_PASS_M 0xFFFFFFFF // Password
|
||||
#define EEPROM_EEPASS1_PASS_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EEPROM_EEPASS2 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EEPROM_EEPASS2_PASS_M 0xFFFFFFFF // Password
|
||||
#define EEPROM_EEPASS2_PASS_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EEPROM_EEINT register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EEPROM_EEINT_INT 0x00000001 // Interrupt Enable
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EEPROM_EEHIDE0 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EEPROM_EEHIDE0_HN_M 0xFFFFFFFE // Hide Block
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EEPROM_EEHIDE register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EEPROM_EEHIDE_HN_M 0xFFFFFFFE // Hide Block
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EEPROM_EEHIDE1 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EEPROM_EEHIDE1_HN_M 0xFFFFFFFF // Hide Block
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EEPROM_EEHIDE2 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EEPROM_EEHIDE2_HN_M 0xFFFFFFFF // Hide Block
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EEPROM_EEDBGME register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EEPROM_EEDBGME_ME 0x00000001 // Mass Erase
|
||||
#define EEPROM_EEDBGME_KEY_M 0xFFFF0000 // Erase Key
|
||||
#define EEPROM_EEDBGME_KEY_S 16
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EEPROM_PP register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EEPROM_PP_SIZE_M 0x0000FFFF // EEPROM Size
|
||||
#define EEPROM_PP_SIZE_64 0x00000000 // 64 bytes of EEPROM
|
||||
#define EEPROM_PP_SIZE_128 0x00000001 // 128 bytes of EEPROM
|
||||
#define EEPROM_PP_SIZE_256 0x00000003 // 256 bytes of EEPROM
|
||||
#define EEPROM_PP_SIZE_512 0x00000007 // 512 bytes of EEPROM
|
||||
#define EEPROM_PP_SIZE_1K 0x0000000F // 1 KB of EEPROM
|
||||
#define EEPROM_PP_SIZE_2K 0x0000001F // 2 KB of EEPROM
|
||||
#define EEPROM_PP_SIZE_3K 0x0000003F // 3 KB of EEPROM
|
||||
#define EEPROM_PP_SIZE_4K 0x0000007F // 4 KB of EEPROM
|
||||
#define EEPROM_PP_SIZE_5K 0x000000FF // 5 KB of EEPROM
|
||||
#define EEPROM_PP_SIZE_6K 0x000001FF // 6 KB of EEPROM
|
||||
#define EEPROM_PP_SIZE_S 0
|
||||
|
||||
#endif // __HW_EEPROM_H__
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,933 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// hw_epi.h - Macros for use in accessing the EPI registers.
|
||||
//
|
||||
// Copyright (c) 2008-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Firmware Development Package.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __HW_EPI_H__
|
||||
#define __HW_EPI_H__
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the External Peripheral Interface register
|
||||
// offsets.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_O_CFG 0x00000000 // EPI Configuration
|
||||
#define EPI_O_BAUD 0x00000004 // EPI Main Baud Rate
|
||||
#define EPI_O_BAUD2 0x00000008 // EPI Main Baud Rate
|
||||
#define EPI_O_HB16CFG 0x00000010 // EPI Host-Bus 16 Configuration
|
||||
#define EPI_O_GPCFG 0x00000010 // EPI General-Purpose
|
||||
// Configuration
|
||||
#define EPI_O_SDRAMCFG 0x00000010 // EPI SDRAM Configuration
|
||||
#define EPI_O_HB8CFG 0x00000010 // EPI Host-Bus 8 Configuration
|
||||
#define EPI_O_HB8CFG2 0x00000014 // EPI Host-Bus 8 Configuration 2
|
||||
#define EPI_O_HB16CFG2 0x00000014 // EPI Host-Bus 16 Configuration 2
|
||||
#define EPI_O_ADDRMAP 0x0000001C // EPI Address Map
|
||||
#define EPI_O_RSIZE0 0x00000020 // EPI Read Size 0
|
||||
#define EPI_O_RADDR0 0x00000024 // EPI Read Address 0
|
||||
#define EPI_O_RPSTD0 0x00000028 // EPI Non-Blocking Read Data 0
|
||||
#define EPI_O_RSIZE1 0x00000030 // EPI Read Size 1
|
||||
#define EPI_O_RADDR1 0x00000034 // EPI Read Address 1
|
||||
#define EPI_O_RPSTD1 0x00000038 // EPI Non-Blocking Read Data 1
|
||||
#define EPI_O_STAT 0x00000060 // EPI Status
|
||||
#define EPI_O_RFIFOCNT 0x0000006C // EPI Read FIFO Count
|
||||
#define EPI_O_READFIFO0 0x00000070 // EPI Read FIFO
|
||||
#define EPI_O_READFIFO1 0x00000074 // EPI Read FIFO Alias 1
|
||||
#define EPI_O_READFIFO2 0x00000078 // EPI Read FIFO Alias 2
|
||||
#define EPI_O_READFIFO3 0x0000007C // EPI Read FIFO Alias 3
|
||||
#define EPI_O_READFIFO4 0x00000080 // EPI Read FIFO Alias 4
|
||||
#define EPI_O_READFIFO5 0x00000084 // EPI Read FIFO Alias 5
|
||||
#define EPI_O_READFIFO6 0x00000088 // EPI Read FIFO Alias 6
|
||||
#define EPI_O_READFIFO7 0x0000008C // EPI Read FIFO Alias 7
|
||||
#define EPI_O_FIFOLVL 0x00000200 // EPI FIFO Level Selects
|
||||
#define EPI_O_WFIFOCNT 0x00000204 // EPI Write FIFO Count
|
||||
#define EPI_O_DMATXCNT 0x00000208 // EPI DMA Transmit Count
|
||||
#define EPI_O_IM 0x00000210 // EPI Interrupt Mask
|
||||
#define EPI_O_RIS 0x00000214 // EPI Raw Interrupt Status
|
||||
#define EPI_O_MIS 0x00000218 // EPI Masked Interrupt Status
|
||||
#define EPI_O_EISC 0x0000021C // EPI Error and Interrupt Status
|
||||
// and Clear
|
||||
#define EPI_O_HB8CFG3 0x00000308 // EPI Host-Bus 8 Configuration 3
|
||||
#define EPI_O_HB16CFG3 0x00000308 // EPI Host-Bus 16 Configuration 3
|
||||
#define EPI_O_HB16CFG4 0x0000030C // EPI Host-Bus 16 Configuration 4
|
||||
#define EPI_O_HB8CFG4 0x0000030C // EPI Host-Bus 8 Configuration 4
|
||||
#define EPI_O_HB8TIME 0x00000310 // EPI Host-Bus 8 Timing Extension
|
||||
#define EPI_O_HB16TIME 0x00000310 // EPI Host-Bus 16 Timing Extension
|
||||
#define EPI_O_HB8TIME2 0x00000314 // EPI Host-Bus 8 Timing Extension
|
||||
#define EPI_O_HB16TIME2 0x00000314 // EPI Host-Bus 16 Timing Extension
|
||||
#define EPI_O_HB16TIME3 0x00000318 // EPI Host-Bus 16 Timing Extension
|
||||
#define EPI_O_HB8TIME3 0x00000318 // EPI Host-Bus 8 Timing Extension
|
||||
#define EPI_O_HB8TIME4 0x0000031C // EPI Host-Bus 8 Timing Extension
|
||||
#define EPI_O_HB16TIME4 0x0000031C // EPI Host-Bus 16 Timing Extension
|
||||
#define EPI_O_HBPSRAM 0x00000360 // EPI Host-Bus PSRAM
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EPI_O_CFG register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_CFG_INTDIV 0x00000100 // Integer Clock Divider Enable
|
||||
#define EPI_CFG_BLKEN 0x00000010 // Block Enable
|
||||
#define EPI_CFG_MODE_M 0x0000000F // Mode Select
|
||||
#define EPI_CFG_MODE_NONE 0x00000000 // General Purpose
|
||||
#define EPI_CFG_MODE_SDRAM 0x00000001 // SDRAM
|
||||
#define EPI_CFG_MODE_HB8 0x00000002 // 8-Bit Host-Bus (HB8)
|
||||
#define EPI_CFG_MODE_HB16 0x00000003 // 16-Bit Host-Bus (HB16)
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EPI_O_BAUD register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_BAUD_COUNT1_M 0xFFFF0000 // Baud Rate Counter 1
|
||||
#define EPI_BAUD_COUNT0_M 0x0000FFFF // Baud Rate Counter 0
|
||||
#define EPI_BAUD_COUNT1_S 16
|
||||
#define EPI_BAUD_COUNT0_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EPI_O_BAUD2 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_BAUD2_COUNT1_M 0xFFFF0000 // CS3n Baud Rate Counter 1
|
||||
#define EPI_BAUD2_COUNT0_M 0x0000FFFF // CS2n Baud Rate Counter 0
|
||||
#define EPI_BAUD2_COUNT1_S 16
|
||||
#define EPI_BAUD2_COUNT0_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EPI_O_HB16CFG register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_HB16CFG_CLKGATE 0x80000000 // Clock Gated
|
||||
#define EPI_HB16CFG_CLKGATEI 0x40000000 // Clock Gated Idle
|
||||
#define EPI_HB16CFG_CLKINV 0x20000000 // Invert Output Clock Enable
|
||||
#define EPI_HB16CFG_RDYEN 0x10000000 // Input Ready Enable
|
||||
#define EPI_HB16CFG_IRDYINV 0x08000000 // Input Ready Invert
|
||||
#define EPI_HB16CFG_XFFEN 0x00800000 // External FIFO FULL Enable
|
||||
#define EPI_HB16CFG_XFEEN 0x00400000 // External FIFO EMPTY Enable
|
||||
#define EPI_HB16CFG_WRHIGH 0x00200000 // WRITE Strobe Polarity
|
||||
#define EPI_HB16CFG_RDHIGH 0x00100000 // READ Strobe Polarity
|
||||
#define EPI_HB16CFG_ALEHIGH 0x00080000 // ALE Strobe Polarity
|
||||
#define EPI_HB16CFG_WRCRE 0x00040000 // PSRAM Configuration Register
|
||||
// Write
|
||||
#define EPI_HB16CFG_RDCRE 0x00020000 // PSRAM Configuration Register
|
||||
// Read
|
||||
#define EPI_HB16CFG_BURST 0x00010000 // Burst Mode
|
||||
#define EPI_HB16CFG_MAXWAIT_M 0x0000FF00 // Maximum Wait
|
||||
#define EPI_HB16CFG_WRWS_M 0x000000C0 // Write Wait States
|
||||
#define EPI_HB16CFG_WRWS_2 0x00000000 // Active WRn is 2 EPI clocks
|
||||
#define EPI_HB16CFG_WRWS_4 0x00000040 // Active WRn is 4 EPI clocks
|
||||
#define EPI_HB16CFG_WRWS_6 0x00000080 // Active WRn is 6 EPI clocks
|
||||
#define EPI_HB16CFG_WRWS_8 0x000000C0 // Active WRn is 8 EPI clocks
|
||||
#define EPI_HB16CFG_RDWS_M 0x00000030 // Read Wait States
|
||||
#define EPI_HB16CFG_RDWS_2 0x00000000 // Active RDn is 2 EPI clocks
|
||||
#define EPI_HB16CFG_RDWS_4 0x00000010 // Active RDn is 4 EPI clocks
|
||||
#define EPI_HB16CFG_RDWS_6 0x00000020 // Active RDn is 6 EPI clocks
|
||||
#define EPI_HB16CFG_RDWS_8 0x00000030 // Active RDn is 8 EPI clocks
|
||||
#define EPI_HB16CFG_BSEL 0x00000004 // Byte Select Configuration
|
||||
#define EPI_HB16CFG_MODE_M 0x00000003 // Host Bus Sub-Mode
|
||||
#define EPI_HB16CFG_MODE_ADMUX 0x00000000 // ADMUX - AD[15:0]
|
||||
#define EPI_HB16CFG_MODE_ADNMUX 0x00000001 // ADNONMUX - D[15:0]
|
||||
#define EPI_HB16CFG_MODE_SRAM 0x00000002 // Continuous Read - D[15:0]
|
||||
#define EPI_HB16CFG_MODE_XFIFO 0x00000003 // XFIFO - D[15:0]
|
||||
#define EPI_HB16CFG_MAXWAIT_S 8
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EPI_O_GPCFG register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_GPCFG_CLKPIN 0x80000000 // Clock Pin
|
||||
#define EPI_GPCFG_CLKGATE 0x40000000 // Clock Gated
|
||||
#define EPI_GPCFG_FRM50 0x04000000 // 50/50 Frame
|
||||
#define EPI_GPCFG_FRMCNT_M 0x03C00000 // Frame Count
|
||||
#define EPI_GPCFG_WR2CYC 0x00080000 // 2-Cycle Writes
|
||||
#define EPI_GPCFG_ASIZE_M 0x00000030 // Address Bus Size
|
||||
#define EPI_GPCFG_ASIZE_NONE 0x00000000 // No address
|
||||
#define EPI_GPCFG_ASIZE_4BIT 0x00000010 // Up to 4 bits wide
|
||||
#define EPI_GPCFG_ASIZE_12BIT 0x00000020 // Up to 12 bits wide. This size
|
||||
// cannot be used with 24-bit data
|
||||
#define EPI_GPCFG_ASIZE_20BIT 0x00000030 // Up to 20 bits wide. This size
|
||||
// cannot be used with data sizes
|
||||
// other than 8
|
||||
#define EPI_GPCFG_DSIZE_M 0x00000003 // Size of Data Bus
|
||||
#define EPI_GPCFG_DSIZE_4BIT 0x00000000 // 8 Bits Wide (EPI0S0 to EPI0S7)
|
||||
#define EPI_GPCFG_DSIZE_16BIT 0x00000001 // 16 Bits Wide (EPI0S0 to EPI0S15)
|
||||
#define EPI_GPCFG_DSIZE_24BIT 0x00000002 // 24 Bits Wide (EPI0S0 to EPI0S23)
|
||||
#define EPI_GPCFG_DSIZE_32BIT 0x00000003 // 32 Bits Wide (EPI0S0 to EPI0S31)
|
||||
#define EPI_GPCFG_FRMCNT_S 22
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EPI_O_SDRAMCFG register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_SDRAMCFG_FREQ_M 0xC0000000 // EPI Frequency Range
|
||||
#define EPI_SDRAMCFG_FREQ_NONE 0x00000000 // 0 - 15 MHz
|
||||
#define EPI_SDRAMCFG_FREQ_15MHZ 0x40000000 // 15 - 30 MHz
|
||||
#define EPI_SDRAMCFG_FREQ_30MHZ 0x80000000 // 30 - 50 MHz
|
||||
#define EPI_SDRAMCFG_RFSH_M 0x07FF0000 // Refresh Counter
|
||||
#define EPI_SDRAMCFG_SLEEP 0x00000200 // Sleep Mode
|
||||
#define EPI_SDRAMCFG_SIZE_M 0x00000003 // Size of SDRAM
|
||||
#define EPI_SDRAMCFG_SIZE_8MB 0x00000000 // 64 megabits (8MB)
|
||||
#define EPI_SDRAMCFG_SIZE_16MB 0x00000001 // 128 megabits (16MB)
|
||||
#define EPI_SDRAMCFG_SIZE_32MB 0x00000002 // 256 megabits (32MB)
|
||||
#define EPI_SDRAMCFG_SIZE_64MB 0x00000003 // 512 megabits (64MB)
|
||||
#define EPI_SDRAMCFG_RFSH_S 16
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EPI_O_HB8CFG register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_HB8CFG_CLKGATE 0x80000000 // Clock Gated
|
||||
#define EPI_HB8CFG_CLKGATEI 0x40000000 // Clock Gated when Idle
|
||||
#define EPI_HB8CFG_CLKINV 0x20000000 // Invert Output Clock Enable
|
||||
#define EPI_HB8CFG_RDYEN 0x10000000 // Input Ready Enable
|
||||
#define EPI_HB8CFG_IRDYINV 0x08000000 // Input Ready Invert
|
||||
#define EPI_HB8CFG_XFFEN 0x00800000 // External FIFO FULL Enable
|
||||
#define EPI_HB8CFG_XFEEN 0x00400000 // External FIFO EMPTY Enable
|
||||
#define EPI_HB8CFG_WRHIGH 0x00200000 // WRITE Strobe Polarity
|
||||
#define EPI_HB8CFG_RDHIGH 0x00100000 // READ Strobe Polarity
|
||||
#define EPI_HB8CFG_ALEHIGH 0x00080000 // ALE Strobe Polarity
|
||||
#define EPI_HB8CFG_MAXWAIT_M 0x0000FF00 // Maximum Wait
|
||||
#define EPI_HB8CFG_WRWS_M 0x000000C0 // Write Wait States
|
||||
#define EPI_HB8CFG_WRWS_2 0x00000000 // Active WRn is 2 EPI clocks
|
||||
#define EPI_HB8CFG_WRWS_4 0x00000040 // Active WRn is 4 EPI clocks
|
||||
#define EPI_HB8CFG_WRWS_6 0x00000080 // Active WRn is 6 EPI clocks
|
||||
#define EPI_HB8CFG_WRWS_8 0x000000C0 // Active WRn is 8 EPI clocks
|
||||
#define EPI_HB8CFG_RDWS_M 0x00000030 // Read Wait States
|
||||
#define EPI_HB8CFG_RDWS_2 0x00000000 // Active RDn is 2 EPI clocks
|
||||
#define EPI_HB8CFG_RDWS_4 0x00000010 // Active RDn is 4 EPI clocks
|
||||
#define EPI_HB8CFG_RDWS_6 0x00000020 // Active RDn is 6 EPI clocks
|
||||
#define EPI_HB8CFG_RDWS_8 0x00000030 // Active RDn is 8 EPI clocks
|
||||
#define EPI_HB8CFG_MODE_M 0x00000003 // Host Bus Sub-Mode
|
||||
#define EPI_HB8CFG_MODE_MUX 0x00000000 // ADMUX - AD[7:0]
|
||||
#define EPI_HB8CFG_MODE_NMUX 0x00000001 // ADNONMUX - D[7:0]
|
||||
#define EPI_HB8CFG_MODE_SRAM 0x00000002 // Continuous Read - D[7:0]
|
||||
#define EPI_HB8CFG_MODE_FIFO 0x00000003 // XFIFO - D[7:0]
|
||||
#define EPI_HB8CFG_MAXWAIT_S 8
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EPI_O_HB8CFG2 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_HB8CFG2_CSCFGEXT 0x08000000 // Chip Select Extended
|
||||
// Configuration
|
||||
#define EPI_HB8CFG2_CSBAUD 0x04000000 // Chip Select Baud Rate and
|
||||
// Multiple Sub-Mode Configuration
|
||||
// enable
|
||||
#define EPI_HB8CFG2_CSCFG_M 0x03000000 // Chip Select Configuration
|
||||
#define EPI_HB8CFG2_CSCFG_ALE 0x00000000 // ALE Configuration
|
||||
#define EPI_HB8CFG2_CSCFG_CS 0x01000000 // CSn Configuration
|
||||
#define EPI_HB8CFG2_CSCFG_DCS 0x02000000 // Dual CSn Configuration
|
||||
#define EPI_HB8CFG2_CSCFG_ADCS 0x03000000 // ALE with Dual CSn Configuration
|
||||
#define EPI_HB8CFG2_WRHIGH 0x00200000 // CS1n WRITE Strobe Polarity
|
||||
#define EPI_HB8CFG2_RDHIGH 0x00100000 // CS1n READ Strobe Polarity
|
||||
#define EPI_HB8CFG2_ALEHIGH 0x00080000 // CS1n ALE Strobe Polarity
|
||||
#define EPI_HB8CFG2_WRWS_M 0x000000C0 // CS1n Write Wait States
|
||||
#define EPI_HB8CFG2_WRWS_2 0x00000000 // Active WRn is 2 EPI clocks
|
||||
#define EPI_HB8CFG2_WRWS_4 0x00000040 // Active WRn is 4 EPI clocks
|
||||
#define EPI_HB8CFG2_WRWS_6 0x00000080 // Active WRn is 6 EPI clocks
|
||||
#define EPI_HB8CFG2_WRWS_8 0x000000C0 // Active WRn is 8 EPI clocks
|
||||
#define EPI_HB8CFG2_RDWS_M 0x00000030 // CS1n Read Wait States
|
||||
#define EPI_HB8CFG2_RDWS_2 0x00000000 // Active RDn is 2 EPI clocks
|
||||
#define EPI_HB8CFG2_RDWS_4 0x00000010 // Active RDn is 4 EPI clocks
|
||||
#define EPI_HB8CFG2_RDWS_6 0x00000020 // Active RDn is 6 EPI clocks
|
||||
#define EPI_HB8CFG2_RDWS_8 0x00000030 // Active RDn is 8 EPI clocks
|
||||
#define EPI_HB8CFG2_MODE_M 0x00000003 // CS1n Host Bus Sub-Mode
|
||||
#define EPI_HB8CFG2_MODE_ADMUX 0x00000000 // ADMUX - AD[7:0]
|
||||
#define EPI_HB8CFG2_MODE_AD 0x00000001 // ADNONMUX - D[7:0]
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EPI_O_HB16CFG2 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_HB16CFG2_CSCFGEXT 0x08000000 // Chip Select Extended
|
||||
// Configuration
|
||||
#define EPI_HB16CFG2_CSBAUD 0x04000000 // Chip Select Baud Rate and
|
||||
// Multiple Sub-Mode Configuration
|
||||
// enable
|
||||
#define EPI_HB16CFG2_CSCFG_M 0x03000000 // Chip Select Configuration
|
||||
#define EPI_HB16CFG2_CSCFG_ALE 0x00000000 // ALE Configuration
|
||||
#define EPI_HB16CFG2_CSCFG_CS 0x01000000 // CSn Configuration
|
||||
#define EPI_HB16CFG2_CSCFG_DCS 0x02000000 // Dual CSn Configuration
|
||||
#define EPI_HB16CFG2_CSCFG_ADCS 0x03000000 // ALE with Dual CSn Configuration
|
||||
#define EPI_HB16CFG2_WRHIGH 0x00200000 // CS1n WRITE Strobe Polarity
|
||||
#define EPI_HB16CFG2_RDHIGH 0x00100000 // CS1n READ Strobe Polarity
|
||||
#define EPI_HB16CFG2_ALEHIGH 0x00080000 // CS1n ALE Strobe Polarity
|
||||
#define EPI_HB16CFG2_WRCRE 0x00040000 // CS1n PSRAM Configuration
|
||||
// Register Write
|
||||
#define EPI_HB16CFG2_RDCRE 0x00020000 // CS1n PSRAM Configuration
|
||||
// Register Read
|
||||
#define EPI_HB16CFG2_BURST 0x00010000 // CS1n Burst Mode
|
||||
#define EPI_HB16CFG2_WRWS_M 0x000000C0 // CS1n Write Wait States
|
||||
#define EPI_HB16CFG2_WRWS_2 0x00000000 // Active WRn is 2 EPI clocks
|
||||
#define EPI_HB16CFG2_WRWS_4 0x00000040 // Active WRn is 4 EPI clocks
|
||||
#define EPI_HB16CFG2_WRWS_6 0x00000080 // Active WRn is 6 EPI clocks
|
||||
#define EPI_HB16CFG2_WRWS_8 0x000000C0 // Active WRn is 8 EPI clocks
|
||||
#define EPI_HB16CFG2_RDWS_M 0x00000030 // CS1n Read Wait States
|
||||
#define EPI_HB16CFG2_RDWS_2 0x00000000 // Active RDn is 2 EPI clocks
|
||||
#define EPI_HB16CFG2_RDWS_4 0x00000010 // Active RDn is 4 EPI clocks
|
||||
#define EPI_HB16CFG2_RDWS_6 0x00000020 // Active RDn is 6 EPI clocks
|
||||
#define EPI_HB16CFG2_RDWS_8 0x00000030 // Active RDn is 8 EPI clocks
|
||||
#define EPI_HB16CFG2_MODE_M 0x00000003 // CS1n Host Bus Sub-Mode
|
||||
#define EPI_HB16CFG2_MODE_ADMUX 0x00000000 // ADMUX - AD[15:0]
|
||||
#define EPI_HB16CFG2_MODE_AD 0x00000001 // ADNONMUX - D[15:0]
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EPI_O_ADDRMAP register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_ADDRMAP_ECSZ_M 0x00000C00 // External Code Size
|
||||
#define EPI_ADDRMAP_ECSZ_256B 0x00000000 // 256 bytes; lower address range:
|
||||
// 0x00 to 0xFF
|
||||
#define EPI_ADDRMAP_ECSZ_64KB 0x00000400 // 64 KB; lower address range:
|
||||
// 0x0000 to 0xFFFF
|
||||
#define EPI_ADDRMAP_ECSZ_16MB 0x00000800 // 16 MB; lower address range:
|
||||
// 0x00.0000 to 0xFF.FFFF
|
||||
#define EPI_ADDRMAP_ECSZ_256MB 0x00000C00 // 256MB; lower address range:
|
||||
// 0x000.0000 to 0x0FFF.FFFF
|
||||
#define EPI_ADDRMAP_ECADR_M 0x00000300 // External Code Address
|
||||
#define EPI_ADDRMAP_ECADR_NONE 0x00000000 // Not mapped
|
||||
#define EPI_ADDRMAP_ECADR_1000 0x00000100 // At 0x1000.0000
|
||||
#define EPI_ADDRMAP_EPSZ_M 0x000000C0 // External Peripheral Size
|
||||
#define EPI_ADDRMAP_EPSZ_256B 0x00000000 // 256 bytes; lower address range:
|
||||
// 0x00 to 0xFF
|
||||
#define EPI_ADDRMAP_EPSZ_64KB 0x00000040 // 64 KB; lower address range:
|
||||
// 0x0000 to 0xFFFF
|
||||
#define EPI_ADDRMAP_EPSZ_16MB 0x00000080 // 16 MB; lower address range:
|
||||
// 0x00.0000 to 0xFF.FFFF
|
||||
#define EPI_ADDRMAP_EPSZ_256MB 0x000000C0 // 256 MB; lower address range:
|
||||
// 0x000.0000 to 0xFFF.FFFF
|
||||
#define EPI_ADDRMAP_EPADR_M 0x00000030 // External Peripheral Address
|
||||
#define EPI_ADDRMAP_EPADR_NONE 0x00000000 // Not mapped
|
||||
#define EPI_ADDRMAP_EPADR_A000 0x00000010 // At 0xA000.0000
|
||||
#define EPI_ADDRMAP_EPADR_C000 0x00000020 // At 0xC000.0000
|
||||
#define EPI_ADDRMAP_EPADR_HBQS 0x00000030 // Only to be used with Host Bus
|
||||
// quad chip select. In quad chip
|
||||
// select mode, CS2n maps to
|
||||
// 0xA000.0000 and CS3n maps to
|
||||
// 0xC000.0000
|
||||
#define EPI_ADDRMAP_ERSZ_M 0x0000000C // External RAM Size
|
||||
#define EPI_ADDRMAP_ERSZ_256B 0x00000000 // 256 bytes; lower address range:
|
||||
// 0x00 to 0xFF
|
||||
#define EPI_ADDRMAP_ERSZ_64KB 0x00000004 // 64 KB; lower address range:
|
||||
// 0x0000 to 0xFFFF
|
||||
#define EPI_ADDRMAP_ERSZ_16MB 0x00000008 // 16 MB; lower address range:
|
||||
// 0x00.0000 to 0xFF.FFFF
|
||||
#define EPI_ADDRMAP_ERSZ_256MB 0x0000000C // 256 MB; lower address range:
|
||||
// 0x000.0000 to 0xFFF.FFFF
|
||||
#define EPI_ADDRMAP_ERADR_M 0x00000003 // External RAM Address
|
||||
#define EPI_ADDRMAP_ERADR_NONE 0x00000000 // Not mapped
|
||||
#define EPI_ADDRMAP_ERADR_6000 0x00000001 // At 0x6000.0000
|
||||
#define EPI_ADDRMAP_ERADR_8000 0x00000002 // At 0x8000.0000
|
||||
#define EPI_ADDRMAP_ERADR_HBQS 0x00000003 // Only to be used with Host Bus
|
||||
// quad chip select. In quad chip
|
||||
// select mode, CS0n maps to
|
||||
// 0x6000.0000 and CS1n maps to
|
||||
// 0x8000.0000
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EPI_O_RSIZE0 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_RSIZE0_SIZE_M 0x00000003 // Current Size
|
||||
#define EPI_RSIZE0_SIZE_8BIT 0x00000001 // Byte (8 bits)
|
||||
#define EPI_RSIZE0_SIZE_16BIT 0x00000002 // Half-word (16 bits)
|
||||
#define EPI_RSIZE0_SIZE_32BIT 0x00000003 // Word (32 bits)
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EPI_O_RADDR0 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_RADDR0_ADDR_M 0xFFFFFFFF // Current Address
|
||||
#define EPI_RADDR0_ADDR_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EPI_O_RPSTD0 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_RPSTD0_POSTCNT_M 0x00001FFF // Post Count
|
||||
#define EPI_RPSTD0_POSTCNT_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EPI_O_RSIZE1 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_RSIZE1_SIZE_M 0x00000003 // Current Size
|
||||
#define EPI_RSIZE1_SIZE_8BIT 0x00000001 // Byte (8 bits)
|
||||
#define EPI_RSIZE1_SIZE_16BIT 0x00000002 // Half-word (16 bits)
|
||||
#define EPI_RSIZE1_SIZE_32BIT 0x00000003 // Word (32 bits)
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EPI_O_RADDR1 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_RADDR1_ADDR_M 0xFFFFFFFF // Current Address
|
||||
#define EPI_RADDR1_ADDR_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EPI_O_RPSTD1 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_RPSTD1_POSTCNT_M 0x00001FFF // Post Count
|
||||
#define EPI_RPSTD1_POSTCNT_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EPI_O_STAT register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_STAT_XFFULL 0x00000100 // External FIFO Full
|
||||
#define EPI_STAT_XFEMPTY 0x00000080 // External FIFO Empty
|
||||
#define EPI_STAT_INITSEQ 0x00000040 // Initialization Sequence
|
||||
#define EPI_STAT_WBUSY 0x00000020 // Write Busy
|
||||
#define EPI_STAT_NBRBUSY 0x00000010 // Non-Blocking Read Busy
|
||||
#define EPI_STAT_ACTIVE 0x00000001 // Register Active
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EPI_O_RFIFOCNT register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_RFIFOCNT_COUNT_M 0x0000000F // FIFO Count
|
||||
#define EPI_RFIFOCNT_COUNT_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EPI_O_READFIFO0
|
||||
// register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_READFIFO0_DATA_M 0xFFFFFFFF // Reads Data
|
||||
#define EPI_READFIFO0_DATA_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EPI_O_READFIFO1
|
||||
// register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_READFIFO1_DATA_M 0xFFFFFFFF // Reads Data
|
||||
#define EPI_READFIFO1_DATA_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EPI_O_READFIFO2
|
||||
// register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_READFIFO2_DATA_M 0xFFFFFFFF // Reads Data
|
||||
#define EPI_READFIFO2_DATA_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EPI_O_READFIFO3
|
||||
// register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_READFIFO3_DATA_M 0xFFFFFFFF // Reads Data
|
||||
#define EPI_READFIFO3_DATA_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EPI_O_READFIFO4
|
||||
// register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_READFIFO4_DATA_M 0xFFFFFFFF // Reads Data
|
||||
#define EPI_READFIFO4_DATA_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EPI_O_READFIFO5
|
||||
// register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_READFIFO5_DATA_M 0xFFFFFFFF // Reads Data
|
||||
#define EPI_READFIFO5_DATA_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EPI_O_READFIFO6
|
||||
// register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_READFIFO6_DATA_M 0xFFFFFFFF // Reads Data
|
||||
#define EPI_READFIFO6_DATA_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EPI_O_READFIFO7
|
||||
// register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_READFIFO7_DATA_M 0xFFFFFFFF // Reads Data
|
||||
#define EPI_READFIFO7_DATA_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EPI_O_FIFOLVL register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_FIFOLVL_WFERR 0x00020000 // Write Full Error
|
||||
#define EPI_FIFOLVL_RSERR 0x00010000 // Read Stall Error
|
||||
#define EPI_FIFOLVL_WRFIFO_M 0x00000070 // Write FIFO
|
||||
#define EPI_FIFOLVL_WRFIFO_EMPT 0x00000000 // Interrupt is triggered while
|
||||
// WRFIFO is empty.
|
||||
#define EPI_FIFOLVL_WRFIFO_2 0x00000020 // Interrupt is triggered until
|
||||
// there are only two slots
|
||||
// available. Thus, trigger is
|
||||
// deasserted when there are two
|
||||
// WRFIFO entries present. This
|
||||
// configuration is optimized for
|
||||
// bursts of 2
|
||||
#define EPI_FIFOLVL_WRFIFO_1 0x00000030 // Interrupt is triggered until
|
||||
// there is one WRFIFO entry
|
||||
// available. This configuration
|
||||
// expects only single writes
|
||||
#define EPI_FIFOLVL_WRFIFO_NFULL \
|
||||
0x00000040 // Trigger interrupt when WRFIFO is
|
||||
// not full, meaning trigger will
|
||||
// continue to assert until there
|
||||
// are four entries in the WRFIFO
|
||||
#define EPI_FIFOLVL_RDFIFO_M 0x00000007 // Read FIFO
|
||||
#define EPI_FIFOLVL_RDFIFO_EMPT 0x00000000 // Empty
|
||||
#define EPI_FIFOLVL_RDFIFO_1 0x00000001 // Trigger when there are 1 or more
|
||||
// entries in the NBRFIFO
|
||||
#define EPI_FIFOLVL_RDFIFO_2 0x00000002 // Trigger when there are 2 or more
|
||||
// entries in the NBRFIFO
|
||||
#define EPI_FIFOLVL_RDFIFO_4 0x00000003 // Trigger when there are 4 or more
|
||||
// entries in the NBRFIFO
|
||||
#define EPI_FIFOLVL_RDFIFO_6 0x00000004 // Trigger when there are 6 or more
|
||||
// entries in the NBRFIFO
|
||||
#define EPI_FIFOLVL_RDFIFO_7 0x00000005 // Trigger when there are 7 or more
|
||||
// entries in the NBRFIFO
|
||||
#define EPI_FIFOLVL_RDFIFO_8 0x00000006 // Trigger when there are 8 entries
|
||||
// in the NBRFIFO
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EPI_O_WFIFOCNT register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_WFIFOCNT_WTAV_M 0x00000007 // Available Write Transactions
|
||||
#define EPI_WFIFOCNT_WTAV_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EPI_O_DMATXCNT register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_DMATXCNT_TXCNT_M 0x0000FFFF // DMA Count
|
||||
#define EPI_DMATXCNT_TXCNT_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EPI_O_IM register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_IM_DMAWRIM 0x00000010 // Write uDMA Interrupt Mask
|
||||
#define EPI_IM_DMARDIM 0x00000008 // Read uDMA Interrupt Mask
|
||||
#define EPI_IM_WRIM 0x00000004 // Write FIFO Empty Interrupt Mask
|
||||
#define EPI_IM_RDIM 0x00000002 // Read FIFO Full Interrupt Mask
|
||||
#define EPI_IM_ERRIM 0x00000001 // Error Interrupt Mask
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EPI_O_RIS register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_RIS_DMAWRRIS 0x00000010 // Write uDMA Raw Interrupt Status
|
||||
#define EPI_RIS_DMARDRIS 0x00000008 // Read uDMA Raw Interrupt Status
|
||||
#define EPI_RIS_WRRIS 0x00000004 // Write Raw Interrupt Status
|
||||
#define EPI_RIS_RDRIS 0x00000002 // Read Raw Interrupt Status
|
||||
#define EPI_RIS_ERRRIS 0x00000001 // Error Raw Interrupt Status
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EPI_O_MIS register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_MIS_DMAWRMIS 0x00000010 // Write uDMA Masked Interrupt
|
||||
// Status
|
||||
#define EPI_MIS_DMARDMIS 0x00000008 // Read uDMA Masked Interrupt
|
||||
// Status
|
||||
#define EPI_MIS_WRMIS 0x00000004 // Write Masked Interrupt Status
|
||||
#define EPI_MIS_RDMIS 0x00000002 // Read Masked Interrupt Status
|
||||
#define EPI_MIS_ERRMIS 0x00000001 // Error Masked Interrupt Status
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EPI_O_EISC register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_EISC_DMAWRIC 0x00000010 // Write uDMA Interrupt Clear
|
||||
#define EPI_EISC_DMARDIC 0x00000008 // Read uDMA Interrupt Clear
|
||||
#define EPI_EISC_WTFULL 0x00000004 // Write FIFO Full Error
|
||||
#define EPI_EISC_RSTALL 0x00000002 // Read Stalled Error
|
||||
#define EPI_EISC_TOUT 0x00000001 // Timeout Error
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EPI_O_HB8CFG3 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_HB8CFG3_WRHIGH 0x00200000 // CS2n WRITE Strobe Polarity
|
||||
#define EPI_HB8CFG3_RDHIGH 0x00100000 // CS2n READ Strobe Polarity
|
||||
#define EPI_HB8CFG3_ALEHIGH 0x00080000 // CS2n ALE Strobe Polarity
|
||||
#define EPI_HB8CFG3_WRWS_M 0x000000C0 // CS2n Write Wait States
|
||||
#define EPI_HB8CFG3_WRWS_2 0x00000000 // Active WRn is 2 EPI clocks
|
||||
#define EPI_HB8CFG3_WRWS_4 0x00000040 // Active WRn is 4 EPI clocks
|
||||
#define EPI_HB8CFG3_WRWS_6 0x00000080 // Active WRn is 6 EPI clocks
|
||||
#define EPI_HB8CFG3_WRWS_8 0x000000C0 // Active WRn is 8 EPI clocks
|
||||
#define EPI_HB8CFG3_RDWS_M 0x00000030 // CS2n Read Wait States
|
||||
#define EPI_HB8CFG3_RDWS_2 0x00000000 // Active RDn is 2 EPI clocks
|
||||
#define EPI_HB8CFG3_RDWS_4 0x00000010 // Active RDn is 4 EPI clocks
|
||||
#define EPI_HB8CFG3_RDWS_6 0x00000020 // Active RDn is 6 EPI clocks
|
||||
#define EPI_HB8CFG3_RDWS_8 0x00000030 // Active RDn is 8 EPI clocks
|
||||
#define EPI_HB8CFG3_MODE_M 0x00000003 // CS2n Host Bus Sub-Mode
|
||||
#define EPI_HB8CFG3_MODE_ADMUX 0x00000000 // ADMUX - AD[7:0]
|
||||
#define EPI_HB8CFG3_MODE_AD 0x00000001 // ADNONMUX - D[7:0]
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EPI_O_HB16CFG3 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_HB16CFG3_WRHIGH 0x00200000 // CS2n WRITE Strobe Polarity
|
||||
#define EPI_HB16CFG3_RDHIGH 0x00100000 // CS2n READ Strobe Polarity
|
||||
#define EPI_HB16CFG3_ALEHIGH 0x00080000 // CS2n ALE Strobe Polarity
|
||||
#define EPI_HB16CFG3_WRCRE 0x00040000 // CS2n PSRAM Configuration
|
||||
// Register Write
|
||||
#define EPI_HB16CFG3_RDCRE 0x00020000 // CS2n PSRAM Configuration
|
||||
// Register Read
|
||||
#define EPI_HB16CFG3_BURST 0x00010000 // CS2n Burst Mode
|
||||
#define EPI_HB16CFG3_WRWS_M 0x000000C0 // CS2n Write Wait States
|
||||
#define EPI_HB16CFG3_WRWS_2 0x00000000 // Active WRn is 2 EPI clocks
|
||||
#define EPI_HB16CFG3_WRWS_4 0x00000040 // Active WRn is 4 EPI clocks
|
||||
#define EPI_HB16CFG3_WRWS_6 0x00000080 // Active WRn is 6 EPI clocks
|
||||
#define EPI_HB16CFG3_WRWS_8 0x000000C0 // Active WRn is 8 EPI clocks
|
||||
#define EPI_HB16CFG3_RDWS_M 0x00000030 // CS2n Read Wait States
|
||||
#define EPI_HB16CFG3_RDWS_2 0x00000000 // Active RDn is 2 EPI clocks
|
||||
#define EPI_HB16CFG3_RDWS_4 0x00000010 // Active RDn is 4 EPI clocks
|
||||
#define EPI_HB16CFG3_RDWS_6 0x00000020 // Active RDn is 6 EPI clocks
|
||||
#define EPI_HB16CFG3_RDWS_8 0x00000030 // Active RDn is 8 EPI clocks
|
||||
#define EPI_HB16CFG3_MODE_M 0x00000003 // CS2n Host Bus Sub-Mode
|
||||
#define EPI_HB16CFG3_MODE_ADMUX 0x00000000 // ADMUX - AD[15:0]
|
||||
#define EPI_HB16CFG3_MODE_AD 0x00000001 // ADNONMUX - D[15:0]
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EPI_O_HB16CFG4 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_HB16CFG4_WRHIGH 0x00200000 // CS3n WRITE Strobe Polarity
|
||||
#define EPI_HB16CFG4_RDHIGH 0x00100000 // CS3n READ Strobe Polarity
|
||||
#define EPI_HB16CFG4_ALEHIGH 0x00080000 // CS3n ALE Strobe Polarity
|
||||
#define EPI_HB16CFG4_WRCRE 0x00040000 // CS3n PSRAM Configuration
|
||||
// Register Write
|
||||
#define EPI_HB16CFG4_RDCRE 0x00020000 // CS3n PSRAM Configuration
|
||||
// Register Read
|
||||
#define EPI_HB16CFG4_BURST 0x00010000 // CS3n Burst Mode
|
||||
#define EPI_HB16CFG4_WRWS_M 0x000000C0 // CS3n Write Wait States
|
||||
#define EPI_HB16CFG4_WRWS_2 0x00000000 // Active WRn is 2 EPI clocks
|
||||
#define EPI_HB16CFG4_WRWS_4 0x00000040 // Active WRn is 4 EPI clocks
|
||||
#define EPI_HB16CFG4_WRWS_6 0x00000080 // Active WRn is 6 EPI clocks
|
||||
#define EPI_HB16CFG4_WRWS_8 0x000000C0 // Active WRn is 8 EPI clocks
|
||||
#define EPI_HB16CFG4_RDWS_M 0x00000030 // CS3n Read Wait States
|
||||
#define EPI_HB16CFG4_RDWS_2 0x00000000 // Active RDn is 2 EPI clocks
|
||||
#define EPI_HB16CFG4_RDWS_4 0x00000010 // Active RDn is 4 EPI clocks
|
||||
#define EPI_HB16CFG4_RDWS_6 0x00000020 // Active RDn is 6 EPI clocks
|
||||
#define EPI_HB16CFG4_RDWS_8 0x00000030 // Active RDn is 8 EPI clocks
|
||||
#define EPI_HB16CFG4_MODE_M 0x00000003 // CS3n Host Bus Sub-Mode
|
||||
#define EPI_HB16CFG4_MODE_ADMUX 0x00000000 // ADMUX - AD[15:0]
|
||||
#define EPI_HB16CFG4_MODE_AD 0x00000001 // ADNONMUX - D[15:0]
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EPI_O_HB8CFG4 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_HB8CFG4_WRHIGH 0x00200000 // CS3n WRITE Strobe Polarity
|
||||
#define EPI_HB8CFG4_RDHIGH 0x00100000 // CS2n READ Strobe Polarity
|
||||
#define EPI_HB8CFG4_ALEHIGH 0x00080000 // CS3n ALE Strobe Polarity
|
||||
#define EPI_HB8CFG4_WRWS_M 0x000000C0 // CS3n Write Wait States
|
||||
#define EPI_HB8CFG4_WRWS_2 0x00000000 // Active WRn is 2 EPI clocks
|
||||
#define EPI_HB8CFG4_WRWS_4 0x00000040 // Active WRn is 4 EPI clocks
|
||||
#define EPI_HB8CFG4_WRWS_6 0x00000080 // Active WRn is 6 EPI clocks
|
||||
#define EPI_HB8CFG4_WRWS_8 0x000000C0 // Active WRn is 8 EPI clocks
|
||||
#define EPI_HB8CFG4_RDWS_M 0x00000030 // CS3n Read Wait States
|
||||
#define EPI_HB8CFG4_RDWS_2 0x00000000 // Active RDn is 2 EPI clocks
|
||||
#define EPI_HB8CFG4_RDWS_4 0x00000010 // Active RDn is 4 EPI clocks
|
||||
#define EPI_HB8CFG4_RDWS_6 0x00000020 // Active RDn is 6 EPI clocks
|
||||
#define EPI_HB8CFG4_RDWS_8 0x00000030 // Active RDn is 8 EPI clocks
|
||||
#define EPI_HB8CFG4_MODE_M 0x00000003 // CS3n Host Bus Sub-Mode
|
||||
#define EPI_HB8CFG4_MODE_ADMUX 0x00000000 // ADMUX - AD[7:0]
|
||||
#define EPI_HB8CFG4_MODE_AD 0x00000001 // ADNONMUX - D[7:0]
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EPI_O_HB8TIME register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_HB8TIME_IRDYDLY_M 0x03000000 // CS0n Input Ready Delay
|
||||
#define EPI_HB8TIME_CAPWIDTH_M 0x00003000 // CS0n Inter-transfer Capture
|
||||
// Width
|
||||
#define EPI_HB8TIME_WRWSM 0x00000010 // Write Wait State Minus One
|
||||
#define EPI_HB8TIME_RDWSM 0x00000001 // Read Wait State Minus One
|
||||
#define EPI_HB8TIME_IRDYDLY_S 24
|
||||
#define EPI_HB8TIME_CAPWIDTH_S 12
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EPI_O_HB16TIME register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_HB16TIME_IRDYDLY_M 0x03000000 // CS0n Input Ready Delay
|
||||
#define EPI_HB16TIME_PSRAMSZ_M 0x00070000 // PSRAM Row Size
|
||||
#define EPI_HB16TIME_PSRAMSZ_0 0x00000000 // No row size limitation
|
||||
#define EPI_HB16TIME_PSRAMSZ_128B \
|
||||
0x00010000 // 128 B
|
||||
#define EPI_HB16TIME_PSRAMSZ_256B \
|
||||
0x00020000 // 256 B
|
||||
#define EPI_HB16TIME_PSRAMSZ_512B \
|
||||
0x00030000 // 512 B
|
||||
#define EPI_HB16TIME_PSRAMSZ_1KB \
|
||||
0x00040000 // 1024 B
|
||||
#define EPI_HB16TIME_PSRAMSZ_2KB \
|
||||
0x00050000 // 2048 B
|
||||
#define EPI_HB16TIME_PSRAMSZ_4KB \
|
||||
0x00060000 // 4096 B
|
||||
#define EPI_HB16TIME_PSRAMSZ_8KB \
|
||||
0x00070000 // 8192 B
|
||||
#define EPI_HB16TIME_CAPWIDTH_M 0x00003000 // CS0n Inter-transfer Capture
|
||||
// Width
|
||||
#define EPI_HB16TIME_WRWSM 0x00000010 // Write Wait State Minus One
|
||||
#define EPI_HB16TIME_RDWSM 0x00000001 // Read Wait State Minus One
|
||||
#define EPI_HB16TIME_IRDYDLY_S 24
|
||||
#define EPI_HB16TIME_CAPWIDTH_S 12
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EPI_O_HB8TIME2 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_HB8TIME2_IRDYDLY_M 0x03000000 // CS1n Input Ready Delay
|
||||
#define EPI_HB8TIME2_CAPWIDTH_M 0x00003000 // CS1n Inter-transfer Capture
|
||||
// Width
|
||||
#define EPI_HB8TIME2_WRWSM 0x00000010 // CS1n Write Wait State Minus One
|
||||
#define EPI_HB8TIME2_RDWSM 0x00000001 // CS1n Read Wait State Minus One
|
||||
#define EPI_HB8TIME2_IRDYDLY_S 24
|
||||
#define EPI_HB8TIME2_CAPWIDTH_S 12
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EPI_O_HB16TIME2
|
||||
// register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_HB16TIME2_IRDYDLY_M 0x03000000 // CS1n Input Ready Delay
|
||||
#define EPI_HB16TIME2_PSRAMSZ_M 0x00070000 // PSRAM Row Size
|
||||
#define EPI_HB16TIME2_PSRAMSZ_0 0x00000000 // No row size limitation
|
||||
#define EPI_HB16TIME2_PSRAMSZ_128B \
|
||||
0x00010000 // 128 B
|
||||
#define EPI_HB16TIME2_PSRAMSZ_256B \
|
||||
0x00020000 // 256 B
|
||||
#define EPI_HB16TIME2_PSRAMSZ_512B \
|
||||
0x00030000 // 512 B
|
||||
#define EPI_HB16TIME2_PSRAMSZ_1KB \
|
||||
0x00040000 // 1024 B
|
||||
#define EPI_HB16TIME2_PSRAMSZ_2KB \
|
||||
0x00050000 // 2048 B
|
||||
#define EPI_HB16TIME2_PSRAMSZ_4KB \
|
||||
0x00060000 // 4096 B
|
||||
#define EPI_HB16TIME2_PSRAMSZ_8KB \
|
||||
0x00070000 // 8192 B
|
||||
#define EPI_HB16TIME2_CAPWIDTH_M \
|
||||
0x00003000 // CS1n Inter-transfer Capture
|
||||
// Width
|
||||
#define EPI_HB16TIME2_WRWSM 0x00000010 // CS1n Write Wait State Minus One
|
||||
#define EPI_HB16TIME2_RDWSM 0x00000001 // CS1n Read Wait State Minus One
|
||||
#define EPI_HB16TIME2_IRDYDLY_S 24
|
||||
#define EPI_HB16TIME2_CAPWIDTH_S \
|
||||
12
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EPI_O_HB16TIME3
|
||||
// register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_HB16TIME3_IRDYDLY_M 0x03000000 // CS2n Input Ready Delay
|
||||
#define EPI_HB16TIME3_PSRAMSZ_M 0x00070000 // PSRAM Row Size
|
||||
#define EPI_HB16TIME3_PSRAMSZ_0 0x00000000 // No row size limitation
|
||||
#define EPI_HB16TIME3_PSRAMSZ_128B \
|
||||
0x00010000 // 128 B
|
||||
#define EPI_HB16TIME3_PSRAMSZ_256B \
|
||||
0x00020000 // 256 B
|
||||
#define EPI_HB16TIME3_PSRAMSZ_512B \
|
||||
0x00030000 // 512 B
|
||||
#define EPI_HB16TIME3_PSRAMSZ_1KB \
|
||||
0x00040000 // 1024 B
|
||||
#define EPI_HB16TIME3_PSRAMSZ_2KB \
|
||||
0x00050000 // 2048 B
|
||||
#define EPI_HB16TIME3_PSRAMSZ_4KB \
|
||||
0x00060000 // 4096 B
|
||||
#define EPI_HB16TIME3_PSRAMSZ_8KB \
|
||||
0x00070000 // 8192 B
|
||||
#define EPI_HB16TIME3_CAPWIDTH_M \
|
||||
0x00003000 // CS2n Inter-transfer Capture
|
||||
// Width
|
||||
#define EPI_HB16TIME3_WRWSM 0x00000010 // CS2n Write Wait State Minus One
|
||||
#define EPI_HB16TIME3_RDWSM 0x00000001 // CS2n Read Wait State Minus One
|
||||
#define EPI_HB16TIME3_IRDYDLY_S 24
|
||||
#define EPI_HB16TIME3_CAPWIDTH_S \
|
||||
12
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EPI_O_HB8TIME3 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_HB8TIME3_IRDYDLY_M 0x03000000 // CS2n Input Ready Delay
|
||||
#define EPI_HB8TIME3_CAPWIDTH_M 0x00003000 // CS2n Inter-transfer Capture
|
||||
// Width
|
||||
#define EPI_HB8TIME3_WRWSM 0x00000010 // CS2n Write Wait State Minus One
|
||||
#define EPI_HB8TIME3_RDWSM 0x00000001 // CS2n Read Wait State Minus One
|
||||
#define EPI_HB8TIME3_IRDYDLY_S 24
|
||||
#define EPI_HB8TIME3_CAPWIDTH_S 12
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EPI_O_HB8TIME4 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_HB8TIME4_IRDYDLY_M 0x03000000 // CS3n Input Ready Delay
|
||||
#define EPI_HB8TIME4_CAPWIDTH_M 0x00003000 // CS3n Inter-transfer Capture
|
||||
// Width
|
||||
#define EPI_HB8TIME4_WRWSM 0x00000010 // CS3n Write Wait State Minus One
|
||||
#define EPI_HB8TIME4_RDWSM 0x00000001 // CS3n Read Wait State Minus One
|
||||
#define EPI_HB8TIME4_IRDYDLY_S 24
|
||||
#define EPI_HB8TIME4_CAPWIDTH_S 12
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EPI_O_HB16TIME4
|
||||
// register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_HB16TIME4_IRDYDLY_M 0x03000000 // CS3n Input Ready Delay
|
||||
#define EPI_HB16TIME4_PSRAMSZ_M 0x00070000 // PSRAM Row Size
|
||||
#define EPI_HB16TIME4_PSRAMSZ_0 0x00000000 // No row size limitation
|
||||
#define EPI_HB16TIME4_PSRAMSZ_128B \
|
||||
0x00010000 // 128 B
|
||||
#define EPI_HB16TIME4_PSRAMSZ_256B \
|
||||
0x00020000 // 256 B
|
||||
#define EPI_HB16TIME4_PSRAMSZ_512B \
|
||||
0x00030000 // 512 B
|
||||
#define EPI_HB16TIME4_PSRAMSZ_1KB \
|
||||
0x00040000 // 1024 B
|
||||
#define EPI_HB16TIME4_PSRAMSZ_2KB \
|
||||
0x00050000 // 2048 B
|
||||
#define EPI_HB16TIME4_PSRAMSZ_4KB \
|
||||
0x00060000 // 4096 B
|
||||
#define EPI_HB16TIME4_PSRAMSZ_8KB \
|
||||
0x00070000 // 8192 B
|
||||
#define EPI_HB16TIME4_CAPWIDTH_M \
|
||||
0x00003000 // CS3n Inter-transfer Capture
|
||||
// Width
|
||||
#define EPI_HB16TIME4_WRWSM 0x00000010 // CS3n Write Wait State Minus One
|
||||
#define EPI_HB16TIME4_RDWSM 0x00000001 // CS3n Read Wait State Minus One
|
||||
#define EPI_HB16TIME4_IRDYDLY_S 24
|
||||
#define EPI_HB16TIME4_CAPWIDTH_S \
|
||||
12
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the EPI_O_HBPSRAM register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_HBPSRAM_CR_M 0x001FFFFF // PSRAM Config Register
|
||||
#define EPI_HBPSRAM_CR_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following definitions are deprecated.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifndef DEPRECATED
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are deprecated defines for the bit fields in the EPI_O_FIFOLVL
|
||||
// register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define EPI_FIFOLVL_WRFIFO_1_4 0x00000020 // Trigger when there are up to 3
|
||||
// spaces available in the WFIFO
|
||||
#define EPI_FIFOLVL_WRFIFO_1_2 0x00000030 // Trigger when there are up to 2
|
||||
// spaces available in the WFIFO
|
||||
#define EPI_FIFOLVL_WRFIFO_3_4 0x00000040 // Trigger when there is 1 space
|
||||
// available in the WFIFO
|
||||
#define EPI_FIFOLVL_RDFIFO_1_8 0x00000001 // Trigger when there are 1 or more
|
||||
// entries in the NBRFIFO
|
||||
#define EPI_FIFOLVL_RDFIFO_1_4 0x00000002 // Trigger when there are 2 or more
|
||||
// entries in the NBRFIFO
|
||||
#define EPI_FIFOLVL_RDFIFO_1_2 0x00000003 // Trigger when there are 4 or more
|
||||
// entries in the NBRFIFO
|
||||
#define EPI_FIFOLVL_RDFIFO_3_4 0x00000004 // Trigger when there are 6 or more
|
||||
// entries in the NBRFIFO
|
||||
#define EPI_FIFOLVL_RDFIFO_7_8 0x00000005 // Trigger when there are 7 or more
|
||||
// entries in the NBRFIFO
|
||||
#define EPI_FIFOLVL_RDFIFO_FULL 0x00000006 // Trigger when there are 8 entries
|
||||
// in the NBRFIFO
|
||||
|
||||
#endif
|
||||
|
||||
#endif // __HW_EPI_H__
|
|
@ -0,0 +1,49 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// hw_fan.h - Macros used when accessing the fan control hardware.
|
||||
//
|
||||
// Copyright (c) 2010-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Firmware Development Package.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __HW_FAN_H__
|
||||
#define __HW_FAN_H__
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the Fan Control register offsets.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#endif // __HW_FAN_H__
|
|
@ -0,0 +1,625 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// hw_flash.h - Macros used when accessing the flash controller.
|
||||
//
|
||||
// Copyright (c) 2005-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Firmware Development Package.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __HW_FLASH_H__
|
||||
#define __HW_FLASH_H__
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the FLASH register offsets.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FLASH_FMA 0x400FD000 // Flash Memory Address
|
||||
#define FLASH_FMD 0x400FD004 // Flash Memory Data
|
||||
#define FLASH_FMC 0x400FD008 // Flash Memory Control
|
||||
#define FLASH_FCRIS 0x400FD00C // Flash Controller Raw Interrupt
|
||||
// Status
|
||||
#define FLASH_FCIM 0x400FD010 // Flash Controller Interrupt Mask
|
||||
#define FLASH_FCMISC 0x400FD014 // Flash Controller Masked
|
||||
// Interrupt Status and Clear
|
||||
#define FLASH_FMC2 0x400FD020 // Flash Memory Control 2
|
||||
#define FLASH_FWBVAL 0x400FD030 // Flash Write Buffer Valid
|
||||
#define FLASH_FLPEKEY 0x400FD03C // Flash Program/Erase Key
|
||||
#define FLASH_FWBN 0x400FD100 // Flash Write Buffer n
|
||||
#define FLASH_PP 0x400FDFC0 // Flash Peripheral Properties
|
||||
#define FLASH_FSIZE 0x400FDFC0 // Flash Size
|
||||
#define FLASH_SSIZE 0x400FDFC4 // SRAM Size
|
||||
#define FLASH_CONF 0x400FDFC8 // Flash Configuration Register
|
||||
#define FLASH_ROMSWMAP 0x400FDFCC // ROM Software Map
|
||||
#define FLASH_DMASZ 0x400FDFD0 // Flash DMA Address Size
|
||||
#define FLASH_DMAST 0x400FDFD4 // Flash DMA Starting Address
|
||||
#define FLASH_RVP 0x400FE0D4 // Reset Vector Pointer
|
||||
#define FLASH_RMCTL 0x400FE0F0 // ROM Control
|
||||
#define FLASH_BOOTCFG 0x400FE1D0 // Boot Configuration
|
||||
#define FLASH_USERREG0 0x400FE1E0 // User Register 0
|
||||
#define FLASH_USERREG1 0x400FE1E4 // User Register 1
|
||||
#define FLASH_USERREG2 0x400FE1E8 // User Register 2
|
||||
#define FLASH_USERREG3 0x400FE1EC // User Register 3
|
||||
#define FLASH_FMPRE0 0x400FE200 // Flash Memory Protection Read
|
||||
// Enable 0
|
||||
#define FLASH_FMPRE1 0x400FE204 // Flash Memory Protection Read
|
||||
// Enable 1
|
||||
#define FLASH_FMPRE2 0x400FE208 // Flash Memory Protection Read
|
||||
// Enable 2
|
||||
#define FLASH_FMPRE3 0x400FE20C // Flash Memory Protection Read
|
||||
// Enable 3
|
||||
#define FLASH_FMPRE4 0x400FE210 // Flash Memory Protection Read
|
||||
// Enable 4
|
||||
#define FLASH_FMPRE5 0x400FE214 // Flash Memory Protection Read
|
||||
// Enable 5
|
||||
#define FLASH_FMPRE6 0x400FE218 // Flash Memory Protection Read
|
||||
// Enable 6
|
||||
#define FLASH_FMPRE7 0x400FE21C // Flash Memory Protection Read
|
||||
// Enable 7
|
||||
#define FLASH_FMPRE8 0x400FE220 // Flash Memory Protection Read
|
||||
// Enable 8
|
||||
#define FLASH_FMPRE9 0x400FE224 // Flash Memory Protection Read
|
||||
// Enable 9
|
||||
#define FLASH_FMPRE10 0x400FE228 // Flash Memory Protection Read
|
||||
// Enable 10
|
||||
#define FLASH_FMPRE11 0x400FE22C // Flash Memory Protection Read
|
||||
// Enable 11
|
||||
#define FLASH_FMPRE12 0x400FE230 // Flash Memory Protection Read
|
||||
// Enable 12
|
||||
#define FLASH_FMPRE13 0x400FE234 // Flash Memory Protection Read
|
||||
// Enable 13
|
||||
#define FLASH_FMPRE14 0x400FE238 // Flash Memory Protection Read
|
||||
// Enable 14
|
||||
#define FLASH_FMPRE15 0x400FE23C // Flash Memory Protection Read
|
||||
// Enable 15
|
||||
#define FLASH_FMPPE0 0x400FE400 // Flash Memory Protection Program
|
||||
// Enable 0
|
||||
#define FLASH_FMPPE1 0x400FE404 // Flash Memory Protection Program
|
||||
// Enable 1
|
||||
#define FLASH_FMPPE2 0x400FE408 // Flash Memory Protection Program
|
||||
// Enable 2
|
||||
#define FLASH_FMPPE3 0x400FE40C // Flash Memory Protection Program
|
||||
// Enable 3
|
||||
#define FLASH_FMPPE4 0x400FE410 // Flash Memory Protection Program
|
||||
// Enable 4
|
||||
#define FLASH_FMPPE5 0x400FE414 // Flash Memory Protection Program
|
||||
// Enable 5
|
||||
#define FLASH_FMPPE6 0x400FE418 // Flash Memory Protection Program
|
||||
// Enable 6
|
||||
#define FLASH_FMPPE7 0x400FE41C // Flash Memory Protection Program
|
||||
// Enable 7
|
||||
#define FLASH_FMPPE8 0x400FE420 // Flash Memory Protection Program
|
||||
// Enable 8
|
||||
#define FLASH_FMPPE9 0x400FE424 // Flash Memory Protection Program
|
||||
// Enable 9
|
||||
#define FLASH_FMPPE10 0x400FE428 // Flash Memory Protection Program
|
||||
// Enable 10
|
||||
#define FLASH_FMPPE11 0x400FE42C // Flash Memory Protection Program
|
||||
// Enable 11
|
||||
#define FLASH_FMPPE12 0x400FE430 // Flash Memory Protection Program
|
||||
// Enable 12
|
||||
#define FLASH_FMPPE13 0x400FE434 // Flash Memory Protection Program
|
||||
// Enable 13
|
||||
#define FLASH_FMPPE14 0x400FE438 // Flash Memory Protection Program
|
||||
// Enable 14
|
||||
#define FLASH_FMPPE15 0x400FE43C // Flash Memory Protection Program
|
||||
// Enable 15
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the FLASH_FMA register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FLASH_FMA_OFFSET_M 0x000FFFFF // Address Offset
|
||||
#define FLASH_FMA_OFFSET_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the FLASH_FMD register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FLASH_FMD_DATA_M 0xFFFFFFFF // Data Value
|
||||
#define FLASH_FMD_DATA_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the FLASH_FMC register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FLASH_FMC_WRKEY 0xA4420000 // FLASH write key
|
||||
#define FLASH_FMC_COMT 0x00000008 // Commit Register Value
|
||||
#define FLASH_FMC_MERASE 0x00000004 // Mass Erase Flash Memory
|
||||
#define FLASH_FMC_ERASE 0x00000002 // Erase a Page of Flash Memory
|
||||
#define FLASH_FMC_WRITE 0x00000001 // Write a Word into Flash Memory
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the FLASH_FCRIS register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FLASH_FCRIS_PROGRIS 0x00002000 // Program Verify Error Raw
|
||||
// Interrupt Status
|
||||
#define FLASH_FCRIS_ERRIS 0x00000800 // Erase Verify Error Raw Interrupt
|
||||
// Status
|
||||
#define FLASH_FCRIS_INVDRIS 0x00000400 // Invalid Data Raw Interrupt
|
||||
// Status
|
||||
#define FLASH_FCRIS_VOLTRIS 0x00000200 // Pump Voltage Raw Interrupt
|
||||
// Status
|
||||
#define FLASH_FCRIS_ERIS 0x00000004 // EEPROM Raw Interrupt Status
|
||||
#define FLASH_FCRIS_PRIS 0x00000002 // Programming Raw Interrupt Status
|
||||
#define FLASH_FCRIS_ARIS 0x00000001 // Access Raw Interrupt Status
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the FLASH_FCIM register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FLASH_FCIM_PROGMASK 0x00002000 // PROGVER Interrupt Mask
|
||||
#define FLASH_FCIM_ERMASK 0x00000800 // ERVER Interrupt Mask
|
||||
#define FLASH_FCIM_INVDMASK 0x00000400 // Invalid Data Interrupt Mask
|
||||
#define FLASH_FCIM_VOLTMASK 0x00000200 // VOLT Interrupt Mask
|
||||
#define FLASH_FCIM_EMASK 0x00000004 // EEPROM Interrupt Mask
|
||||
#define FLASH_FCIM_PMASK 0x00000002 // Programming Interrupt Mask
|
||||
#define FLASH_FCIM_AMASK 0x00000001 // Access Interrupt Mask
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the FLASH_FCMISC register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FLASH_FCMISC_PROGMISC 0x00002000 // PROGVER Masked Interrupt Status
|
||||
// and Clear
|
||||
#define FLASH_FCMISC_ERMISC 0x00000800 // ERVER Masked Interrupt Status
|
||||
// and Clear
|
||||
#define FLASH_FCMISC_INVDMISC 0x00000400 // Invalid Data Masked Interrupt
|
||||
// Status and Clear
|
||||
#define FLASH_FCMISC_VOLTMISC 0x00000200 // VOLT Masked Interrupt Status and
|
||||
// Clear
|
||||
#define FLASH_FCMISC_EMISC 0x00000004 // EEPROM Masked Interrupt Status
|
||||
// and Clear
|
||||
#define FLASH_FCMISC_PMISC 0x00000002 // Programming Masked Interrupt
|
||||
// Status and Clear
|
||||
#define FLASH_FCMISC_AMISC 0x00000001 // Access Masked Interrupt Status
|
||||
// and Clear
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the FLASH_FMC2 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FLASH_FMC2_WRKEY 0xA4420000 // FLASH write key
|
||||
#define FLASH_FMC2_WRBUF 0x00000001 // Buffered Flash Memory Write
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the FLASH_FWBVAL register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FLASH_FWBVAL_FWB_M 0xFFFFFFFF // Flash Memory Write Buffer
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the FLASH_FLPEKEY register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FLASH_FLPEKEY_PEKEY_M 0x0000FFFF // Key Value
|
||||
#define FLASH_FLPEKEY_PEKEY_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the FLASH_FWBN register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FLASH_FWBN_DATA_M 0xFFFFFFFF // Data
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the FLASH_PP register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FLASH_PP_PFC 0x40000000 // Prefetch Buffer Mode
|
||||
#define FLASH_PP_FMM 0x20000000 // Flash Mirror Mode
|
||||
#define FLASH_PP_DFA 0x10000000 // DMA Flash Access
|
||||
#define FLASH_PP_EESS_M 0x00780000 // EEPROM Sector Size of the
|
||||
// physical bank
|
||||
#define FLASH_PP_EESS_1KB 0x00000000 // 1 KB
|
||||
#define FLASH_PP_EESS_2KB 0x00080000 // 2 KB
|
||||
#define FLASH_PP_EESS_4KB 0x00100000 // 4 KB
|
||||
#define FLASH_PP_EESS_8KB 0x00180000 // 8 KB
|
||||
#define FLASH_PP_MAINSS_M 0x00070000 // Flash Sector Size of the
|
||||
// physical bank
|
||||
#define FLASH_PP_MAINSS_1KB 0x00000000 // 1 KB
|
||||
#define FLASH_PP_MAINSS_2KB 0x00010000 // 2 KB
|
||||
#define FLASH_PP_MAINSS_4KB 0x00020000 // 4 KB
|
||||
#define FLASH_PP_MAINSS_8KB 0x00030000 // 8 KB
|
||||
#define FLASH_PP_MAINSS_16KB 0x00040000 // 16 KB
|
||||
#define FLASH_PP_SIZE_M 0x0000FFFF // Flash Size
|
||||
#define FLASH_PP_SIZE_512KB 0x000000FF // 512 KB of Flash
|
||||
#define FLASH_PP_SIZE_1MB 0x000001FF // 1024 KB of Flash
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the FLASH_FSIZE register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FLASH_FSIZE_SIZE_M 0x0000FFFF // Flash Size
|
||||
#define FLASH_FSIZE_SIZE_32KB 0x0000000F // 32 KB of Flash
|
||||
#define FLASH_FSIZE_SIZE_64KB 0x0000001F // 64 KB of Flash
|
||||
#define FLASH_FSIZE_SIZE_128KB 0x0000003F // 128 KB of Flash
|
||||
#define FLASH_FSIZE_SIZE_256KB 0x0000007F // 256 KB of Flash
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the FLASH_SSIZE register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FLASH_SSIZE_SIZE_M 0x0000FFFF // SRAM Size
|
||||
#define FLASH_SSIZE_SIZE_12KB 0x0000002F // 12 KB of SRAM
|
||||
#define FLASH_SSIZE_SIZE_24KB 0x0000005F // 24 KB of SRAM
|
||||
#define FLASH_SSIZE_SIZE_32KB 0x0000007F // 32 KB of SRAM
|
||||
#define FLASH_SSIZE_SIZE_256KB 0x000003FF // 256 KB of SRAM
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the FLASH_CONF register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FLASH_CONF_FMME 0x40000000 // Flash Mirror Mode Enable
|
||||
#define FLASH_CONF_SPFE 0x20000000 // Single Prefetch Mode Enable
|
||||
#define FLASH_CONF_CLRTV 0x00100000 // Clear Valid Tags
|
||||
#define FLASH_CONF_FPFON 0x00020000 // Force Prefetch On
|
||||
#define FLASH_CONF_FPFOFF 0x00010000 // Force Prefetch Off
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the FLASH_ROMSWMAP register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FLASH_ROMSWMAP_SAFERTOS 0x00000001 // SafeRTOS Present
|
||||
#define FLASH_ROMSWMAP_SW0EN_M 0x00000003 // ROM SW Region 0 Availability
|
||||
#define FLASH_ROMSWMAP_SW0EN_NOTVIS \
|
||||
0x00000000 // Software region not available to
|
||||
// the core
|
||||
#define FLASH_ROMSWMAP_SW0EN_CORE \
|
||||
0x00000001 // Region available to core
|
||||
#define FLASH_ROMSWMAP_SW1EN_M 0x0000000C // ROM SW Region 1 Availability
|
||||
#define FLASH_ROMSWMAP_SW1EN_NOTVIS \
|
||||
0x00000000 // Software region not available to
|
||||
// the core
|
||||
#define FLASH_ROMSWMAP_SW1EN_CORE \
|
||||
0x00000004 // Region available to core
|
||||
#define FLASH_ROMSWMAP_SW2EN_M 0x00000030 // ROM SW Region 2 Availability
|
||||
#define FLASH_ROMSWMAP_SW2EN_NOTVIS \
|
||||
0x00000000 // Software region not available to
|
||||
// the core
|
||||
#define FLASH_ROMSWMAP_SW2EN_CORE \
|
||||
0x00000010 // Region available to core
|
||||
#define FLASH_ROMSWMAP_SW3EN_M 0x000000C0 // ROM SW Region 3 Availability
|
||||
#define FLASH_ROMSWMAP_SW3EN_NOTVIS \
|
||||
0x00000000 // Software region not available to
|
||||
// the core
|
||||
#define FLASH_ROMSWMAP_SW3EN_CORE \
|
||||
0x00000040 // Region available to core
|
||||
#define FLASH_ROMSWMAP_SW4EN_M 0x00000300 // ROM SW Region 4 Availability
|
||||
#define FLASH_ROMSWMAP_SW4EN_NOTVIS \
|
||||
0x00000000 // Software region not available to
|
||||
// the core
|
||||
#define FLASH_ROMSWMAP_SW4EN_CORE \
|
||||
0x00000100 // Region available to core
|
||||
#define FLASH_ROMSWMAP_SW5EN_M 0x00000C00 // ROM SW Region 5 Availability
|
||||
#define FLASH_ROMSWMAP_SW5EN_NOTVIS \
|
||||
0x00000000 // Software region not available to
|
||||
// the core
|
||||
#define FLASH_ROMSWMAP_SW5EN_CORE \
|
||||
0x00000400 // Region available to core
|
||||
#define FLASH_ROMSWMAP_SW6EN_M 0x00003000 // ROM SW Region 6 Availability
|
||||
#define FLASH_ROMSWMAP_SW6EN_NOTVIS \
|
||||
0x00000000 // Software region not available to
|
||||
// the core
|
||||
#define FLASH_ROMSWMAP_SW6EN_CORE \
|
||||
0x00001000 // Region available to core
|
||||
#define FLASH_ROMSWMAP_SW7EN_M 0x0000C000 // ROM SW Region 7 Availability
|
||||
#define FLASH_ROMSWMAP_SW7EN_NOTVIS \
|
||||
0x00000000 // Software region not available to
|
||||
// the core
|
||||
#define FLASH_ROMSWMAP_SW7EN_CORE \
|
||||
0x00004000 // Region available to core
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the FLASH_DMASZ register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FLASH_DMASZ_SIZE_M 0x0003FFFF // uDMA-accessible Memory Size
|
||||
#define FLASH_DMASZ_SIZE_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the FLASH_DMAST register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FLASH_DMAST_ADDR_M 0x1FFFF800 // Contains the starting address of
|
||||
// the flash region accessible by
|
||||
// uDMA if the FLASHPP register DFA
|
||||
// bit is set
|
||||
#define FLASH_DMAST_ADDR_S 11
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the FLASH_RVP register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FLASH_RVP_RV_M 0xFFFFFFFF // Reset Vector Pointer Address
|
||||
#define FLASH_RVP_RV_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the FLASH_RMCTL register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FLASH_RMCTL_BA 0x00000001 // Boot Alias
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the FLASH_BOOTCFG register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FLASH_BOOTCFG_NW 0x80000000 // Not Written
|
||||
#define FLASH_BOOTCFG_PORT_M 0x0000E000 // Boot GPIO Port
|
||||
#define FLASH_BOOTCFG_PORT_A 0x00000000 // Port A
|
||||
#define FLASH_BOOTCFG_PORT_B 0x00002000 // Port B
|
||||
#define FLASH_BOOTCFG_PORT_C 0x00004000 // Port C
|
||||
#define FLASH_BOOTCFG_PORT_D 0x00006000 // Port D
|
||||
#define FLASH_BOOTCFG_PORT_E 0x00008000 // Port E
|
||||
#define FLASH_BOOTCFG_PORT_F 0x0000A000 // Port F
|
||||
#define FLASH_BOOTCFG_PORT_G 0x0000C000 // Port G
|
||||
#define FLASH_BOOTCFG_PORT_H 0x0000E000 // Port H
|
||||
#define FLASH_BOOTCFG_PIN_M 0x00001C00 // Boot GPIO Pin
|
||||
#define FLASH_BOOTCFG_PIN_0 0x00000000 // Pin 0
|
||||
#define FLASH_BOOTCFG_PIN_1 0x00000400 // Pin 1
|
||||
#define FLASH_BOOTCFG_PIN_2 0x00000800 // Pin 2
|
||||
#define FLASH_BOOTCFG_PIN_3 0x00000C00 // Pin 3
|
||||
#define FLASH_BOOTCFG_PIN_4 0x00001000 // Pin 4
|
||||
#define FLASH_BOOTCFG_PIN_5 0x00001400 // Pin 5
|
||||
#define FLASH_BOOTCFG_PIN_6 0x00001800 // Pin 6
|
||||
#define FLASH_BOOTCFG_PIN_7 0x00001C00 // Pin 7
|
||||
#define FLASH_BOOTCFG_POL 0x00000200 // Boot GPIO Polarity
|
||||
#define FLASH_BOOTCFG_EN 0x00000100 // Boot GPIO Enable
|
||||
#define FLASH_BOOTCFG_KEY 0x00000010 // KEY Select
|
||||
#define FLASH_BOOTCFG_DBG1 0x00000002 // Debug Control 1
|
||||
#define FLASH_BOOTCFG_DBG0 0x00000001 // Debug Control 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the FLASH_USERREG0 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FLASH_USERREG0_DATA_M 0xFFFFFFFF // User Data
|
||||
#define FLASH_USERREG0_DATA_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the FLASH_USERREG1 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FLASH_USERREG1_DATA_M 0xFFFFFFFF // User Data
|
||||
#define FLASH_USERREG1_DATA_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the FLASH_USERREG2 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FLASH_USERREG2_DATA_M 0xFFFFFFFF // User Data
|
||||
#define FLASH_USERREG2_DATA_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the FLASH_USERREG3 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FLASH_USERREG3_DATA_M 0xFFFFFFFF // User Data
|
||||
#define FLASH_USERREG3_DATA_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the FLASH_FMPRE8 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FLASH_FMPRE8_READ_ENABLE_M \
|
||||
0xFFFFFFFF // Flash Read Enable
|
||||
#define FLASH_FMPRE8_READ_ENABLE_S \
|
||||
0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the FLASH_FMPRE9 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FLASH_FMPRE9_READ_ENABLE_M \
|
||||
0xFFFFFFFF // Flash Read Enable
|
||||
#define FLASH_FMPRE9_READ_ENABLE_S \
|
||||
0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the FLASH_FMPRE10 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FLASH_FMPRE10_READ_ENABLE_M \
|
||||
0xFFFFFFFF // Flash Read Enable
|
||||
#define FLASH_FMPRE10_READ_ENABLE_S \
|
||||
0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the FLASH_FMPRE11 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FLASH_FMPRE11_READ_ENABLE_M \
|
||||
0xFFFFFFFF // Flash Read Enable
|
||||
#define FLASH_FMPRE11_READ_ENABLE_S \
|
||||
0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the FLASH_FMPRE12 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FLASH_FMPRE12_READ_ENABLE_M \
|
||||
0xFFFFFFFF // Flash Read Enable
|
||||
#define FLASH_FMPRE12_READ_ENABLE_S \
|
||||
0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the FLASH_FMPRE13 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FLASH_FMPRE13_READ_ENABLE_M \
|
||||
0xFFFFFFFF // Flash Read Enable
|
||||
#define FLASH_FMPRE13_READ_ENABLE_S \
|
||||
0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the FLASH_FMPRE14 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FLASH_FMPRE14_READ_ENABLE_M \
|
||||
0xFFFFFFFF // Flash Read Enable
|
||||
#define FLASH_FMPRE14_READ_ENABLE_S \
|
||||
0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the FLASH_FMPRE15 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FLASH_FMPRE15_READ_ENABLE_M \
|
||||
0xFFFFFFFF // Flash Read Enable
|
||||
#define FLASH_FMPRE15_READ_ENABLE_S \
|
||||
0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the FLASH_FMPPE8 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FLASH_FMPPE8_PROG_ENABLE_M \
|
||||
0xFFFFFFFF // Flash Programming Enable
|
||||
#define FLASH_FMPPE8_PROG_ENABLE_S \
|
||||
0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the FLASH_FMPPE9 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FLASH_FMPPE9_PROG_ENABLE_M \
|
||||
0xFFFFFFFF // Flash Programming Enable
|
||||
#define FLASH_FMPPE9_PROG_ENABLE_S \
|
||||
0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the FLASH_FMPPE10 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FLASH_FMPPE10_PROG_ENABLE_M \
|
||||
0xFFFFFFFF // Flash Programming Enable
|
||||
#define FLASH_FMPPE10_PROG_ENABLE_S \
|
||||
0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the FLASH_FMPPE11 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FLASH_FMPPE11_PROG_ENABLE_M \
|
||||
0xFFFFFFFF // Flash Programming Enable
|
||||
#define FLASH_FMPPE11_PROG_ENABLE_S \
|
||||
0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the FLASH_FMPPE12 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FLASH_FMPPE12_PROG_ENABLE_M \
|
||||
0xFFFFFFFF // Flash Programming Enable
|
||||
#define FLASH_FMPPE12_PROG_ENABLE_S \
|
||||
0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the FLASH_FMPPE13 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FLASH_FMPPE13_PROG_ENABLE_M \
|
||||
0xFFFFFFFF // Flash Programming Enable
|
||||
#define FLASH_FMPPE13_PROG_ENABLE_S \
|
||||
0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the FLASH_FMPPE14 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FLASH_FMPPE14_PROG_ENABLE_M \
|
||||
0xFFFFFFFF // Flash Programming Enable
|
||||
#define FLASH_FMPPE14_PROG_ENABLE_S \
|
||||
0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the FLASH_FMPPE15 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FLASH_FMPPE15_PROG_ENABLE_M \
|
||||
0xFFFFFFFF // Flash Programming Enable
|
||||
#define FLASH_FMPPE15_PROG_ENABLE_S \
|
||||
0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the erase size of the FLASH block that is
|
||||
// erased by an erase operation, and the protect size is the size of the FLASH
|
||||
// block that is protected by each protection register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FLASH_PROTECT_SIZE 0x00000800
|
||||
#define FLASH_ERASE_SIZE 0x00000400
|
||||
|
||||
#endif // __HW_FLASH_H__
|
|
@ -0,0 +1,213 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// hw_gpio.h - Defines and Macros for GPIO hardware.
|
||||
//
|
||||
// Copyright (c) 2005-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Firmware Development Package.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __HW_GPIO_H__
|
||||
#define __HW_GPIO_H__
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the GPIO register offsets.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define GPIO_O_DATA 0x00000000 // GPIO Data
|
||||
#define GPIO_O_DIR 0x00000400 // GPIO Direction
|
||||
#define GPIO_O_IS 0x00000404 // GPIO Interrupt Sense
|
||||
#define GPIO_O_IBE 0x00000408 // GPIO Interrupt Both Edges
|
||||
#define GPIO_O_IEV 0x0000040C // GPIO Interrupt Event
|
||||
#define GPIO_O_IM 0x00000410 // GPIO Interrupt Mask
|
||||
#define GPIO_O_RIS 0x00000414 // GPIO Raw Interrupt Status
|
||||
#define GPIO_O_MIS 0x00000418 // GPIO Masked Interrupt Status
|
||||
#define GPIO_O_ICR 0x0000041C // GPIO Interrupt Clear
|
||||
#define GPIO_O_AFSEL 0x00000420 // GPIO Alternate Function Select
|
||||
#define GPIO_O_DR2R 0x00000500 // GPIO 2-mA Drive Select
|
||||
#define GPIO_O_DR4R 0x00000504 // GPIO 4-mA Drive Select
|
||||
#define GPIO_O_DR8R 0x00000508 // GPIO 8-mA Drive Select
|
||||
#define GPIO_O_ODR 0x0000050C // GPIO Open Drain Select
|
||||
#define GPIO_O_PUR 0x00000510 // GPIO Pull-Up Select
|
||||
#define GPIO_O_PDR 0x00000514 // GPIO Pull-Down Select
|
||||
#define GPIO_O_SLR 0x00000518 // GPIO Slew Rate Control Select
|
||||
#define GPIO_O_DEN 0x0000051C // GPIO Digital Enable
|
||||
#define GPIO_O_LOCK 0x00000520 // GPIO Lock
|
||||
#define GPIO_O_CR 0x00000524 // GPIO Commit
|
||||
#define GPIO_O_AMSEL 0x00000528 // GPIO Analog Mode Select
|
||||
#define GPIO_O_PCTL 0x0000052C // GPIO Port Control
|
||||
#define GPIO_O_ADCCTL 0x00000530 // GPIO ADC Control
|
||||
#define GPIO_O_DMACTL 0x00000534 // GPIO DMA Control
|
||||
#define GPIO_O_SI 0x00000538 // GPIO Select Interrupt
|
||||
#define GPIO_O_DR12R 0x0000053C // GPIO 12-mA Drive Select
|
||||
#define GPIO_O_WAKEPEN 0x00000540 // GPIO Wake Pin Enable
|
||||
#define GPIO_O_WAKELVL 0x00000544 // GPIO Wake Level
|
||||
#define GPIO_O_WAKESTAT 0x00000548 // GPIO Wake Status
|
||||
#define GPIO_O_PP 0x00000FC0 // GPIO Peripheral Property
|
||||
#define GPIO_O_PC 0x00000FC4 // GPIO Peripheral Configuration
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the GPIO_O_IM register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define GPIO_IM_DMAIME 0x00000100 // GPIO uDMA Done Interrupt Mask
|
||||
// Enable
|
||||
#define GPIO_IM_GPIO_M 0x000000FF // GPIO Interrupt Mask Enable
|
||||
#define GPIO_IM_GPIO_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the GPIO_O_RIS register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define GPIO_RIS_DMARIS 0x00000100 // GPIO uDMA Done Interrupt Raw
|
||||
// Status
|
||||
#define GPIO_RIS_GPIO_M 0x000000FF // GPIO Interrupt Raw Status
|
||||
#define GPIO_RIS_GPIO_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the GPIO_O_MIS register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define GPIO_MIS_DMAMIS 0x00000100 // GPIO uDMA Done Masked Interrupt
|
||||
// Status
|
||||
#define GPIO_MIS_GPIO_M 0x000000FF // GPIO Masked Interrupt Status
|
||||
#define GPIO_MIS_GPIO_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the GPIO_O_ICR register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define GPIO_ICR_DMAIC 0x00000100 // GPIO uDMA Interrupt Clear
|
||||
#define GPIO_ICR_GPIO_M 0x000000FF // GPIO Interrupt Clear
|
||||
#define GPIO_ICR_GPIO_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the GPIO_O_LOCK register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define GPIO_LOCK_M 0xFFFFFFFF // GPIO Lock
|
||||
#define GPIO_LOCK_UNLOCKED 0x00000000 // The GPIOCR register is unlocked
|
||||
// and may be modified
|
||||
#define GPIO_LOCK_LOCKED 0x00000001 // The GPIOCR register is locked
|
||||
// and may not be modified
|
||||
#define GPIO_LOCK_KEY 0x4C4F434B // Unlocks the GPIO_CR register
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the GPIO_O_SI register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define GPIO_SI_SUM 0x00000001 // Summary Interrupt
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the GPIO_O_DR12R register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define GPIO_DR12R_DRV12_M 0x000000FF // Output Pad 12-mA Drive Enable
|
||||
#define GPIO_DR12R_DRV12_12MA 0x00000001 // The corresponding GPIO pin has
|
||||
// 12-mA drive. This encoding is
|
||||
// only valid if the GPIOPP EDE bit
|
||||
// is set and the appropriate
|
||||
// GPIOPC EDM bit field is
|
||||
// programmed to 0x3
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the GPIO_O_WAKEPEN register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define GPIO_WAKEPEN_WAKEP4 0x00000010 // P[4] Wake Enable
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the GPIO_O_WAKELVL register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define GPIO_WAKELVL_WAKELVL4 0x00000010 // P[4] Wake Level
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the GPIO_O_WAKESTAT
|
||||
// register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define GPIO_WAKESTAT_STAT4 0x00000010 // P[4] Wake Status
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the GPIO_O_PP register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define GPIO_PP_EDE 0x00000001 // Extended Drive Enable
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the GPIO_O_PC register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define GPIO_PC_EDM7_M 0x0000C000 // Extended Drive Mode Bit 7
|
||||
#define GPIO_PC_EDM6_M 0x00003000 // Extended Drive Mode Bit 6
|
||||
#define GPIO_PC_EDM5_M 0x00000C00 // Extended Drive Mode Bit 5
|
||||
#define GPIO_PC_EDM4_M 0x00000300 // Extended Drive Mode Bit 4
|
||||
#define GPIO_PC_EDM3_M 0x000000C0 // Extended Drive Mode Bit 3
|
||||
#define GPIO_PC_EDM2_M 0x00000030 // Extended Drive Mode Bit 2
|
||||
#define GPIO_PC_EDM1_M 0x0000000C // Extended Drive Mode Bit 1
|
||||
#define GPIO_PC_EDM0_M 0x00000003 // Extended Drive Mode Bit 0
|
||||
#define GPIO_PC_EDM0_DISABLE 0x00000000 // Drive values of 2, 4 and 8 mA
|
||||
// are maintained. GPIO n Drive
|
||||
// Select (GPIODRnR) registers
|
||||
// function as normal
|
||||
#define GPIO_PC_EDM0_6MA 0x00000001 // An additional 6 mA option is
|
||||
// provided
|
||||
#define GPIO_PC_EDM0_PLUS2MA 0x00000003 // A 2 mA driver is always enabled;
|
||||
// setting the corresponding
|
||||
// GPIODR4R register bit adds 2 mA
|
||||
// and setting the corresponding
|
||||
// GPIODR8R of GPIODR12R register
|
||||
// bit adds an additional 4 mA
|
||||
#define GPIO_PC_EDM7_S 14
|
||||
#define GPIO_PC_EDM6_S 12
|
||||
#define GPIO_PC_EDM5_S 10
|
||||
#define GPIO_PC_EDM4_S 8
|
||||
#define GPIO_PC_EDM3_S 6
|
||||
#define GPIO_PC_EDM2_S 4
|
||||
#define GPIO_PC_EDM1_S 2
|
||||
|
||||
#endif // __HW_GPIO_H__
|
|
@ -0,0 +1,483 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// hw_hibernate.h - Defines and Macros for the Hibernation module.
|
||||
//
|
||||
// Copyright (c) 2007-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Firmware Development Package.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __HW_HIBERNATE_H__
|
||||
#define __HW_HIBERNATE_H__
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the Hibernation module register addresses.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define HIB_RTCC 0x400FC000 // Hibernation RTC Counter
|
||||
#define HIB_RTCM0 0x400FC004 // Hibernation RTC Match 0
|
||||
#define HIB_RTCLD 0x400FC00C // Hibernation RTC Load
|
||||
#define HIB_CTL 0x400FC010 // Hibernation Control
|
||||
#define HIB_IM 0x400FC014 // Hibernation Interrupt Mask
|
||||
#define HIB_RIS 0x400FC018 // Hibernation Raw Interrupt Status
|
||||
#define HIB_MIS 0x400FC01C // Hibernation Masked Interrupt
|
||||
// Status
|
||||
#define HIB_IC 0x400FC020 // Hibernation Interrupt Clear
|
||||
#define HIB_RTCT 0x400FC024 // Hibernation RTC Trim
|
||||
#define HIB_RTCSS 0x400FC028 // Hibernation RTC Sub Seconds
|
||||
#define HIB_IO 0x400FC02C // Hibernation IO Configuration
|
||||
#define HIB_DATA 0x400FC030 // Hibernation Data
|
||||
#define HIB_CALCTL 0x400FC300 // Hibernation Calendar Control
|
||||
#define HIB_CAL0 0x400FC310 // Hibernation Calendar 0
|
||||
#define HIB_CAL1 0x400FC314 // Hibernation Calendar 1
|
||||
#define HIB_CALLD0 0x400FC320 // Hibernation Calendar Load 0
|
||||
#define HIB_CALLD1 0x400FC324 // Hibernation Calendar Load
|
||||
#define HIB_CALM0 0x400FC330 // Hibernation Calendar Match 0
|
||||
#define HIB_CALM1 0x400FC334 // Hibernation Calendar Match 1
|
||||
#define HIB_LOCK 0x400FC360 // Hibernation Lock
|
||||
#define HIB_TPCTL 0x400FC400 // HIB Tamper Control
|
||||
#define HIB_TPSTAT 0x400FC404 // HIB Tamper Status
|
||||
#define HIB_TPIO 0x400FC410 // HIB Tamper I/O Control
|
||||
#define HIB_TPLOG0 0x400FC4E0 // HIB Tamper Log 0
|
||||
#define HIB_TPLOG1 0x400FC4E4 // HIB Tamper Log 1
|
||||
#define HIB_TPLOG2 0x400FC4E8 // HIB Tamper Log 2
|
||||
#define HIB_TPLOG3 0x400FC4EC // HIB Tamper Log 3
|
||||
#define HIB_TPLOG4 0x400FC4F0 // HIB Tamper Log 4
|
||||
#define HIB_TPLOG5 0x400FC4F4 // HIB Tamper Log 5
|
||||
#define HIB_TPLOG6 0x400FC4F8 // HIB Tamper Log 6
|
||||
#define HIB_TPLOG7 0x400FC4FC // HIB Tamper Log 7
|
||||
#define HIB_PP 0x400FCFC0 // Hibernation Peripheral
|
||||
// Properties
|
||||
#define HIB_CC 0x400FCFC8 // Hibernation Clock Control
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the HIB_RTCC register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define HIB_RTCC_M 0xFFFFFFFF // RTC Counter
|
||||
#define HIB_RTCC_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the HIB_RTCM0 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define HIB_RTCM0_M 0xFFFFFFFF // RTC Match 0
|
||||
#define HIB_RTCM0_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the HIB_RTCLD register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define HIB_RTCLD_M 0xFFFFFFFF // RTC Load
|
||||
#define HIB_RTCLD_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the HIB_CTL register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define HIB_CTL_WRC 0x80000000 // Write Complete/Capable
|
||||
#define HIB_CTL_RETCLR 0x40000000 // GPIO Retention/Clear
|
||||
#define HIB_CTL_OSCSEL 0x00080000 // Oscillator Select
|
||||
#define HIB_CTL_OSCDRV 0x00020000 // Oscillator Drive Capability
|
||||
#define HIB_CTL_OSCBYP 0x00010000 // Oscillator Bypass
|
||||
#define HIB_CTL_VBATSEL_M 0x00006000 // Select for Low-Battery
|
||||
// Comparator
|
||||
#define HIB_CTL_VBATSEL_1_9V 0x00000000 // 1.9 Volts
|
||||
#define HIB_CTL_VBATSEL_2_1V 0x00002000 // 2.1 Volts (default)
|
||||
#define HIB_CTL_VBATSEL_2_3V 0x00004000 // 2.3 Volts
|
||||
#define HIB_CTL_VBATSEL_2_5V 0x00006000 // 2.5 Volts
|
||||
#define HIB_CTL_BATCHK 0x00000400 // Check Battery Status
|
||||
#define HIB_CTL_BATWKEN 0x00000200 // Wake on Low Battery
|
||||
#define HIB_CTL_VDD3ON 0x00000100 // VDD Powered
|
||||
#define HIB_CTL_VABORT 0x00000080 // Power Cut Abort Enable
|
||||
#define HIB_CTL_CLK32EN 0x00000040 // Clocking Enable
|
||||
#define HIB_CTL_PINWEN 0x00000010 // External Wake Pin Enable
|
||||
#define HIB_CTL_RTCWEN 0x00000008 // RTC Wake-up Enable
|
||||
#define HIB_CTL_HIBREQ 0x00000002 // Hibernation Request
|
||||
#define HIB_CTL_RTCEN 0x00000001 // RTC Timer Enable
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the HIB_IM register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define HIB_IM_VDDFAIL 0x00000080 // VDD Fail Interrupt Mask
|
||||
#define HIB_IM_RSTWK 0x00000040 // Reset Pad I/O Wake-Up Interrupt
|
||||
// Mask
|
||||
#define HIB_IM_PADIOWK 0x00000020 // Pad I/O Wake-Up Interrupt Mask
|
||||
#define HIB_IM_WC 0x00000010 // External Write Complete/Capable
|
||||
// Interrupt Mask
|
||||
#define HIB_IM_EXTW 0x00000008 // External Wake-Up Interrupt Mask
|
||||
#define HIB_IM_LOWBAT 0x00000004 // Low Battery Voltage Interrupt
|
||||
// Mask
|
||||
#define HIB_IM_RTCALT0 0x00000001 // RTC Alert 0 Interrupt Mask
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the HIB_RIS register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define HIB_RIS_VDDFAIL 0x00000080 // VDD Fail Raw Interrupt Status
|
||||
#define HIB_RIS_RSTWK 0x00000040 // Reset Pad I/O Wake-Up Raw
|
||||
// Interrupt Status
|
||||
#define HIB_RIS_PADIOWK 0x00000020 // Pad I/O Wake-Up Raw Interrupt
|
||||
// Status
|
||||
#define HIB_RIS_WC 0x00000010 // Write Complete/Capable Raw
|
||||
// Interrupt Status
|
||||
#define HIB_RIS_EXTW 0x00000008 // External Wake-Up Raw Interrupt
|
||||
// Status
|
||||
#define HIB_RIS_LOWBAT 0x00000004 // Low Battery Voltage Raw
|
||||
// Interrupt Status
|
||||
#define HIB_RIS_RTCALT0 0x00000001 // RTC Alert 0 Raw Interrupt Status
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the HIB_MIS register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define HIB_MIS_VDDFAIL 0x00000080 // VDD Fail Interrupt Mask
|
||||
#define HIB_MIS_RSTWK 0x00000040 // Reset Pad I/O Wake-Up Interrupt
|
||||
// Mask
|
||||
#define HIB_MIS_PADIOWK 0x00000020 // Pad I/O Wake-Up Interrupt Mask
|
||||
#define HIB_MIS_WC 0x00000010 // Write Complete/Capable Masked
|
||||
// Interrupt Status
|
||||
#define HIB_MIS_EXTW 0x00000008 // External Wake-Up Masked
|
||||
// Interrupt Status
|
||||
#define HIB_MIS_LOWBAT 0x00000004 // Low Battery Voltage Masked
|
||||
// Interrupt Status
|
||||
#define HIB_MIS_RTCALT0 0x00000001 // RTC Alert 0 Masked Interrupt
|
||||
// Status
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the HIB_IC register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define HIB_IC_VDDFAIL 0x00000080 // VDD Fail Interrupt Clear
|
||||
#define HIB_IC_RSTWK 0x00000040 // Reset Pad I/O Wake-Up Interrupt
|
||||
// Clear
|
||||
#define HIB_IC_PADIOWK 0x00000020 // Pad I/O Wake-Up Interrupt Clear
|
||||
#define HIB_IC_WC 0x00000010 // Write Complete/Capable Interrupt
|
||||
// Clear
|
||||
#define HIB_IC_EXTW 0x00000008 // External Wake-Up Interrupt Clear
|
||||
#define HIB_IC_LOWBAT 0x00000004 // Low Battery Voltage Interrupt
|
||||
// Clear
|
||||
#define HIB_IC_RTCALT0 0x00000001 // RTC Alert0 Masked Interrupt
|
||||
// Clear
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the HIB_RTCT register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define HIB_RTCT_TRIM_M 0x0000FFFF // RTC Trim Value
|
||||
#define HIB_RTCT_TRIM_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the HIB_RTCSS register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define HIB_RTCSS_RTCSSM_M 0x7FFF0000 // RTC Sub Seconds Match
|
||||
#define HIB_RTCSS_RTCSSC_M 0x00007FFF // RTC Sub Seconds Count
|
||||
#define HIB_RTCSS_RTCSSM_S 16
|
||||
#define HIB_RTCSS_RTCSSC_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the HIB_IO register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define HIB_IO_IOWRC 0x80000000 // I/O Write Complete
|
||||
#define HIB_IO_WURSTEN 0x00000010 // Reset Wake Source Enable
|
||||
#define HIB_IO_WUUNLK 0x00000001 // I/O Wake Pad Configuration
|
||||
// Enable
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the HIB_DATA register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define HIB_DATA_RTD_M 0xFFFFFFFF // Hibernation Module NV Data
|
||||
#define HIB_DATA_RTD_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the HIB_CALCTL register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define HIB_CALCTL_CAL24 0x00000004 // Calendar Mode
|
||||
#define HIB_CALCTL_CALEN 0x00000001 // RTC Calendar/Counter Mode Select
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the HIB_CAL0 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define HIB_CAL0_VALID 0x80000000 // Valid Calendar Load
|
||||
#define HIB_CAL0_AMPM 0x00400000 // AM/PM Designation
|
||||
#define HIB_CAL0_HR_M 0x001F0000 // Hours
|
||||
#define HIB_CAL0_MIN_M 0x00003F00 // Minutes
|
||||
#define HIB_CAL0_SEC_M 0x0000003F // Seconds
|
||||
#define HIB_CAL0_HR_S 16
|
||||
#define HIB_CAL0_MIN_S 8
|
||||
#define HIB_CAL0_SEC_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the HIB_CAL1 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define HIB_CAL1_VALID 0x80000000 // Valid Calendar Load
|
||||
#define HIB_CAL1_DOW_M 0x07000000 // Day of Week
|
||||
#define HIB_CAL1_YEAR_M 0x007F0000 // Year Value
|
||||
#define HIB_CAL1_MON_M 0x00000F00 // Month
|
||||
#define HIB_CAL1_DOM_M 0x0000001F // Day of Month
|
||||
#define HIB_CAL1_DOW_S 24
|
||||
#define HIB_CAL1_YEAR_S 16
|
||||
#define HIB_CAL1_MON_S 8
|
||||
#define HIB_CAL1_DOM_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the HIB_CALLD0 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define HIB_CALLD0_AMPM 0x00400000 // AM/PM Designation
|
||||
#define HIB_CALLD0_HR_M 0x001F0000 // Hours
|
||||
#define HIB_CALLD0_MIN_M 0x00003F00 // Minutes
|
||||
#define HIB_CALLD0_SEC_M 0x0000003F // Seconds
|
||||
#define HIB_CALLD0_HR_S 16
|
||||
#define HIB_CALLD0_MIN_S 8
|
||||
#define HIB_CALLD0_SEC_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the HIB_CALLD1 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define HIB_CALLD1_DOW_M 0x07000000 // Day of Week
|
||||
#define HIB_CALLD1_YEAR_M 0x007F0000 // Year Value
|
||||
#define HIB_CALLD1_MON_M 0x00000F00 // Month
|
||||
#define HIB_CALLD1_DOM_M 0x0000001F // Day of Month
|
||||
#define HIB_CALLD1_DOW_S 24
|
||||
#define HIB_CALLD1_YEAR_S 16
|
||||
#define HIB_CALLD1_MON_S 8
|
||||
#define HIB_CALLD1_DOM_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the HIB_CALM0 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define HIB_CALM0_AMPM 0x00400000 // AM/PM Designation
|
||||
#define HIB_CALM0_HR_M 0x001F0000 // Hours
|
||||
#define HIB_CALM0_MIN_M 0x00003F00 // Minutes
|
||||
#define HIB_CALM0_SEC_M 0x0000003F // Seconds
|
||||
#define HIB_CALM0_HR_S 16
|
||||
#define HIB_CALM0_MIN_S 8
|
||||
#define HIB_CALM0_SEC_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the HIB_CALM1 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define HIB_CALM1_DOM_M 0x0000001F // Day of Month
|
||||
#define HIB_CALM1_DOM_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the HIB_LOCK register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define HIB_LOCK_HIBLOCK_M 0xFFFFFFFF // HIbernate Lock
|
||||
#define HIB_LOCK_HIBLOCK_KEY 0xA3359554 // Hibernate Lock Key
|
||||
#define HIB_LOCK_HIBLOCK_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the HIB_TPCTL register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define HIB_TPCTL_WAKE 0x00000800 // Wake from Hibernate on a Tamper
|
||||
// Event
|
||||
#define HIB_TPCTL_MEMCLR_M 0x00000300 // HIB Memory Clear on Tamper Event
|
||||
#define HIB_TPCTL_MEMCLR_NONE 0x00000000 // Do not Clear HIB memory on
|
||||
// tamper event
|
||||
#define HIB_TPCTL_MEMCLR_LOW32 0x00000100 // Clear Lower 32 Bytes of HIB
|
||||
// memory on tamper event
|
||||
#define HIB_TPCTL_MEMCLR_HIGH32 0x00000200 // Clear upper 32 Bytes of HIB
|
||||
// memory on tamper event
|
||||
#define HIB_TPCTL_MEMCLR_ALL 0x00000300 // Clear all HIB memory on tamper
|
||||
// event
|
||||
#define HIB_TPCTL_TPCLR 0x00000010 // Tamper Event Clear
|
||||
#define HIB_TPCTL_TPEN 0x00000001 // Tamper Module Enable
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the HIB_TPSTAT register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define HIB_TPSTAT_STATE_M 0x0000000C // Tamper Module Status
|
||||
#define HIB_TPSTAT_STATE_DISABLED \
|
||||
0x00000000 // Tamper disabled
|
||||
#define HIB_TPSTAT_STATE_CONFIGED \
|
||||
0x00000004 // Tamper configured
|
||||
#define HIB_TPSTAT_STATE_ERROR 0x00000008 // Tamper pin event occurred
|
||||
#define HIB_TPSTAT_XOSCST 0x00000002 // External Oscillator Status
|
||||
#define HIB_TPSTAT_XOSCFAIL 0x00000001 // External Oscillator Failure
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the HIB_TPIO register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define HIB_TPIO_GFLTR3 0x08000000 // TMPR3 Glitch Filtering
|
||||
#define HIB_TPIO_PUEN3 0x04000000 // TMPR3 Internal Weak Pull-up
|
||||
// Enable
|
||||
#define HIB_TPIO_LEV3 0x02000000 // TMPR3 Trigger Level
|
||||
#define HIB_TPIO_EN3 0x01000000 // TMPR3 Enable
|
||||
#define HIB_TPIO_GFLTR2 0x00080000 // TMPR2 Glitch Filtering
|
||||
#define HIB_TPIO_PUEN2 0x00040000 // TMPR2 Internal Weak Pull-up
|
||||
// Enable
|
||||
#define HIB_TPIO_LEV2 0x00020000 // TMPR2 Trigger Level
|
||||
#define HIB_TPIO_EN2 0x00010000 // TMPR2 Enable
|
||||
#define HIB_TPIO_GFLTR1 0x00000800 // TMPR1 Glitch Filtering
|
||||
#define HIB_TPIO_PUEN1 0x00000400 // TMPR1 Internal Weak Pull-up
|
||||
// Enable
|
||||
#define HIB_TPIO_LEV1 0x00000200 // TMPR1 Trigger Level
|
||||
#define HIB_TPIO_EN1 0x00000100 // TMPR1Enable
|
||||
#define HIB_TPIO_GFLTR0 0x00000008 // TMPR0 Glitch Filtering
|
||||
#define HIB_TPIO_PUEN0 0x00000004 // TMPR0 Internal Weak Pull-up
|
||||
// Enable
|
||||
#define HIB_TPIO_LEV0 0x00000002 // TMPR0 Trigger Level
|
||||
#define HIB_TPIO_EN0 0x00000001 // TMPR0 Enable
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the HIB_TPLOG0 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define HIB_TPLOG0_TIME_M 0xFFFFFFFF // Tamper Log Calendar Information
|
||||
#define HIB_TPLOG0_TIME_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the HIB_TPLOG1 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define HIB_TPLOG1_XOSC 0x00010000 // Status of external 32
|
||||
#define HIB_TPLOG1_TRIG3 0x00000008 // Status of TMPR[3] Trigger
|
||||
#define HIB_TPLOG1_TRIG2 0x00000004 // Status of TMPR[2] Trigger
|
||||
#define HIB_TPLOG1_TRIG1 0x00000002 // Status of TMPR[1] Trigger
|
||||
#define HIB_TPLOG1_TRIG0 0x00000001 // Status of TMPR[0] Trigger
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the HIB_TPLOG2 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define HIB_TPLOG2_TIME_M 0xFFFFFFFF // Tamper Log Calendar Information
|
||||
#define HIB_TPLOG2_TIME_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the HIB_TPLOG3 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define HIB_TPLOG3_XOSC 0x00010000 // Status of external 32
|
||||
#define HIB_TPLOG3_TRIG3 0x00000008 // Status of TMPR[3] Trigger
|
||||
#define HIB_TPLOG3_TRIG2 0x00000004 // Status of TMPR[2] Trigger
|
||||
#define HIB_TPLOG3_TRIG1 0x00000002 // Status of TMPR[1] Trigger
|
||||
#define HIB_TPLOG3_TRIG0 0x00000001 // Status of TMPR[0] Trigger
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the HIB_TPLOG4 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define HIB_TPLOG4_TIME_M 0xFFFFFFFF // Tamper Log Calendar Information
|
||||
#define HIB_TPLOG4_TIME_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the HIB_TPLOG5 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define HIB_TPLOG5_XOSC 0x00010000 // Status of external 32
|
||||
#define HIB_TPLOG5_TRIG3 0x00000008 // Status of TMPR[3] Trigger
|
||||
#define HIB_TPLOG5_TRIG2 0x00000004 // Status of TMPR[2] Trigger
|
||||
#define HIB_TPLOG5_TRIG1 0x00000002 // Status of TMPR[1] Trigger
|
||||
#define HIB_TPLOG5_TRIG0 0x00000001 // Status of TMPR[0] Trigger
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the HIB_TPLOG6 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define HIB_TPLOG6_TIME_M 0xFFFFFFFF // Tamper Log Calendar Information
|
||||
#define HIB_TPLOG6_TIME_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the HIB_TPLOG7 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define HIB_TPLOG7_XOSC 0x00010000 // Status of external 32
|
||||
#define HIB_TPLOG7_TRIG3 0x00000008 // Status of TMPR[3] Trigger
|
||||
#define HIB_TPLOG7_TRIG2 0x00000004 // Status of TMPR[2] Trigger
|
||||
#define HIB_TPLOG7_TRIG1 0x00000002 // Status of TMPR[1] Trigger
|
||||
#define HIB_TPLOG7_TRIG0 0x00000001 // Status of TMPR[0] Trigger
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the HIB_PP register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define HIB_PP_TAMPER 0x00000002 // Tamper Pin Presence
|
||||
#define HIB_PP_WAKENC 0x00000001 // Wake Pin Presence
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the HIB_CC register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define HIB_CC_SYSCLKEN 0x00000001 // RTCOSC to System Clock Enable
|
||||
|
||||
#endif // __HW_HIBERNATE_H__
|
|
@ -0,0 +1,470 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// hw_i2c.h - Macros used when accessing the I2C master and slave hardware.
|
||||
//
|
||||
// Copyright (c) 2005-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Firmware Development Package.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __HW_I2C_H__
|
||||
#define __HW_I2C_H__
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the I2C register offsets.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define I2C_O_MSA 0x00000000 // I2C Master Slave Address
|
||||
#define I2C_O_MCS 0x00000004 // I2C Master Control/Status
|
||||
#define I2C_O_MDR 0x00000008 // I2C Master Data
|
||||
#define I2C_O_MTPR 0x0000000C // I2C Master Timer Period
|
||||
#define I2C_O_MIMR 0x00000010 // I2C Master Interrupt Mask
|
||||
#define I2C_O_MRIS 0x00000014 // I2C Master Raw Interrupt Status
|
||||
#define I2C_O_MMIS 0x00000018 // I2C Master Masked Interrupt
|
||||
// Status
|
||||
#define I2C_O_MICR 0x0000001C // I2C Master Interrupt Clear
|
||||
#define I2C_O_MCR 0x00000020 // I2C Master Configuration
|
||||
#define I2C_O_MCLKOCNT 0x00000024 // I2C Master Clock Low Timeout
|
||||
// Count
|
||||
#define I2C_O_MBMON 0x0000002C // I2C Master Bus Monitor
|
||||
#define I2C_O_MBLEN 0x00000030 // I2C Master Burst Length
|
||||
#define I2C_O_MBCNT 0x00000034 // I2C Master Burst Count
|
||||
#define I2C_O_MCR2 0x00000038 // I2C Master Configuration 2
|
||||
#define I2C_O_SOAR 0x00000800 // I2C Slave Own Address
|
||||
#define I2C_O_SCSR 0x00000804 // I2C Slave Control/Status
|
||||
#define I2C_O_SDR 0x00000808 // I2C Slave Data
|
||||
#define I2C_O_SIMR 0x0000080C // I2C Slave Interrupt Mask
|
||||
#define I2C_O_SRIS 0x00000810 // I2C Slave Raw Interrupt Status
|
||||
#define I2C_O_SMIS 0x00000814 // I2C Slave Masked Interrupt
|
||||
// Status
|
||||
#define I2C_O_SICR 0x00000818 // I2C Slave Interrupt Clear
|
||||
#define I2C_O_SOAR2 0x0000081C // I2C Slave Own Address 2
|
||||
#define I2C_O_SACKCTL 0x00000820 // I2C Slave ACK Control
|
||||
#define I2C_O_FIFODATA 0x00000F00 // I2C FIFO Data
|
||||
#define I2C_O_FIFOCTL 0x00000F04 // I2C FIFO Control
|
||||
#define I2C_O_FIFOSTATUS 0x00000F08 // I2C FIFO Status
|
||||
#define I2C_O_PP 0x00000FC0 // I2C Peripheral Properties
|
||||
#define I2C_O_PC 0x00000FC4 // I2C Peripheral Configuration
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// 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_RS 0x00000001 // Receive not send
|
||||
#define I2C_MSA_SA_S 1
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// 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_BURST 0x00000040 // Burst Enable
|
||||
#define I2C_MCS_BUSBSY 0x00000040 // Bus Busy
|
||||
#define I2C_MCS_IDLE 0x00000020 // I2C Idle
|
||||
#define I2C_MCS_QCMD 0x00000020 // Quick Command
|
||||
#define I2C_MCS_ARBLST 0x00000010 // Arbitration Lost
|
||||
#define I2C_MCS_HS 0x00000010 // High-Speed Enable
|
||||
#define I2C_MCS_ACK 0x00000008 // Data Acknowledge Enable
|
||||
#define I2C_MCS_DATACK 0x00000008 // Acknowledge Data
|
||||
#define I2C_MCS_ADRACK 0x00000004 // Acknowledge Address
|
||||
#define I2C_MCS_STOP 0x00000004 // Generate STOP
|
||||
#define I2C_MCS_ERROR 0x00000002 // Error
|
||||
#define I2C_MCS_START 0x00000002 // Generate START
|
||||
#define I2C_MCS_RUN 0x00000001 // I2C Master Enable
|
||||
#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 // This byte contains the data
|
||||
// transferred during a transaction
|
||||
#define I2C_MDR_DATA_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the I2C_O_MTPR register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define I2C_MTPR_PULSEL_M 0x00070000 // Glitch Suppression Pulse Width
|
||||
#define I2C_MTPR_PULSEL_BYPASS 0x00000000 // Bypass
|
||||
#define I2C_MTPR_PULSEL_1 0x00010000 // 1 clock
|
||||
#define I2C_MTPR_PULSEL_2 0x00020000 // 2 clocks
|
||||
#define I2C_MTPR_PULSEL_3 0x00030000 // 3 clocks
|
||||
#define I2C_MTPR_PULSEL_4 0x00040000 // 4 clocks
|
||||
#define I2C_MTPR_PULSEL_8 0x00050000 // 8 clocks
|
||||
#define I2C_MTPR_PULSEL_16 0x00060000 // 16 clocks
|
||||
#define I2C_MTPR_PULSEL_31 0x00070000 // 31 clocks
|
||||
#define I2C_MTPR_HS 0x00000080 // High-Speed Enable
|
||||
#define I2C_MTPR_TPR_M 0x0000007F // Timer 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_GFE 0x00000040 // I2C Glitch Filter Enable
|
||||
#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_MCR2 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define I2C_MCR2_GFPW_M 0x00000070 // I2C Glitch Filter Pulse Width
|
||||
#define I2C_MCR2_GFPW_BYPASS 0x00000000 // Bypass
|
||||
#define I2C_MCR2_GFPW_1 0x00000010 // 1 clock
|
||||
#define I2C_MCR2_GFPW_2 0x00000020 // 2 clocks
|
||||
#define I2C_MCR2_GFPW_3 0x00000030 // 3 clocks
|
||||
#define I2C_MCR2_GFPW_4 0x00000040 // 4 clocks
|
||||
#define I2C_MCR2_GFPW_8 0x00000050 // 8 clocks
|
||||
#define I2C_MCR2_GFPW_16 0x00000060 // 16 clocks
|
||||
#define I2C_MCR2_GFPW_31 0x00000070 // 31 clocks
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// 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_RXFIFO 0x00000004 // RX FIFO Enable
|
||||
#define I2C_SCSR_TXFIFO 0x00000002 // TX FIFO Enable
|
||||
#define I2C_SCSR_TREQ 0x00000002 // Transmit Request
|
||||
#define I2C_SCSR_DA 0x00000001 // Device Active
|
||||
#define I2C_SCSR_RREQ 0x00000001 // Receive Request
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// 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_RXFFIM 0x00000100 // Receive FIFO Full 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_RXFFRIS 0x00000100 // Receive FIFO Full 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 TX FIFO Write 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_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_RXTRIG_S 16
|
||||
#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_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
|
||||
|
||||
#endif // __HW_I2C_H__
|
|
@ -0,0 +1,491 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// hw_ints.h - Macros that define the interrupt assignment on Tiva C Series
|
||||
// MCUs.
|
||||
//
|
||||
// Copyright (c) 2005-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Firmware Development Package.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#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
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// TM4C123 Class Interrupts
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define INT_GPIOA_TM4C123 16 // GPIO Port A
|
||||
#define INT_GPIOB_TM4C123 17 // GPIO Port B
|
||||
#define INT_GPIOC_TM4C123 18 // GPIO Port C
|
||||
#define INT_GPIOD_TM4C123 19 // GPIO Port D
|
||||
#define INT_GPIOE_TM4C123 20 // GPIO Port E
|
||||
#define INT_UART0_TM4C123 21 // UART0
|
||||
#define INT_UART1_TM4C123 22 // UART1
|
||||
#define INT_SSI0_TM4C123 23 // SSI0
|
||||
#define INT_I2C0_TM4C123 24 // I2C0
|
||||
#define INT_PWM0_FAULT_TM4C123 25 // PWM0 Fault
|
||||
#define INT_PWM0_0_TM4C123 26 // PWM0 Generator 0
|
||||
#define INT_PWM0_1_TM4C123 27 // PWM0 Generator 1
|
||||
#define INT_PWM0_2_TM4C123 28 // PWM0 Generator 2
|
||||
#define INT_QEI0_TM4C123 29 // QEI0
|
||||
#define INT_ADC0SS0_TM4C123 30 // ADC0 Sequence 0
|
||||
#define INT_ADC0SS1_TM4C123 31 // ADC0 Sequence 1
|
||||
#define INT_ADC0SS2_TM4C123 32 // ADC0 Sequence 2
|
||||
#define INT_ADC0SS3_TM4C123 33 // ADC0 Sequence 3
|
||||
#define INT_WATCHDOG_TM4C123 34 // Watchdog Timers 0 and 1
|
||||
#define INT_TIMER0A_TM4C123 35 // 16/32-Bit Timer 0A
|
||||
#define INT_TIMER0B_TM4C123 36 // 16/32-Bit Timer 0B
|
||||
#define INT_TIMER1A_TM4C123 37 // 16/32-Bit Timer 1A
|
||||
#define INT_TIMER1B_TM4C123 38 // 16/32-Bit Timer 1B
|
||||
#define INT_TIMER2A_TM4C123 39 // 16/32-Bit Timer 2A
|
||||
#define INT_TIMER2B_TM4C123 40 // 16/32-Bit Timer 2B
|
||||
#define INT_COMP0_TM4C123 41 // Analog Comparator 0
|
||||
#define INT_COMP1_TM4C123 42 // Analog Comparator 1
|
||||
#define INT_COMP2_TM4C123 43 // Analog Comparator 2
|
||||
#define INT_SYSCTL_TM4C123 44 // System Control
|
||||
#define INT_FLASH_TM4C123 45 // Flash Memory Control and EEPROM
|
||||
// Control
|
||||
#define INT_GPIOF_TM4C123 46 // GPIO Port F
|
||||
#define INT_GPIOG_TM4C123 47 // GPIO Port G
|
||||
#define INT_GPIOH_TM4C123 48 // GPIO Port H
|
||||
#define INT_UART2_TM4C123 49 // UART2
|
||||
#define INT_SSI1_TM4C123 50 // SSI1
|
||||
#define INT_TIMER3A_TM4C123 51 // 16/32-Bit Timer 3A
|
||||
#define INT_TIMER3B_TM4C123 52 // Timer 3B
|
||||
#define INT_I2C1_TM4C123 53 // I2C1
|
||||
#define INT_QEI1_TM4C123 54 // QEI1
|
||||
#define INT_CAN0_TM4C123 55 // CAN0
|
||||
#define INT_CAN1_TM4C123 56 // CAN1
|
||||
#define INT_HIBERNATE_TM4C123 59 // Hibernation Module
|
||||
#define INT_USB0_TM4C123 60 // USB
|
||||
#define INT_PWM0_3_TM4C123 61 // PWM Generator 3
|
||||
#define INT_UDMA_TM4C123 62 // uDMA Software
|
||||
#define INT_UDMAERR_TM4C123 63 // uDMA Error
|
||||
#define INT_ADC1SS0_TM4C123 64 // ADC1 Sequence 0
|
||||
#define INT_ADC1SS1_TM4C123 65 // ADC1 Sequence 1
|
||||
#define INT_ADC1SS2_TM4C123 66 // ADC1 Sequence 2
|
||||
#define INT_ADC1SS3_TM4C123 67 // ADC1 Sequence 3
|
||||
#define INT_GPIOJ_TM4C123 70 // GPIO Port J
|
||||
#define INT_GPIOK_TM4C123 71 // GPIO Port K
|
||||
#define INT_GPIOL_TM4C123 72 // GPIO Port L
|
||||
#define INT_SSI2_TM4C123 73 // SSI2
|
||||
#define INT_SSI3_TM4C123 74 // SSI3
|
||||
#define INT_UART3_TM4C123 75 // UART3
|
||||
#define INT_UART4_TM4C123 76 // UART4
|
||||
#define INT_UART5_TM4C123 77 // UART5
|
||||
#define INT_UART6_TM4C123 78 // UART6
|
||||
#define INT_UART7_TM4C123 79 // UART7
|
||||
#define INT_I2C2_TM4C123 84 // I2C2
|
||||
#define INT_I2C3_TM4C123 85 // I2C3
|
||||
#define INT_TIMER4A_TM4C123 86 // 16/32-Bit Timer 4A
|
||||
#define INT_TIMER4B_TM4C123 87 // 16/32-Bit Timer 4B
|
||||
#define INT_TIMER5A_TM4C123 108 // 16/32-Bit Timer 5A
|
||||
#define INT_TIMER5B_TM4C123 109 // 16/32-Bit Timer 5B
|
||||
#define INT_WTIMER0A_TM4C123 110 // 32/64-Bit Timer 0A
|
||||
#define INT_WTIMER0B_TM4C123 111 // 32/64-Bit Timer 0B
|
||||
#define INT_WTIMER1A_TM4C123 112 // 32/64-Bit Timer 1A
|
||||
#define INT_WTIMER1B_TM4C123 113 // 32/64-Bit Timer 1B
|
||||
#define INT_WTIMER2A_TM4C123 114 // 32/64-Bit Timer 2A
|
||||
#define INT_WTIMER2B_TM4C123 115 // 32/64-Bit Timer 2B
|
||||
#define INT_WTIMER3A_TM4C123 116 // 32/64-Bit Timer 3A
|
||||
#define INT_WTIMER3B_TM4C123 117 // 32/64-Bit Timer 3B
|
||||
#define INT_WTIMER4A_TM4C123 118 // 32/64-Bit Timer 4A
|
||||
#define INT_WTIMER4B_TM4C123 119 // 32/64-Bit Timer 4B
|
||||
#define INT_WTIMER5A_TM4C123 120 // 32/64-Bit Timer 5A
|
||||
#define INT_WTIMER5B_TM4C123 121 // 32/64-Bit Timer 5B
|
||||
#define INT_SYSEXC_TM4C123 122 // System Exception (imprecise)
|
||||
#define INT_I2C4_TM4C123 125 // I2C4
|
||||
#define INT_I2C5_TM4C123 126 // I2C5
|
||||
#define INT_GPIOM_TM4C123 127 // GPIO Port M
|
||||
#define INT_GPION_TM4C123 128 // GPIO Port N
|
||||
#define INT_GPIOP0_TM4C123 132 // GPIO Port P (Summary or P0)
|
||||
#define INT_GPIOP1_TM4C123 133 // GPIO Port P1
|
||||
#define INT_GPIOP2_TM4C123 134 // GPIO Port P2
|
||||
#define INT_GPIOP3_TM4C123 135 // GPIO Port P3
|
||||
#define INT_GPIOP4_TM4C123 136 // GPIO Port P4
|
||||
#define INT_GPIOP5_TM4C123 137 // GPIO Port P5
|
||||
#define INT_GPIOP6_TM4C123 138 // GPIO Port P6
|
||||
#define INT_GPIOP7_TM4C123 139 // GPIO Port P7
|
||||
#define INT_GPIOQ0_TM4C123 140 // GPIO Port Q (Summary or Q0)
|
||||
#define INT_GPIOQ1_TM4C123 141 // GPIO Port Q1
|
||||
#define INT_GPIOQ2_TM4C123 142 // GPIO Port Q2
|
||||
#define INT_GPIOQ3_TM4C123 143 // GPIO Port Q3
|
||||
#define INT_GPIOQ4_TM4C123 144 // GPIO Port Q4
|
||||
#define INT_GPIOQ5_TM4C123 145 // GPIO Port Q5
|
||||
#define INT_GPIOQ6_TM4C123 146 // GPIO Port Q6
|
||||
#define INT_GPIOQ7_TM4C123 147 // GPIO Port Q7
|
||||
#define INT_PWM1_0_TM4C123 150 // PWM1 Generator 0
|
||||
#define INT_PWM1_1_TM4C123 151 // PWM1 Generator 1
|
||||
#define INT_PWM1_2_TM4C123 152 // PWM1 Generator 2
|
||||
#define INT_PWM1_3_TM4C123 153 // PWM1 Generator 3
|
||||
#define INT_PWM1_FAULT_TM4C123 154 // PWM1 Fault
|
||||
#define NUM_INTERRUPTS_TM4C123 155
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// TM4C129 Class Interrupts
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define INT_GPIOA_TM4C129 16 // GPIO Port A
|
||||
#define INT_GPIOB_TM4C129 17 // GPIO Port B
|
||||
#define INT_GPIOC_TM4C129 18 // GPIO Port C
|
||||
#define INT_GPIOD_TM4C129 19 // GPIO Port D
|
||||
#define INT_GPIOE_TM4C129 20 // GPIO Port E
|
||||
#define INT_UART0_TM4C129 21 // UART0
|
||||
#define INT_UART1_TM4C129 22 // UART1
|
||||
#define INT_SSI0_TM4C129 23 // SSI0
|
||||
#define INT_I2C0_TM4C129 24 // I2C0
|
||||
#define INT_PWM0_FAULT_TM4C129 25 // PWM Fault
|
||||
#define INT_PWM0_0_TM4C129 26 // PWM Generator 0
|
||||
#define INT_PWM0_1_TM4C129 27 // PWM Generator 1
|
||||
#define INT_PWM0_2_TM4C129 28 // PWM Generator 2
|
||||
#define INT_QEI0_TM4C129 29 // QEI0
|
||||
#define INT_ADC0SS0_TM4C129 30 // ADC0 Sequence 0
|
||||
#define INT_ADC0SS1_TM4C129 31 // ADC0 Sequence 1
|
||||
#define INT_ADC0SS2_TM4C129 32 // ADC0 Sequence 2
|
||||
#define INT_ADC0SS3_TM4C129 33 // ADC0 Sequence 3
|
||||
#define INT_WATCHDOG_TM4C129 34 // Watchdog Timers 0 and 1
|
||||
#define INT_TIMER0A_TM4C129 35 // 16/32-Bit Timer 0A
|
||||
#define INT_TIMER0B_TM4C129 36 // 16/32-Bit Timer 0B
|
||||
#define INT_TIMER1A_TM4C129 37 // 16/32-Bit Timer 1A
|
||||
#define INT_TIMER1B_TM4C129 38 // 16/32-Bit Timer 1B
|
||||
#define INT_TIMER2A_TM4C129 39 // 16/32-Bit Timer 2A
|
||||
#define INT_TIMER2B_TM4C129 40 // 16/32-Bit Timer 2B
|
||||
#define INT_COMP0_TM4C129 41 // Analog Comparator 0
|
||||
#define INT_COMP1_TM4C129 42 // Analog Comparator 1
|
||||
#define INT_COMP2_TM4C129 43 // Analog Comparator 2
|
||||
#define INT_SYSCTL_TM4C129 44 // System Control
|
||||
#define INT_FLASH_TM4C129 45 // Flash Memory Control
|
||||
#define INT_GPIOF_TM4C129 46 // GPIO Port F
|
||||
#define INT_GPIOG_TM4C129 47 // GPIO Port G
|
||||
#define INT_GPIOH_TM4C129 48 // GPIO Port H
|
||||
#define INT_UART2_TM4C129 49 // UART2
|
||||
#define INT_SSI1_TM4C129 50 // SSI1
|
||||
#define INT_TIMER3A_TM4C129 51 // 16/32-Bit Timer 3A
|
||||
#define INT_TIMER3B_TM4C129 52 // 16/32-Bit Timer 3B
|
||||
#define INT_I2C1_TM4C129 53 // I2C1
|
||||
#define INT_CAN0_TM4C129 54 // CAN 0
|
||||
#define INT_CAN1_TM4C129 55 // CAN1
|
||||
#define INT_EMAC0_TM4C129 56 // Ethernet MAC
|
||||
#define INT_HIBERNATE_TM4C129 57 // HIB
|
||||
#define INT_USB0_TM4C129 58 // USB MAC
|
||||
#define INT_PWM0_3_TM4C129 59 // PWM Generator 3
|
||||
#define INT_UDMA_TM4C129 60 // uDMA 0 Software
|
||||
#define INT_UDMAERR_TM4C129 61 // uDMA 0 Error
|
||||
#define INT_ADC1SS0_TM4C129 62 // ADC1 Sequence 0
|
||||
#define INT_ADC1SS1_TM4C129 63 // ADC1 Sequence 1
|
||||
#define INT_ADC1SS2_TM4C129 64 // ADC1 Sequence 2
|
||||
#define INT_ADC1SS3_TM4C129 65 // ADC1 Sequence 3
|
||||
#define INT_EPI0_TM4C129 66 // EPI 0
|
||||
#define INT_GPIOJ_TM4C129 67 // GPIO Port J
|
||||
#define INT_GPIOK_TM4C129 68 // GPIO Port K
|
||||
#define INT_GPIOL_TM4C129 69 // GPIO Port L
|
||||
#define INT_SSI2_TM4C129 70 // SSI 2
|
||||
#define INT_SSI3_TM4C129 71 // SSI 3
|
||||
#define INT_UART3_TM4C129 72 // UART 3
|
||||
#define INT_UART4_TM4C129 73 // UART 4
|
||||
#define INT_UART5_TM4C129 74 // UART 5
|
||||
#define INT_UART6_TM4C129 75 // UART 6
|
||||
#define INT_UART7_TM4C129 76 // UART 7
|
||||
#define INT_I2C2_TM4C129 77 // I2C 2
|
||||
#define INT_I2C3_TM4C129 78 // I2C 3
|
||||
#define INT_TIMER4A_TM4C129 79 // Timer 4A
|
||||
#define INT_TIMER4B_TM4C129 80 // Timer 4B
|
||||
#define INT_TIMER5A_TM4C129 81 // Timer 5A
|
||||
#define INT_TIMER5B_TM4C129 82 // Timer 5B
|
||||
#define INT_SYSEXC_TM4C129 83 // Floating-Point Exception
|
||||
// (imprecise)
|
||||
#define INT_I2C4_TM4C129 86 // I2C 4
|
||||
#define INT_I2C5_TM4C129 87 // I2C 5
|
||||
#define INT_GPIOM_TM4C129 88 // GPIO Port M
|
||||
#define INT_GPION_TM4C129 89 // GPIO Port N
|
||||
#define INT_TAMPER0_TM4C129 91 // Tamper
|
||||
#define INT_GPIOP0_TM4C129 92 // GPIO Port P (Summary or P0)
|
||||
#define INT_GPIOP1_TM4C129 93 // GPIO Port P1
|
||||
#define INT_GPIOP2_TM4C129 94 // GPIO Port P2
|
||||
#define INT_GPIOP3_TM4C129 95 // GPIO Port P3
|
||||
#define INT_GPIOP4_TM4C129 96 // GPIO Port P4
|
||||
#define INT_GPIOP5_TM4C129 97 // GPIO Port P5
|
||||
#define INT_GPIOP6_TM4C129 98 // GPIO Port P6
|
||||
#define INT_GPIOP7_TM4C129 99 // GPIO Port P7
|
||||
#define INT_GPIOQ0_TM4C129 100 // GPIO Port Q (Summary or Q0)
|
||||
#define INT_GPIOQ1_TM4C129 101 // GPIO Port Q1
|
||||
#define INT_GPIOQ2_TM4C129 102 // GPIO Port Q2
|
||||
#define INT_GPIOQ3_TM4C129 103 // GPIO Port Q3
|
||||
#define INT_GPIOQ4_TM4C129 104 // GPIO Port Q4
|
||||
#define INT_GPIOQ5_TM4C129 105 // GPIO Port Q5
|
||||
#define INT_GPIOQ6_TM4C129 106 // GPIO Port Q6
|
||||
#define INT_GPIOQ7_TM4C129 107 // GPIO Port Q7
|
||||
#define INT_GPIOR_TM4C129 108 // GPIO Port R
|
||||
#define INT_GPIOS_TM4C129 109 // GPIO Port S
|
||||
#define INT_SHA0_TM4C129 110 // SHA/MD5
|
||||
#define INT_AES0_TM4C129 111 // AES
|
||||
#define INT_DES0_TM4C129 112 // DES
|
||||
#define INT_LCD0_TM4C129 113 // LCD
|
||||
#define INT_TIMER6A_TM4C129 114 // 16/32-Bit Timer 6A
|
||||
#define INT_TIMER6B_TM4C129 115 // 16/32-Bit Timer 6B
|
||||
#define INT_TIMER7A_TM4C129 116 // 16/32-Bit Timer 7A
|
||||
#define INT_TIMER7B_TM4C129 117 // 16/32-Bit Timer 7B
|
||||
#define INT_I2C6_TM4C129 118 // I2C 6
|
||||
#define INT_I2C7_TM4C129 119 // I2C 7
|
||||
#define INT_ONEWIRE0_TM4C129 121 // 1-Wire
|
||||
#define INT_I2C8_TM4C129 125 // I2C 8
|
||||
#define INT_I2C9_TM4C129 126 // I2C 9
|
||||
#define INT_GPIOT_TM4C129 127 // GPIO T
|
||||
#define NUM_INTERRUPTS_TM4C129 129
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// TM4C123 Interrupt Class Definition
|
||||
//
|
||||
//*****************************************************************************
|
||||
#if defined(TARGET_IS_TM4C123_RA1) || defined(TARGET_IS_TM4C123_RA2) || \
|
||||
defined(TARGET_IS_TM4C123_RA3) || defined(TARGET_IS_TM4C123_RB0) || \
|
||||
defined(TARGET_IS_TM4C123_RB1) || defined(PART_TM4C1230C3PM) || \
|
||||
defined(PART_TM4C1230D5PM) || defined(PART_TM4C1230E6PM) || \
|
||||
defined(PART_TM4C1230H6PM) || defined(PART_TM4C1231C3PM) || \
|
||||
defined(PART_TM4C1231D5PM) || defined(PART_TM4C1231D5PZ) || \
|
||||
defined(PART_TM4C1231E6PM) || defined(PART_TM4C1231E6PZ) || \
|
||||
defined(PART_TM4C1231H6PM) || defined(PART_TM4C1231H6PZ) || \
|
||||
defined(PART_TM4C1232C3PM) || defined(PART_TM4C1232D5PM) || \
|
||||
defined(PART_TM4C1232E6PM) || defined(PART_TM4C1232H6PM) || \
|
||||
defined(PART_TM4C1233C3PM) || defined(PART_TM4C1233D5PM) || \
|
||||
defined(PART_TM4C1233D5PZ) || defined(PART_TM4C1233E6PM) || \
|
||||
defined(PART_TM4C1233E6PZ) || defined(PART_TM4C1233H6PM) || \
|
||||
defined(PART_TM4C1233H6PZ) || defined(PART_TM4C1236D5PM) || \
|
||||
defined(PART_TM4C1236E6PM) || defined(PART_TM4C1236H6PM) || \
|
||||
defined(PART_TM4C1237D5PM) || defined(PART_TM4C1237D5PZ) || \
|
||||
defined(PART_TM4C1237E6PM) || defined(PART_TM4C1237E6PZ) || \
|
||||
defined(PART_TM4C1237H6PM) || defined(PART_TM4C1237H6PZ) || \
|
||||
defined(PART_TM4C123AE6PM) || defined(PART_TM4C123AH6PM) || \
|
||||
defined(PART_TM4C123BE6PM) || defined(PART_TM4C123BE6PZ) || \
|
||||
defined(PART_TM4C123BH6PM) || defined(PART_TM4C123BH6PZ) || \
|
||||
defined(PART_TM4C123FE6PM) || defined(PART_TM4C123FH6PM) || \
|
||||
defined(PART_TM4C123GE6PM) || defined(PART_TM4C123GE6PZ) || \
|
||||
defined(PART_TM4C123GH6PM) || defined(PART_TM4C123GH6PZ) || \
|
||||
defined(PART_TM4C1231H6PGE) || defined(PART_TM4C1233H6PGE) || \
|
||||
defined(PART_TM4C1237H6PGE) || defined(PART_TM4C123BH6PGE) || \
|
||||
defined(PART_TM4C123BH6ZRB) || defined(PART_TM4C123GH6PGE) || \
|
||||
defined(PART_TM4C123GH6ZRB)
|
||||
#define INT_RESOLVE(intname, class) intname##TM4C123
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// TM4C129 Interrupt Class Definition
|
||||
//
|
||||
//*****************************************************************************
|
||||
#elif defined(TARGET_IS_TM4C129_RA0) || defined(PART_TM4C1290NCPDT) || \
|
||||
defined(PART_TM4C1290NCZAD) || defined(PART_TM4C1292NCPDT) || \
|
||||
defined(PART_TM4C1292NCZAD) || defined(PART_TM4C1294KCPDT) || \
|
||||
defined(PART_TM4C1294NCPDT) || defined(PART_TM4C1294NCZAD) || \
|
||||
defined(PART_TM4C1297NCZAD) || defined(PART_TM4C1299KCZAD) || \
|
||||
defined(PART_TM4C1299NCZAD) || defined(PART_TM4C129CNCPDT) || \
|
||||
defined(PART_TM4C129CNCZAD) || defined(PART_TM4C129DNCPDT) || \
|
||||
defined(PART_TM4C129DNCZAD) || defined(PART_TM4C129EKCPDT) || \
|
||||
defined(PART_TM4C129ENCPDT) || defined(PART_TM4C129ENCZAD) || \
|
||||
defined(PART_TM4C129LNCZAD) || defined(PART_TM4C129XKCZAD) || \
|
||||
defined(PART_TM4C129XNCZAD)
|
||||
#define INT_RESOLVE(intname, class) intname##TM4C129
|
||||
#else
|
||||
#define INT_DEVICE_CLASS "UNKNOWN"
|
||||
#endif
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Macros to resolve the INT_PERIPH_CLASS name to a common INT_PERIPH name.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define INT_CONCAT(intname, class) INT_RESOLVE(intname, class)
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the interrupt assignments.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define INT_ADC0SS0 INT_CONCAT(INT_ADC0SS0_, INT_DEVICE_CLASS)
|
||||
#define INT_ADC0SS1 INT_CONCAT(INT_ADC0SS1_, INT_DEVICE_CLASS)
|
||||
#define INT_ADC0SS2 INT_CONCAT(INT_ADC0SS2_, INT_DEVICE_CLASS)
|
||||
#define INT_ADC0SS3 INT_CONCAT(INT_ADC0SS3_, INT_DEVICE_CLASS)
|
||||
#define INT_ADC1SS0 INT_CONCAT(INT_ADC1SS0_, INT_DEVICE_CLASS)
|
||||
#define INT_ADC1SS1 INT_CONCAT(INT_ADC1SS1_, INT_DEVICE_CLASS)
|
||||
#define INT_ADC1SS2 INT_CONCAT(INT_ADC1SS2_, INT_DEVICE_CLASS)
|
||||
#define INT_ADC1SS3 INT_CONCAT(INT_ADC1SS3_, INT_DEVICE_CLASS)
|
||||
#define INT_AES0 INT_CONCAT(INT_AES0_, INT_DEVICE_CLASS)
|
||||
#define INT_CAN0 INT_CONCAT(INT_CAN0_, INT_DEVICE_CLASS)
|
||||
#define INT_CAN1 INT_CONCAT(INT_CAN1_, INT_DEVICE_CLASS)
|
||||
#define INT_COMP0 INT_CONCAT(INT_COMP0_, INT_DEVICE_CLASS)
|
||||
#define INT_COMP1 INT_CONCAT(INT_COMP1_, INT_DEVICE_CLASS)
|
||||
#define INT_COMP2 INT_CONCAT(INT_COMP2_, INT_DEVICE_CLASS)
|
||||
#define INT_DES0 INT_CONCAT(INT_DES0_, INT_DEVICE_CLASS)
|
||||
#define INT_EMAC0 INT_CONCAT(INT_EMAC0_, INT_DEVICE_CLASS)
|
||||
#define INT_EPI0 INT_CONCAT(INT_EPI0_, INT_DEVICE_CLASS)
|
||||
#define INT_FLASH INT_CONCAT(INT_FLASH_, INT_DEVICE_CLASS)
|
||||
#define INT_GPIOA INT_CONCAT(INT_GPIOA_, INT_DEVICE_CLASS)
|
||||
#define INT_GPIOB INT_CONCAT(INT_GPIOB_, INT_DEVICE_CLASS)
|
||||
#define INT_GPIOC INT_CONCAT(INT_GPIOC_, INT_DEVICE_CLASS)
|
||||
#define INT_GPIOD INT_CONCAT(INT_GPIOD_, INT_DEVICE_CLASS)
|
||||
#define INT_GPIOE INT_CONCAT(INT_GPIOE_, INT_DEVICE_CLASS)
|
||||
#define INT_GPIOF INT_CONCAT(INT_GPIOF_, INT_DEVICE_CLASS)
|
||||
#define INT_GPIOG INT_CONCAT(INT_GPIOG_, INT_DEVICE_CLASS)
|
||||
#define INT_GPIOH INT_CONCAT(INT_GPIOH_, INT_DEVICE_CLASS)
|
||||
#define INT_GPIOJ INT_CONCAT(INT_GPIOJ_, INT_DEVICE_CLASS)
|
||||
#define INT_GPIOK INT_CONCAT(INT_GPIOK_, INT_DEVICE_CLASS)
|
||||
#define INT_GPIOL INT_CONCAT(INT_GPIOL_, INT_DEVICE_CLASS)
|
||||
#define INT_GPIOM INT_CONCAT(INT_GPIOM_, INT_DEVICE_CLASS)
|
||||
#define INT_GPION INT_CONCAT(INT_GPION_, INT_DEVICE_CLASS)
|
||||
#define INT_GPIOP0 INT_CONCAT(INT_GPIOP0_, INT_DEVICE_CLASS)
|
||||
#define INT_GPIOP1 INT_CONCAT(INT_GPIOP1_, INT_DEVICE_CLASS)
|
||||
#define INT_GPIOP2 INT_CONCAT(INT_GPIOP2_, INT_DEVICE_CLASS)
|
||||
#define INT_GPIOP3 INT_CONCAT(INT_GPIOP3_, INT_DEVICE_CLASS)
|
||||
#define INT_GPIOP4 INT_CONCAT(INT_GPIOP4_, INT_DEVICE_CLASS)
|
||||
#define INT_GPIOP5 INT_CONCAT(INT_GPIOP5_, INT_DEVICE_CLASS)
|
||||
#define INT_GPIOP6 INT_CONCAT(INT_GPIOP6_, INT_DEVICE_CLASS)
|
||||
#define INT_GPIOP7 INT_CONCAT(INT_GPIOP7_, INT_DEVICE_CLASS)
|
||||
#define INT_GPIOQ0 INT_CONCAT(INT_GPIOQ0_, INT_DEVICE_CLASS)
|
||||
#define INT_GPIOQ1 INT_CONCAT(INT_GPIOQ1_, INT_DEVICE_CLASS)
|
||||
#define INT_GPIOQ2 INT_CONCAT(INT_GPIOQ2_, INT_DEVICE_CLASS)
|
||||
#define INT_GPIOQ3 INT_CONCAT(INT_GPIOQ3_, INT_DEVICE_CLASS)
|
||||
#define INT_GPIOQ4 INT_CONCAT(INT_GPIOQ4_, INT_DEVICE_CLASS)
|
||||
#define INT_GPIOQ5 INT_CONCAT(INT_GPIOQ5_, INT_DEVICE_CLASS)
|
||||
#define INT_GPIOQ6 INT_CONCAT(INT_GPIOQ6_, INT_DEVICE_CLASS)
|
||||
#define INT_GPIOQ7 INT_CONCAT(INT_GPIOQ7_, INT_DEVICE_CLASS)
|
||||
#define INT_GPIOR INT_CONCAT(INT_GPIOR_, INT_DEVICE_CLASS)
|
||||
#define INT_GPIOS INT_CONCAT(INT_GPIOS_, INT_DEVICE_CLASS)
|
||||
#define INT_GPIOT INT_CONCAT(INT_GPIOT_, INT_DEVICE_CLASS)
|
||||
#define INT_HIBERNATE INT_CONCAT(INT_HIBERNATE_, INT_DEVICE_CLASS)
|
||||
#define INT_I2C0 INT_CONCAT(INT_I2C0_, INT_DEVICE_CLASS)
|
||||
#define INT_I2C1 INT_CONCAT(INT_I2C1_, INT_DEVICE_CLASS)
|
||||
#define INT_I2C2 INT_CONCAT(INT_I2C2_, INT_DEVICE_CLASS)
|
||||
#define INT_I2C3 INT_CONCAT(INT_I2C3_, INT_DEVICE_CLASS)
|
||||
#define INT_I2C4 INT_CONCAT(INT_I2C4_, INT_DEVICE_CLASS)
|
||||
#define INT_I2C5 INT_CONCAT(INT_I2C5_, INT_DEVICE_CLASS)
|
||||
#define INT_I2C6 INT_CONCAT(INT_I2C6_, INT_DEVICE_CLASS)
|
||||
#define INT_I2C7 INT_CONCAT(INT_I2C7_, INT_DEVICE_CLASS)
|
||||
#define INT_I2C8 INT_CONCAT(INT_I2C8_, INT_DEVICE_CLASS)
|
||||
#define INT_I2C9 INT_CONCAT(INT_I2C9_, INT_DEVICE_CLASS)
|
||||
#define INT_LCD0 INT_CONCAT(INT_LCD0_, INT_DEVICE_CLASS)
|
||||
#define INT_ONEWIRE0 INT_CONCAT(INT_ONEWIRE0_, INT_DEVICE_CLASS)
|
||||
#define INT_PWM0_0 INT_CONCAT(INT_PWM0_0_, INT_DEVICE_CLASS)
|
||||
#define INT_PWM0_1 INT_CONCAT(INT_PWM0_1_, INT_DEVICE_CLASS)
|
||||
#define INT_PWM0_2 INT_CONCAT(INT_PWM0_2_, INT_DEVICE_CLASS)
|
||||
#define INT_PWM0_3 INT_CONCAT(INT_PWM0_3_, INT_DEVICE_CLASS)
|
||||
#define INT_PWM0_FAULT INT_CONCAT(INT_PWM0_FAULT_, INT_DEVICE_CLASS)
|
||||
#define INT_PWM1_0 INT_CONCAT(INT_PWM1_0_, INT_DEVICE_CLASS)
|
||||
#define INT_PWM1_1 INT_CONCAT(INT_PWM1_1_, INT_DEVICE_CLASS)
|
||||
#define INT_PWM1_2 INT_CONCAT(INT_PWM1_2_, INT_DEVICE_CLASS)
|
||||
#define INT_PWM1_3 INT_CONCAT(INT_PWM1_3_, INT_DEVICE_CLASS)
|
||||
#define INT_PWM1_FAULT INT_CONCAT(INT_PWM1_FAULT_, INT_DEVICE_CLASS)
|
||||
#define INT_QEI0 INT_CONCAT(INT_QEI0_, INT_DEVICE_CLASS)
|
||||
#define INT_QEI1 INT_CONCAT(INT_QEI1_, INT_DEVICE_CLASS)
|
||||
#define INT_SHA0 INT_CONCAT(INT_SHA0_, INT_DEVICE_CLASS)
|
||||
#define INT_SSI0 INT_CONCAT(INT_SSI0_, INT_DEVICE_CLASS)
|
||||
#define INT_SSI1 INT_CONCAT(INT_SSI1_, INT_DEVICE_CLASS)
|
||||
#define INT_SSI2 INT_CONCAT(INT_SSI2_, INT_DEVICE_CLASS)
|
||||
#define INT_SSI3 INT_CONCAT(INT_SSI3_, INT_DEVICE_CLASS)
|
||||
#define INT_SYSCTL INT_CONCAT(INT_SYSCTL_, INT_DEVICE_CLASS)
|
||||
#define INT_SYSEXC INT_CONCAT(INT_SYSEXC_, INT_DEVICE_CLASS)
|
||||
#define INT_TAMPER0 INT_CONCAT(INT_TAMPER0_, INT_DEVICE_CLASS)
|
||||
#define INT_TIMER0A INT_CONCAT(INT_TIMER0A_, INT_DEVICE_CLASS)
|
||||
#define INT_TIMER0B INT_CONCAT(INT_TIMER0B_, INT_DEVICE_CLASS)
|
||||
#define INT_TIMER1A INT_CONCAT(INT_TIMER1A_, INT_DEVICE_CLASS)
|
||||
#define INT_TIMER1B INT_CONCAT(INT_TIMER1B_, INT_DEVICE_CLASS)
|
||||
#define INT_TIMER2A INT_CONCAT(INT_TIMER2A_, INT_DEVICE_CLASS)
|
||||
#define INT_TIMER2B INT_CONCAT(INT_TIMER2B_, INT_DEVICE_CLASS)
|
||||
#define INT_TIMER3A INT_CONCAT(INT_TIMER3A_, INT_DEVICE_CLASS)
|
||||
#define INT_TIMER3B INT_CONCAT(INT_TIMER3B_, INT_DEVICE_CLASS)
|
||||
#define INT_TIMER4A INT_CONCAT(INT_TIMER4A_, INT_DEVICE_CLASS)
|
||||
#define INT_TIMER4B INT_CONCAT(INT_TIMER4B_, INT_DEVICE_CLASS)
|
||||
#define INT_TIMER5A INT_CONCAT(INT_TIMER5A_, INT_DEVICE_CLASS)
|
||||
#define INT_TIMER5B INT_CONCAT(INT_TIMER5B_, INT_DEVICE_CLASS)
|
||||
#define INT_TIMER6A INT_CONCAT(INT_TIMER6A_, INT_DEVICE_CLASS)
|
||||
#define INT_TIMER6B INT_CONCAT(INT_TIMER6B_, INT_DEVICE_CLASS)
|
||||
#define INT_TIMER7A INT_CONCAT(INT_TIMER7A_, INT_DEVICE_CLASS)
|
||||
#define INT_TIMER7B INT_CONCAT(INT_TIMER7B_, INT_DEVICE_CLASS)
|
||||
#define INT_UART0 INT_CONCAT(INT_UART0_, INT_DEVICE_CLASS)
|
||||
#define INT_UART1 INT_CONCAT(INT_UART1_, INT_DEVICE_CLASS)
|
||||
#define INT_UART2 INT_CONCAT(INT_UART2_, INT_DEVICE_CLASS)
|
||||
#define INT_UART3 INT_CONCAT(INT_UART3_, INT_DEVICE_CLASS)
|
||||
#define INT_UART4 INT_CONCAT(INT_UART4_, INT_DEVICE_CLASS)
|
||||
#define INT_UART5 INT_CONCAT(INT_UART5_, INT_DEVICE_CLASS)
|
||||
#define INT_UART6 INT_CONCAT(INT_UART6_, INT_DEVICE_CLASS)
|
||||
#define INT_UART7 INT_CONCAT(INT_UART7_, INT_DEVICE_CLASS)
|
||||
#define INT_UDMA INT_CONCAT(INT_UDMA_, INT_DEVICE_CLASS)
|
||||
#define INT_UDMAERR INT_CONCAT(INT_UDMAERR_, INT_DEVICE_CLASS)
|
||||
#define INT_USB0 INT_CONCAT(INT_USB0_, INT_DEVICE_CLASS)
|
||||
#define INT_WATCHDOG INT_CONCAT(INT_WATCHDOG_, INT_DEVICE_CLASS)
|
||||
#define INT_WTIMER0A INT_CONCAT(INT_WTIMER0A_, INT_DEVICE_CLASS)
|
||||
#define INT_WTIMER0B INT_CONCAT(INT_WTIMER0B_, INT_DEVICE_CLASS)
|
||||
#define INT_WTIMER1A INT_CONCAT(INT_WTIMER1A_, INT_DEVICE_CLASS)
|
||||
#define INT_WTIMER1B INT_CONCAT(INT_WTIMER1B_, INT_DEVICE_CLASS)
|
||||
#define INT_WTIMER2A INT_CONCAT(INT_WTIMER2A_, INT_DEVICE_CLASS)
|
||||
#define INT_WTIMER2B INT_CONCAT(INT_WTIMER2B_, INT_DEVICE_CLASS)
|
||||
#define INT_WTIMER3A INT_CONCAT(INT_WTIMER3A_, INT_DEVICE_CLASS)
|
||||
#define INT_WTIMER3B INT_CONCAT(INT_WTIMER3B_, INT_DEVICE_CLASS)
|
||||
#define INT_WTIMER4A INT_CONCAT(INT_WTIMER4A_, INT_DEVICE_CLASS)
|
||||
#define INT_WTIMER4B INT_CONCAT(INT_WTIMER4B_, INT_DEVICE_CLASS)
|
||||
#define INT_WTIMER5A INT_CONCAT(INT_WTIMER5A_, INT_DEVICE_CLASS)
|
||||
#define INT_WTIMER5B INT_CONCAT(INT_WTIMER5B_, INT_DEVICE_CLASS)
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the total number of interrupts.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define NUM_INTERRUPTS INT_CONCAT(NUM_INTERRUPTS_, INT_DEVICE_CLASS)
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the total number of priority levels.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define NUM_PRIORITY 8
|
||||
#define NUM_PRIORITY_BITS 3
|
||||
|
||||
#endif // __HW_INTS_H__
|
|
@ -0,0 +1,575 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// hw_lcd.h - Defines and macros used when accessing the LCD controller.
|
||||
//
|
||||
// Copyright (c) 2011-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Firmware Development Package.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __HW_LCD_H__
|
||||
#define __HW_LCD_H__
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the LCD register offsets.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define LCD_O_PID 0x00000000 // LCD PID Register Format
|
||||
#define LCD_O_CTL 0x00000004 // LCD Control
|
||||
#define LCD_O_LIDDCTL 0x0000000C // LCD LIDD Control
|
||||
#define LCD_O_LIDDCS0CFG 0x00000010 // LCD LIDD CS0 Configuration
|
||||
#define LCD_O_LIDDCS0ADDR 0x00000014 // LIDD CS0 Read/Write Address
|
||||
#define LCD_O_LIDDCS0DATA 0x00000018 // LIDD CS0 Data Read/Write
|
||||
// Initiation
|
||||
#define LCD_O_LIDDCS1CFG 0x0000001C // LIDD CS1 Configuration
|
||||
#define LCD_O_LIDDCS1ADDR 0x00000020 // LIDD CS1 Address Read/Write
|
||||
// Initiation
|
||||
#define LCD_O_LIDDCS1DATA 0x00000024 // LIDD CS1 Data Read/Write
|
||||
// Initiation
|
||||
#define LCD_O_RASTRCTL 0x00000028 // LCD Raster Control
|
||||
#define LCD_O_RASTRTIM0 0x0000002C // LCD Raster Timing 0
|
||||
#define LCD_O_RASTRTIM1 0x00000030 // LCD Raster Timing 1
|
||||
#define LCD_O_RASTRTIM2 0x00000034 // LCD Raster Timing 2
|
||||
#define LCD_O_RASTRSUBP1 0x00000038 // LCD Raster Subpanel Display 1
|
||||
#define LCD_O_RASTRSUBP2 0x0000003C // LCD Raster Subpanel Display 2
|
||||
#define LCD_O_DMACTL 0x00000040 // LCD DMA Control
|
||||
#define LCD_O_DMABAFB0 0x00000044 // LCD DMA Frame Buffer 0 Base
|
||||
// Address
|
||||
#define LCD_O_DMACAFB0 0x00000048 // LCD DMA Frame Buffer 0 Ceiling
|
||||
// Address
|
||||
#define LCD_O_DMABAFB1 0x0000004C // LCD DMA Frame Buffer 1 Base
|
||||
// Address
|
||||
#define LCD_O_DMACAFB1 0x00000050 // LCD DMA Frame Buffer 1 Ceiling
|
||||
// Address
|
||||
#define LCD_O_SYSCFG 0x00000054 // LCD System Configuration
|
||||
// Register
|
||||
#define LCD_O_RISSET 0x00000058 // LCD Interrupt Raw Status and Set
|
||||
// Register
|
||||
#define LCD_O_MISCLR 0x0000005C // LCD Interrupt Status and Clear
|
||||
#define LCD_O_IM 0x00000060 // LCD Interrupt Mask
|
||||
#define LCD_O_IENC 0x00000064 // LCD Interrupt Enable Clear
|
||||
#define LCD_O_CLKEN 0x0000006C // LCD Clock Enable
|
||||
#define LCD_O_CLKRESET 0x00000070 // LCD Clock Resets
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the LCD_O_PID register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define LCD_PID_MAJOR_M 0x00000700 // Major Release Number
|
||||
#define LCD_PID_MINOR_M 0x0000003F // Minor Release Number
|
||||
#define LCD_PID_MAJOR_S 8
|
||||
#define LCD_PID_MINOR_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the LCD_O_CTL register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define LCD_CTL_CLKDIV_M 0x0000FF00 // Clock Divisor
|
||||
#define LCD_CTL_UFLOWRST 0x00000002 // Underflow Restart
|
||||
#define LCD_CTL_LCDMODE 0x00000001 // LCD Mode Select
|
||||
#define LCD_CTL_CLKDIV_S 8
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the LCD_O_LIDDCTL register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define LCD_LIDDCTL_DMACS 0x00000200 // CS0/CS1 Select for LIDD DMA
|
||||
// Writes
|
||||
#define LCD_LIDDCTL_DMAEN 0x00000100 // LIDD DMA Enable
|
||||
#define LCD_LIDDCTL_CS1E1 0x00000080 // Chip Select 1 (CS1)/Enable 1(E1)
|
||||
// Polarity Control
|
||||
#define LCD_LIDDCTL_CS0E0 0x00000040 // Chip Select 0 (CS0)/Enable 0
|
||||
// (E0) Polarity Control
|
||||
#define LCD_LIDDCTL_WRDIRINV 0x00000020 // Write Strobe (WR) /Direction
|
||||
// (DIR) Polarity Control
|
||||
#define LCD_LIDDCTL_RDEN 0x00000010 // Read Strobe (RD) /Direct Enable
|
||||
// (EN) Polarity Control
|
||||
#define LCD_LIDDCTL_ALE 0x00000008 // Address Latch Enable (ALE)
|
||||
// Polarity Control
|
||||
#define LCD_LIDDCTL_MODE_M 0x00000007 // LIDD Mode Select
|
||||
#define LCD_LIDDCTL_MODE_SYNCM68 \
|
||||
0x00000000 // Synchronous Motorola 6800 Mode
|
||||
#define LCD_LIDDCTL_MODE_ASYNCM68 \
|
||||
0x00000001 // Asynchronous Motorola 6800 Mode
|
||||
#define LCD_LIDDCTL_MODE_SYNCM80 \
|
||||
0x00000002 // Synchronous Intel 8080 mode
|
||||
#define LCD_LIDDCTL_MODE_ASYNCM80 \
|
||||
0x00000003 // Asynchronous Intel 8080 mode
|
||||
#define LCD_LIDDCTL_MODE_ASYNCHIT \
|
||||
0x00000004 // Asynchronous Hitachi mode
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the LCD_O_LIDDCS0CFG
|
||||
// register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define LCD_LIDDCS0CFG_WRSU_M 0xF8000000 // Write Strobe (WR) Set-Up Cycles
|
||||
#define LCD_LIDDCS0CFG_WRDUR_M 0x07E00000 // Write Strobe (WR) Duration
|
||||
// Cycles
|
||||
#define LCD_LIDDCS0CFG_WRHOLD_M 0x001E0000 // Write Strobe (WR) Hold cycles
|
||||
#define LCD_LIDDCS0CFG_RDSU_M 0x0001F000 // Read Strobe (RD) Set-Up cycles
|
||||
#define LCD_LIDDCS0CFG_RDDUR_M 0x00000FC0 // Read Strobe (RD) Duration cycles
|
||||
#define LCD_LIDDCS0CFG_RDHOLD_M 0x0000003C // Read Strobe (RD) Hold cycles
|
||||
#define LCD_LIDDCS0CFG_GAP_M 0x00000003 // Field value defines the number
|
||||
// of LCDMCLK cycles (GAP +1)
|
||||
// between the end of one CS0
|
||||
// (LCDAC) device access and the
|
||||
// start of another CS0 (LCDAC)
|
||||
// device access unless the two
|
||||
// accesses are both reads
|
||||
#define LCD_LIDDCS0CFG_WRSU_S 27
|
||||
#define LCD_LIDDCS0CFG_WRDUR_S 21
|
||||
#define LCD_LIDDCS0CFG_WRHOLD_S 17
|
||||
#define LCD_LIDDCS0CFG_RDSU_S 12
|
||||
#define LCD_LIDDCS0CFG_RDDUR_S 6
|
||||
#define LCD_LIDDCS0CFG_RDHOLD_S 2
|
||||
#define LCD_LIDDCS0CFG_GAP_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the LCD_O_LIDDCS0ADDR
|
||||
// register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define LCD_LIDDCS0ADDR_CS0ADDR_M \
|
||||
0x0000FFFF // LCD Address
|
||||
#define LCD_LIDDCS0ADDR_CS0ADDR_S \
|
||||
0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the LCD_O_LIDDCS0DATA
|
||||
// register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define LCD_LIDDCS0DATA_CS0DATA_M \
|
||||
0x0000FFFF // LCD Data Read/Write
|
||||
#define LCD_LIDDCS0DATA_CS0DATA_S \
|
||||
0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the LCD_O_LIDDCS1CFG
|
||||
// register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define LCD_LIDDCS1CFG_WRSU_M 0xF8000000 // Write Strobe (WR) Set-Up Cycles
|
||||
#define LCD_LIDDCS1CFG_WRDUR_M 0x07E00000 // Write Strobe (WR) Duration
|
||||
// Cycles
|
||||
#define LCD_LIDDCS1CFG_WRHOLD_M 0x001E0000 // Write Strobe (WR) Hold cycles
|
||||
#define LCD_LIDDCS1CFG_RDSU_M 0x0001F000 // Read Strobe (RD) Set-Up cycles
|
||||
#define LCD_LIDDCS1CFG_RDDUR_M 0x00000FC0 // Read Strobe (RD) Duration cycles
|
||||
#define LCD_LIDDCS1CFG_RDHOLD_M 0x0000003C // Read Strobe (RD) Hold cycles
|
||||
#define LCD_LIDDCS1CFG_GAP_M 0x00000003 // Field value defines the number
|
||||
// of LCDMCLK cycles (GAP + 1)
|
||||
// between the end of one CS1
|
||||
// (LCDAC) device access and the
|
||||
// start of another CS0 (LCDAC)
|
||||
// device access unless the two
|
||||
// accesses are both reads
|
||||
#define LCD_LIDDCS1CFG_WRSU_S 27
|
||||
#define LCD_LIDDCS1CFG_WRDUR_S 21
|
||||
#define LCD_LIDDCS1CFG_WRHOLD_S 17
|
||||
#define LCD_LIDDCS1CFG_RDSU_S 12
|
||||
#define LCD_LIDDCS1CFG_RDDUR_S 6
|
||||
#define LCD_LIDDCS1CFG_RDHOLD_S 2
|
||||
#define LCD_LIDDCS1CFG_GAP_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the LCD_O_LIDDCS1ADDR
|
||||
// register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define LCD_LIDDCS1ADDR_CS1ADDR_M \
|
||||
0x0000FFFF // LCD Address Bus
|
||||
#define LCD_LIDDCS1ADDR_CS1ADDR_S \
|
||||
0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the LCD_O_LIDDCS1DATA
|
||||
// register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define LCD_LIDDCS1DATA_CS0DATA_M \
|
||||
0x0000FFFF // LCD Data Read/Write Initiation
|
||||
#define LCD_LIDDCS1DATA_CS0DATA_S \
|
||||
0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the LCD_O_RASTRCTL register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define LCD_RASTRCTL_TFT24UPCK 0x04000000 // 24-bit TFT Mode Packing
|
||||
#define LCD_RASTRCTL_TFT24 0x02000000 // 24-Bit TFT Mode
|
||||
#define LCD_RASTRCTL_FRMBUFSZ 0x01000000 // Frame Buffer Select
|
||||
#define LCD_RASTRCTL_TFTMAP 0x00800000 // TFT Mode Alternate Signal
|
||||
// Mapping for Palettized
|
||||
// Framebuffer
|
||||
#define LCD_RASTRCTL_NIBMODE 0x00400000 // Nibble Mode
|
||||
#define LCD_RASTRCTL_PALMODE_M 0x00300000 // Pallette Loading Mode
|
||||
#define LCD_RASTRCTL_PALMODE_PALDAT \
|
||||
0x00000000 // Palette and data loading, reset
|
||||
// value
|
||||
#define LCD_RASTRCTL_PALMODE_PAL \
|
||||
0x00100000 // Palette loading only
|
||||
#define LCD_RASTRCTL_PALMODE_DAT \
|
||||
0x00200000 // Data loading only
|
||||
#define LCD_RASTRCTL_REQDLY_M 0x000FF000 // Palette Loading Delay
|
||||
#define LCD_RASTRCTL_MONO8B 0x00000200 // Mono 8-Bit
|
||||
#define LCD_RASTRCTL_RDORDER 0x00000100 // Raster Data Order Select
|
||||
#define LCD_RASTRCTL_LCDTFT 0x00000080 // LCD TFT
|
||||
#define LCD_RASTRCTL_LCDBW 0x00000002 // LCD Monochrome
|
||||
#define LCD_RASTRCTL_LCDEN 0x00000001 // LCD Controller Enable for Raster
|
||||
// Operations
|
||||
#define LCD_RASTRCTL_REQDLY_S 12
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the LCD_O_RASTRTIM0
|
||||
// register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define LCD_RASTRTIM0_HBP_M 0xFF000000 // Horizontal Back Porch Lowbits
|
||||
#define LCD_RASTRTIM0_HFP_M 0x00FF0000 // Horizontal Front Porch Lowbits
|
||||
#define LCD_RASTRTIM0_HSW_M 0x0000FC00 // Horizontal Sync Pulse Width
|
||||
// Lowbits
|
||||
#define LCD_RASTRTIM0_PPL_M 0x000003F0 // Pixels-per-line LSB[9:4]
|
||||
#define LCD_RASTRTIM0_MSBPPL 0x00000008 // Pixels-per-line MSB[10]
|
||||
#define LCD_RASTRTIM0_HBP_S 24
|
||||
#define LCD_RASTRTIM0_HFP_S 16
|
||||
#define LCD_RASTRTIM0_HSW_S 10
|
||||
#define LCD_RASTRTIM0_PPL_S 4
|
||||
#define LCD_RASTRTIM0_MSBPPL_S 3
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the LCD_O_RASTRTIM1
|
||||
// register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define LCD_RASTRTIM1_VBP_M 0xFF000000 // Vertical Back Porch
|
||||
#define LCD_RASTRTIM1_VFP_M 0x00FF0000 // Vertical Front Porch
|
||||
#define LCD_RASTRTIM1_VSW_M 0x0000FC00 // Vertical Sync Width Pulse
|
||||
#define LCD_RASTRTIM1_LPP_M 0x000003FF // Lines Per Panel
|
||||
#define LCD_RASTRTIM1_VBP_S 24
|
||||
#define LCD_RASTRTIM1_VFP_S 16
|
||||
#define LCD_RASTRTIM1_VSW_S 10
|
||||
#define LCD_RASTRTIM1_LPP_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the LCD_O_RASTRTIM2
|
||||
// register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define LCD_RASTRTIM2_HSW_M 0x78000000 // Bits 9:6 of the horizontal sync
|
||||
// width field
|
||||
#define LCD_RASTRTIM2_MSBLPP 0x04000000 // MSB of Lines Per Panel
|
||||
#define LCD_RASTRTIM2_PXLCLKCTL 0x02000000 // Hsync/Vsync Pixel Clock Control
|
||||
// On/Off
|
||||
#define LCD_RASTRTIM2_PSYNCRF 0x01000000 // Program HSYNC/VSYNC Rise or Fall
|
||||
#define LCD_RASTRTIM2_INVOE 0x00800000 // Invert Output Enable
|
||||
#define LCD_RASTRTIM2_INVPXLCLK 0x00400000 // Invert Pixel Clock
|
||||
#define LCD_RASTRTIM2_IHS 0x00200000 // Invert Hysync
|
||||
#define LCD_RASTRTIM2_IVS 0x00100000 // Invert Vsync
|
||||
#define LCD_RASTRTIM2_ACBI_M 0x000F0000 // AC Bias Pins Transitions per
|
||||
// Interrupt
|
||||
#define LCD_RASTRTIM2_ACBF_M 0x0000FF00 // AC Bias Pin Frequency
|
||||
#define LCD_RASTRTIM2_MSBHBP_M 0x00000030 // Bits 9:8 of the horizontal back
|
||||
// porch field
|
||||
#define LCD_RASTRTIM2_MSBHFP_M 0x00000003 // Bits 9:8 of the horizontal front
|
||||
// porch field
|
||||
#define LCD_RASTRTIM2_HSW_S 27
|
||||
#define LCD_RASTRTIM2_MSBLPP_S 26
|
||||
#define LCD_RASTRTIM2_ACBI_S 16
|
||||
#define LCD_RASTRTIM2_ACBF_S 8
|
||||
#define LCD_RASTRTIM2_MSBHBP_S 4
|
||||
#define LCD_RASTRTIM2_MSBHFP_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the LCD_O_RASTRSUBP1
|
||||
// register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define LCD_RASTRSUBP1_SPEN 0x80000000 // Sub Panel Enable
|
||||
#define LCD_RASTRSUBP1_HOLS 0x20000000 // High or Low Signal
|
||||
#define LCD_RASTRSUBP1_LPPT_M 0x03FF0000 // Line Per Panel Threshold
|
||||
#define LCD_RASTRSUBP1_DPDLSB_M 0x0000FFFF // Default Pixel Data LSB[15:0]
|
||||
#define LCD_RASTRSUBP1_LPPT_S 16
|
||||
#define LCD_RASTRSUBP1_DPDLSB_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the LCD_O_RASTRSUBP2
|
||||
// register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define LCD_RASTRSUBP2_LPPTMSB 0x00000100 // Lines Per Panel Threshold Bit 10
|
||||
#define LCD_RASTRSUBP2_DPDMSB_M 0x000000FF // Default Pixel Data MSB [23:16]
|
||||
#define LCD_RASTRSUBP2_DPDMSB_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the LCD_O_DMACTL register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define LCD_DMACTL_FIFORDY_M 0x00000700 // DMA FIFO threshold
|
||||
#define LCD_DMACTL_FIFORDY_8 0x00000000 // 8 words
|
||||
#define LCD_DMACTL_FIFORDY_16 0x00000100 // 16 words
|
||||
#define LCD_DMACTL_FIFORDY_32 0x00000200 // 32 words
|
||||
#define LCD_DMACTL_FIFORDY_64 0x00000300 // 64 words
|
||||
#define LCD_DMACTL_FIFORDY_128 0x00000400 // 128 words
|
||||
#define LCD_DMACTL_FIFORDY_256 0x00000500 // 256 words
|
||||
#define LCD_DMACTL_FIFORDY_512 0x00000600 // 512 words
|
||||
#define LCD_DMACTL_BURSTSZ_M 0x00000070 // Burst Size setting for DMA
|
||||
// transfers (all DMA transfers are
|
||||
// 32 bits wide):
|
||||
#define LCD_DMACTL_BURSTSZ_4 0x00000020 // burst size of 4
|
||||
#define LCD_DMACTL_BURSTSZ_8 0x00000030 // burst size of 8
|
||||
#define LCD_DMACTL_BURSTSZ_16 0x00000040 // burst size of 16
|
||||
#define LCD_DMACTL_BYTESWAP 0x00000008 // This bit controls the bytelane
|
||||
// ordering of the data on the
|
||||
// output of the DMA module
|
||||
#define LCD_DMACTL_BIGDEND 0x00000002 // Big Endian Enable
|
||||
#define LCD_DMACTL_FMODE 0x00000001 // Frame Mode
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the LCD_O_DMABAFB0 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define LCD_DMABAFB0_FB0BA_M 0xFFFFFFFC // Frame Buffer 0 Base Address
|
||||
// pointer
|
||||
#define LCD_DMABAFB0_FB0BA_S 2
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the LCD_O_DMACAFB0 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define LCD_DMACAFB0_FB0CA_M 0xFFFFFFFC // Frame Buffer 0 Ceiling Address
|
||||
// pointer
|
||||
#define LCD_DMACAFB0_FB0CA_S 2
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the LCD_O_DMABAFB1 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define LCD_DMABAFB1_FB1BA_M 0xFFFFFFFC // Frame Buffer 1 Base Address
|
||||
// pointer
|
||||
#define LCD_DMABAFB1_FB1BA_S 2
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the LCD_O_DMACAFB1 register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define LCD_DMACAFB1_FB1CA_M 0xFFFFFFFC // Frame Buffer 1 Ceiling Address
|
||||
// pointer
|
||||
#define LCD_DMACAFB1_FB1CA_S 2
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the LCD_O_SYSCFG register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define LCD_SYSCFG_STDBY_M 0x00000030 // Standby Mode
|
||||
#define LCD_SYSCFG_STDBY_FORCE 0x00000000 // Force-standby mode: local
|
||||
// initiator is unconditionally
|
||||
// placed in standby state. Backup
|
||||
// mode, for debug only
|
||||
#define LCD_SYSCFG_STDBY_NONE 0x00000010 // No-standby mode: local initiator
|
||||
// is unconditionally placed out of
|
||||
// standby state. Backup mode, for
|
||||
// debug only
|
||||
#define LCD_SYSCFG_STDBY_SMART 0x00000020 // Smart-standby mode: local
|
||||
// initiator standby status depends
|
||||
// on local conditions, that is,
|
||||
// the module's functional
|
||||
// requirement from the initiator.
|
||||
// IP module shall not generate
|
||||
// (initiator-related) wakeup
|
||||
// events
|
||||
#define LCD_SYSCFG_IDLEMODE_M 0x0000000C // Idle Mode
|
||||
#define LCD_SYSCFG_IDLEMODE_FORCE \
|
||||
0x00000000 // Force-idle mode: local target's
|
||||
// idle state follows
|
||||
// (acknowledges) the system's idle
|
||||
// requests unconditionally, that
|
||||
// is, regardless of the IP
|
||||
// module's internal requirements.
|
||||
// Backup mode, for debug only
|
||||
#define LCD_SYSCFG_IDLEMODE_NONE \
|
||||
0x00000004 // No-idle mode: local target never
|
||||
// enters idle state. Backup mode,
|
||||
// for debug only
|
||||
#define LCD_SYSCFG_IDLEMODE_SMART \
|
||||
0x00000008 // Smart-idle mode: local target's
|
||||
// idle state eventually follows
|
||||
// (acknowledges) the system's idle
|
||||
// requests, depending on the IP
|
||||
// module's internal requirements.
|
||||
// IP module shall not generate
|
||||
// (IRQ- or DMA-requestrelated)
|
||||
// wakeup events
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the LCD_O_RISSET register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define LCD_RISSET_EOF1 0x00000200 // DMA End-of-Frame 1 Raw Interrupt
|
||||
// Status and Set
|
||||
#define LCD_RISSET_EOF0 0x00000100 // DMA End-of-Frame 0 Raw Interrupt
|
||||
// Status and Set
|
||||
#define LCD_RISSET_PALLOAD 0x00000040 // DMA Palette Loaded Raw Interrupt
|
||||
// Status and Set
|
||||
#define LCD_RISSET_FIFOU 0x00000020 // DMA FIFO Underflow Raw Interrupt
|
||||
// Status and Set
|
||||
#define LCD_RISSET_ACBS 0x00000008 // AC Bias Count Raw Interrupt
|
||||
// Status and Set
|
||||
#define LCD_RISSET_SYNCS 0x00000004 // Frame Synchronization Lost Raw
|
||||
// Interrupt Status and Set
|
||||
#define LCD_RISSET_RRASTRDONE 0x00000002 // Raster Mode Frame Done interrupt
|
||||
#define LCD_RISSET_DONE 0x00000001 // Raster or LIDD Frame Done
|
||||
// (shared, depends on whether
|
||||
// Raster or LIDD mode enabled) Raw
|
||||
// Interrupt Status and Set
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the LCD_O_MISCLR register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define LCD_MISCLR_EOF1 0x00000200 // DMA End-of-Frame 1 Enabled
|
||||
// Interrupt and Clear
|
||||
#define LCD_MISCLR_EOF0 0x00000100 // DMA End-of-Frame 0 Raw Interrupt
|
||||
// and Clear
|
||||
#define LCD_MISCLR_PALLOAD 0x00000040 // DMA Palette Loaded Enabled
|
||||
// Interrupt and Clear
|
||||
#define LCD_MISCLR_FIFOU 0x00000020 // DMA FIFO Underflow Enabled
|
||||
// Interrupt and Clear
|
||||
#define LCD_MISCLR_ACBS 0x00000008 // AC Bias Count Enabled Interrupt
|
||||
// and Clear
|
||||
#define LCD_MISCLR_SYNCS 0x00000004 // Frame Synchronization Lost
|
||||
// Enabled Interrupt and Clear
|
||||
#define LCD_MISCLR_RRASTRDONE 0x00000002 // Raster Mode Frame Done interrupt
|
||||
#define LCD_MISCLR_DONE 0x00000001 // Raster or LIDD Frame Done
|
||||
// (shared, depends on whether
|
||||
// Raster or LIDD mode enabled)
|
||||
// Enabled Interrupt and Clear
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the LCD_O_IM register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define LCD_IM_EOF1 0x00000200 // DMA End-of-Frame 1 Interrupt
|
||||
// Enable Set
|
||||
#define LCD_IM_EOF0 0x00000100 // DMA End-of-Frame 0 Interrupt
|
||||
// Enable Set
|
||||
#define LCD_IM_PALLOAD 0x00000040 // DMA Palette Loaded Interrupt
|
||||
// Enable Set
|
||||
#define LCD_IM_FIFOU 0x00000020 // DMA FIFO Underflow Interrupt
|
||||
// Enable Set
|
||||
#define LCD_IM_ACBS 0x00000008 // AC Bias Count Interrupt Enable
|
||||
// Set
|
||||
#define LCD_IM_SYNCS 0x00000004 // Frame Synchronization Lost
|
||||
// Interrupt Enable Set
|
||||
#define LCD_IM_RRASTRDONE 0x00000002 // Raster Mode Frame Done Interrupt
|
||||
// Enable Set
|
||||
#define LCD_IM_DONE 0x00000001 // Raster or LIDD Frame Done
|
||||
// (shared, depends on whether
|
||||
// Raster or LIDD mode enabled)
|
||||
// Interrupt Enable Set
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the LCD_O_IENC register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define LCD_IENC_EOF1 0x00000200 // DMA End-of-Frame 1 Interrupt
|
||||
// Enable Clear
|
||||
#define LCD_IENC_EOF0 0x00000100 // DMA End-of-Frame 0 Interrupt
|
||||
// Enable Clear
|
||||
#define LCD_IENC_PALLOAD 0x00000040 // DMA Palette Loaded Interrupt
|
||||
// Enable Clear
|
||||
#define LCD_IENC_FIFOU 0x00000020 // DMA FIFO Underflow Interrupt
|
||||
// Enable Clear
|
||||
#define LCD_IENC_ACBS 0x00000008 // AC Bias Count Interrupt Enable
|
||||
// Clear
|
||||
#define LCD_IENC_SYNCS 0x00000004 // Frame Synchronization Lost
|
||||
// Interrupt Enable Clear
|
||||
#define LCD_IENC_RRASTRDONE 0x00000002 // Raster Mode Frame Done Interrupt
|
||||
// Enable Clear
|
||||
#define LCD_IENC_DONE 0x00000001 // Raster or LIDD Frame Done
|
||||
// (shared, depends on whether
|
||||
// Raster or LIDD mode enabled)
|
||||
// Interrupt Enable Clear
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the LCD_O_CLKEN register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define LCD_CLKEN_DMA 0x00000004 // DMA Clock Enable
|
||||
#define LCD_CLKEN_LIDD 0x00000002 // LIDD Submodule Clock Enable
|
||||
#define LCD_CLKEN_CORE 0x00000001 // LCD Core Clock Enable
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the LCD_O_CLKRESET register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define LCD_CLKRESET_MAIN 0x00000008 // Software Reset for the entire
|
||||
// LCD module
|
||||
#define LCD_CLKRESET_DMA 0x00000004 // Software Reset for the DMA
|
||||
// submodule
|
||||
#define LCD_CLKRESET_LIDD 0x00000002 // Software Reset for the LIDD
|
||||
// submodule (character displays)
|
||||
#define LCD_CLKRESET_CORE 0x00000001 // Software Reset for the Core,
|
||||
// which encompasses the Raster
|
||||
// Active Matrix and Passive Matrix
|
||||
// logic
|
||||
|
||||
#endif // __HW_LCD_H__
|
|
@ -0,0 +1,151 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// hw_memmap.h - Macros defining the memory map of the device.
|
||||
//
|
||||
// Copyright (c) 2005-2014 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 2.1.0.12573 of the Tiva Firmware Development Package.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __HW_MEMMAP_H__
|
||||
#define __HW_MEMMAP_H__
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the base address of the memories and
|
||||
// peripherals.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FLASH_BASE 0x00000000 // FLASH memory
|
||||
#define SRAM_BASE 0x20000000 // SRAM memory
|
||||
#define WATCHDOG0_BASE 0x40000000 // Watchdog0
|
||||
#define WATCHDOG1_BASE 0x40001000 // Watchdog1
|
||||
#define GPIO_PORTA_BASE 0x40004000 // GPIO Port A
|
||||
#define GPIO_PORTB_BASE 0x40005000 // GPIO Port B
|
||||
#define GPIO_PORTC_BASE 0x40006000 // GPIO Port C
|
||||
#define GPIO_PORTD_BASE 0x40007000 // GPIO Port D
|
||||
#define SSI0_BASE 0x40008000 // SSI0
|
||||
#define SSI1_BASE 0x40009000 // SSI1
|
||||
#define SSI2_BASE 0x4000A000 // SSI2
|
||||
#define SSI3_BASE 0x4000B000 // SSI3
|
||||
#define UART0_BASE 0x4000C000 // UART0
|
||||
#define UART1_BASE 0x4000D000 // UART1
|
||||
#define UART2_BASE 0x4000E000 // UART2
|
||||
#define UART3_BASE 0x4000F000 // UART3
|
||||
#define UART4_BASE 0x40010000 // UART4
|
||||
#define UART5_BASE 0x40011000 // UART5
|
||||
#define UART6_BASE 0x40012000 // UART6
|
||||
#define UART7_BASE 0x40013000 // UART7
|
||||
#define I2C0_BASE 0x40020000 // I2C0
|
||||
#define I2C1_BASE 0x40021000 // I2C1
|
||||
#define I2C2_BASE 0x40022000 // I2C2
|
||||
#define I2C3_BASE 0x40023000 // I2C3
|
||||
#define GPIO_PORTE_BASE 0x40024000 // GPIO Port E
|
||||
#define GPIO_PORTF_BASE 0x40025000 // GPIO Port F
|
||||
#define GPIO_PORTG_BASE 0x40026000 // GPIO Port G
|
||||
#define GPIO_PORTH_BASE 0x40027000 // GPIO Port H
|
||||
#define PWM0_BASE 0x40028000 // Pulse Width Modulator (PWM)
|
||||
#define PWM1_BASE 0x40029000 // Pulse Width Modulator (PWM)
|
||||
#define QEI0_BASE 0x4002C000 // QEI0
|
||||
#define QEI1_BASE 0x4002D000 // QEI1
|
||||
#define TIMER0_BASE 0x40030000 // Timer0
|
||||
#define TIMER1_BASE 0x40031000 // Timer1
|
||||
#define TIMER2_BASE 0x40032000 // Timer2
|
||||
#define TIMER3_BASE 0x40033000 // Timer3
|
||||
#define TIMER4_BASE 0x40034000 // Timer4
|
||||
#define TIMER5_BASE 0x40035000 // Timer5
|
||||
#define WTIMER0_BASE 0x40036000 // Wide Timer0
|
||||
#define WTIMER1_BASE 0x40037000 // Wide Timer1
|
||||
#define ADC0_BASE 0x40038000 // ADC0
|
||||
#define ADC1_BASE 0x40039000 // ADC1
|
||||
#define COMP_BASE 0x4003C000 // Analog comparators
|
||||
#define GPIO_PORTJ_BASE 0x4003D000 // GPIO Port J
|
||||
#define CAN0_BASE 0x40040000 // CAN0
|
||||
#define CAN1_BASE 0x40041000 // CAN1
|
||||
#define WTIMER2_BASE 0x4004C000 // Wide Timer2
|
||||
#define WTIMER3_BASE 0x4004D000 // Wide Timer3
|
||||
#define WTIMER4_BASE 0x4004E000 // Wide Timer4
|
||||
#define WTIMER5_BASE 0x4004F000 // Wide Timer5
|
||||
#define USB0_BASE 0x40050000 // USB 0 Controller
|
||||
#define GPIO_PORTA_AHB_BASE 0x40058000 // GPIO Port A (high speed)
|
||||
#define GPIO_PORTB_AHB_BASE 0x40059000 // GPIO Port B (high speed)
|
||||
#define GPIO_PORTC_AHB_BASE 0x4005A000 // GPIO Port C (high speed)
|
||||
#define GPIO_PORTD_AHB_BASE 0x4005B000 // GPIO Port D (high speed)
|
||||
#define GPIO_PORTE_AHB_BASE 0x4005C000 // GPIO Port E (high speed)
|
||||
#define GPIO_PORTF_AHB_BASE 0x4005D000 // GPIO Port F (high speed)
|
||||
#define GPIO_PORTG_AHB_BASE 0x4005E000 // GPIO Port G (high speed)
|
||||
#define GPIO_PORTH_AHB_BASE 0x4005F000 // GPIO Port H (high speed)
|
||||
#define GPIO_PORTJ_AHB_BASE 0x40060000 // GPIO Port J (high speed)
|
||||
#define GPIO_PORTK_BASE 0x40061000 // GPIO Port K
|
||||
#define GPIO_PORTL_BASE 0x40062000 // GPIO Port L
|
||||
#define GPIO_PORTM_BASE 0x40063000 // GPIO Port M
|
||||
#define GPIO_PORTN_BASE 0x40064000 // GPIO Port N
|
||||
#define GPIO_PORTP_BASE 0x40065000 // GPIO Port P
|
||||
#define GPIO_PORTQ_BASE 0x40066000 // GPIO Port Q
|
||||
#define GPIO_PORTR_BASE 0x40067000 // General-Purpose Input/Outputs
|
||||
// (GPIOs)
|
||||
#define GPIO_PORTS_BASE 0x40068000 // General-Purpose Input/Outputs
|
||||
// (GPIOs)
|
||||
#define GPIO_PORTT_BASE 0x40069000 // General-Purpose Input/Outputs
|
||||
// (GPIOs)
|
||||
#define EEPROM_BASE 0x400AF000 // EEPROM memory
|
||||
#define ONEWIRE0_BASE 0x400B6000 // 1-Wire Master Module
|
||||
#define I2C8_BASE 0x400B8000 // I2C8
|
||||
#define I2C9_BASE 0x400B9000 // I2C9
|
||||
#define I2C4_BASE 0x400C0000 // I2C4
|
||||
#define I2C5_BASE 0x400C1000 // I2C5
|
||||
#define I2C6_BASE 0x400C2000 // I2C6
|
||||
#define I2C7_BASE 0x400C3000 // I2C7
|
||||
#define EPI0_BASE 0x400D0000 // EPI0
|
||||
#define TIMER6_BASE 0x400E0000 // General-Purpose Timers
|
||||
#define TIMER7_BASE 0x400E1000 // General-Purpose Timers
|
||||
#define EMAC0_BASE 0x400EC000 // Ethernet Controller
|
||||
#define SYSEXC_BASE 0x400F9000 // System Exception Module
|
||||
#define HIB_BASE 0x400FC000 // Hibernation Module
|
||||
#define FLASH_CTRL_BASE 0x400FD000 // FLASH Controller
|
||||
#define SYSCTL_BASE 0x400FE000 // System Control
|
||||
#define UDMA_BASE 0x400FF000 // uDMA Controller
|
||||
#define CCM0_BASE 0x44030000 // Cyclical Redundancy Check (CRC)
|
||||
#define SHAMD5_BASE 0x44034000 // SHA/MD5 Accelerator
|
||||
#define AES_BASE 0x44036000 // Advance Encryption
|
||||
// Hardware-Accelerated Module
|
||||
#define DES_BASE 0x44038000 // Data Encryption Standard
|
||||
// Accelerator (DES)
|
||||
#define LCD0_BASE 0x44050000 // LCD Controller
|
||||
#define ITM_BASE 0xE0000000 // Instrumentation Trace Macrocell
|
||||
#define DWT_BASE 0xE0001000 // Data Watchpoint and Trace
|
||||
#define FPB_BASE 0xE0002000 // FLASH Patch and Breakpoint
|
||||
#define NVIC_BASE 0xE000E000 // Nested Vectored Interrupt Ctrl
|
||||
#define TPIU_BASE 0xE0040000 // Trace Port Interface Unit
|
||||
|
||||
#endif // __HW_MEMMAP_H__
|
File diff suppressed because it is too large
Load Diff
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue