提交 3a1c1c45 编写于 作者: A ArdaFu

[bsp] Add BSP for TM4C1294XL (TI Tiva C Series Connected LaunchPad)

上级 fc6747ef
# 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')
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)
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')
/*
* 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;
}
/*
* 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();
}
/*
* 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
/*
* 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;
}
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')
/*
* 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);
/*
* 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
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')
此差异已折叠。
//*****************************************************************************
//
// 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__
此差异已折叠。
//*****************************************************************************
//
// 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__
此差异已折叠。
//*****************************************************************************
//
// 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__
此差异已折叠。
此差异已折叠。
此差异已折叠。
//*****************************************************************************
//
// 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__
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册