git-svn-id: svn://svn.code.sf.net/p/chibios/svn/trunk@1092 35acf78f-673a-0410-8e92-d51de3d6d3f4

This commit is contained in:
gdisirio 2009-08-20 12:58:07 +00:00
parent 0770ffb75e
commit 9193bc2a81
12 changed files with 2 additions and 1644 deletions

View File

@ -92,7 +92,8 @@ ASMSRC = $(PORTASM) \
INCDIR = $(PORTINC) $(KERNINC) $(TESTINC) \
../../os/io \
../../os/io/platforms/LPC214x \
../../os/various
../../os/various \
../../os/ports/GCC/ARM7/LPC214x
#
# Project, sources and paths

View File

@ -1,35 +0,0 @@
/*
ChibiOS/RT - Copyright (C) 2006-2007 Giovanni Di Sirio.
This file is part of ChibiOS/RT.
ChibiOS/RT is free software; you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation; either version 3 of the License, or
(at your option) any later version.
ChibiOS/RT is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef _WFI_H_
#define _WFI_H_
#include "lpc214x.h"
#ifndef port_wait_for_interrupt
#if ENABLE_WFI_IDLE != 0
#define port_wait_for_interrupt() { \
PCON = 1; \
}
#else
#define port_wait_for_interrupt()
#endif
#endif
#endif /* _WFI_H_ */

View File

