Merge pull request #3530 from kaspar030/update_msba2
cpu: lpc2387: provide periph/* implementations, update to use newlib module.dev/timer
commit
3922b6c852
@ -1,2 +1,4 @@
|
||||
FEATURES_PROVIDED += periph_gpio
|
||||
FEATURES_PROVIDED += periph_rtc
|
||||
FEATURES_PROVIDED += periph_spi
|
||||
FEATURES_MCU_GROUP = arm7
|
||||
|
@ -1,3 +0,0 @@
|
||||
ifneq (,$(filter ltc4150,$(USEMODULE)))
|
||||
USEMODULE += gpioint
|
||||
endif
|
@ -1,50 +0,0 @@
|
||||
/*
|
||||
* Copyright (C) 2008-2009, Freie Universitaet Berlin
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser
|
||||
* General Public License v2.1. See the file LICENSE in the top level
|
||||
* directory for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup msba2
|
||||
* @ingroup ltc4150
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file
|
||||
* @brief LTC4150 MSB-A2 specific implemetation
|
||||
*
|
||||
* @author Heiko Will
|
||||
* @author Michael Baar
|
||||
* @author Kaspar Schleiser <kaspar@schleiser.de>
|
||||
*/
|
||||
|
||||
#include <stdio.h>
|
||||
#include "lpc2387.h"
|
||||
#include "ltc4150_arch.h"
|
||||
#include "gpioint.h"
|
||||
|
||||
void __attribute__((__no_instrument_function__)) ltc4150_disable_int(void)
|
||||
{
|
||||
gpioint_set(0, BIT4, GPIOINT_DISABLE, NULL);
|
||||
}
|
||||
|
||||
void __attribute__((__no_instrument_function__)) ltc4150_enable_int(void)
|
||||
{
|
||||
gpioint_set(0, BIT4, GPIOINT_FALLING_EDGE, <c4150_interrupt);
|
||||
}
|
||||
|
||||
void __attribute__((__no_instrument_function__)) ltc4150_sync_blocking(void)
|
||||
{
|
||||
while (!(FIO0PIN & BIT4)) {};
|
||||
}
|
||||
|
||||
void __attribute__((__no_instrument_function__)) ltc4150_arch_init(void)
|
||||
{
|
||||
FIO0DIR |= BIT5;
|
||||
FIO0SET = BIT5;
|
||||
}
|
||||
|
||||
/** @} */
|
@ -1,205 +0,0 @@
|
||||
/*
|
||||
* Copyright (C) 2008-2009, Freie Universitaet Berlin
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser
|
||||
* General Public License v2.1. See the file LICENSE in the top level
|
||||
* directory for more details.
|
||||
*/
|
||||
|
||||
/*
|
||||
* debug_uart.c: provides initial serial debug output
|
||||
*
|
||||
* @author Kaspar Schleiser <kaspar@schleiser.de>
|
||||
* @author Heiko Will <hwill@inf.fu-berlin.de>
|
||||
*/
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <stdio.h>
|
||||
#include "lpc23xx.h"
|
||||
#include "VIC.h"
|
||||
#include "kernel.h"
|
||||
|
||||
#include "board_uart0.h"
|
||||
|
||||
/**
|
||||
* @file
|
||||
* @ingroup lpc2387
|
||||
*
|
||||
* @version $Revision$
|
||||
*
|
||||
* @note $Id$
|
||||
*/
|
||||
|
||||
typedef struct toprint_t {
|
||||
unsigned int len;
|
||||
char content[];
|
||||
} toprint_t;
|
||||
|
||||
#define QUEUESIZE 255
|
||||
static volatile toprint_t *queue[QUEUESIZE];
|
||||
static volatile unsigned char queue_head = 0;
|
||||
static volatile unsigned char queue_tail = 0;
|
||||
static volatile unsigned char queue_items = 0;
|
||||
|
||||
static volatile unsigned int actual_pos = 0;
|
||||
static volatile unsigned int running = 0;
|
||||
static volatile unsigned int fifo = 0;
|
||||
|
||||
static volatile toprint_t *actual = NULL;
|
||||
|
||||
static inline void enqueue(void)
|
||||
{
|
||||
queue_items++;
|
||||
queue_tail++;
|
||||
}
|
||||
|
||||
static inline void dequeue(void)
|
||||
{
|
||||
actual = (queue[queue_head]);
|
||||
queue_items--;
|
||||
queue_head++;
|
||||
}
|
||||
|
||||
static void push_queue(void)
|
||||
{
|
||||
running = 1;
|
||||
lpm_prevent_sleep |= LPM_PREVENT_SLEEP_UART;
|
||||
start:
|
||||
|
||||
if (!actual) {
|
||||
if (queue_items) {
|
||||
dequeue();
|
||||
}
|
||||
else {
|
||||
running = 0;
|
||||
lpm_prevent_sleep &= ~LPM_PREVENT_SLEEP_UART;
|
||||
|
||||
if (!fifo)
|
||||
while (!(U0LSR & BIT6)) {};
|
||||
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
while ((actual_pos < actual->len) && (fifo++ < 16)) {
|
||||
U0THR = actual->content[actual_pos++];
|
||||
}
|
||||
|
||||
if (actual_pos == actual->len) {
|
||||
free((void *)actual);
|
||||
actual = NULL;
|
||||
actual_pos = 0;
|
||||
goto start;
|
||||
}
|
||||
}
|
||||
|
||||
int uart_active(void)
|
||||
{
|
||||
return (running || fifo);
|
||||
}
|
||||
|
||||
void stdio_flush(void)
|
||||
{
|
||||
U0IER &= ~BIT1; // disable THRE interrupt
|
||||
|
||||
while (running) {
|
||||
while (!(U0LSR & (BIT5 | BIT6))) {}; // transmit fifo
|
||||
|
||||
fifo = 0;
|
||||
|
||||
push_queue(); // dequeue to fifo
|
||||
}
|
||||
|
||||
U0IER |= BIT1; // enable THRE interrupt
|
||||
}
|
||||
|
||||
void UART0_IRQHandler(void) __attribute__((interrupt("IRQ")));
|
||||
void UART0_IRQHandler(void)
|
||||
{
|
||||
int iir;
|
||||
iir = U0IIR;
|
||||
|
||||
switch (iir & UIIR_ID_MASK) {
|
||||
case UIIR_THRE_INT: // Transmit Holding Register Empty
|
||||
fifo = 0;
|
||||
push_queue();
|
||||
break;
|
||||
|
||||
case UIIR_CTI_INT: // Character Timeout Indicator
|
||||
case UIIR_RDA_INT: // Receive Data Available
|
||||
#ifdef MODULE_UART0
|
||||
if (uart0_handler_pid != KERNEL_PID_UNDEF) {
|
||||
do {
|
||||
int c = U0RBR;
|
||||
uart0_handle_incoming(c);
|
||||
}
|
||||
while (U0LSR & ULSR_RDR);
|
||||
|
||||
uart0_notify_thread();
|
||||
}
|
||||
|
||||
#endif
|
||||
break;
|
||||
|
||||
default:
|
||||
U0LSR;
|
||||
U0RBR;
|
||||
break;
|
||||
} // switch
|
||||
|
||||
VICVectAddr = 0; // Acknowledge Interrupt
|
||||
}
|
||||
|
||||
int uart0_puts(char *astring, int length)
|
||||
{
|
||||
/* while (queue_items == (QUEUESIZE-1)) {} ;
|
||||
U0IER = 0;
|
||||
queue[queue_tail] = malloc(length+sizeof(unsigned int));
|
||||
queue[queue_tail]->len = length;
|
||||
memcpy(&queue[queue_tail]->content,astring,length);
|
||||
enqueue();
|
||||
if (!running)
|
||||
push_queue();
|
||||
U0IER |= BIT0 | BIT1; // enable RX irq
|
||||
*/
|
||||
/* alternative without queue:*/
|
||||
int i;
|
||||
|
||||
for (i = 0; i < length; i++) {
|
||||
while (!(U0LSR & BIT5));
|
||||
|
||||
U0THR = astring[i];
|
||||
}
|
||||
|
||||
/* */
|
||||
|
||||
return length;
|
||||
}
|
||||
|
||||
int
|
||||
bl_uart_init(void)
|
||||
{
|
||||
PCONP |= PCUART0; // power on
|
||||
|
||||
// UART0 clock divider is CCLK/8
|
||||
PCLKSEL0 |= BIT6 + BIT7;
|
||||
|
||||
U0LCR = 0x83; // 8 bits, no Parity, 1 Stop bit
|
||||
|
||||
// TODO: UART Baudrate calculation using uart->config->speed
|
||||
/*
|
||||
* Baudrate calculation
|
||||
* BR = PCLK (9 MHz) / (16 x 256 x DLM + DLL) x (1/(DIVADDVAL/MULVAL))
|
||||
*/
|
||||
U0FDR = 0x92; // DIVADDVAL = 0010 = 2, MULVAL = 1001 = 9
|
||||
U0DLM = 0x00;
|
||||
U0DLL = 0x04;
|
||||
|
||||
U0LCR = 0x03; // DLAB = 0
|
||||
U0FCR = 0x07; // Enable and reset TX and RX FIFO
|
||||
|
||||
/* irq */
|
||||
install_irq(UART0_INT, UART0_IRQHandler, 6);
|
||||
U0IER |= BIT0; // enable only RX irq
|
||||
return 1;
|
||||
}
|
@ -1,5 +1,7 @@
|
||||
FEATURES_PROVIDED += periph_gpio
|
||||
FEATURES_PROVIDED += periph_pwm
|
||||
FEATURES_PROVIDED += periph_rtc
|
||||
FEATURES_PROVIDED += periph_spi
|
||||
FEATURES_PROVIDED += cpp
|
||||
FEATURES_PROVIDED += config
|
||||
FEATURES_MCU_GROUP = arm7
|
||||
|
@ -1,2 +1,4 @@
|
||||
FEATURES_PROVIDED += periph_gpio
|
||||
FEATURES_PROVIDED += periph_rtc
|
||||
FEATURES_PROVIDED += periph_spi
|
||||
FEATURES_MCU_GROUP = arm7
|
||||
|
@ -1 +0,0 @@
|
||||
include $(RIOTBASE)/Makefile.base
|
@ -1,164 +0,0 @@
|
||||
/*
|
||||
* Copyright 2009, Freie Universitaet Berlin (FUB). All rights reserved.
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser
|
||||
* General Public License v2.1. See the file LICENSE in the top level
|
||||
* directory for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup lpc2387
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file
|
||||
* @brief LPC2387 GPIO Interrupt Multiplexer implementation
|
||||
*
|
||||
* @author Michael Baar <michael.baar@fu-berlin.de>
|
||||
* @version $Revision: 1508 $
|
||||
*
|
||||
* @note $Id: lpc2387-gpioint.c 1508 2009-10-26 15:10:02Z baar $
|
||||
* @see dev_gpioint
|
||||
*/
|
||||
|
||||
#include <stdio.h>
|
||||
#include "lpc2387.h"
|
||||
#include "gpioint.h"
|
||||
#include "cpu.h"
|
||||
#include "irq.h"
|
||||
|
||||
struct irq_callback_t {
|
||||
fp_irqcb callback;
|
||||
};
|
||||
|
||||
static struct irq_callback_t gpioint0[32];
|
||||
static struct irq_callback_t gpioint2[32];
|
||||
|
||||
|
||||
void gpioint_init(void)
|
||||
{
|
||||
extern void GPIO_IRQHandler(void);
|
||||
|
||||
/* GPIO Init */
|
||||
INTWAKE |= GPIO0WAKE | GPIO2WAKE; /* allow GPIO to wake up from power down */
|
||||
install_irq(GPIO_INT, &GPIO_IRQHandler, IRQP_GPIO); /* install irq handler */
|
||||
}
|
||||
|
||||
/*---------------------------------------------------------------------------*/
|
||||
bool
|
||||
gpioint_set(int port, uint32_t bitmask, int flags, fp_irqcb callback)
|
||||
{
|
||||
struct irq_callback_t *cbdata;
|
||||
unsigned long bit;
|
||||
volatile unsigned long *en_f;
|
||||
volatile unsigned long *en_r;
|
||||
volatile unsigned long *en_clr;
|
||||
|
||||
/* lookup registers */
|
||||
bit = bitarithm_msb(bitmask); /* get irq mapping table index */
|
||||
|
||||
switch(port) {
|
||||
case 0: /* PORT0 */
|
||||
cbdata = gpioint0;
|
||||
en_f = &IO0_INT_EN_F;
|
||||
en_r = &IO0_INT_EN_R;
|
||||
en_clr = &IO0_INT_CLR;
|
||||
break;
|
||||
|
||||
case 2: /* PORT2 */
|
||||
cbdata = gpioint2;
|
||||
en_f = &IO2_INT_EN_F;
|
||||
en_r = &IO2_INT_EN_R;
|
||||
en_clr = &IO2_INT_CLR;
|
||||
break;
|
||||
|
||||
default: /* unsupported */
|
||||
return false; /* fail */
|
||||
}
|
||||
|
||||
/* reconfigure irq */
|
||||
unsigned long cpsr = disableIRQ();
|
||||
*en_clr |= bitmask; /* clear interrupt */
|
||||
|
||||
if ((flags & GPIOINT_FALLING_EDGE) != 0) {
|
||||
*en_f |= bitmask; /* enable falling edge */
|
||||
}
|
||||
else {
|
||||
*en_f &= ~bitmask; /* disable falling edge */
|
||||
}
|
||||
|
||||
if ((flags & GPIOINT_RISING_EDGE) != 0) {
|
||||
*en_r |= bitmask; /* enable rising edge */
|
||||
}
|
||||
else {
|
||||
*en_r &= ~bitmask; /* disable rising edge */
|
||||
}
|
||||
|
||||
if (((flags & (GPIOINT_FALLING_EDGE | GPIOINT_RISING_EDGE)) != 0)) {
|
||||
cbdata[bit].callback = callback;
|
||||
|
||||
}
|
||||
else {
|
||||
cbdata[bit].callback = NULL; /* remove from interrupt mapping table */
|
||||
}
|
||||
|
||||
restoreIRQ(cpsr);
|
||||
|
||||
return true; /* success */
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
static void __attribute__((__no_instrument_function__)) test_irq(int port, unsigned long f_mask, unsigned long r_mask, struct irq_callback_t *pcb)
|
||||
{
|
||||
(void) port;
|
||||
|
||||
/* Test each bit of rising and falling masks, if set trigger interrupt
|
||||
* on corresponding device */
|
||||
do {
|
||||
if ((pcb->callback != NULL)) {
|
||||
if ((r_mask & 1) | (f_mask & 1)) {
|
||||
pcb->callback(); /* pass to handler */
|
||||
}
|
||||
}
|
||||
|
||||
f_mask >>= 1UL;
|
||||
r_mask >>= 1UL;
|
||||
pcb++;
|
||||
}
|
||||
while ((f_mask != 0) || (r_mask != 0));
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
void GPIO_IRQHandler(void) __attribute__((interrupt("IRQ")));
|
||||
/**
|
||||
* @brief GPIO Interrupt handler function
|
||||
* @internal
|
||||
*
|
||||
* Invoked whenever an activated gpio interrupt is triggered by a rising
|
||||
* or falling edge.
|
||||
*/
|
||||
void __attribute__((__no_instrument_function__)) GPIO_IRQHandler(void)
|
||||
{
|
||||
if (IO_INT_STAT & BIT0) { /* interrupt(s) on PORT0 pending */
|
||||
unsigned long int_stat_f = IO0_INT_STAT_F; /* save content */
|
||||
unsigned long int_stat_r = IO0_INT_STAT_R; /* save content */
|
||||
|
||||
IO0_INT_CLR = int_stat_f; /* clear flags of fallen pins */
|
||||
IO0_INT_CLR = int_stat_r; /* clear flags of risen pins */
|
||||
|
||||
test_irq(0, int_stat_f, int_stat_r, gpioint0);
|
||||
}
|
||||
|
||||
if (IO_INT_STAT & BIT2) { /* interrupt(s) on PORT2 pending */
|
||||
unsigned long int_stat_f = IO2_INT_STAT_F; /* save content */
|
||||
unsigned long int_stat_r = IO2_INT_STAT_R; /* save content */
|
||||
|
||||
IO2_INT_CLR = int_stat_f; /* clear flags of fallen pins */
|
||||
IO2_INT_CLR = int_stat_r; /* clear flags of risen pins */
|
||||
|
||||
test_irq(2, int_stat_f, int_stat_r, gpioint2);
|
||||
}
|
||||
|
||||
VICVectAddr = 0; /* Acknowledge Interrupt */
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/** @} */
|
@ -0,0 +1,88 @@
|
||||
/*
|
||||
* Copyright (C) 2015 Kaspar Schleiser <kaspar@schleiser.de>
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser
|
||||
* General Public License v2.1. See the file LICENSE in the top level
|
||||
* directory for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup cpu_lpc2387
|
||||
* @{
|
||||
*
|
||||
* @file
|
||||
* @brief CPU specific definitions for internal peripheral handling
|
||||
*
|
||||
* @author Kaspar Schleiser <kaspar@schleiser.de>
|
||||
*/
|
||||
|
||||
#ifndef PERIPH_CPU_H_
|
||||
#define PERIPH_CPU_H_
|
||||
|
||||
#include "cpu.h"
|
||||
#include "periph/dev_enums.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
#include <stdint.h>
|
||||
#include "cpu.h"
|
||||
|
||||
/**
|
||||
* @brief LPC2387 MCU defines
|
||||
* @{
|
||||
*/
|
||||
#define __IO volatile
|
||||
|
||||
/**
|
||||
* @brief Fast GPIO register definition struct
|
||||
*/
|
||||
typedef struct {
|
||||
__IO uint32_t DIR; /**< he */
|
||||
uint32_t _reserved[3]; /**< really */
|
||||
__IO uint32_t MASK; /**< wants */
|
||||
__IO uint32_t PIN; /**< to */
|
||||
__IO uint32_t SET; /**< know */
|
||||
__IO uint32_t CLR; /**< everything */
|
||||
} FIO_PORT_t;
|
||||
|
||||
#define FIO_PORTS ((FIO_PORT_t*)FIO_BASE_ADDR)
|
||||
#define PINSEL ((__IO uint32_t *)(PINSEL_BASE_ADDR))
|
||||
#define PINMODE ((__IO uint32_t *)(PINSEL_BASE_ADDR + 0x40))
|
||||
|
||||
int gpio_init_mux(unsigned pin, unsigned mux);
|
||||
void gpio_init_states(void);
|
||||
|
||||
#define GPIO(port, pin) (port*32 + pin)
|
||||
|
||||
#define HAVE_GPIO_PP_T
|
||||
typedef enum {
|
||||
GPIO_PULLUP = 0, /**< enable internal pull-up resistor */
|
||||
GPIO_NOPULL = 2, /**< do not use internal pull resistors */
|
||||
GPIO_PULLDOWN = 3 /**< enable internal pull-down resistor */
|
||||
} gpio_pp_t;
|
||||
|
||||
#define HAVE_GPIO_FLANK_T
|
||||
typedef enum {
|
||||
GPIO_FALLING = 1, /**< emit interrupt on falling flank */
|
||||
GPIO_RISING = 2, /**< emit interrupt on rising flank */
|
||||
GPIO_BOTH = 3 /**< emit interrupt on both flanks */
|
||||
} gpio_flank_t;
|
||||
|
||||
/**
|
||||
* @brief declare needed generic SPI functions
|
||||
* @{
|
||||
*/
|
||||
#define PERIPH_SPI_NEEDS_TRANSFER_BYTES
|
||||
#define PERIPH_SPI_NEEDS_TRANSFER_REG
|
||||
#define PERIPH_SPI_NEEDS_TRANSFER_REGS
|
||||
/* @} */
|
||||
|
||||
/* @} */
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* PERIPH_CPU_H_ */
|
||||
/** @} */
|
@ -1,68 +0,0 @@
|
||||
/*
|
||||
* syscalls.c - MCU dependent syscall implementation for LPCXXXX
|
||||
* Copyright (C) 2013 Oliver Hahm <oliver.hahm@inria.fr>
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser
|
||||
* General Public License v2.1. See the file LICENSE in the top level
|
||||
* directory for more details.
|
||||
*/
|
||||
|
||||
#include <errno.h>
|
||||
#include <stdint.h>
|
||||
#include <sys/unistd.h>
|
||||
#include <stdio.h>
|
||||
#include "irq.h"
|
||||
|
||||
/**
|
||||
* @name Heaps (defined in linker script)
|
||||
* @{
|
||||
*/
|
||||
#define NUM_HEAPS 3
|
||||
|
||||
extern uintptr_t __heap1_start; ///< start of heap memory space
|
||||
extern uintptr_t __heap1_max; ///< maximum for end of heap memory space
|
||||
extern uintptr_t __heap2_start; ///< start of heap memory space
|
||||
extern uintptr_t __heap2_max; ///< maximum for end of heap memory space
|
||||
extern uintptr_t __heap3_start; ///< start of heap memory space
|
||||
extern uintptr_t __heap3_max; ///< maximum for end of heap memory space
|
||||
|
||||
/// current position in heap
|
||||
static caddr_t heap[NUM_HEAPS] = {(caddr_t)&__heap1_start,(caddr_t)&__heap3_start,(caddr_t)&__heap2_start}; // add heap3 before heap2 cause Heap3 address is lower then addr of heap2
|
||||
/// maximum position in heap
|
||||
static const caddr_t heap_max[NUM_HEAPS] = {(caddr_t)&__heap1_max,(caddr_t)&__heap3_max,(caddr_t)&__heap2_max};
|
||||
// start position in heap
|
||||
static const caddr_t heap_start[NUM_HEAPS] = {(caddr_t)&__heap1_start,(caddr_t)&__heap3_start,(caddr_t)&__heap2_start};
|
||||
|
||||
/** @} */
|
||||
|
||||
/*-----------------------------------------------------------------------------------*/
|
||||
void heap_stats(void)
|
||||
{
|
||||
for(int i = 0; i < NUM_HEAPS; i++)
|
||||
printf("# heap %i: %p -- %p -> %p (%li of %li free)\n", i, heap_start[i], heap[i], heap_max[i],
|
||||
(uint32_t)heap_max[i] - (uint32_t)heap[i], (uint32_t)heap_max[i] - (uint32_t)heap_start[i]);
|
||||
}
|
||||
|
||||
/*-----------------------------------------------------------------------------------*/
|
||||
caddr_t _sbrk_r(struct _reent *r, ptrdiff_t incr)
|
||||
{
|
||||
uint32_t cpsr = disableIRQ();
|
||||
|
||||
/* check all heaps for a chunk of the requested size */
|
||||
for (volatile uint8_t iUsedHeap = 0; iUsedHeap < NUM_HEAPS; iUsedHeap++ ) {
|
||||
caddr_t new_heap = heap[iUsedHeap] + incr;
|
||||
|
||||
if( new_heap <= heap_max[iUsedHeap] ) {
|
||||
caddr_t prev_heap = heap[iUsedHeap];
|
||||
heap[iUsedHeap] = new_heap;
|
||||
|
||||
r->_errno = 0;
|
||||
restoreIRQ(cpsr);
|
||||
return prev_heap;
|
||||
}
|
||||
}
|
||||
restoreIRQ(cpsr);
|
||||
|
||||
r->_errno = ENOMEM;
|
||||
return NULL;
|
||||
}
|
@ -0,0 +1,311 @@
|
||||
/*
|
||||
* Copyright (C) 2015 Kaspar Schleiser <kaspar@schleiser.de>
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser
|
||||
* General Public License v2.1. See the file LICENSE in the top level
|
||||
* directory for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup lpc2387
|
||||
* @{
|
||||
*
|
||||
* @file
|
||||
* @brief CPU specific low-level GPIO driver implementation for the LPC2387
|
||||
*
|
||||
* @author Kaspar Schleiser <kaspar@schleiser.de>
|
||||
*
|
||||
* @}
|
||||
*/
|
||||
|
||||
#include <assert.h>
|
||||
#include <stdint.h>
|
||||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
|
||||
#include "irq.h"
|
||||
#include "periph/gpio.h"
|
||||
#include "bitfield.h"
|
||||
|
||||
#define ENABLE_DEBUG (0)
|
||||
#include "debug.h"
|
||||
|
||||
#define GPIO_NUM_ISR (16)
|
||||
|
||||
static BITFIELD(_gpio_config_bitfield, GPIO_NUM_ISR);
|
||||
|
||||
typedef struct {
|
||||
gpio_cb_t cb; /**< callback called from GPIO interrupt */
|
||||
void *arg; /**< argument passed to the callback */
|
||||
} gpio_state_t;
|
||||
|
||||
static gpio_state_t _gpio_states[GPIO_NUM_ISR];
|
||||
static BITFIELD(_gpio_rising, GPIO_NUM_ISR);
|
||||
static BITFIELD(_gpio_falling, GPIO_NUM_ISR);
|
||||
static uint8_t _gpio_isr_map[64]; /* only ports 0+2 can have ISRs */
|
||||
|
||||
static void _gpio_configure(gpio_t pin, unsigned rising, unsigned falling);
|
||||
|
||||
void gpio_init_ports(void) {
|
||||
SCS |= 0x1; /* set GPIO ports 0 and 1 to FIO mode (3.7.2) */
|
||||
memset(&_gpio_isr_map[0], 0xff, 64);
|
||||
}
|
||||
|
||||
static int _isr_map_entry(gpio_t pin) {
|
||||
unsigned _pin = pin & 31;
|
||||
unsigned port = pin >> 5;
|
||||
|
||||
/* lpc2387 can only interrupt in pins of port 0 and 2 */
|
||||
if (port && port != 2) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
if (port) {
|
||||
_pin += 32;
|
||||
}
|
||||
|
||||
return _pin;
|
||||
}
|
||||
|
||||
int gpio_init(gpio_t pin, gpio_dir_t dir, gpio_pp_t pullup)
|
||||
{
|
||||
unsigned _pin = pin & 31;
|
||||
unsigned port = pin >> 5;
|
||||
|
||||
FIO_PORT_t *_port = &FIO_PORTS[port];
|
||||
|
||||
/* set mask */
|
||||
_port->MASK = ~(0x1<<_pin);
|
||||
|
||||
/* set direction */
|
||||
_port->DIR = ~0;
|
||||
|
||||
/* set pullup/pulldown **/
|
||||
PINMODE[pin>>4] |= pullup << (_pin*2);
|
||||
|
||||
gpio_init_mux(pin, 0);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int gpio_init_mux(unsigned pin, unsigned mux) {
|
||||
unsigned _pin = pin & 31;
|
||||
PINSEL[pin>>4] &= ~(0x1 << (_pin*2));
|
||||
return 0;
|
||||
}
|
||||
|
||||
int gpio_init_int(gpio_t pin, gpio_pp_t pullup, gpio_flank_t flank,
|
||||
gpio_cb_t cb, void *arg)
|
||||
{
|
||||
DEBUG("gpio_init_int(): pin %u\n", pin);
|
||||
int isr_map_entry;
|
||||
|
||||
/* check if interrupt is possible for this pin */
|
||||
if ((isr_map_entry = _isr_map_entry(pin)) == -1) {
|
||||
DEBUG("gpio_init_int(): pin %u cannot be used to generate interrupts.\n", pin);
|
||||
return -1;
|
||||
}
|
||||
|
||||
/* find free isr state entry */
|
||||
int _state_index = _gpio_isr_map[isr_map_entry];
|
||||
|
||||
if (_state_index == 0xff) {
|
||||
_state_index = bf_get_unset(_gpio_config_bitfield, GPIO_NUM_ISR);
|
||||
_gpio_isr_map[isr_map_entry] = _state_index;
|
||||
DEBUG("gpio_init_int(): pin has state_index=%i isr_map_entry=%i\n", _state_index, isr_map_entry);
|
||||
}
|
||||
|
||||
if (_state_index == 0xff) {
|
||||
#if DEVELHELP
|
||||
puts("lpc2387: gpio: warning: no free gpio callback state!");
|
||||
#endif
|
||||
return -1;
|
||||
}
|
||||
|
||||
/* store callback */
|
||||
_gpio_states[_state_index].cb = cb;
|
||||
_gpio_states[_state_index].arg = arg;
|
||||
|
||||
extern void GPIO_IRQHandler(void);
|
||||
gpio_init(pin, GPIO_DIR_IN, pullup);
|
||||
|
||||
if (flank & GPIO_FALLING) {
|
||||
bf_set(_gpio_falling, _state_index);
|
||||
}
|
||||
else {
|
||||
bf_unset(_gpio_falling, _state_index);
|
||||
}
|
||||
|
||||
if (flank & GPIO_RISING) {
|
||||
bf_set(_gpio_rising, _state_index);
|
||||
}
|
||||
else {
|
||||
bf_unset(_gpio_rising, _state_index);
|
||||
}
|
||||
|
||||
_gpio_configure(pin, flank & GPIO_RISING, flank & GPIO_FALLING);
|
||||
|
||||
/* activate irq */
|
||||
INTWAKE |= GPIO0WAKE | GPIO2WAKE; /* allow GPIO to wake up from power down */
|
||||
install_irq(GPIO_INT, &GPIO_IRQHandler, IRQP_GPIO); /* install irq handler */
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static void _gpio_configure(gpio_t pin, unsigned rising, unsigned falling)
|
||||
{
|
||||
unsigned _pin = pin & 31;
|
||||
unsigned port = pin >> 5;
|
||||
|
||||
/* set irq settings */
|
||||
volatile unsigned long *en_f;
|
||||
volatile unsigned long *en_r;
|
||||
volatile unsigned long *en_clr;
|
||||
|
||||
if (!port) {
|
||||
en_f = &IO0_INT_EN_F;
|
||||
en_r = &IO0_INT_EN_R;
|
||||
en_clr = &IO0_INT_CLR;
|
||||
}
|
||||
else {
|
||||
en_f = &IO2_INT_EN_F;
|
||||
en_r = &IO2_INT_EN_R;
|
||||
en_clr = &IO2_INT_CLR;
|
||||
}
|
||||
|
||||
/* configure irq */
|
||||
unsigned int bit = 0x1 << _pin;
|
||||
|
||||
unsigned state = disableIRQ();
|
||||
|
||||
*en_clr |= bit; /* clear interrupt */
|
||||
|
||||
if (falling) {
|
||||
*en_f |= bit; /* enable falling edge */
|
||||
}
|
||||
else {
|
||||
*en_f &= ~bit; /* disable falling edge */
|
||||
}
|
||||
|
||||
if (rising) {
|
||||
*en_r |= bit; /* enable rising edge */
|
||||
}
|
||||
else {
|
||||
*en_r &= ~bit; /* disable rising edge */
|
||||
}
|
||||
|
||||
restoreIRQ(state);
|
||||
}
|
||||
|
||||
void gpio_irq_enable(gpio_t pin)
|
||||
{
|
||||
int isr_map_entry =_isr_map_entry(pin);
|
||||
int _state_index = _gpio_isr_map[isr_map_entry];
|
||||
|
||||
if (_state_index == 0xff) {
|
||||
DEBUG("gpio_irq_enable(): trying to enable unconfigured pin.\n");
|
||||
return;
|
||||
}
|
||||
|
||||
_gpio_configure(pin,
|
||||
bf_isset(_gpio_rising, _state_index),
|
||||
bf_isset(_gpio_falling, _state_index));
|
||||
}
|
||||
|
||||
void gpio_irq_disable(gpio_t dev)
|
||||
{
|
||||
_gpio_configure(dev, 0, 0);
|
||||
}
|
||||
|
||||
int gpio_read(gpio_t pin)
|
||||
{
|
||||
unsigned _pin = pin & 31;
|
||||
unsigned port = pin >> 5;
|
||||
FIO_PORT_t *_port = &FIO_PORTS[port];
|
||||
_port->MASK = ~(1<<_pin);
|
||||
return _port->PIN != 0;
|
||||
}
|
||||
|
||||
void gpio_set(gpio_t pin)
|
||||
{
|
||||
unsigned _pin = pin & 31;
|
||||
unsigned port = pin >> 5;
|
||||
FIO_PORT_t *_port = &FIO_PORTS[port];
|
||||
_port->MASK = ~(1<<_pin);
|
||||
_port->SET = ~0;
|
||||
}
|
||||
|
||||
void gpio_clear(gpio_t pin)
|
||||
{
|
||||
unsigned _pin = pin & 31;
|
||||
unsigned port = pin >> 5;
|
||||
FIO_PORT_t *_port = &FIO_PORTS[port];
|
||||
_port->MASK = ~(1<<_pin);
|
||||
_port->CLR = ~0;
|
||||
}
|
||||
|
||||
void gpio_toggle(gpio_t dev)
|
||||
{
|
||||
if (gpio_read(dev)) {
|
||||
gpio_clear(dev);
|
||||
}
|
||||
else {
|
||||
gpio_set(dev);
|
||||
}
|
||||
}
|
||||
|
||||
void gpio_write(gpio_t dev, int value)
|
||||
{
|
||||
if (value) {
|
||||
gpio_set(dev);
|
||||
}
|
||||
else {
|
||||
gpio_clear(dev);
|
||||
}
|
||||
}
|
||||
|
||||
static void test_irq(int port, unsigned long f_mask, unsigned long r_mask)
|
||||
{
|
||||
/* Test each bit of rising and falling masks, if set trigger interrupt
|
||||
* on corresponding device */
|
||||
unsigned bit = 0x1;
|
||||
int n = 0;
|
||||
while (bit) {
|
||||
if ((r_mask & bit) | (f_mask & bit)) {
|
||||
int _state_index = _gpio_isr_map[n + (port<<1)];
|
||||
if (_state_index != 0xff) {
|
||||
_gpio_states[_state_index].cb(_gpio_states[_state_index].arg);
|
||||
}
|
||||
}
|
||||
|
||||
bit <<= 1;
|
||||
n++;
|
||||
}
|
||||
}
|
||||
|
||||
void GPIO_IRQHandler(void) __attribute__((interrupt("IRQ")));
|
||||
|
||||
void GPIO_IRQHandler(void)
|
||||
{
|
||||
if (IO_INT_STAT & BIT0) { /* interrupt(s) on PORT0 pending */
|
||||
unsigned long int_stat_f = IO0_INT_STAT_F; /* save content */
|
||||
unsigned long int_stat_r = IO0_INT_STAT_R; /* save content */
|
||||
|
||||
IO0_INT_CLR = int_stat_f; /* clear flags of fallen pins */
|
||||
IO0_INT_CLR = int_stat_r; /* clear flags of risen pins */
|
||||
|
||||
test_irq(0, int_stat_f, int_stat_r);
|
||||
}
|
||||
|
||||
if (IO_INT_STAT & BIT2) { /* interrupt(s) on PORT2 pending */
|
||||
unsigned long int_stat_f = IO2_INT_STAT_F; /* save content */
|
||||
unsigned long int_stat_r = IO2_INT_STAT_R; /* save content */
|
||||
|
||||
IO2_INT_CLR = int_stat_f; /* clear flags of fallen pins */
|
||||
IO2_INT_CLR = int_stat_r; /* clear flags of risen pins */
|
||||
|
||||
test_irq(2, int_stat_f, int_stat_r);
|
||||
}
|
||||
|
||||
VICVectAddr = 0; /* Acknowledge Interrupt */
|
||||
}
|
@ -0,0 +1,197 @@
|
||||
/*
|
||||
* Copyright (C) 2015 Kaspar Schleiser <kaspar@schleiser.de>
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser General
|
||||
* Public License v2.1. See the file LICENSE in the top level directory for more
|
||||
* details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup cpu_lpc2387
|
||||
* @{
|
||||
*
|
||||
* @file
|
||||
* @brief Low-level SPI driver implementation
|
||||
*
|
||||
* @author Kaspar Schleiser <kaspar@schleiser.de>
|
||||
*
|
||||
* @}
|
||||
*/
|
||||
|
||||
#include "cpu.h"
|
||||
#include "mutex.h"
|
||||
#include "periph/gpio.h"
|
||||
#include "periph/spi.h"
|
||||
#include "periph_conf.h"
|
||||
#include "board.h"
|
||||
#define ENABLE_DEBUG (0)
|
||||
#include "debug.h"
|
||||
|
||||
#if SPI_0_EN
|
||||
|
||||
#define SPI_TX_EMPTY (SSP0SR & SSPSR_TFE)
|
||||
#define SPI_BUSY (SSP0SR & SSPSR_BSY)
|
||||
#define SPI_RX_AVAIL (SSP0SR & SSPSR_RNE)
|
||||
|
||||
/**
|
||||
* @brief Array holding one pre-initialized mutex for each SPI device
|
||||
*/
|
||||
static mutex_t locks[] = {
|
||||
#if SPI_0_EN
|
||||
[SPI_0] = MUTEX_INIT,
|
||||
#endif
|
||||
#if SPI_1_EN
|
||||
[SPI_1] = MUTEX_INIT,
|
||||
#endif
|
||||
#if SPI_2_EN
|
||||
[SPI_2] = MUTEX_INIT
|
||||
#endif
|
||||
};
|
||||
|
||||
int spi_init_master(spi_t dev, spi_conf_t conf, spi_speed_t speed)
|
||||
{
|
||||
if (dev) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
uint32_t f_baud = 0;
|
||||
switch(speed)
|
||||
{
|
||||
case SPI_SPEED_100KHZ:
|
||||
f_baud = 100;
|
||||
break;
|
||||
case SPI_SPEED_400KHZ:
|
||||
f_baud = 400;
|
||||
break;
|
||||
case SPI_SPEED_1MHZ:
|
||||
f_baud = 1000;
|
||||
break;
|
||||
case SPI_SPEED_5MHZ:
|
||||
f_baud = 5000;
|
||||
break;
|
||||
case SPI_SPEED_10MHZ:
|
||||
f_baud = 10000;
|
||||
break;
|
||||
}
|
||||
|
||||
#if 0
|
||||
/* TODO */
|
||||
switch(conf)
|
||||
{
|
||||
case SPI_CONF_FIRST_RISING:
|
||||
/**< first data bit is transacted on the first rising SCK edge */
|
||||
cpha = 0;
|
||||
cpol = 0;
|
||||
break;
|
||||
case SPI_CONF_SECOND_RISING:
|
||||
/**< first data bit is transacted on the second rising SCK edge */
|
||||
cpha = 1;
|
||||
cpol = 0;
|
||||
break;
|
||||
case SPI_CONF_FIRST_FALLING:
|
||||
/**< first data bit is transacted on the first falling SCK edge */
|
||||
cpha = 0;
|
||||
cpol = 1;
|
||||
break;
|
||||
case SPI_CONF_SECOND_FALLING:
|
||||
/**< first data bit is transacted on the second falling SCK edge */
|
||||
cpha = 1;
|
||||
cpol = 1;
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
|
||||
/* Power*/
|
||||
PCONP |= PCSSP0; /* Enable power for SSP0 (default is on)*/
|
||||
|
||||
/* PIN Setup*/
|
||||
PINSEL3 |= BIT8 + BIT9; /* Set CLK function to SPI*/
|
||||
PINSEL3 |= BIT14 + BIT15; /* Set MISO function to SPI*/
|
||||
PINSEL3 |= BIT16 + BIT17; /* Set MOSI function to SPI*/
|
||||
|
||||
/* Interface Setup*/
|
||||
SSP0CR0 = 7;
|
||||
|
||||
/* Clock Setup*/
|
||||
uint32_t pclksel;
|
||||
uint32_t cpsr;
|
||||
lpc2387_pclk_scale(F_CPU / 1000, f_baud, &pclksel, &cpsr);
|
||||
PCLKSEL1 &= ~(BIT10 | BIT11); /* CCLK to PCLK divider*/
|
||||
PCLKSEL1 |= pclksel << 10;
|
||||
SSP0CPSR = cpsr;
|
||||
|
||||
/* Enable*/
|
||||
SSP0CR1 |= BIT1; /* SSP-Enable*/
|
||||
int dummy;
|
||||
|
||||
/* Clear RxFIFO:*/
|
||||
while (SPI_RX_AVAIL) { /* while RNE (Receive FIFO Not Empty)...*/
|
||||
dummy = SSP0DR; /* read data*/
|
||||
}
|
||||
|
||||
/* to suppress unused-but-set-variable */
|
||||
(void) dummy;
|
||||
return 0;
|
||||
}
|
||||
|
||||
int spi_init_slave(spi_t dev, spi_conf_t conf, char (*cb)(char))
|
||||
{
|
||||
(void)dev;
|
||||
(void)conf;
|
||||
(void)cb;
|
||||
printf("%s:%s(): stub\n", RIOT_FILE_RELATIVE, __func__);
|
||||
/* TODO */
|
||||
return 0;
|
||||
}
|
||||
|
||||
void spi_transmission_begin(spi_t dev, char reset_val)
|
||||
{
|
||||
(void)dev;
|
||||
(void)reset_val;
|
||||
printf("%s:%s(): stub\n", RIOT_FILE_RELATIVE, __func__);
|
||||
/* TODO*/
|
||||
}
|
||||
|
||||
int spi_acquire(spi_t dev)
|
||||
{
|
||||
if (dev >= SPI_NUMOF) {
|
||||
return -1;
|
||||
}
|
||||
mutex_lock(&locks[dev]);
|
||||
return 0;
|
||||
}
|
||||
|
||||
int spi_release(spi_t dev)
|
||||
{
|
||||
if (dev >= SPI_NUMOF) {
|
||||
return -1;
|
||||
}
|
||||
mutex_unlock(&locks[dev]);
|
||||
return 0;
|
||||
}
|
||||
|
||||
int spi_transfer_byte(spi_t dev, char out, char *in)
|
||||
{
|
||||
while (!SPI_TX_EMPTY);
|
||||
SSP0DR = out;
|
||||
while (SPI_BUSY);
|
||||
while (!SPI_RX_AVAIL);
|
||||
|
||||
char tmp = (char)SSP0DR;
|
||||
|
||||
if (in != NULL) {
|
||||
*in = tmp;
|
||||
}
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
void spi_poweron(spi_t dev)
|
||||
{
|
||||
}
|
||||
|
||||
void spi_poweroff(spi_t dev)
|
||||
{
|
||||
}
|
||||
|
||||
#endif /* SPI_0_EN */
|
@ -0,0 +1,125 @@
|
||||
/*
|
||||
* Copyright (C) 2008-2015, Freie Universitaet Berlin
|
||||
*
|
||||
* This file is subject to the terms and conditions of the GNU Lesser
|
||||
* General Public License v2.1. See the file LICENSE in the top level
|
||||
* directory for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @ingroup cpu_lpc2387
|
||||
* @{
|
||||
*
|
||||
* @file
|
||||
* @brief Peripheral UART driver implementation
|
||||
*
|
||||
* @author Kaspar Schleiser <kaspar@schleiser.de>
|
||||
* @author Heiko Will <hwill@inf.fu-berlin.de>
|
||||
* @author Hauke Petersen <hauke.petersen@fu-berlin.de>
|
||||
*
|
||||
* @}
|
||||
*/
|
||||
|
||||
#include <stdlib.h>
|
||||