@ -1,523 +0,0 @@
/*
ChibiOS/RT - Copyright (C) 2006-2007 Giovanni Di Sirio.
This file is part of ChibiOS/RT.
ChibiOS/RT is free software; you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation; either version 3 of the License, or
(at your option) any later version.
ChibiOS/RT is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
/**
* @file lpc214x.h
* @brief LPC214x register definitions
*/
#ifndef _LPC214X_H_
#define _LPC214X_H_
typedef volatile unsigned char IOREG8;
typedef volatile unsigned int IOREG32;
/*
* System.
*/
#define MEMMAP (*((IOREG32 *)0xE01FC040))
#define PCON (*((IOREG32 *)0xE01FC0C0))
#define PCONP (*((IOREG32 *)0xE01FC0C4))
#define VPBDIV (*((IOREG32 *)0xE01FC100))
#define EXTINT (*((IOREG32 *)0xE01FC140))
#define INTWAKE (*((IOREG32 *)0xE01FC144))
#define EXTMODE (*((IOREG32 *)0xE01FC148))
#define EXTPOLAR (*((IOREG32 *)0xE01FC14C))
#define RSID (*((IOREG32 *)0xE01FC180))
#define CSPR (*((IOREG32 *)0xE01FC184))
#define SCS (*((IOREG32 *)0xE01FC1A0))
#define VPD_D4 0
#define VPD_D1 1
#define VPD_D2 2
#define VPD_RESERVED 3
#define PCTIM0 (1 << 1)
#define PCTIM1 (1 << 2)
#define PCUART0 (1 << 3)
#define PCUART1 (1 << 4)
#define PCPWM0 (1 << 5)
#define PCI2C0 (1 << 7)
#define PCSPI0 (1 << 8)
#define PCRTC (1 << 9)
#define PCSPI1 (1 << 10)
#define PCAD0 (1 << 12)
#define PCI2C1 (1 << 19)
#define PCAD1 (1 << 20)
#define PCUSB (1 << 31)
#define PCALL (PCTIM0 | PCTIM1 | PCUART0 | PCUART1 | \
PCPWM0 | PCI2C0 | PCSPI0 | PCRTC | PCSPI1 | \
PCAD0 | PCI2C1 | PCAD1 | PCUSB)
#define EINT0 1
#define EINT1 2
#define EINT2 4
#define EINT3 8
#define EXTWAKE0 1
#define EXTWAKE1 2
#define EXTWAKE2 4
#define EXTWAKE3 8
#define USBWAKE 0x20
#define BODWAKE 0x4000
#define RTCWAKE 0x8000
#define EXTMODE0 1
#define EXTMODE1 2
#define EXTMODE2 4
#define EXTMODE3 8
#define EXTPOLAR0 1
#define EXTPOLAR1 2
#define EXTPOLAR2 4
#define EXTPOLAR3 8
typedef struct {
IOREG32 PLL_CON;
IOREG32 PLL_CFG;
IOREG32 PLL_STAT;
IOREG32 PLL_FEED;
} PLL;
#define PLL0Base ((PLL *)0xE01FC080)
#define PLL1Base ((PLL *)0xE01FC0A0)
#define PLL0CON (PLL0Base->PLL_CON)
#define PLL0CFG (PLL0Base->PLL_CFG)
#define PLL0STAT (PLL0Base->PLL_STAT)
#define PLL0FEED (PLL0Base->PLL_FEED)
#define PLL1CON (PLL1Base->PLL_CON)
#define PLL1CFG (PLL1Base->PLL_CFG)
#define PLL1STAT (PLL1Base->PLL_STAT)
#define PLL1FEED (PLL1Base->PLL_FEED)
/*
* Pins.
*/
typedef struct {
IOREG32 PS_SEL0;
IOREG32 PS_SEL1;
IOREG32 PS_SEL2;
} PS;
#define PSBase ((PS *)0xE002C000)
#define PINSEL0 (PSBase->PS_SEL0)
#define PINSEL1 (PSBase->PS_SEL1)
#define PINSEL2 (PSBase->PS_SEL2)
/*
* VIC
*/
#define SOURCE_WDT 0
#define SOURCE_ARMCore0 2
#define SOURCE_ARMCore1 3
#define SOURCE_Timer0 4
#define SOURCE_Timer1 5
#define SOURCE_UART0 6
#define SOURCE_UART1 7
#define SOURCE_PWM0 8
#define SOURCE_I2C0 9
#define SOURCE_SPI0 10
#define SOURCE_SPI1 11
#define SOURCE_PLL 12
#define SOURCE_RTC 13
#define SOURCE_EINT0 14
#define SOURCE_EINT1 15
#define SOURCE_EINT2 16
#define SOURCE_EINT3 17
#define SOURCE_ADC0 18
#define SOURCE_I2C1 19
#define SOURCE_BOD 20
#define SOURCE_ADC1 21
#define SOURCE_USB 22
#define INTMASK(n) (1 << (n))
#define ALLINTMASK (INTMASK(SOURCE_WDT) | INTMASK(SOURCE_ARMCore0) | \
INTMASK(SOURCE_ARMCore1) | INTMASK(SOURCE_Timer0) | \
INTMASK(SOURCE_Timer1) | INTMASK(SOURCE_UART0) | \
INTMASK(SOURCE_UART1) | INTMASK(SOURCE_PWM0) | \
INTMASK(SOURCE_I2C0) | INTMASK(SOURCE_SPI0) | \
INTMASK(SOURCE_SPI1) | INTMASK(SOURCE_PLL) | \
INTMASK(SOURCE_RTC) | INTMASK(SOURCE_EINT0) | \
INTMASK(SOURCE_EINT1) | INTMASK(SOURCE_EINT2) | \
INTMASK(SOURCE_EINT3) | INTMASK(SOURCE_ADC0) | \
INTMASK(SOURCE_I2C1) | INTMASK(SOURCE_BOD) | \
INTMASK(SOURCE_ADC1) | INTMASK(SOURCE_USB))
typedef struct {
IOREG32 VIC_IRQStatus;
IOREG32 VIC_FIQStatus;
IOREG32 VIC_RawIntr;
IOREG32 VIC_IntSelect;
IOREG32 VIC_IntEnable;
IOREG32 VIC_IntEnClear;
IOREG32 VIC_SoftInt;
IOREG32 VIC_SoftIntClear;
IOREG32 VIC_Protection;
IOREG32 unused1[3];
IOREG32 VIC_VectAddr;
IOREG32 VIC_DefVectAddr;
IOREG32 unused2[50];
IOREG32 VIC_VectAddrs[16];
IOREG32 unused3[48];
IOREG32 VIC_VectCntls[16];
} VIC;
#define VICBase ((VIC *)0xFFFFF000)
#define VICVectorsBase ((IOREG32 *)0xFFFFF100)
#define VICControlsBase ((IOREG32 *)0xFFFFF200)
#define VICIRQStatus (VICBase->VIC_IRQStatus)
#define VICFIQStatus (VICBase->VIC_FIQStatus)
#define VICRawIntr (VICBase->VIC_RawIntr)
#define VICIntSelect (VICBase->VIC_IntSelect)
#define VICIntEnable (VICBase->VIC_IntEnable)
#define VICIntEnClear (VICBase->VIC_IntEnClear)
#define VICSoftInt (VICBase->VIC_SoftInt)
#define VICSoftIntClear (VICBase->VIC_SoftIntClear)
#define VICProtection (VICBase->VIC_Protection)
#define VICVectAddr (VICBase->VIC_VectAddr)
#define VICDefVectAddr (VICBase->VIC_DefVectAddr)
#define VICVectAddrs(n) (VICBase->VIC_VectAddrs[n])
#define VICVectCntls(n) (VICBase->VIC_VectCntls[n])
/*
* MAM.
*/
typedef struct {
IOREG32 MAM_Control;
IOREG32 MAM_Timing;
} MAM;
#define MAMBase ((MAM *)0xE01FC000)
#define MAMCR (MAMBase->MAM_Control)
#define MAMTIM (MAMBase->MAM_Timing)
/*
* GPIO - FIO.
*/
typedef struct {
IOREG32 IO_PIN;
IOREG32 IO_SET;
IOREG32 IO_DIR;
IOREG32 IO_CLR;
} GPIO;
#define GPIO0Base ((GPIO *)0xE0028000)
#define IO0PIN (GPIO0Base->IO_PIN)
#define IO0SET (GPIO0Base->IO_SET)
#define IO0DIR (GPIO0Base->IO_DIR)
#define IO0CLR (GPIO0Base->IO_CLR)
#define GPIO1Base ((GPIO *)0xE0028010)
#define IO1PIN (GPIO1Base->IO_PIN)
#define IO1SET (GPIO1Base->IO_SET)
#define IO1DIR (GPIO1Base->IO_DIR)
#define IO1CLR (GPIO1Base->IO_CLR)
typedef struct {
IOREG32 FIO_DIR;
IOREG32 unused1;
IOREG32 unused2;
IOREG32 unused3;
IOREG32 FIO_MASK;
IOREG32 FIO_PIN;
IOREG32 FIO_SET;
IOREG32 FIO_CLR;
} FIO;
#define FIO0Base ((FIO *)0x3FFFC000)
#define FIO0DIR (FIO0Base->FIO_DIR)
#define FIO0MASK (FIO0Base->FIO_MASK)
#define FIO0PIN (FIO0Base->FIO_PIN)
#define FIO0SET (FIO0Base->FIO_SET)
#define FIO0CLR (FIO0Base->FIO_CLR)
#define FIO1Base ((FIO *)0x3FFFC020)
#define FIO1DIR (FIO1Base->FIO_DIR)
#define FIO1MASK (FIO1Base->FIO_MASK)
#define FIO1PIN (FIO1Base->FIO_PIN)
#define FIO1SET (FIO1Base->FIO_SET)
#define FIO1CLR (FIO1Base->FIO_CLR)
/*
* UART.
*/
typedef struct {
union {
IOREG32 UART_RBR;
IOREG32 UART_THR;
IOREG32 UART_DLL;
};
union {
IOREG32 UART_IER;
IOREG32 UART_DLM;
};
union {
IOREG32 UART_IIR;
IOREG32 UART_FCR;
};
IOREG32 UART_LCR;
IOREG32 UART_MCR; // UART1 only
IOREG32 UART_LSR;
IOREG32 unused18;
IOREG32 UART_SCR;
IOREG32 UART_ACR;
IOREG32 unused24;
IOREG32 UART_FDR;
IOREG32 unused2C;
IOREG32 UART_TER;
} UART;
#define U0Base ((UART *)0xE000C000)
#define U0RBR (U0Base->UART_RBR)
#define U0THR (U0Base->UART_THR)
#define U0DLL (U0Base->UART_DLL)
#define U0IER (U0Base->UART_IER)
#define U0DLM (U0Base->UART_DLM)
#define U0IIR (U0Base->UART_IIR)
#define U0FCR (U0Base->UART_FCR)
#define U0LCR (U0Base->UART_LCR)
#define U0LSR (U0Base->UART_LSR)
#define U0SCR (U0Base->UART_SCR)
#define U0ACR (U0Base->UART_ACR)
#define U0FDR (U0Base->UART_FDR)
#define U0TER (U0Base->UART_TER)
#define U1Base ((UART *)0xE0010000)
#define U1RBR (U1Base->UART_RBR)
#define U1THR (U1Base->UART_THR)
#define U1DLL (U1Base->UART_DLL)
#define U1IER (U1Base->UART_IER)
#define U1DLM (U1Base->UART_DLM)
#define U1IIR (U1Base->UART_IIR)
#define U1FCR (U1Base->UART_FCR)
#define U1MCR (U1Base->UART_MCR)
#define U1LCR (U1Base->UART_LCR)
#define U1LSR (U1Base->UART_LSR)
#define U1SCR (U1Base->UART_SCR)
#define U1ACR (U1Base->UART_ACR)
#define U1FDR (U1Base->UART_FDR)
#define U1TER (U1Base->UART_TER)
#define IIR_SRC_MASK 0x0F
#define IIR_SRC_NONE 0x01
#define IIR_SRC_TX 0x02
#define IIR_SRC_RX 0x04
#define IIR_SRC_ERROR 0x06
#define IIR_SRC_TIMEOUT 0x0C
#define IER_RBR 1
#define IER_THRE 2
#define IER_STATUS 4
#define IIR_INT_PENDING 1
#define LCR_WL5 0
#define LCR_WL6 1
#define LCR_WL7 2
#define LCR_WL8 3
#define LCR_STOP1 0
#define LCR_STOP2 4
#define LCR_NOPARITY 0
#define LCR_PARITYODD 0x08
#define LCR_PARITYEVEN 0x18
#define LCR_PARITYONE 0x28
#define LCR_PARITYZERO 0x38
#define LCR_BREAK_ON 0x40
#define LCR_DLAB 0x80
#define FCR_ENABLE 1
#define FCR_RXRESET 2
#define FCR_TXRESET 4
#define FCR_TRIGGER0 0
#define FCR_TRIGGER1 0x40
#define FCR_TRIGGER2 0x80
#define FCR_TRIGGER3 0xC0
#define LSR_RBR_FULL 1
#define LSR_OVERRUN 2
#define LSR_PARITY 4
#define LSR_FRAMING 8
#define LSR_BREAK 0x10
#define LSR_THRE 0x20
#define LSR_TEMT 0x40
#define LSR_RXFE 0x80
#define TER_ENABLE 0x80
/*
* SSP.
*/
typedef struct {
IOREG32 SSP_CR0;
IOREG32 SSP_CR1;
IOREG32 SSP_DR;
IOREG32 SSP_SR;
IOREG32 SSP_CPSR;
IOREG32 SSP_IMSC;
IOREG32 SSP_RIS;
IOREG32 SSP_MIS;
IOREG32 SSP_ICR;
} SSP;
#define SSPBase ((SSP *)0xE0068000)
#define SSPCR0 (SSPBase->SSP_CR0)
#define SSPCR1 (SSPBase->SSP_CR1)
#define SSPDR (SSPBase->SSP_DR)
#define SSPSR (SSPBase->SSP_SR)
#define SSPCPSR (SSPBase->SSP_CPSR)
#define SSPIMSC (SSPBase->SSP_IMSC)
#define SSPRIS (SSPBase->SSP_RIS)
#define SSPMIS (SSPBase->SSP_MIS)
#define SSPICR (SSPBase->SSP_ICR)
#define CR0_DSS4BIT 3
#define CR0_DSS5BIT 4
#define CR0_DSS6BIT 5
#define CR0_DSS7BIT 6
#define CR0_DSS8BIT 7
#define CR0_DSS9BIT 8
#define CR0_DSS10BIT 9
#define CR0_DSS11BIT 0xA
#define CR0_DSS12BIT 0xB
#define CR0_DSS13BIT 0xC
#define CR0_DSS14BIT 0xD
#define CR0_DSS15BIT 0xE
#define CR0_DSS16BIT 0xF
#define CR0_FRFSPI 0
#define CR0_FRFSSI 0x10
#define CR0_FRFMW 0x20
#define CR0_CPOL 0x40
#define CR0_CPHA 0x80
#define CR0_CLOCKRATE(n) ((n) << 8)
#define CR1_LBM 1
#define CR1_SSE 2
#define CR1_MS 4
#define CR1_SOD 8
#define SR_TFE 1
#define SR_TNF 2
#define SR_RNE 4
#define SR_RFF 8
#define SR_BSY 0x10
#define IMSC_ROR 1
#define IMSC_RT 2
#define IMSC_RX 4
#define IMSC_TX 8
#define RIS_ROR 1
#define RIS_RT 2
#define RIS_RX 4
#define RIS_TX 8
#define MIS_ROR 1
#define MIS_RT 2
#define MIS_RX 4
#define MIS_TX 8
#define ICR_ROR 1
#define ICR_RT 2
/*
* Timers/Counters.
*/
typedef struct {
IOREG32 TC_IR;
IOREG32 TC_TCR;
IOREG32 TC_TC;
IOREG32 TC_PR;
IOREG32 TC_PC;
IOREG32 TC_MCR;
IOREG32 TC_MR0;
IOREG32 TC_MR1;
IOREG32 TC_MR2;
IOREG32 TC_MR3;
IOREG32 TC_CCR;
IOREG32 TC_CR0;
IOREG32 TC_CR1;
IOREG32 TC_CR2;
IOREG32 TC_CR3;
IOREG32 TC_EMR;
IOREG32 TC_CTCR;
} TC;
#define T0Base ((TC *)0xE0004000)
#define T0IR (T0Base->TC_IR)
#define T0TCR (T0Base->TC_TCR)
#define T0TC (T0Base->TC_TC)
#define T0PR (T0Base->TC_PR)
#define T0PC (T0Base->TC_PC)
#define T0MCR (T0Base->TC_MCR)
#define T0MR0 (T0Base->TC_MR0)
#define T0MR1 (T0Base->TC_MR1)
#define T0MR2 (T0Base->TC_MR2)
#define T0MR3 (T0Base->TC_MR3)
#define T0CCR (T0Base->TC_CCR)
#define T0CR0 (T0Base->TC_CR0)
#define T0CR1 (T0Base->TC_CR1)
#define T0CR2 (T0Base->TC_CR2)
#define T0CR3 (T0Base->TC_CR3)
#define T0EMR (T0Base->TC_EMR)
#define T0CTCR (T0Base->TC_CTCR)
#define T1Base ((TC *)0xE0008000)
#define T1IR (T1Base->TC_IR)
#define T1TCR (T1Base->TC_TCR)
#define T1TC (T1Base->TC_TC)
#define T1PR (T1Base->TC_PR)
#define T1PC (T1Base->TC_PC)
#define T1MCR (T1Base->TC_MCR)
#define T1MR0 (T1Base->TC_MR0)
#define T1MR1 (T1Base->TC_MR1)
#define T1MR2 (T1Base->TC_MR2)
#define T1MR3 (T1Base->TC_MR3)
#define T1CCR (T1Base->TC_CCR)
#define T1CR0 (T1Base->TC_CR0)
#define T1CR1 (T1Base->TC_CR1)
#define T1CR2 (T1Base->TC_CR2)
#define T1CR3 (T1Base->TC_CR3)
#define T1EMR (T1Base->TC_EMR)
#define T1CTCR (T1Base->TC_CTCR)
/*
* Watchdog.
*/
typedef struct {
IOREG32 WD_MOD;
IOREG32 WD_TC;
IOREG32 WD_FEED;
IOREG32 WD_TV;
} WD;
#define WDBase ((WD *)0xE0000000)
#define WDMOD (WDBase->WD_MOD)
#define WDTC (WDBase->WD_TC)
#define WDFEED (WDBase->WD_FEED)
#define WDTV (WDBase->WD_TV)
/*
* DAC.
*/
#define DACR (*((IOREG32 *)0xE006C000))
#endif /* _LPC214X_H_ */

View File

@ -1,268 +0,0 @@
/*
ChibiOS/RT - Copyright (C) 2006-2007 Giovanni Di Sirio.
This file is part of ChibiOS/RT.
ChibiOS/RT is free software; you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation; either version 3 of the License, or
(at your option) any later version.
ChibiOS/RT is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
/**
* @file LPC214x/lpc214x_serial.c
* @brief LPC214x Serial driver code.
* @addtogroup LPC214x_SERIAL
* @{
*/
#include <ch.h>
#include "lpc214x.h"
#include "vic.h"
#include "lpc214x_serial.h"
#include "board.h"
#if USE_LPC214x_UART0 || defined(__DOXYGEN__)
/** @brief UART0 serial driver identifier.*/
FullDuplexDriver COM1;
static uint8_t ib1[SERIAL_BUFFERS_SIZE];
static uint8_t ob1[SERIAL_BUFFERS_SIZE];
#endif
#if USE_LPC214x_UART1 || defined(__DOXYGEN__)
/** @brief UART1 serial driver identifier.*/
FullDuplexDriver COM2;
static uint8_t ib2[SERIAL_BUFFERS_SIZE];
static uint8_t ob2[SERIAL_BUFFERS_SIZE];
#endif
/**
* @brief Error handling routine.
* @param[in] err UART LSR register value
* @param[in] com communication channel associated to the USART
*/
static void SetError(IOREG32 err, FullDuplexDriver *com) {
dflags_t sts = 0;
if (err & LSR_OVERRUN)
sts |= SD_OVERRUN_ERROR;
if (err & LSR_PARITY)
sts |= SD_PARITY_ERROR;
if (err & LSR_FRAMING)
sts |= SD_FRAMING_ERROR;
if (err & LSR_BREAK)
sts |= SD_BREAK_DETECTED;
chSysLockFromIsr();
chFDDAddFlagsI(com, sts);
chSysUnlockFromIsr();
}
/** @cond never*/
__attribute__((noinline))
/** @endcond*/
/**
* @brief Common IRQ handler.
* @param[in] u pointer to an UART I/O block
* @param[in] com communication channel associated to the UART
* @note Tries hard to clear all the pending interrupt sources, we dont want to
* go through the whole ISR and have another interrupt soon after.
*/
static void ServeInterrupt(UART *u, FullDuplexDriver *com) {
while (TRUE) {
switch (u->UART_IIR & IIR_SRC_MASK) {
case IIR_SRC_NONE:
return;
case IIR_SRC_ERROR:
SetError(u->UART_LSR, com);
break;
case IIR_SRC_TIMEOUT:
case IIR_SRC_RX:
while (u->UART_LSR & LSR_RBR_FULL) {
chSysLockFromIsr();
if (chIQPutI(&com->d2.iqueue, u->UART_RBR) < Q_OK)
chFDDAddFlagsI(com, SD_OVERRUN_ERROR);
chSysUnlockFromIsr();
}
chSysLockFromIsr();
chEvtBroadcastI(&com->d1.ievent);
chSysUnlockFromIsr();
break;
case IIR_SRC_TX:
{
#if UART_FIFO_PRELOAD > 0
int i = UART_FIFO_PRELOAD;
do {
chSysLockFromIsr();
msg_t b = chOQGetI(&com->d2.oqueue);
chSysUnlockFromIsr();
if (b < Q_OK) {
u->UART_IER &= ~IER_THRE;
chSysLockFromIsr();
chEvtBroadcastI(&com->d1.oevent);
chSysUnlockFromIsr();
break;
}
u->UART_THR = b;
} while (--i);
#else
chSysLockFromIsr();
msg_t b = chFDDRequestDataI(com);
chSysUnlockFromIsr();
if (b < Q_OK)
u->UART_IER &= ~IER_THRE;
else
u->UART_THR = b;
#endif
}
default:
u->UART_THR;
u->UART_RBR;
}
}
}
#if UART_FIFO_PRELOAD > 0
static void preload(UART *u, FullDuplexDriver *com) {
if (u->UART_LSR & LSR_THRE) {
int i = UART_FIFO_PRELOAD;
do {
chSysLockFromIsr();
msg_t b = chOQGetI(&com->d2.oqueue);
chSysUnlockFromIsr();
if (b < Q_OK) {
chSysLockFromIsr();
chEvtBroadcastI(&com->d1.oevent);
chSysUnlockFromIsr();
return;
}
u->UART_THR = b;
} while (--i);
}
u->UART_IER |= IER_THRE;
}
#endif
#if USE_LPC214x_UART0 || defined(__DOXYGEN__)
CH_IRQ_HANDLER(UART0IrqHandler) {
CH_IRQ_PROLOGUE();
ServeInterrupt(U0Base, &COM1);
VICVectAddr = 0;
CH_IRQ_EPILOGUE();
}
static void OutNotify1(void) {
#if UART_FIFO_PRELOAD > 0
preload(U0Base, &COM1);
#else
UART *u = U0Base;
if (u->UART_LSR & LSR_THRE) {
chSysLockFromIsr();
u->UART_THR = chOQGetI(&COM1.sd_oqueue);
chSysUnlockFromIsr();
}
u->UART_IER |= IER_THRE;
#endif
}
#endif
#if USE_LPC214x_UART1 || defined(__DOXYGEN__)
CH_IRQ_HANDLER(UART1IrqHandler) {
CH_IRQ_PROLOGUE();
ServeInterrupt(U1Base, &COM2);
VICVectAddr = 0;
CH_IRQ_EPILOGUE();
}
static void OutNotify2(void) {
#if UART_FIFO_PRELOAD > 0
preload(U1Base, &COM2);
#else
UART *u = U1Base;
if (u->UART_LSR & LSR_THRE)
u->UART_THR = chOQGetI(&COM2.sd_oqueue);
u->UART_IER |= IER_THRE;
#endif
}
#endif
/**
* @brief UART setup.
* @param[in] u pointer to an UART I/O block
* @param[in] speed serial port speed in bits per second
* @param[in] lcr the value for the @p LCR register
* @param[in] fcr the value for the @p FCR register
* @note Must be invoked with interrupts disabled.
* @note Does not reset the I/O queues.
*/
void uart_setup(UART *u, int speed, int lcr, int fcr) {
int div = PCLK / (speed << 4);
u->UART_LCR = lcr | LCR_DLAB;
u->UART_DLL = div;
u->UART_DLM = div >> 8;
u->UART_LCR = lcr;
u->UART_FCR = FCR_ENABLE | FCR_RXRESET | FCR_TXRESET | fcr;
u->UART_ACR = 0;
u->UART_FDR = 0x10;
u->UART_TER = TER_ENABLE;
u->UART_IER = IER_RBR | IER_STATUS;
}
/**
* @brief Serial driver initialization.
* @param[in] vector1 IRC vector to be used for UART0
* @param[in] vector2 IRC vector to be used for UART1
* @note Handshake pads are not enabled inside this function because they
* may have another use, enable them externally if needed.
* RX and TX pads are handled inside.
*/
void serial_init(int vector1, int vector2) {
#if USE_LPC214x_UART0
SetVICVector(UART0IrqHandler, vector1, SOURCE_UART0);
PCONP = (PCONP & PCALL) | PCUART0;
chFDDInit(&COM1, ib1, sizeof ib1, NULL, ob1, sizeof ob1, OutNotify1);
uart_setup(U0Base,
DEFAULT_UART_BITRATE,
LCR_WL8 | LCR_STOP1 | LCR_NOPARITY,
FCR_TRIGGER0);
VICIntEnable = INTMASK(SOURCE_UART0);
#endif
#if USE_LPC214x_UART1
SetVICVector(UART1IrqHandler, vector2, SOURCE_UART1);
PCONP = (PCONP & PCALL) | PCUART1;
chFDDInit(&COM2, ib2, sizeof ib2, NULL, ob2, sizeof ob2, OutNotify2);
uart_setup(U1Base,
DEFAULT_UART_BITRATE,
LCR_WL8 | LCR_STOP1 | LCR_NOPARITY,
FCR_TRIGGER0);
VICIntEnable = INTMASK(SOURCE_UART0) | INTMASK(SOURCE_UART1);
#endif
}
/** @} */

View File

@ -1,102 +0,0 @@
/*
ChibiOS/RT - Copyright (C) 2006-2007 Giovanni Di Sirio.
This file is part of ChibiOS/RT.
ChibiOS/RT is free software; you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation; either version 3 of the License, or
(at your option) any later version.
ChibiOS/RT is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
/**
* @file LPC214x/lpc214x_serial.h
* @brief LPC214x Serial driver macros and structures.
* @addtogroup LPC214x_SERIAL
* @{
*/
#ifndef _LPC214x_SERIAL_H_
#define _LPC214x_SERIAL_H_
/**
* @brief Serial buffers size.
* @details Configuration parameter, you can change the depth of the queue
* buffers depending on the requirements of your application.
* @note The default is 128 bytes for both the transmission and receive buffers.
*/
#if !defined(SERIAL_BUFFERS_SIZE) || defined(__DOXYGEN__)
#define SERIAL_BUFFERS_SIZE 128
#endif
/**
* @brief Default bit rate.
* @details Configuration parameter, at startup the UARTs are configured at
* this speed.
* @note It is possible to use @p SetUART() in order to change the working
* parameters at runtime.
*/
#if !defined(DEFAULT_UART_BITRATE) || defined(__DOXYGEN__)
#define DEFAULT_UART_BITRATE 38400
#endif
/**
* @brief FIFO preload parameter.
* @details Configuration parameter, this values defines how many bytes are
* preloaded in the HW transmit FIFO for each interrupt, the maximum value is
* 16 the minimum is 2, the value 0 disables the feature.
* @note An high value reduces the number of interrupts generated but can
* also increase the worst case interrupt response time because the
* preload loops.
* @note The value zero disables the feature and reverts to a simpler code
* that will generate an interrupt for each output byte but is much
* smaller and simpler.
*/
#if !defined(UART_FIFO_PRELOAD) || defined(__DOXYGEN__)
#define UART_FIFO_PRELOAD 16
#endif
/**
* @brief UART0 driver enable switch.
* @details If set to @p TRUE the support for USART1 is included.
* @note The default is @p TRUE .
*/
#if !defined(USE_LPC214x_UART0) || defined(__DOXYGEN__)
#define USE_LPC214x_UART0 TRUE
#endif
/**
* @brief UART1 driver enable switch.
* @details If set to @p TRUE the support for USART2 is included.
* @note The default is @p TRUE.
*/
#if !defined(USE_LPC214x_UART1) || defined(__DOXYGEN__)
#define USE_LPC214x_UART1 TRUE
#endif
#ifdef __cplusplus
extern "C" {
#endif
void serial_init(int vector1, int vector2);
void uart_setup(UART *u, int speed, int lcr, int fcr);
CH_IRQ_HANDLER(UART0IrqHandler);
CH_IRQ_HANDLER(UART1IrqHandler);
#ifdef __cplusplus
}
#endif
/** @cond never*/
extern FullDuplexDriver COM1, COM2;
/** @endcond*/
#endif /* _LPC214x_SERIAL_H_*/
/** @} */

View File

@ -1,133 +0,0 @@
/*
ChibiOS/RT - Copyright (C) 2006-2007 Giovanni Di Sirio.
This file is part of ChibiOS/RT.
ChibiOS/RT is free software; you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation; either version 3 of the License, or
(at your option) any later version.
ChibiOS/RT is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
/**
* @file LPC214x/lpc214x_ssp.c
* @brief LPC214x SSP driver code.
* @addtogroup LPC214x_SSP
* @{
*/
#include <ch.h>
#include <pal.h>
#include "lpc214x.h"
#include "lpc214x_ssp.h"
#if LPC214x_SSP_USE_MUTEX
static Semaphore me;
#endif
/**
* @brief Aquires access to the SSP bus.
* @note This function also handles the mutual exclusion on the SSP bus if
* the @p LPC214x_SSP_USE_MUTEX option is enabled.
*/
void sspAcquireBus(void) {
#if LPC214x_SSP_USE_MUTEX
chSemWait(&me);
#endif
palClearPad(IOPORT_A, 20);
}
/**
* @brief Releases the SSP bus.
* @note This function also handles the mutual exclusion on the SSP bus if
* the @p LPC214x_SSP_USE_MUTEX option is enabled.
*/
void sspReleaseBus(void) {
palClearPad(IOPORT_A, 20);
#if LPC214x_SSP_USE_MUTEX
chSemSignal(&me);
#endif
}
/**
* @brief Synchronous SSP transfer.
* @param[in] in pointer to the incoming data buffer, if this parameter is set
* to @p NULL then the incoming data is discarded
* @param[out] out pointer to the outgoing data buffer, if this parameter is
* set to @p NULL then 0xFF bytes will be output
* @param[in] n the number of bytes to be transferred
* @note The transfer is performed in a software loop and is not interrupt
* driven for performance reasons, this function should be invoked
* by a low priority thread in order to "play nice" with the
* rest of the system. This kind of peripheral would really need a
* dedicated DMA channel.
*/
void sspRW(uint8_t *in, uint8_t *out, size_t n) {
int icnt, ocnt;
SSP *ssp = SSPBase;
icnt = ocnt = n;
while (icnt) {
if (ssp->SSP_SR & SR_RNE) {
if (in)
*in++ = ssp->SSP_DR;
else
ssp->SSP_DR;
icnt--;
continue; /* Priority over transmission. */
}
if (ocnt && (ssp->SSP_SR & SR_TNF)) {
if (out)
ssp->SSP_DR = *out++;
else
ssp->SSP_DR = 0xFF;
ocnt--;
}
}
}
/**
* @brief SSP setup.
* @param[in] cpsr the value for the @p CPSR register
* @param[in] cr0 the value for the @p CR0 register
* @param[in] cr1 the value for the @p CR1 register
*/
void ssp_setup(int cpsr, int cr0, int cr1) {
SSP *ssp = SSPBase;
ssp->SSP_CR1 = 0;
ssp->SSP_CR0 = cr0;
ssp->SSP_CPSR = cpsr;
ssp->SSP_CR1 = cr1 | CR1_SSE;
}
/**
* @brief SSP subsystem initialization.
*/
void ssp_init(void) {
/* Enables the SPI1 clock */
PCONP = (PCONP & PCALL) | PCSPI1;
/* Clock = PCLK / 2 (fastest). */
ssp_setup(2, CR0_DSS8BIT | CR0_FRFSPI | CR0_CLOCKRATE(0), 0);
#if LPC214x_SSP_USE_MUTEX
chSemInit(&me, 1);
#endif
}
/** @} */

View File

@ -1,54 +0,0 @@
/*
ChibiOS/RT - Copyright (C) 2006-2007 Giovanni Di Sirio.
This file is part of ChibiOS/RT.
ChibiOS/RT is free software; you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation; either version 3 of the License, or
(at your option) any later version.
ChibiOS/RT is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
/**
* @file LPC214x/lpc214x_ssp.h
* @brief LPC214x SSP driver macros and structures.
* @addtogroup LPC214x_SSP
* @{
*/
#ifndef _LPC214x_SSP_H_
#define _LPC214x_SSP_H_
/**
* @brief SSP bus mutual exclusion control.
* @details Configuration parameter, if set to @p TRUE enforces mutual
* exclusion when invoking @p sspAcquireBus() and @p sspReleaseBus().
* @note The internally used synchronization mechanism is a @p Semaphore.
*/
#if !defined(LPC214x_SSP_USE_MUTEX) || defined(__DOXYGEN__)
#define LPC214x_SSP_USE_MUTEX TRUE
#endif
#ifdef __cplusplus
}
#endif
void ssp_init(void);
void ssp_setup(int cpsr, int cr0, int cr1);
void sspAcquireBus(void);
void sspReleaseBus(void);
void sspRW(uint8_t *in, uint8_t *out, size_t n);
#ifdef __cplusplus
}
#endif
#endif /* _LPC214x_SSP_H_*/
/** @} */

View File

@ -1,89 +0,0 @@
/*
ChibiOS/RT - Copyright (C) 2006-2007 Giovanni Di Sirio.
This file is part of ChibiOS/RT.
ChibiOS/RT is free software; you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation; either version 3 of the License, or
(at your option) any later version.
ChibiOS/RT is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
/**
* @file LPC214x/pal_lld.c
* @brief LPC214x FIO low level driver code
* @addtogroup LPC214x_PAL
* @{
*/
#include <ch.h>
#include <pal.h>
/**
* @brief LPC214x I/O ports configuration.
* @details FIO units and PINSEL registers initialization.
*
* @param[in] config the LPC214x ports configuration
*/
void _pal_lld_init(const LPC214xFIOConfig *config) {
/* Enables the access through the fast registers.*/
SCS = 3;
/* I/O pads initial assignment, device drivers may change this setup at a
* later time.*/
PINSEL0 = config->pinsel0;
PINSEL1 = config->pinsel1;
PINSEL2 = config->pinsel2;
/* I/O pads direction initial setting.*/
FIO0Base->FIO_MASK = 0;
FIO0Base->FIO_PIN = config->P0Data.pin;
FIO0Base->FIO_DIR = config->P0Data.dir;
FIO1Base->FIO_MASK = 0;
FIO1Base->FIO_PIN = config->P1Data.pin;
FIO1Base->FIO_DIR = config->P1Data.dir;
}
/**
* @brief Pads mode setup.
* @details This function programs a pads group belonging to the same port
* with the specified mode.
*
* @param[in] port the port identifier
* @param[in] mask the group mask
* @param[in] mode the mode
*
* @note This function is not meant to be invoked directly by the application
* code.
* @note @p PAL_MODE_UNCONNECTED is implemented as push pull output with high
* state.
* @note This function does not alter the @p PINSELx registers. Alternate
* functions setup must be handled by device-specific code.
*/
void _pal_lld_setgroupmode(ioportid_t port,
ioportmask_t mask,
uint_fast8_t mode) {
switch (mode) {
case PAL_MODE_RESET:
case PAL_MODE_INPUT:
port->FIO_DIR &= ~mask;
break;
case PAL_MODE_UNCONNECTED:
port->FIO_PIN |= mask;
case PAL_MODE_OUTPUT_PUSHPULL:
port->FIO_DIR |= mask;
break;
}
}
/** @} */

View File

@ -1,252 +0,0 @@
/*
ChibiOS/RT - Copyright (C) 2006-2007 Giovanni Di Sirio.
This file is part of ChibiOS/RT.
ChibiOS/RT is free software; you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation; either version 3 of the License, or
(at your option) any later version.
ChibiOS/RT is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
/**
* @file LPC214x/pal_lld.h
* @brief LPC214x FIO low level driver header
* @addtogroup LPC214x_PAL
* @{
*/
#ifndef _PAL_LLD_H_
#define _PAL_LLD_H_
#include "lpc214x.h"
/*===========================================================================*/
/* Unsupported modes and specific modes */
/*===========================================================================*/
#undef PAL_MODE_INPUT_PULLUP
#undef PAL_MODE_INPUT_PULLDOWN
#undef PAL_MODE_OUTPUT_OPENDRAIN
/*===========================================================================*/
/* I/O Ports Types and constants. */
/*===========================================================================*/
/**
* @brief FIO port setup info.
*/
typedef struct {
/** Initial value for FIO_PIN register.*/
uint32_t pin;
/** Initial value for FIO_DIR register.*/
uint32_t dir;
} lpc214x_fio_setup_t;
/**
* @brief LPC214x FIO static initializer.
* @details An instance of this structure must be passed to @p palInit() at
* system startup time in order to initialized the digital I/O
* subsystem. This represents only the initial setup, specific pads
* or whole ports can be reprogrammed at later time.
*/
typedef struct {
/** @brief PINSEL0 initial value.*/
uint32_t pinsel0;
/** @brief PINSEL1 initial value.*/
uint32_t pinsel1;
/** @brief PINSEL2 initial value.*/
uint32_t pinsel2;
/** @brief Port 0 setup data.*/
lpc214x_fio_setup_t P0Data;
/** @brief Port 1 setup data.*/
lpc214x_fio_setup_t P1Data;
} LPC214xFIOConfig;
/**
* @brief Width, in bits, of an I/O port.
*/
#define PAL_IOPORTS_WIDTH 32
/**
* @brief Digital I/O port sized unsigned type.
*/
typedef uint32_t ioportmask_t;
/**
* @brief Port Identifier.
*/
typedef FIO * ioportid_t;
/*===========================================================================*/
/* I/O Ports Identifiers. */
/*===========================================================================*/
/**
* @brief FIO port 0 identifier.
*/
#define IOPORT_A FIO0Base
/**
* @brief FIO port 1 identifier.
*/
#define IOPORT_B FIO1Base
/*===========================================================================*/
/* Implementation, some of the following macros could be implemented as */
/* functions, please put them in a file named ioports_lld.c if so. */
/*===========================================================================*/
/**
* @brief FIO subsystem initialization.
* @details Enables the access through the fast registers.
*/
#define pal_lld_init(config) _pal_lld_init(config)
/**
* @brief Reads an I/O port.
* @details This function is implemented by reading the FIO PIN register, the
* implementation has no side effects.
*
* @param[in] port the port identifier
* @return the port bits
*
* @note This function is not meant to be invoked directly by the application
* code.
*/
#define pal_lld_readport(port) ((port)->FIO_PIN)
/**
* @brief Reads the output latch.
* @details This function is implemented by reading the FIO SET register, the
* implementation has no side effects.
*
* @param[in] port the port identifier
* @return The latched logical states.
*
* @note This function is not meant to be invoked directly by the application
* code.
*/
#define pal_lld_readlatch(port) ((port)->FIO_SET)
/**
* @brief Writes a bits mask on a I/O port.
* @details This function is implemented by writing the FIO PIN register, the
* implementation has no side effects.
*
* @param[in] port the port identifier
* @param[in] bits the bits to be written on the specified port
*
* @note This function is not meant to be invoked directly by the application
* code.
*/
#define pal_lld_writeport(port, bits) ((port)->FIO_PIN = (bits))
/**
* @brief Sets a bits mask on a I/O port.
* @details This function is implemented by writing the FIO SET register, the
* implementation has no side effects.
*
* @param[in] port the port identifier
* @param[in] bits the bits to be ORed on the specified port
*
* @note This function is not meant to be invoked directly by the application
* code.
*/
#define pal_lld_setport(port, bits) ((port)->FIO_SET = (bits))
/**
* @brief Clears a bits mask on a I/O port.
* @details This function is implemented by writing the FIO CLR register, the
* implementation has no side effects.
*
* @param[in] port the port identifier
* @param[in] bits the bits to be cleared on the specified port
*
* @note This function is not meant to be invoked directly by the application
* code.
*/
#define pal_lld_clearport(port, bits) ((port)->FIO_CLR = (bits))
/**
* @brief Writes a value on an I/O bus.
* @details This function is implemented by writing the FIO PIN and MASK
* registers, the implementation is not atomic because the multiple
* accesses.
*
* @param[in] port the port identifier
* @param[in] mask the group mask
* @param[in] offset the group bit offset within the port
* @param[in] bits the bits to be written. Values exceeding the group width
* are masked.
*
* @note This function is not meant to be invoked directly by the application
* code.
*/
#define pal_lld_writegroup(port, mask, offset, bits) { \
(port)->FIO_MASK = (mask) << (offset); \
(port)->FIO_PIN = (bits) << (offset); \
(port)->FIO_MASK = 0; \
}
/**
* @brief Pads group mode setup.
* @details This function programs a pads group belonging to the same port
* with the specified mode.
*
* @param[in] port the port identifier
* @param[in] mask the group mask
* @param[in] mode the mode
*
* @note This function is not meant to be invoked directly by the application
* code.
* @note @p PAL_MODE_UNCONNECTED is implemented as push pull output with high
* state.
* @note This function does not alter the @p PINSELx registers. Alternate
* functions setup must be handled by device-specific code.
*/
#define pal_lld_setgroupmode(port, mask, mode) \
_pal_lld_setgroupmode(port, mask, mode)
/**
* @brief Writes a logical state on an output pad.
*
* @param[in] port the port identifier
* @param[in] pad the pad number within the port
* @param[out] bit the logical value, the value must be @p 0 or @p 1
*
* @note This function is not meant to be invoked directly by the application
* code.
*/
#define pal_lld_writepad(port, pad, bit) pal_lld_writegroup(port, 1, pad, bit)
/**
* @brief FIO port setup.
* @details This function programs the pins direction within a port.
*/
#define pal_lld_lpc214x_set_direction(port, dir) { \
(port)->FIO_DIR = (dir); \
}
#ifdef __cplusplus
extern "C" {
#endif
void _pal_lld_init(const LPC214xFIOConfig *config);
void _pal_lld_setgroupmode(ioportid_t port,
ioportmask_t mask,
uint_fast8_t mode);
#ifdef __cplusplus
}
#endif
#endif /* _PAL_LLD_H_ */
/** @} */

View File

@ -1,83 +0,0 @@
/*
ChibiOS/RT - Copyright (C) 2006-2007 Giovanni Di Sirio.
This file is part of ChibiOS/RT.
ChibiOS/RT is free software; you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation; either version 3 of the License, or
(at your option) any later version.
ChibiOS/RT is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
/**
* @defgroup LPC214x LPC214x Support
* @brief LPC214x specific support.
* @details The LPC214x support includes:
* - VIC support code.
* - I/O ports driver.
* - Buffered, interrupt driven, serial driver.
* - SSP driver.
* - A MMC/SD demo driver.
* - A timer driven buzzer demo driver.
* - A minimal demo, useful as project template.
* - A demo supporting the kernel test suite.
* - A C++ demo supporting the kernel test suite.
* .
* @ingroup ARM7
*/
/**
* @defgroup LPC214x_VIC VIC Support
* @brief VIC peripheral support.
*
* @ingroup LPC214x
*/
/**
* @defgroup LPC214x_PAL I/O Ports Support
* @brief I/O Ports peripherals support.
* @details This module supports the LPC214x FIO controller. The controller
* supports the following features (see @ref PAL):
* - 32 bits wide ports.
* - Atomic set/reset functions.
* - Output latched regardless of the pad setting.
* - Direct read of input pads regardless of the pad setting.
* .
* <h2>Supported Setup Modes</h2>
* - @p PAL_MODE_RESET.
* - @p PAL_MODE_UNCONNECTED.
* - @p PAL_MODE_INPUT.
* - @p PAL_MODE_OUTPUT_PUSHPULL.
* .
* Any attempt to setup an invalid mode is ignored.
*
* <h2>Suboptimal Behavior</h2>
* - Pad/port toggling operations are not atomic.
* - Pad/group mode setup is not atomic.
* .
* @ingroup LPC214x
*/
/**
* @defgroup LPC214x_SERIAL UART Support
* @brief UART peripherals support.
* @details The serial driver supports the LPC214x UART peripherals.
*
* @ingroup LPC214x
*/
/**
* @defgroup LPC214x_SSP SSP Support
* @brief SSP peripheral support.
* @details This SPI driver supports the LPC214x SSP peripheral.
*
* @ingroup LPC214x
*/

View File

@ -1,63 +0,0 @@
/*
ChibiOS/RT - Copyright (C) 2006-2007 Giovanni Di Sirio.
This file is part of ChibiOS/RT.
ChibiOS/RT is free software; you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation; either version 3 of the License, or
(at your option) any later version.
ChibiOS/RT is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
/**
* @file LPC214x/vic.c
* @brief LPC214x VIC peripheral support code.
* @addtogroup LPC214x_VIC
* @{
*/
#include <ch.h>
#include "lpc214x.h"
/**
* @brief VIC Initialization.
* @note Better reset everything in the VIC, it is a HUGE source of trouble.
*/
void vic_init(void) {
int i;
VIC *vic = VICBase;
vic->VIC_IntSelect = 0; /* All sources assigned to IRQ. */
vic->VIC_SoftIntClear = ALLINTMASK; /* No interrupts enforced */
vic->VIC_IntEnClear = ALLINTMASK; /* All sources disabled. */
for (i = 0; i < 16; i++) {
vic->VIC_VectCntls[i] = 0;
vic->VIC_VectAddrs[i] = 0;
vic->VIC_VectAddr = 0;
}
}
/**
* @brief Initializes a VIC vector.
* @details Set a vector for an interrupt source and enables it.
* @param[in] handler the pointer to the IRQ service routine
* @param[in] vector the vector number
* @param[in] source the IRQ source to be associated to the vector
*/
void SetVICVector(void *handler, int vector, int source) {
VIC *vicp = VICBase;
vicp->VIC_VectAddrs[vector] = (IOREG32)handler;
vicp->VIC_VectCntls[vector] = (IOREG32)(source | 0x20);
}
/** @} */

View File

@ -1,41 +0,0 @@
/*
ChibiOS/RT - Copyright (C) 2006-2007 Giovanni Di Sirio.
This file is part of ChibiOS/RT.
ChibiOS/RT is free software; you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation; either version 3 of the License, or
(at your option) any later version.
ChibiOS/RT is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
/**
* @file LPC214x/vic.h
* @brief LPC214x VIC peripheral support code.
* @addtogroup LPC214x_VIC
* @{
*/
#ifndef _VIC_H_
#define _VIC_H_
#ifdef __cplusplus
extern "C" {
#endif
void vic_init(void);
void SetVICVector(void *handler, int vector, int source);
#ifdef __cplusplus
}
#endif
#endif /* _VIC_H_ */
/** @} */