This commit is contained in:
Mark Qvist 2014-04-03 22:21:37 +02:00
commit c898b090dd
1049 changed files with 288572 additions and 0 deletions

View file

@ -0,0 +1,54 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2007 Develer S.r.l. (http://www.develer.com/)
*
* -->
*
* \brief Low-level ADC module for ARM (inplementation).
*
* \author Daniele Basile <asterix@develer.com>
*
* This module is automatically included so no need to include
* in test list.
* notest: arm
*
*/
#ifndef WIZ_AUTOGEN
#warning This file is deprecated, you should use adc_at91.c
#include <cpu/detect.h>
#if CPU_ARM_AT91
#include "adc_at91.c"
/*#elif Add other ARM families here */
#else
#error Unknown CPU
#endif
#endif /* WIZ_AUTOGEN */

View file

@ -0,0 +1,46 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2007 Develer S.r.l. (http://www.develer.com/)
*
* -->
*
* \brief Low-level ADC module for ARM (interface).
*
* \author Daniele Basile <asterix@develer.com>
*
*/
#include <cpu/detect.h>
#if CPU_ARM_AT91
#include "adc_at91.h"
/*#elif Add other ARM families here */
#else
#error Unknown CPU
#endif

View file

@ -0,0 +1,210 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2008 Develer S.r.l. (http://www.develer.com/)
*
* -->
*
* \brief ADC hardware-specific implementation
*
* This ADC module should be use both whit kernel or none.
* If you are using a kernel, the adc drive does not wait the finish of
* conversion but use a singal every time a required conversion are
* ended. This signal wake up a process that return a result of
* conversion. Otherwise, if you not use a kernl, this module wait
* whit a loop the finishing of conversion.
*
*
* \author Daniele Basile <asterix@develer.com>
*/
#include "adc_at91.h"
#include <cpu/irq.h>
#include "cfg/cfg_adc.h"
#include "cfg/cfg_proc.h"
#include "cfg/cfg_signal.h"
#include <cfg/macros.h>
#include <cfg/compiler.h>
// Define log settings for cfg/log.h.
#define LOG_LEVEL ADC_LOG_LEVEL
#define LOG_FORMAT ADC_LOG_FORMAT
#include <cfg/log.h>
#include <drv/adc.h>
#include <io/arm.h>
#if CONFIG_KERN
#include <cfg/module.h>
#include <kern/proc.h>
#include <kern/signal.h>
#if !CONFIG_KERN_SIGNALS
#error Signals must be active to use ADC with kernel
#endif
/* Signal adc convertion end */
#define SIG_ADC_COMPLETE SIG_USER0
/* ADC waiting process */
static struct Process *adc_process;
/**
* ADC ISR.
* Simply signal the adc process that convertion is complete.
*/
static DECLARE_ISR(adc_conversion_end_irq)
{
sig_post(adc_process, SIG_ADC_COMPLETE);
/* Inform hw that we have served the IRQ */
AIC_EOICR = 0;
}
static void adc_enable_irq(void)
{
// Disable all interrupt
ADC_IDR = 0xFFFFFFFF;
//Register interrupt vector
AIC_SVR(ADC_ID) = adc_conversion_end_irq;
AIC_SMR(ADC_ID) = AIC_SRCTYPE_INT_EDGE_TRIGGERED;
AIC_IECR = BV(ADC_ID);
//Enable data ready irq
ADC_IER = BV(ADC_DRDY);
}
#endif /* CONFIG_KERN */
/**
* Select mux channel \a ch.
* \todo only first 8 channels are selectable!
*/
void adc_hw_select_ch(uint8_t ch)
{
//Disable all channels
ADC_CHDR = ADC_CH_MASK;
//Enable select channel
ADC_CHER = BV(ch);
}
/**
* Start an ADC convertion.
* If a kernel is present, preempt until convertion is complete, otherwise
* a busy wait on ADC_DRDY bit is done.
*/
uint16_t adc_hw_read(void)
{
#if CONFIG_KERN
/* Ensure ADC is not already in use by another process */
ASSERT(adc_process == NULL);
adc_process = proc_current();
#endif
// Start convertion
ADC_CR = BV(ADC_START);
#if CONFIG_KERN
// Ensure IRQs enabled.
IRQ_ASSERT_ENABLED();
sig_wait(SIG_ADC_COMPLETE);
/* Prevent race condition in case of preemptive kernel */
uint16_t ret = ADC_LCDR;
MEMORY_BARRIER;
adc_process = NULL;
return ret;
#else
//Wait in polling until is done
while (!(ADC_SR & BV(ADC_DRDY)));
//Return the last converted data
return(ADC_LCDR);
#endif
}
/**
* Init ADC hardware.
*/
void adc_hw_init(void)
{
//Init ADC pins.
ADC_INIT_PINS();
/*
* Set adc mode register:
* - Disable hardware trigger and enable software trigger.
* - Select normal mode.
* - Set ADC_BITS bit convertion resolution.
*
* \{
*/
ADC_MR = 0;
#if ADC_BITS == 10
ADC_MR &= ~BV(ADC_LOWRES);
#elif ADC_BITS == 8
ADC_MR |= BV(ADC_LOWRES);
#else
#error No select bit resolution is supported to this CPU
#endif
/* \} */
LOG_INFO("Computed ADC_CLOCK %ld\n", ADC_COMPUTED_CLOCK);
LOG_INFO("prescaler[%ld], stup[%ld], shtim[%ld]\n",ADC_COMPUTED_PRESCALER, ADC_COMPUTED_STARTUPTIME, ADC_COMPUTED_SHTIME);
//Apply computed prescaler value
ADC_MR &= ~ADC_PRESCALER_MASK;
ADC_MR |= ((ADC_COMPUTED_PRESCALER << ADC_PRESCALER_SHIFT) & ADC_PRESCALER_MASK);
LOG_INFO("prescaler[%ld]\n", (ADC_COMPUTED_PRESCALER << ADC_PRESCALER_SHIFT) & ADC_PRESCALER_MASK);
//Apply computed start up time
ADC_MR &= ~ADC_STARTUP_MASK;
ADC_MR |= ((ADC_COMPUTED_STARTUPTIME << ADC_STARTUP_SHIFT) & ADC_STARTUP_MASK);
LOG_INFO("sttime[%ld]\n", (ADC_COMPUTED_STARTUPTIME << ADC_STARTUP_SHIFT) & ADC_STARTUP_MASK);
//Apply computed sample and hold time
ADC_MR &= ~ADC_SHTIME_MASK;
ADC_MR |= ((ADC_COMPUTED_SHTIME << ADC_SHTIME_SHIFT) & ADC_SHTIME_MASK);
LOG_INFO("shtime[%ld]\n", (ADC_COMPUTED_SHTIME << ADC_SHTIME_SHIFT) & ADC_SHTIME_MASK);
#if CONFIG_KERN
//Register and enable irq for adc.
adc_enable_irq();
#endif
}

View file

@ -0,0 +1,95 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2008 Develer S.r.l. (http://www.develer.com/)
*
* -->
*
* \brief ADC hardware-specific definition
*
* \author Daniele Basile <asterix@develer.com>
*/
#ifndef DRV_ADC_AT91_H
#define DRV_ADC_AT91_H
#include <hw/hw_cpufreq.h>
#include "cfg/cfg_adc.h"
#include <cfg/compiler.h>
/**
* ADC config define.
*/
#define ADC_MUX_MAXCH 8 //Max number of channel for ADC.
#define ADC_BITS 10 //Bit resolution for ADC converter.
/**
* Macro for computing correct value to write into ADC
* register.
*/
#define ADC_COMPUTED_PRESCALER (DIV_ROUNDUP(CPU_FREQ, 2 * CONFIG_ADC_CLOCK) - 1)
#define ADC_COMPUTED_CLOCK (CPU_FREQ / ((ADC_COMPUTED_PRESCALER + 1) * 2))
#define ADC_COMPUTED_STARTUPTIME (((CONFIG_ADC_STARTUP_TIME * ADC_COMPUTED_CLOCK) / 8000000UL) - 1)
#define ADC_COMPUTED_SHTIME ((uint32_t)((CONFIG_ADC_SHTIME * (uint64_t)ADC_COMPUTED_CLOCK) / 1000000000UL) - 1)
/**
* Init pins macro for adc.
*/
/**
* Define PIO controller for enable ADC function.
* \{
*/
#if CPU_ARM_SAM7X
#define ADC_PIO_DISABLE PIOB_PDR
#define ADC_PIO_EN_FUNC PIOB_ASR
#elif CPU_ARM_SAM7S_LARGE
#define ADC_PIO_DISABLE PIOA_PDR
#define ADC_PIO_EN_FUNC PIOA_BSR
#else
#error No ADC pins name definitions for selected ARM CPU
#endif
/*\}*/
/**
* Init the ADC pins.
* Implement it if necessary.
*/
#define ADC_INIT_PINS() \
do { \
} while (0)
void adc_hw_select_ch(uint8_t ch);
uint16_t adc_hw_read(void);
void adc_hw_init(void);
#endif /* DRV_ADC_AT91_H */

View file

@ -0,0 +1,473 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2010 Develer S.r.l. (http://www.develer.com/)
* All Rights Reserved.
* -->
*
* \brief EMAC driver for AT91SAM7X Family.
*
* \author Daniele Basile <asterix@develer.com>
* \author Andrea Righi <arighi@develer.com>
*/
#include "cfg/cfg_eth.h"
#define LOG_LEVEL ETH_LOG_LEVEL
#define LOG_FORMAT ETH_LOG_FORMAT
#include <cfg/log.h>
#include <cfg/debug.h>
#include <cfg/log.h>
#include <cfg/macros.h>
#include <cfg/compiler.h>
#include <io/at91sam7.h>
#include <io/arm.h>
#include <cpu/power.h>
#include <cpu/types.h>
#include <cpu/irq.h>
#include <drv/timer.h>
#include <drv/eth.h>
#include <mware/event.h>
#include <string.h>
#include "eth_at91.h"
#define EMAC_RX_INTS (BV(EMAC_RCOMP) | BV(EMAC_ROVR) | BV(EMAC_RXUBR))
#define EMAC_TX_INTS (BV(EMAC_TCOMP) | BV(EMAC_TXUBR) | BV(EMAC_RLEX))
/* Silent Doxygen bug... */
#ifndef __doxygen__
/*
* NOTE: this buffer should be declared as 'volatile' because it is read by the
* hardware. However, this is accessed only via memcpy() that should guarantee
* coherency when copying from/to buffers.
*/
static uint8_t tx_buf[EMAC_TX_BUFFERS * EMAC_TX_BUFSIZ] ALIGNED(8);
static volatile BufDescriptor tx_buf_tab[EMAC_TX_DESCRIPTORS] ALIGNED(8);
/*
* NOTE: this buffer should be declared as 'volatile' because it is wrote by
* the hardware. However, this is accessed only via memcpy() that should
* guarantee coherency when copying from/to buffers.
*/
static uint8_t rx_buf[EMAC_RX_BUFFERS * EMAC_RX_BUFSIZ] ALIGNED(8);
static volatile BufDescriptor rx_buf_tab[EMAC_RX_DESCRIPTORS] ALIGNED(8);
#endif
static int tx_buf_idx;
static int tx_buf_offset;
static int rx_buf_idx;
static Event recv_wait, send_wait;
static DECLARE_ISR(emac_irqHandler)
{
/* Read interrupt status and disable interrupts. */
uint32_t isr = EMAC_ISR;
/* Receiver interrupt */
if ((isr & EMAC_RX_INTS))
{
if (isr & BV(EMAC_RCOMP))
event_do(&recv_wait);
EMAC_RSR = EMAC_RX_INTS;
}
/* Transmitter interrupt */
if (isr & EMAC_TX_INTS)
{
if (isr & BV(EMAC_TCOMP))
event_do(&send_wait);
EMAC_TSR = EMAC_TX_INTS;
}
AIC_EOICR = 0;
}
/*
* \brief Read contents of PHY register.
*
* \param reg PHY register number.
*
* \return Contents of the specified register.
*/
static uint16_t phy_hw_read(reg8_t reg)
{
// PHY read command.
EMAC_MAN = EMAC_SOF | EMAC_RW_READ | (NIC_PHY_ADDR << EMAC_PHYA_SHIFT)
| ((reg << EMAC_REGA_SHIFT) & EMAC_REGA) | EMAC_CODE;
// Wait until PHY logic completed.
while (!(EMAC_NSR & BV(EMAC_IDLE)))
cpu_relax();
// Get data from PHY maintenance register.
return (uint16_t)(EMAC_MAN & EMAC_DATA);
}
/*
* \brief Write value to PHY register.
*
* \param reg PHY register number.
* \param val Value to write.
*/
static void phy_hw_write(reg8_t reg, uint16_t val)
{
// PHY write command.
EMAC_MAN = EMAC_SOF | EMAC_RW_WRITE | (NIC_PHY_ADDR << EMAC_PHYA_SHIFT)
| ((reg << EMAC_REGA_SHIFT) & EMAC_REGA) | EMAC_CODE | val;
// Wait until PHY logic completed.
while (!(EMAC_NSR & BV(EMAC_IDLE)))
cpu_relax();
}
static int emac_reset(void)
{
uint16_t phy_cr;
// Enable devices
PMC_PCER = BV(PIOA_ID);
PMC_PCER = BV(PIOB_ID);
PMC_PCER = BV(EMAC_ID);
// Disable RMII and TESTMODE by disabling pull-ups.
PIOB_PUDR = BV(PHY_COL_RMII_BIT) | BV(PHY_RXDV_TESTMODE_BIT);
// Disable PHY power down.
PIOB_PER = BV(PHY_PWRDN_BIT);
PIOB_OER = BV(PHY_PWRDN_BIT);
PIOB_CODR = BV(PHY_PWRDN_BIT);
// Toggle external hardware reset pin.
RSTC_MR = RSTC_KEY | (1 << RSTC_ERSTL_SHIFT) | BV(RSTC_URSTEN);
RSTC_CR = RSTC_KEY | BV(RSTC_EXTRST);
while ((RSTC_SR & BV(RSTC_NRSTL)) == 0)
cpu_relax();
// Configure MII port.
PIOB_ASR = PHY_MII_PINS;
PIOB_BSR = 0;
PIOB_PDR = PHY_MII_PINS;
// Enable receive and transmit clocks.
EMAC_USRIO = BV(EMAC_CLKEN);
// Enable management port.
EMAC_NCR |= BV(EMAC_MPE);
EMAC_NCFGR |= EMAC_CLK_HCLK_32;
// Set local MAC address.
EMAC_SA1L = (mac_addr[3] << 24) | (mac_addr[2] << 16) |
(mac_addr[1] << 8) | mac_addr[0];
EMAC_SA1H = (mac_addr[5] << 8) | mac_addr[4];
// Wait for PHY ready
timer_delay(255);
// Clear MII isolate.
phy_hw_read(NIC_PHY_BMCR);
phy_cr = phy_hw_read(NIC_PHY_BMCR);
phy_cr &= ~NIC_PHY_BMCR_ISOLATE;
phy_hw_write(NIC_PHY_BMCR, phy_cr);
phy_cr = phy_hw_read(NIC_PHY_BMCR);
LOG_INFO("%s: PHY ID %#04x %#04x\n",
__func__,
phy_hw_read(NIC_PHY_ID1), phy_hw_read(NIC_PHY_ID2));
// Wait for auto negotiation completed.
phy_hw_read(NIC_PHY_BMSR);
for (;;)
{
if (phy_hw_read(NIC_PHY_BMSR) & NIC_PHY_BMSR_ANCOMPL)
break;
cpu_relax();
}
// Disable management port.
EMAC_NCR &= ~BV(EMAC_MPE);
return 0;
}
static int emac_start(void)
{
uint32_t addr;
int i;
for (i = 0; i < EMAC_RX_DESCRIPTORS; i++)
{
addr = (uint32_t)(rx_buf + (i * EMAC_RX_BUFSIZ));
rx_buf_tab[i].addr = addr & BUF_ADDRMASK;
}
rx_buf_tab[EMAC_RX_DESCRIPTORS - 1].addr |= RXBUF_WRAP;
for (i = 0; i < EMAC_TX_DESCRIPTORS; i++)
{
addr = (uint32_t)(tx_buf + (i * EMAC_TX_BUFSIZ));
tx_buf_tab[i].addr = addr & BUF_ADDRMASK;
tx_buf_tab[i].stat = TXS_USED;
}
tx_buf_tab[EMAC_TX_DESCRIPTORS - 1].stat = TXS_USED | TXS_WRAP;
/* Tell the EMAC where to find the descriptors. */
EMAC_RBQP = (uint32_t)rx_buf_tab;
EMAC_TBQP = (uint32_t)tx_buf_tab;
/* Clear receiver status. */
EMAC_RSR = BV(EMAC_OVR) | BV(EMAC_REC) | BV(EMAC_BNA);
/* Copy all frames and discard FCS. */
EMAC_NCFGR |= BV(EMAC_CAF) | BV(EMAC_DRFCS);
/* Enable receiver, transmitter and statistics. */
EMAC_NCR |= BV(EMAC_TE) | BV(EMAC_RE) | BV(EMAC_WESTAT);
return 0;
}
ssize_t eth_putFrame(const uint8_t *buf, size_t len)
{
size_t wr_len;
if (UNLIKELY(!len))
return -1;
ASSERT(len <= sizeof(tx_buf));
/* Check if the transmit buffer is available */
while (!(tx_buf_tab[tx_buf_idx].stat & TXS_USED))
event_wait(&send_wait);
/* Copy the data into the buffer and prepare descriptor */
wr_len = MIN(len, (size_t)EMAC_TX_BUFSIZ - tx_buf_offset);
memcpy((uint8_t *)tx_buf_tab[tx_buf_idx].addr + tx_buf_offset,
buf, wr_len);
tx_buf_offset += wr_len;
return wr_len;
}
void eth_sendFrame(void)
{
tx_buf_tab[tx_buf_idx].stat = (tx_buf_offset & TXS_LENGTH_FRAME) |
TXS_LAST_BUFF |
((tx_buf_idx == EMAC_TX_DESCRIPTORS - 1) ? TXS_WRAP : 0);
EMAC_NCR |= BV(EMAC_TSTART);
tx_buf_offset = 0;
if (++tx_buf_idx >= EMAC_TX_DESCRIPTORS)
tx_buf_idx = 0;
}
ssize_t eth_send(const uint8_t *buf, size_t len)
{
if (UNLIKELY(!len))
return -1;
len = eth_putFrame(buf, len);
eth_sendFrame();
return len;
}
static void eth_buf_realign(int idx)
{
/* Empty buffer found. Realign. */
do {
rx_buf_tab[rx_buf_idx].addr &= ~RXBUF_OWNERSHIP;
if (++rx_buf_idx >= EMAC_RX_BUFFERS)
rx_buf_idx = 0;
} while (idx != rx_buf_idx);
}
static size_t __eth_getFrameLen(void)
{
int idx, n = EMAC_RX_BUFFERS;
skip:
/* Skip empty buffers */
while ((n > 0) && !(rx_buf_tab[rx_buf_idx].addr & RXBUF_OWNERSHIP))
{
if (++rx_buf_idx >= EMAC_RX_BUFFERS)
rx_buf_idx = 0;
n--;
}
if (UNLIKELY(!n))
{
LOG_INFO("no frame found\n");
return 0;
}
/* Search the start of frame and cleanup fragments */
while ((n > 0) && (rx_buf_tab[rx_buf_idx].addr & RXBUF_OWNERSHIP) &&
!(rx_buf_tab[rx_buf_idx].stat & RXS_SOF))
{
rx_buf_tab[rx_buf_idx].addr &= ~RXBUF_OWNERSHIP;
if (++rx_buf_idx >= EMAC_RX_BUFFERS)
rx_buf_idx = 0;
n--;
}
if (UNLIKELY(!n))
{
LOG_INFO("no SOF found\n");
return 0;
}
/* Search end of frame to evaluate the total frame size */
idx = rx_buf_idx;
restart:
while (n > 0)
{
if (UNLIKELY(!(rx_buf_tab[idx].addr & RXBUF_OWNERSHIP)))
{
/* Empty buffer found. Realign. */
eth_buf_realign(idx);
goto skip;
}
if (rx_buf_tab[idx].stat & RXS_EOF)
return rx_buf_tab[idx].stat & RXS_LENGTH_FRAME;
if (UNLIKELY((idx != rx_buf_idx) &&
(rx_buf_tab[idx].stat & RXS_SOF)))
{
/* Another start of frame found. Realign. */
eth_buf_realign(idx);
goto restart;
}
if (++idx >= EMAC_RX_BUFFERS)
idx = 0;
n--;
}
LOG_INFO("no EOF found\n");
return 0;
}
size_t eth_getFrameLen(void)
{
size_t len;
/* Check if there is at least one available frame in the buffer */
while (1)
{
len = __eth_getFrameLen();
if (LIKELY(len))
break;
/* Wait for RX interrupt */
event_wait(&recv_wait);
}
return len;
}
ssize_t eth_getFrame(uint8_t *buf, size_t len)
{
uint8_t *addr;
size_t rd_len = 0;
if (UNLIKELY(!len))
return -1;
ASSERT(len <= sizeof(rx_buf));
/* Copy data from the RX buffer */
addr = (uint8_t *)(rx_buf_tab[rx_buf_idx].addr & BUF_ADDRMASK);
if (addr + len > &rx_buf[countof(rx_buf)])
{
size_t count = &rx_buf[countof(rx_buf)] - addr;
memcpy(buf, addr, count);
memcpy(buf + count, rx_buf, len - count);
}
else
{
memcpy(buf, addr, len);
}
/* Update descriptors */
while (rd_len < len)
{
if (len - rd_len >= EMAC_RX_BUFSIZ)
rd_len += EMAC_RX_BUFSIZ;
else
rd_len += len - rd_len;
if (UNLIKELY(!(rx_buf_tab[rx_buf_idx].addr & RXBUF_OWNERSHIP)))
{
LOG_INFO("bad frame found\n");
return 0;
}
rx_buf_tab[rx_buf_idx].addr &= ~RXBUF_OWNERSHIP;
if (++rx_buf_idx >= EMAC_RX_DESCRIPTORS)
rx_buf_idx = 0;
}
return rd_len;
}
ssize_t eth_recv(uint8_t *buf, size_t len)
{
if (UNLIKELY(!len))
return -1;
len = MIN(len, eth_getFrameLen());
return len ? eth_getFrame(buf, len) : 0;
}
int eth_init()
{
cpu_flags_t flags;
emac_reset();
emac_start();
event_initGeneric(&recv_wait);
event_initGeneric(&send_wait);
// Register interrupt vector
IRQ_SAVE_DISABLE(flags);
/* Disable all emac interrupts */
EMAC_IDR = 0xFFFFFFFF;
/* Set the vector. */
AIC_SVR(EMAC_ID) = emac_irqHandler;
/* Initialize to edge triggered with defined priority. */
AIC_SMR(EMAC_ID) = AIC_SRCTYPE_INT_EDGE_TRIGGERED;
/* Clear pending interrupt */
AIC_ICCR = BV(EMAC_ID);
/* Enable the system IRQ */
AIC_IECR = BV(EMAC_ID);
/* Enable interrupts */
EMAC_IER = EMAC_RX_INTS | EMAC_TX_INTS;
IRQ_RESTORE(flags);
return 0;
}

View file

@ -0,0 +1,165 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2009 Develer S.r.l. (http://www.develer.com/)
* All Rights Reserved.
* -->
*
* \brief EMAC driver for AT91SAM7X Family, interface.
*
* \author Daniele Basile <asterix@develer.com>
* \author Andrea Righi <arighi@develer.com>
*/
#ifndef ETH_AT91_H
#define ETH_AT91_H
// Settings and definition for DAVICOM 9161A
// \{
#define NIC_PHY_ADDR 31
//Registry definition
#define NIC_PHY_BMCR 0x00 // Basic mode control register.
#define NIC_PHY_BMCR_COLTEST 0x0080 // Collision test.
#define NIC_PHY_BMCR_FDUPLEX 0x0100 // Full duplex mode.
#define NIC_PHY_BMCR_ANEGSTART 0x0200 // Restart auto negotiation.
#define NIC_PHY_BMCR_ISOLATE 0x0400 // Isolate from MII.
#define NIC_PHY_BMCR_PWRDN 0x0800 // Power-down.
#define NIC_PHY_BMCR_ANEGENA 0x1000 // Enable auto negotiation.
#define NIC_PHY_BMCR_100MBPS 0x2000 // Select 100 Mbps.
#define NIC_PHY_BMCR_LOOPBACK 0x4000 // Enable loopback mode.
#define NIC_PHY_BMCR_RESET 0x8000 // Software reset.
#define NIC_PHY_BMSR 0x01 // Basic mode status register.
#define NIC_PHY_BMSR_ANCOMPL 0x0020 // Auto negotiation complete.
#define NIC_PHY_BMSR_ANEGCAPABLE 0x0008 // Able to do auto-negotiation
#define NIC_PHY_BMSR_LINKSTAT 0x0004 // Link status.
#define NIC_PHY_ID1 0x02 // PHY identifier register 1.
#define NIC_PHY_ID2 0x03 // PHY identifier register 2.
#define NIC_PHY_ANAR 0x04 // Auto negotiation advertisement register.
#define NIC_PHY_ANLPAR 0x05 // Auto negotiation link partner availability register.
#define NIC_PHY_ANER 0x06 // Auto negotiation expansion register.
// Pin definition for DAVICOM 9161A
// See schematic for at91sam7x-ek evalution board
#define PHY_TXCLK_ISOLATE_BIT 0
#define PHY_REFCLK_XT2_BIT 0
#define PHY_TXEN_BIT 1
#define PHY_TXD0_BIT 2
#define PHY_TXD1_BIT 3
#define PHY_CRS_AD4_BIT 4
#define PHY_RXD0_AD0_BIT 5
#define PHY_RXD1_AD1_BIT 6
#define PHY_RXER_RXD4_RPTR_BIT 7
#define PHY_MDC_BIT 8
#define PHY_MDIO_BIT 9
#define PHY_TXD2_BIT 10
#define PHY_TXD3_BIT 11
#define PHY_TXER_TXD4_BIT 12
#define PHY_RXD2_AD2_BIT 13
#define PHY_RXD3_AD3_BIT 14
#define PHY_RXDV_TESTMODE_BIT 15
#define PHY_COL_RMII_BIT 16
#define PHY_RXCLK_10BTSER_BIT 17
#define PHY_PWRDN_BIT 18
#define PHY_MDINTR_BIT 26
#define PHY_MII_PINS BV(PHY_REFCLK_XT2_BIT) \
| BV(PHY_TXEN_BIT) \
| BV(PHY_TXD0_BIT) \
| BV(PHY_TXD1_BIT) \
| BV(PHY_CRS_AD4_BIT) \
| BV(PHY_RXD0_AD0_BIT) \
| BV(PHY_RXD1_AD1_BIT) \
| BV(PHY_RXER_RXD4_RPTR_BIT) \
| BV(PHY_MDC_BIT) \
| BV(PHY_MDIO_BIT) \
| BV(PHY_TXD2_BIT) \
| BV(PHY_TXD3_BIT) \
| BV(PHY_TXER_TXD4_BIT) \
| BV(PHY_RXD2_AD2_BIT) \
| BV(PHY_RXD3_AD3_BIT) \
| BV(PHY_RXDV_TESTMODE_BIT) \
| BV(PHY_COL_RMII_BIT) \
| BV(PHY_RXCLK_10BTSER_BIT)
// \}
#define EMAC_TX_BUFSIZ 1518 //!!! Don't change this
#define EMAC_TX_BUFFERS 1 //!!! Don't change this
#define EMAC_TX_DESCRIPTORS EMAC_TX_BUFFERS
#define EMAC_RX_BUFFERS 32 //!!! Don't change this
#define EMAC_RX_BUFSIZ 128 //!!! Don't change this
#define EMAC_RX_DESCRIPTORS EMAC_RX_BUFFERS
// Flag to manage local tx buffer
#define TXS_USED 0x80000000 //Used buffer.
#define TXS_WRAP 0x40000000 //Last descriptor.
#define TXS_ERROR 0x20000000 //Retry limit exceeded.
#define TXS_UNDERRUN 0x10000000 //Transmit underrun.
#define TXS_NO_BUFFER 0x08000000 //Buffer exhausted.
#define TXS_NO_CRC 0x00010000 //CRC not appended.
#define TXS_LAST_BUFF 0x00008000 //Last buffer of frame.
#define TXS_LENGTH_FRAME 0x000007FF // Length of frame including FCS.
// Flag to manage local rx buffer
#define RXBUF_OWNERSHIP 0x00000001
#define RXBUF_WRAP 0x00000002
#define BUF_ADDRMASK 0xFFFFFFFC
#define RXS_BROADCAST_ADDR 0x80000000 // Broadcast address detected.
#define RXS_MULTICAST_HASH 0x40000000 // Multicast hash match.
#define RXS_UNICAST_HASH 0x20000000 // Unicast hash match.
#define RXS_EXTERNAL_ADDR 0x10000000 // External address match.
#define RXS_SA1_ADDR 0x04000000 // Specific address register 1 match.
#define RXS_SA2_ADDR 0x02000000 // Specific address register 2 match.
#define RXS_SA3_ADDR 0x01000000 // Specific address register 3 match.
#define RXS_SA4_ADDR 0x00800000 // Specific address register 4 match.
#define RXS_TYPE_ID 0x00400000 // Type ID match.
#define RXS_VLAN_TAG 0x00200000 // VLAN tag detected.
#define RXS_PRIORITY_TAG 0x00100000 // Priority tag detected.
#define RXS_VLAN_PRIORITY 0x000E0000 // VLAN priority.
#define RXS_CFI_IND 0x00010000 // Concatenation format indicator.
#define RXS_EOF 0x00008000 // End of frame.
#define RXS_SOF 0x00004000 // Start of frame.
#define RXS_RBF_OFFSET 0x00003000 // Receive buffer offset mask.
#define RXS_LENGTH_FRAME 0x000007FF // Length of frame including FCS.
#define EMAC_RSR_BITS (BV(EMAC_BNA) | BV(EMAC_REC) | BV(EMAC_OVR))
#define EMAC_TSR_BITS (BV(EMAC_UBR) | BV(EMAC_COL) | BV(EMAC_RLES) | \
BV(EMAC_BEX) | BV(EMAC_COMP) | BV(EMAC_UND))
typedef struct BufDescriptor
{
volatile uint32_t addr;
volatile uint32_t stat;
} BufDescriptor;
#endif /* ETH_AT91_H */

View file

@ -0,0 +1,48 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2007 Develer S.r.l. (http://www.develer.com/)
*
* -->
*
* \brief Low-level flash module for ARM (interface).
*
* \author Daniele Basile <asterix@develer.com>
*
*/
#include <cpu/detect.h>
#if CPU_ARM_AT91
#include "flash_at91.h"
#elif CPU_ARM_LPC2
#include "flash_lpc2.h"
/*#elif Add other ARM families here */
#else
#error Unknown CPU
#endif

View file

@ -0,0 +1,241 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2009 Develer S.r.l. (http://www.develer.com/)
*
* -->
*
* \author Daniele Basile <asterix@develer.com>
*
* \brief At91sam7 Internal flash read/write driver.
*
*
*/
#include "flash_at91.h"
#include "cfg/cfg_emb_flash.h"
#include <cfg/macros.h>
// Define log settings for cfg/log.h
#define LOG_LEVEL CONFIG_FLASH_EMB_LOG_LEVEL
#define LOG_FORMAT CONFIG_FLASH_EMB_LOG_FORMAT
#include <cfg/log.h>
#include <cpu/irq.h>
#include <cpu/attr.h>
#include <cpu/power.h>
#include <io/kfile.h>
#include <io/kblock.h>
#include <io/arm.h>
#include <drv/timer.h>
#include <drv/flash.h>
#include <string.h>
struct FlashHardware
{
uint8_t status;
};
/**
* Really send the flash write command.
*
* \note This function has to be placed in RAM because
* executing code from flash while a writing process
* is in progress is forbidden.
*/
RAM_FUNC NOINLINE static void write_page(uint32_t page)
{
// Send the 'write page' command
MC_FCR = MC_KEY | MC_FCMD_WP | (MC_PAGEN_MASK & (page << 8));
// Wait for the end of command
while(!(MC_FSR & BV(MC_FRDY)))
{
//NOP;
}
}
/**
* Send write command.
*
* After WR command cpu write bufferd page into flash memory.
*
*/
INLINE void flash_sendWRcmd(uint32_t page)
{
cpu_flags_t flags;
LOG_INFO("Writing page %ld...\n", page);
IRQ_SAVE_DISABLE(flags);
write_page(page);
IRQ_RESTORE(flags);
LOG_INFO("Done\n");
}
/**
* Return true if no error are occurred after flash memory
* read or write operation, otherwise return error code.
*/
static bool flash_getStatus(struct KBlock *blk)
{
Flash *fls = FLASH_CAST(blk);
/*
* This bit is set to one if an invalid command and/or a bad keywords was/were
* written in the Flash Command Register.
*/
if(MC_FSR & BV(MC_PROGE))
{
fls->hw->status |= FLASH_WR_ERR;
LOG_ERR("flash not erased..\n");
return false;
}
/*
* This bit is set to one if we programming of at least one locked lock
* region.
*/
if(MC_FSR & BV(MC_LOCKE))
{
fls->hw->status |= FLASH_WR_PROTECT;
LOG_ERR("wr protect..\n");
return false;
}
return true;
}
static size_t at91_flash_readDirect(struct KBlock *blk, block_idx_t idx, void *buf, size_t offset, size_t size)
{
memcpy(buf, (void *)(idx * blk->blk_size + FLASH_BASE + offset), size);
return size;
}
static size_t at91_flash_writeDirect(struct KBlock *blk, block_idx_t idx, const void *_buf, size_t offset, size_t size)
{
ASSERT(offset == 0);
ASSERT(size == blk->blk_size);
uint32_t *addr = (uint32_t *)(idx * blk->blk_size + FLASH_BASE);
const uint8_t *buf = (const uint8_t *)_buf;
while (size)
{
uint32_t data = (*(buf + 3) << 24) |
(*(buf + 2) << 16) |
(*(buf + 1) << 8) |
*buf;
*addr = data;
size -= 4;
buf += 4;
addr++;
}
flash_sendWRcmd(idx);
if (!flash_getStatus(blk))
return 0;
return blk->blk_size;
}
static int at91_flash_error(struct KBlock *blk)
{
Flash *fls = FLASH_CAST(blk);
return fls->hw->status;
}
static void at91_flash_clearerror(struct KBlock *blk)
{
Flash *fls = FLASH_CAST(blk);
fls->hw->status = 0;
}
static const KBlockVTable flash_at91_buffered_vt =
{
.readDirect = at91_flash_readDirect,
.writeDirect = at91_flash_writeDirect,
.readBuf = kblock_swReadBuf,
.writeBuf = kblock_swWriteBuf,
.load = kblock_swLoad,
.store = kblock_swStore,
.error = at91_flash_error,
.clearerr = at91_flash_clearerror,
};
static const KBlockVTable flash_at91_unbuffered_vt =
{
.readDirect = at91_flash_readDirect,
.writeDirect = at91_flash_writeDirect,
.error = at91_flash_error,
.clearerr = at91_flash_clearerror,
};
static struct FlashHardware flash_at91_hw;
static uint8_t flash_buf[FLASH_PAGE_SIZE_BYTES];
static void common_init(Flash *fls)
{
memset(fls, 0, sizeof(*fls));
DB(fls->blk.priv.type = KBT_FLASH);
fls->hw = &flash_at91_hw;
fls->blk.blk_size = FLASH_PAGE_SIZE_BYTES;
fls->blk.blk_cnt = FLASH_MEM_SIZE / FLASH_PAGE_SIZE_BYTES;
}
void flash_hw_init(Flash *fls, UNUSED_ARG(int, flags))
{
common_init(fls);
fls->blk.priv.vt = &flash_at91_buffered_vt;
fls->blk.priv.flags |= KB_BUFFERED | KB_PARTIAL_WRITE;
fls->blk.priv.buf = flash_buf;
/* Load the first block in the cache */
memcpy(fls->blk.priv.buf, (void *)(FLASH_BASE), fls->blk.blk_size);
}
void flash_hw_initUnbuffered(Flash *fls, UNUSED_ARG(int, flags))
{
common_init(fls);
fls->blk.priv.vt = &flash_at91_unbuffered_vt;
}

View file

@ -0,0 +1,52 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2009 Develer S.r.l. (http://www.develer.com/)
*
* -->
*
* \author Daniele Basile <asterix@develer.com>
*
* \brief At91sam7 Internal flash read/write driver.
*
*
*/
#ifndef FLASH_AT91_H
#define FLASH_AT91_H
#include "cfg/cfg_emb_flash.h"
#if !CONFIG_FLASH_DISABLE_OLD_API
/* For backwards compatibility */
#define FlashAt91 Flash
#define flash_at91_init(fls) flash_init(fls);
#endif /* !CONFIG_FLASH_DISABLE_OLD_API */
#endif /* DRV_FLASH_ARM_H */

View file

@ -0,0 +1,365 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2010 Develer S.r.l. (http://www.develer.com/)
*
* -->
*
* \author Francesco Sacchi <batt@develer.com>
* \author Daniele Basile <asterix@develer.com>
*
* \brief NPX lpc23xx embedded flash read/write driver.
*
* notest:arm
*/
#include "flash_lpc2.h"
#include "cfg/cfg_emb_flash.h"
// Define log settings for cfg/log.h
#define LOG_LEVEL CONFIG_FLASH_EMB_LOG_LEVEL
#define LOG_FORMAT CONFIG_FLASH_EMB_LOG_FORMAT
#include <cfg/log.h>
#include <cfg/macros.h>
#include <cpu/irq.h>
#include <cpu/attr.h>
#include <cpu/power.h>
#include <cpu/types.h>
#include <io/kblock.h>
#include <io/arm.h>
#include <drv/timer.h>
#include <drv/flash.h>
#include <struct/bitarray.h>
#include <string.h>
/* Embedded flash programming defines. */
#define IAP_ADDRESS 0x7ffffff1
typedef enum IapCommands
{
PREPARE_SECTOR_FOR_WRITE = 50,
COPY_RAM_TO_FLASH = 51,
ERASE_SECTOR = 52,
BLANK_CHECK_SECTOR = 53,
READ_PART_ID = 54,
READ_BOOT_VER = 55,
COMPARE = 56,
REINVOKE_ISP = 57,
} IapCommands;
#if CPU_ARM_LPC2378
#define FLASH_MEM_SIZE (504 * 1024L)
#define FLASH_PAGE_SIZE_BYTES 4096
#define FLASH_REAL_PAGE_CNT 28
#else
#error Unknown CPU
#endif
#define CMD_SUCCESS 0
struct FlashHardware
{
uint8_t status;
int flags;
};
#define FLASH_PAGE_CNT FLASH_MEM_SIZE / FLASH_PAGE_SIZE_BYTES
BITARRAY_ALLOC(page_dirty, FLASH_PAGE_CNT);
static BitArray lpc2_bitx;
uint8_t erase_group[] = {
4096 / FLASH_PAGE_SIZE_BYTES, 4096 / FLASH_PAGE_SIZE_BYTES,
4096 / FLASH_PAGE_SIZE_BYTES, 4096 / FLASH_PAGE_SIZE_BYTES,
4096 / FLASH_PAGE_SIZE_BYTES, 4096 / FLASH_PAGE_SIZE_BYTES,
4096 / FLASH_PAGE_SIZE_BYTES, 4096 / FLASH_PAGE_SIZE_BYTES,
32768 / FLASH_PAGE_SIZE_BYTES, 32768 / FLASH_PAGE_SIZE_BYTES,
32768 / FLASH_PAGE_SIZE_BYTES, 32768 / FLASH_PAGE_SIZE_BYTES,
32768 / FLASH_PAGE_SIZE_BYTES, 32768 / FLASH_PAGE_SIZE_BYTES,
32768 / FLASH_PAGE_SIZE_BYTES, 32768 / FLASH_PAGE_SIZE_BYTES,
32768 / FLASH_PAGE_SIZE_BYTES, 32768 / FLASH_PAGE_SIZE_BYTES,
32768 / FLASH_PAGE_SIZE_BYTES, 32768 / FLASH_PAGE_SIZE_BYTES,
32768 / FLASH_PAGE_SIZE_BYTES, 32768 / FLASH_PAGE_SIZE_BYTES,
4096 / FLASH_PAGE_SIZE_BYTES, 4096 / FLASH_PAGE_SIZE_BYTES,
4096 / FLASH_PAGE_SIZE_BYTES, 4096 / FLASH_PAGE_SIZE_BYTES,
4096 / FLASH_PAGE_SIZE_BYTES, 4096 / FLASH_PAGE_SIZE_BYTES,
};
typedef struct IapCmd
{
uint32_t cmd;
uint32_t param[4];
} IapCmd;
typedef struct IapRes
{
uint32_t status;
uint32_t res[2];
} IapRes;
typedef void (*iap_callback_t)(IapCmd *, IapRes *);
iap_callback_t iap = (iap_callback_t)IAP_ADDRESS;
static size_t sector_size(uint32_t page)
{
if (page < 8)
return 4096;
else if (page < 22)
return 32768;
else if (page < 28)
return 4096;
ASSERT(0);
return 0;
}
static size_t sector_addr(uint32_t page)
{
if (page < 8)
return page * 4096;
else if (page < 22)
return (page - 8) * 32768 + 4096 * 8;
else if (page < 28)
return (page - 22) * 4096 + 32768 * 14 + 4096 * 8;
ASSERT(0);
return 0;
}
static uint32_t addr_to_sector(size_t addr)
{
if (addr < 4096 * 8)
return addr / 4096;
else if (addr < 4096 * 8 + 32768L * 14)
return ((addr - 4096 * 8) / 32768) + 8;
else if (addr < 4096 * 8 + 32768L * 14 + 4096 * 6)
return ((addr - 4096 * 8 - 32768L * 14) / 4096) + 22;
ASSERT(0);
return 0;
}
static size_t lpc2_flash_readDirect(struct KBlock *blk, block_idx_t idx, void *buf, size_t offset, size_t size)
{
memcpy(buf, (void *)(idx * blk->blk_size + offset), size);
return size;
}
static size_t lpc2_flash_writeDirect(struct KBlock *blk, block_idx_t idx, const void *_buf, size_t offset, size_t size)
{
ASSERT(offset == 0);
ASSERT(FLASH_PAGE_SIZE_BYTES == size);
Flash *fls = FLASH_CAST(blk);
if (!(fls->hw->flags & FLASH_WRITE_ONCE))
ASSERT(sector_size(idx) <= FLASH_PAGE_SIZE_BYTES);
const uint8_t *buf = (const uint8_t *)_buf;
cpu_flags_t flags;
//Compute page address of current page.
uint32_t addr = idx * blk->blk_size;
uint32_t sector = addr_to_sector(addr);
// Compute the first page index in the sector to manage the status
int idx_sector = sector_addr(sector) / blk->blk_size;
LOG_INFO("Writing page[%ld]sector[%ld]idx[%d]\n", idx, sector, idx_sector);
IRQ_SAVE_DISABLE(flags);
IapCmd cmd;
IapRes res;
cmd.cmd = PREPARE_SECTOR_FOR_WRITE;
cmd.param[0] = cmd.param[1] = sector;
iap(&cmd, &res);
if (res.status != CMD_SUCCESS)
goto flash_error;
if ((fls->hw->flags & FLASH_WRITE_ONCE) &&
bitarray_isRangeFull(&lpc2_bitx, idx_sector, erase_group[sector]))
{
kputs("blocchi pieni\n");
ASSERT(0);
goto flash_error;
}
bool erase = false;
if ((fls->hw->flags & FLASH_WRITE_ONCE) &&
bitarray_isRangeEmpty(&lpc2_bitx, idx_sector, erase_group[sector]))
erase = true;
if (!(fls->hw->flags & FLASH_WRITE_ONCE))
erase = true;
if (erase)
{
cmd.cmd = ERASE_SECTOR;
cmd.param[0] = cmd.param[1] = sector;
cmd.param[2] = CPU_FREQ / 1000;
iap(&cmd, &res);
if (res.status != CMD_SUCCESS)
goto flash_error;
}
LOG_INFO("Writing page [%ld], addr [%ld] in sector[%ld]\n", idx, addr, sector);
cmd.cmd = PREPARE_SECTOR_FOR_WRITE;
cmd.param[0] = cmd.param[1] = sector;
iap(&cmd, &res);
if (res.status != CMD_SUCCESS)
goto flash_error;
if (fls->hw->flags & FLASH_WRITE_ONCE)
{
if (bitarray_test(&lpc2_bitx, idx))
{
ASSERT(0);
goto flash_error;
}
else
bitarray_set(&lpc2_bitx, idx);
}
cmd.cmd = COPY_RAM_TO_FLASH;
cmd.param[0] = addr;
cmd.param[1] = (uint32_t)buf;
cmd.param[2] = FLASH_PAGE_SIZE_BYTES;
cmd.param[3] = CPU_FREQ / 1000;
iap(&cmd, &res);
if (res.status != CMD_SUCCESS)
goto flash_error;
IRQ_RESTORE(flags);
LOG_INFO("Done\n");
return blk->blk_size;
flash_error:
IRQ_RESTORE(flags);
LOG_ERR("%ld\n", res.status);
fls->hw->status |= FLASH_WR_ERR;
return 0;
}
static int lpc2_flash_close(UNUSED_ARG(struct KBlock, *blk))
{
memset(page_dirty, 0, sizeof(page_dirty));
return 0;
}
static int lpc2_flash_error(struct KBlock *blk)
{
Flash *fls = FLASH_CAST(blk);
return fls->hw->status;
}
static void lpc2_flash_clearerror(struct KBlock *blk)
{
Flash *fls = FLASH_CAST(blk);
fls->hw->status = 0;
}
static const KBlockVTable flash_lpc2_buffered_vt =
{
.readDirect = lpc2_flash_readDirect,
.writeDirect = lpc2_flash_writeDirect,
.readBuf = kblock_swReadBuf,
.writeBuf = kblock_swWriteBuf,
.load = kblock_swLoad,
.store = kblock_swStore,
.close = lpc2_flash_close,
.error = lpc2_flash_error,
.clearerr = lpc2_flash_clearerror,
};
static const KBlockVTable flash_lpc2_unbuffered_vt =
{
.readDirect = lpc2_flash_readDirect,
.writeDirect = lpc2_flash_writeDirect,
.close = lpc2_flash_close,
.error = lpc2_flash_error,
.clearerr = lpc2_flash_clearerror,
};
static struct FlashHardware flash_lpc2_hw;
static uint8_t flash_buf[FLASH_PAGE_SIZE_BYTES];
static void common_init(Flash *fls, int flags)
{
memset(fls, 0, sizeof(*fls));
DB(fls->blk.priv.type = KBT_FLASH);
fls->hw = &flash_lpc2_hw;
fls->hw->flags = flags;
fls->blk.blk_size = FLASH_PAGE_SIZE_BYTES;
fls->blk.blk_cnt = FLASH_MEM_SIZE / FLASH_PAGE_SIZE_BYTES;
bitarray_init(&lpc2_bitx, FLASH_PAGE_CNT, page_dirty, sizeof(page_dirty));
}
void flash_hw_init(Flash *fls, int flags)
{
common_init(fls, flags);
fls->blk.priv.vt = &flash_lpc2_buffered_vt;
fls->blk.priv.flags |= KB_BUFFERED | KB_PARTIAL_WRITE;
fls->blk.priv.buf = flash_buf;
/* Load the first block in the cache */
void *flash_start = 0x0;
memcpy(fls->blk.priv.buf, flash_start, fls->blk.blk_size);
}
void flash_hw_initUnbuffered(Flash *fls, int flags)
{
common_init(fls, flags);
fls->blk.priv.vt = &flash_lpc2_unbuffered_vt;
}

View file

@ -0,0 +1,44 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2010 Develer S.r.l. (http://www.develer.com/)
*
* -->
*
* \author Daniele Basile <asterix@develer.com>
*
* \brief NPX lpc23xx embedded flash read/write driver.
*
*
*/
#ifndef FLASH_LPC2_H
#define FLASH_LPC2_H
#endif /* DRV_FLASH_ARM_H */

View file

@ -0,0 +1,48 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2010 Develer S.r.l. (http://www.develer.com/)
*
* -->
*
* \brief Low-level I2C module for ARM (interface).
*
* \author Daniele Basile <asterix@develer.com>
*
*/
#include <cpu/detect.h>
#if CPU_ARM_AT91
#include "i2c_at91.h"
#elif CPU_ARM_LPC2378
#include "i2c_lpc2.h"
/*#elif Add other ARM families here */
#else
#error Unknown CPU
#endif

View file

@ -0,0 +1,54 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2010 Develer S.r.l. (http://www.develer.com/)
*
* -->
*
* \brief Driver for the AT91SAM7X I2C (interface)
*
* \author Daniele Basile <asterix@develer.com>
*
*/
#ifndef I2C_AT91_H
#define I2C_AT91_H
#include <drv/i2c.h>
/**
* \name I2C devices enum
*/
enum
{
I2C0,
I2C_CNT /**< Number of serial ports */
};
#endif /* I2C_AT91_H */

View file

@ -0,0 +1,336 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2010 Develer S.r.l. (http://www.develer.com/)
*
* -->
*
* \brief Driver for the LPC23xx I2C (implementation)
*
* \author Daniele Basile <asterix@develer.com>
*/
#include "cfg/cfg_i2c.h"
#define LOG_LEVEL I2C_LOG_LEVEL
#define LOG_FORMAT I2C_LOG_FORMAT
#include <cfg/log.h>
#include <cfg/debug.h>
#include <cfg/macros.h> // BV()
#include <cpu/detect.h>
#include <cpu/irq.h>
#include <cpu/power.h>
#include <drv/timer.h>
#include <drv/i2c.h>
#include <io/lpc23xx.h>
struct I2cHardware
{
uint32_t base;
uint32_t pconp;
uint32_t pinsel_port;
uint32_t pinsel;
uint32_t pinsel_mask;
uint32_t pclksel;
uint32_t pclk_mask;
uint32_t pclk_div;
};
/*
* Wait that SI bit is set.
*
* Note: this bit is set when the I2C state changes. However, entering
* state F8 does not set SI since there is nothing for an interrupt service
* routine to do in that case.
*/
#define WAIT_SI(i2c) \
do { \
ticks_t start = timer_clock(); \
while( !(HWREG(i2c->hw->base + I2C_CONSET_OFF) & BV(I2CON_SI)) ) \
{ \
if (timer_clock() - start > ms_to_ticks(CONFIG_I2C_START_TIMEOUT)) \
{ \
LOG_ERR("Timeout SI assert\n"); \
LOG_ERR("[%08lx]\n", HWREG(i2c->hw->base + I2C_STAT_OFF)); \
break; \
} \
cpu_relax(); \
} \
} while (0)
static void i2c_hw_restart(I2c *i2c)
{
// Clear all pending flags.
HWREG(i2c->hw->base + I2C_CONCLR_OFF) = BV(I2CON_STAC) | BV(I2CON_SIC) | BV(I2CON_AAC);
// Set start and ack bit.
HWREG(i2c->hw->base + I2C_CONSET_OFF) = BV(I2CON_STA);
WAIT_SI(i2c);
}
static void i2c_hw_stop(I2c *i2c)
{
/* Set the stop bit */
HWREG(i2c->hw->base + I2C_CONSET_OFF) = BV(I2CON_STO);
/* Clear pending flags */
HWREG(i2c->hw->base + I2C_CONCLR_OFF) = BV(I2CON_STAC) | BV(I2CON_SIC) | BV(I2CON_AAC);
}
static void i2c_lpc2_putc(I2c *i2c, uint8_t data)
{
HWREG(i2c->hw->base + I2C_DAT_OFF) = data;
HWREG(i2c->hw->base + I2C_CONCLR_OFF) = BV(I2CON_SIC);
WAIT_SI(i2c);
uint32_t status = HWREG(i2c->hw->base + I2C_STAT_OFF);
/* Generate the stop if we finish to send all programmed bytes */
if (i2c->xfer_size == 1)
{
if (I2C_TEST_STOP(i2c->flags) == I2C_STOP)
i2c_hw_stop(i2c);
}
if (status == I2C_STAT_DATA_NACK)
{
LOG_ERR("Data NACK\n");
i2c->errors |= I2C_NO_ACK;
i2c_hw_stop(i2c);
}
else if ((status == I2C_STAT_ERROR) || (status == I2C_STAT_UNKNOW))
{
LOG_ERR("I2C error.\n");
i2c->errors |= I2C_ERR;
i2c_hw_stop(i2c);
}
}
static uint8_t i2c_lpc2_getc(I2c *i2c)
{
/*
* Set ack bit if we want read more byte, otherwise
* we disable it
*/
if (i2c->xfer_size > 1)
HWREG(i2c->hw->base + I2C_CONSET_OFF) = BV(I2CON_AA);
else
HWREG(i2c->hw->base + I2C_CONCLR_OFF) = BV(I2CON_AAC);
HWREG(i2c->hw->base + I2C_CONCLR_OFF) = BV(I2CON_SIC);
WAIT_SI(i2c);
uint32_t status = HWREG(i2c->hw->base + I2C_STAT_OFF);
uint8_t data = (uint8_t)HWREG(i2c->hw->base + I2C_DAT_OFF);
if (status == I2C_STAT_RDATA_ACK)
{
return data;
}
else if (status == I2C_STAT_RDATA_NACK)
{
/*
* last byte to read generate the stop if
* required
*/
if (I2C_TEST_STOP(i2c->flags) == I2C_STOP)
i2c_hw_stop(i2c);
return data;
}
else if ((status == I2C_STAT_ERROR) || (status == I2C_STAT_UNKNOW))
{
LOG_ERR("I2C error.\n");
i2c->errors |= I2C_ERR;
i2c_hw_stop(i2c);
}
return 0xFF;
}
static void i2c_lpc2_start(struct I2c *i2c, uint16_t slave_addr)
{
if (I2C_TEST_START(i2c->flags) == I2C_START_W)
{
ticks_t start = timer_clock();
while (true)
{
i2c_hw_restart(i2c);
uint8_t status = HWREG(i2c->hw->base + I2C_STAT_OFF);
/* Start status ok, set addres and the R/W bit */
if ((status == I2C_STAT_SEND) || (status == I2C_STAT_RESEND))
HWREG(i2c->hw->base + I2C_DAT_OFF) = slave_addr & ~I2C_READBIT;
/* Clear the start bit and clear the SI bit */
HWREG(i2c->hw->base + I2C_CONCLR_OFF) = BV(I2CON_SIC) | BV(I2CON_STAC);
if (status == I2C_STAT_SLAW_ACK)
break;
if (status == I2C_STAT_ARB_LOST)
{
LOG_ERR("Arbitration lost\n");
i2c->errors |= I2C_ARB_LOST;
i2c_hw_stop(i2c);
}
if (timer_clock() - start > ms_to_ticks(CONFIG_I2C_START_TIMEOUT))
{
LOG_ERR("Timeout on I2C START\n");
i2c->errors |= I2C_NO_ACK;
i2c_hw_stop(i2c);
break;
}
}
}
else if (I2C_TEST_START(i2c->flags) == I2C_START_R)
{
i2c_hw_restart(i2c);
uint8_t status = HWREG(i2c->hw->base + I2C_STAT_OFF);
/* Start status ok, set addres and the R/W bit */
if ((status == I2C_STAT_SEND) || (status == I2C_STAT_RESEND))
HWREG(i2c->hw->base + I2C_DAT_OFF) = slave_addr | I2C_READBIT;
/* Clear the start bit and clear the SI bit */
HWREG(i2c->hw->base + I2C_CONCLR_OFF) = BV(I2CON_SIC) | BV(I2CON_STAC);
WAIT_SI(i2c);
status = HWREG(i2c->hw->base + I2C_STAT_OFF);
if (status == I2C_STAT_SLAR_NACK)
{
LOG_ERR("SLAR NACK:%02x\n", status);
i2c->errors |= I2C_NO_ACK;
i2c_hw_stop(i2c);
}
if (status == I2C_STAT_ARB_LOST)
{
LOG_ERR("Arbitration lost\n");
i2c->errors |= I2C_ARB_LOST;
i2c_hw_stop(i2c);
}
}
else
{
ASSERT(0);
}
}
static const I2cVT i2c_lpc_vt =
{
.start = i2c_lpc2_start,
.getc = i2c_lpc2_getc,
.putc = i2c_lpc2_putc,
.write = i2c_genericWrite,
.read = i2c_genericRead,
};
static struct I2cHardware i2c_lpc2_hw[] =
{
{ /* I2C0 */
.base = I2C0_BASE_ADDR,
.pconp = BV(PCONP_PCI2C0),
.pinsel_port = PINSEL1_OFF,
.pinsel = I2C0_PINSEL,
.pinsel_mask = I2C0_PINSEL_MASK,
.pclksel = PCLKSEL0_OFF,
.pclk_mask = I2C0_PCLK_MASK,
.pclk_div = I2C0_PCLK_DIV8,
},
{ /* I2C1 */
.base = I2C1_BASE_ADDR,
.pconp = BV(PCONP_PCI2C1),
.pinsel_port = PINSEL0_OFF,
.pinsel = I2C1_PINSEL,
.pinsel_mask = I2C1_PINSEL_MASK,
.pclksel = PCLKSEL1_OFF,
.pclk_mask = I2C1_PCLK_MASK,
.pclk_div = I2C1_PCLK_DIV8,
},
{ /* I2C2 */
.base = I2C2_BASE_ADDR,
.pconp = BV(PCONP_PCI2C2),
.pinsel_port = PINSEL0_OFF,
.pinsel = I2C2_PINSEL,
.pinsel_mask = I2C2_PINSEL_MASK,
.pclksel = PCLKSEL1_OFF,
.pclk_mask = I2C2_PCLK_MASK,
.pclk_div = I2C2_PCLK_DIV8,
},
};
/**
* Initialize I2C module.
*/
void i2c_hw_init(I2c *i2c, int dev, uint32_t clock)
{
i2c->hw = &i2c_lpc2_hw[dev];
i2c->vt = &i2c_lpc_vt;
/* Enable I2C clock */
PCONP |= i2c->hw->pconp;
ASSERT(clock <= 400000);
HWREG(i2c->hw->base + I2C_CONCLR_OFF) = BV(I2CON_I2ENC) | BV(I2CON_STAC) | BV(I2CON_SIC) | BV(I2CON_AAC);
/*
* Bit Frequency = Fplk / (I2C_I2SCLH + I2C_I2SCLL)
* value of I2SCLH and I2SCLL must be different
*/
HWREG(SCB_BASE_ADDR + i2c->hw->pclksel) &= ~i2c->hw->pclk_mask;
HWREG(SCB_BASE_ADDR + i2c->hw->pclksel) |= i2c->hw->pclk_div;
HWREG(i2c->hw->base + I2C_SCLH_OFF) = (((CPU_FREQ / 8) / clock) / 2) + 1;
HWREG(i2c->hw->base + I2C_SCLL_OFF) = (((CPU_FREQ / 8) / clock) / 2);
ASSERT(HWREG(i2c->hw->base + I2C_SCLH_OFF) > 4);
ASSERT(HWREG(i2c->hw->base + I2C_SCLL_OFF) > 4);
/* Assign pins to SCL and SDA */
HWREG(PINSEL_BASE_ADDR + i2c->hw->pinsel_port) &= ~i2c->hw->pinsel_mask;
HWREG(PINSEL_BASE_ADDR + i2c->hw->pinsel_port) |= i2c->hw->pinsel;
// Enable I2C
HWREG(i2c->hw->base + I2C_CONSET_OFF) = BV(I2CON_I2EN);
}

View file

@ -0,0 +1,56 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2010 Develer S.r.l. (http://www.develer.com/)
*
* -->
*
* \brief Driver for the LPC23xx I2C (interface)
*
* \author Daniele Basile <asterix@develer.com>
*
*/
#ifndef I2C_LPC2_H
#define I2C_LPC2_H
#include <drv/i2c.h>
/**
* \name I2C devices enum
*/
enum
{
I2C0,
I2C1,
I2C2,
I2C_CNT /**< Number of serial ports */
};
#endif /* I2C_LPC2_H */

View file

@ -0,0 +1,185 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2009 Develer S.r.l. (http://www.develer.com/)
* -->
*
* \brief I2S driver implementation.
*
* \author Luca Ottaviano <lottaviano@develer.com>
*/
/*
* TODO: Revise the public api of this module to be more generic. Evalutate to
* implement the more generic layer to be common to all I2S BeRTOS drivers.
*/
#include "i2s_at91.h"
#include "cfg/cfg_i2s.h"
// Define log settings for cfg/log.h.
#define LOG_LEVEL I2S_LOG_LEVEL
#define LOG_FORMAT I2S_LOG_FORMAT
#include <cfg/log.h>
#include <drv/timer.h>
#include <io/arm.h>
#define DATALEN (15 & SSC_DATLEN_MASK)
// FIXME: this is not correct for 16 <= DATALEN < 24
#define PDC_DIV ((DATALEN / 8) + 1)
/*
* PDC_DIV must be 1, 2 or 4, which are the bytes that are transferred
* each time the PDC reads from memory.
*/
STATIC_ASSERT(PDC_DIV % 2 == 0);
#define PDC_COUNT (CONFIG_PLAY_BUF_LEN / PDC_DIV)
static uint8_t play_buf1[CONFIG_PLAY_BUF_LEN];
static uint8_t play_buf2[CONFIG_PLAY_BUF_LEN];
// the buffer in PDC next is play_buf2
volatile bool is_second_buf_next;
uint8_t *i2s_getBuffer(unsigned buf_num)
{
LOG_INFO("getBuffer start\n");
if (i2s_isPlaying())
{
ASSERT(0);
return 0;
}
if (buf_num == I2S_SECOND_BUF)
return play_buf2;
else if (buf_num == I2S_FIRST_BUF)
return play_buf1;
else
return 0;
}
uint8_t *i2s_getFreeBuffer(void)
{
if (!i2s_isPlaying())
{
ASSERT(0);
return 0;
}
// wait PDC transmission end
if (!(SSC_SR & BV(SSC_ENDTX)))
return 0;
uint8_t *ret_buf = 0;
// the last time we got called, the second buffer was in PDC next
if (is_second_buf_next)
{
is_second_buf_next = false;
ret_buf = play_buf1;
}
// the last time the first buffer was in PDC next
else
{
is_second_buf_next = true;
ret_buf = play_buf2;
}
if (ret_buf)
{
SSC_TNPR = (reg32_t) ret_buf;
SSC_TNCR = PDC_COUNT;
}
return ret_buf;
}
bool i2s_start(void)
{
/* Some time must pass between disabling and enabling again the transmission
* on SSC. A good empirical value seems >15 us. We try to avoid putting an
* explicit delay, instead we disable the transmitter when a sound finishes
* and hope that the delay has passed before we enter here again.
*/
SSC_CR = BV(SSC_TXDIS);
timer_delay(10);
SSC_PTCR = BV(PDC_TXTDIS);
SSC_TPR = (reg32_t)play_buf1;
SSC_TCR = PDC_COUNT;
SSC_TNPR = (reg32_t)play_buf2;
SSC_TNCR = PDC_COUNT;
is_second_buf_next = true;
SSC_PTCR = BV(PDC_TXTEN);
/* enable output */
SSC_CR = BV(SSC_TXEN);
return true;
}
#define BITS_PER_CHANNEL 16
#define N_OF_CHANNEL 2
// TODO: check the computed value?
/* The last parameter (2) is due to the hadware on at91sam7s. */
#define MCK_DIV (CPU_FREQ / CONFIG_SAMPLE_FREQ / BITS_PER_CHANNEL / N_OF_CHANNEL / 2)
#define CONFIG_DELAY 1
#define CONFIG_PERIOD 15
#define CONFIG_DATNB 1
#define CONFIG_FSLEN 15
#define DELAY ((CONFIG_DELAY << SSC_STTDLY_SHIFT) & SSC_STTDLY_MASK)
#define PERIOD ((CONFIG_PERIOD << (SSC_PERIOD_SHIFT)) & SSC_PERIOD_MASK)
#define DATNB ((CONFIG_DATNB << SSC_DATNB_SHIFT) & SSC_DATNB_MASK)
#define FSLEN ((CONFIG_FSLEN << SSC_FSLEN_SHIFT) & SSC_FSLEN_MASK)
#define SSC_DMA_IRQ_PRIORITY 5
void i2s_init(void)
{
PIOA_PDR = BV(SSC_TK) | BV(SSC_TF) | BV(SSC_TD);
/* reset device */
SSC_CR = BV(SSC_SWRST);
SSC_CMR = MCK_DIV & SSC_DIV_MASK;
SSC_TCMR = SSC_CKS_DIV | SSC_CKO_CONT | SSC_CKG_NONE | DELAY | PERIOD | SSC_START_FALL_F;
SSC_TFMR = DATALEN | DATNB | FSLEN | BV(SSC_MSBF) | SSC_FSOS_NEGATIVE;
/* Disable all irqs */
SSC_IDR = 0xFFFFFFFF;
/* Enable the SSC IRQ */
AIC_IECR = BV(SSC_ID);
/* enable i2s */
PMC_PCER = BV(SSC_ID);
/* Enable SSC */
SSC_CR = BV(SSC_TXEN);
}

View file

@ -0,0 +1,115 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2009 Develer S.r.l. (http://www.develer.com/)
*
* -->
*
* \brief I2S driver functions.
*
* This driver uses a double buffering technique to keep i2s bus busy. First fill in the two buffers
* using i2s_getBuffer(), then start audio playing with i2s_start(). Then call i2s_getFreeBuffer()
* until you have finished your samples. The reproduction will automatically stop if you don't
* call i2s_getFreeBuffer() frequently enough.
*
* Example:
* \code
* // fill in the buffers before start
* buf = i2s_getBuffer(I2S_FIRST_BUF);
* // ...
* buf = i2s_getBuffer(I2S_SECOND_BUF);
* // ...
* // here the driver will play only the first two buffers...
* i2s_start();
* // ...call getFreeBuffer() to continue playing.
* while (!(buf = i2s_getFreeBuffer()))
* ;
* // now fill the buffer again
* \endcode
*
* \author Luca Ottaviano <lottaviano@develer.com>
*
* $WIZ$ module_name = "i2s"
* $WIZ$ module_configuration = "bertos/cfg/cfg_i2s.h"
* $WIZ$ module_supports = "at91"
*/
#ifndef DRV_I2S_AT91_H
#define DRV_I2S_AT91_H
#include <cfg/compiler.h>
#include <cfg/macros.h>
#include <io/arm.h>
/**
* First buffer.
*/
#define I2S_FIRST_BUF 0
/**
* Second buffer.
*/
#define I2S_SECOND_BUF 1
/**
* Initializes the module and sets current buffer to I2S_FIRST_BUF.
*/
void i2s_init(void);
/**
* Returns one of the two buffers or NULL if none is available.
*
* You can't call this function if you have already started the player.
* \param buf_num The number of the buffer, ie I2S_FIRST_BUF or I2S_SECOND_BUF.
* \return A pointer to the buffer if the buffer is available (not full), 0 on errors
*/
uint8_t *i2s_getBuffer(unsigned buf_num);
/**
* Returns a buffer that will be played after the current one.
*
* You should fill it faster than your reproduction time. You can't call this function
* if the player is not running
* \return The next buffer to be played, 0 if both are busy.
*/
uint8_t *i2s_getFreeBuffer(void);
/**
* Starts playing from I2S_FIRST_BUFFER.
*
* You must have filled both buffers before calling this function. Does nothing if already playing.
* \return false on errors, true otherwise.
*/
bool i2s_start(void);
INLINE bool i2s_isPlaying(void)
{
return !(SSC_SR & BV(SSC_TXEMPTY));
}
#endif /* DRV_I2S_AT91_H */

View file

@ -0,0 +1,48 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2007 Develer S.r.l. (http://www.develer.com/)
*
* -->
*
*
* \author Francesco Sacchi <batt@develer.com>
*
* \brief Low-level kdebug module for ARM (inplementation).
*/
#include <cpu/detect.h>
#if CPU_ARM_AT91
#include "kdebug_at91.c"
#elif CPU_ARM_LPC2
#include "kdebug_lpc2.c"
/*#elif Add other ARM families here */
#else
#error Unknown CPU
#endif

View file

@ -0,0 +1,93 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2007 Develer S.r.l. (http://www.develer.com/)
*
* -->
*
* \brief ARM debug support (implementation).
*
* \author Francesco Sacchi <batt@develer.com>
*/
#include "kdebug_at91.h"
#include <hw/hw_cpufreq.h> /* for CPU_FREQ */
#include "hw/hw_ser.h" /* Required for bus macros overrides */
#include "cfg/cfg_debug.h"
#include <cfg/macros.h> /* for BV(), DIV_ROUND */
#include <io/arm.h>
#if CONFIG_KDEBUG_PORT == KDEBUG_PORT_DBGU
#define KDBG_WAIT_READY() while (!(DBGU_SR & BV(US_TXRDY))) {}
#define KDBG_WAIT_TXDONE() while (!(DBGU_SR & BV(US_TXEMPTY))) {}
#define KDBG_WRITE_CHAR(c) do { DBGU_THR = (c); } while(0)
/* Debug unit is used only for debug purposes so does not generate interrupts. */
#define KDBG_MASK_IRQ(old) do { (void)old; } while(0)
/* Debug unit is used only for debug purposes so does not generate interrupts. */
#define KDBG_RESTORE_IRQ(old) do { (void)old; } while(0)
typedef uint32_t kdbg_irqsave_t;
#else
#error CONFIG_KDEBUG_PORT should be KDEBUG_PORT_DBGU
#endif
INLINE void kdbg_hw_init(void)
{
#if CONFIG_KDEBUG_PORT == KDEBUG_PORT_DBGU
/* Disable all DBGU interrupts. */
DBGU_IDR = 0xFFFFFFFF;
/* Reset DBGU */
DBGU_CR = BV(US_RSTRX) | BV(US_RSTTX) | BV(US_RXDIS) | BV(US_TXDIS);
/* Set baudrate */
DBGU_BRGR = DIV_ROUND(CPU_FREQ, 16 * CONFIG_KDEBUG_BAUDRATE);
/* Set DBGU mode to 8 data bits, no parity and 1 stop bit. */
DBGU_MR = US_CHMODE_NORMAL | US_CHRL_8 | US_PAR_NO | US_NBSTOP_1;
/* Enable DBGU transmitter. */
DBGU_CR = BV(US_TXEN);
/* Disable PIO on DGBU tx pin. */
PIOA_PDR = BV(DTXD);
PIOA_ASR = BV(DTXD);
#if 0 /* Disable Rx for now */
/* Enable DBGU receiver. */
DBGU_CR = BV(US_RXEN);
/* Disable PIO on DGBU rx pin. */
PIOA_PDR = BV(DRXD);
PIOA_ASR = BV(DRXD);
#endif
#else
#error CONFIG_KDEBUG_PORT should be KDEBUG_PORT_DBGU
#endif /* CONFIG_KDEBUG_PORT == KDEBUG_PORT_DBGU */
}

View file

@ -0,0 +1,54 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2007 Develer S.r.l. (http://www.develer.com/)
*
* -->
*
*
* \author Francesco Sacchi <batt@develer.com>
*
* \brief ARM debug support (interface).
*/
#ifndef DRV_KDEBUG_AT91_H
#define DRV_KDEBUG_AT91_H
/**
* \name Values for CONFIG_KDEBUG_PORT.
*
* Select which hardware UART to use for system debug.
*
* \{
*/
#define KDEBUG_PORT_DBGU 0 ///< Debug on Debug Unit.
#define KDEBUG_PORT_DEFAULT KDEBUG_PORT_DBGU ///< Default debug port.
/* \} */
#endif /* DRV_KDEBUG_AT91_H */

View file

@ -0,0 +1,92 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2010 Develer S.r.l. (http://www.develer.com/)
*
* -->
*
* \brief ARM debug support (implementation).
*
* \author Francesco Sacchi <batt@develer.com>
*/
#include <hw/hw_cpufreq.h> /* for CPU_FREQ */
#include "hw/hw_ser.h" /* Required for bus macros overrides */
#include "cfg/cfg_debug.h"
#include <cfg/macros.h> /* for BV(), DIV_ROUND */
#include <io/lpc23xx.h>
#if CONFIG_KDEBUG_PORT == 0
#define KDBG_WAIT_READY() while (!(U0LSR & BV(5))) {}
#define KDBG_WAIT_TXDONE() while (!(U0LSR & BV(6))) {}
#define KDBG_WRITE_CHAR(c) do { U0THR = (c); } while(0)
#define KDBG_MASK_IRQ(old) do { \
(old) = U0IER; \
U0IER &= ~BV(1); \
} while(0)
#define KDBG_RESTORE_IRQ(old) do { \
KDBG_WAIT_TXDONE(); \
U0IER = (old); \
} while(0)
typedef uint32_t kdbg_irqsave_t;
#else
#error CONFIG_KDEBUG_PORT should be 0
#endif
INLINE void kdbg_hw_init(void)
{
#if CONFIG_KDEBUG_PORT == 0
/* Enable clock for UART0 */
PCONP = BV(3);
/* Set UART0 clk to CPU_FREQ */
PCLKSEL0 &= ~0xC0;
PCLKSEL0 |= 0x40;
/* Set 8bit, 1 stop bit, no parity, DLAB = 1 (enable divisor modify) */
U0LCR = 0x83;
U0DLL = DIV_ROUND(CPU_FREQ, 16 * CONFIG_KDEBUG_BAUDRATE) & 0xFF;
U0DLM = (DIV_ROUND(CPU_FREQ, 16 * CONFIG_KDEBUG_BAUDRATE) >> 8) & 0xFF;
U0FDR = 0x10;
/* Assign TX pin to UART0*/
PINSEL0 &= ~0x30;
PINSEL0 |= 0x10;
/* Set 8bit, 1 stop bit, no parity, DLAB = 0 (disable divisor modify) */
U0LCR = 0x03;
/* Enable transmitter */
U0TER = BV(7);
#else
#error CONFIG_KDEBUG_PORT should be 0
#endif /* CONFIG_KDEBUG_PORT == 0 */
}

View file

@ -0,0 +1,56 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2007 Develer S.r.l. (http://www.develer.com/)
*
* -->
*
* \brief Low-level PWM module for ARM (inplementation).
*
*
* \author Daniele Basile <asterix@develer.com>
*
* This module is automatically included so no need to include
* in test list.
* notest: arm
*
*/
#ifndef WIZ_AUTOGEN
#warning This file is deprecated, you should use pwm_at91.c
#include <cpu/detect.h>
#if CPU_ARM_AT91
#include "pwm_at91.c"
/*#elif Add other ARM families here */
#else
#error Unknown CPU
#endif
#endif /* WIZ_AUTOGEN */

View file

@ -0,0 +1,47 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2007 Develer S.r.l. (http://www.develer.com/)
*
* -->
*
* \brief Low-level PWM module for ARM (interface).
*
*
* \author Daniele Basile <asterix@develer.com>
*
*/
#include <cpu/detect.h>
#if CPU_ARM_AT91
#include "pwm_at91.h"
/*#elif Add other ARM families here */
#else
#error Unknown CPU
#endif

View file

@ -0,0 +1,387 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2011 Develer S.r.l. (http://www.develer.com/)
*
* -->
*
*
* \brief PWM hardware-specific implementation
*
* \author Daniele Basile <asterix@develer.com>
* \author Francesco Sacchi <batt@develer.com>
*/
#include <drv/pwm.h>
#include "pwm_at91.h"
#include <hw/hw_cpufreq.h>
#include "cfg/cfg_pwm.h"
// Define logging setting (for cfg/log.h module).
#define LOG_LEVEL PWM_LOG_LEVEL
#define LOG_FORMAT PWM_LOG_FORMAT
#include <cfg/log.h>
#include <cfg/macros.h>
#include <cfg/debug.h>
#include <io/arm.h>
#include <cpu/irq.h>
#define PWM_HW_MAX_PRESCALER_STEP 10
#define PWM_HW_MAX_PERIOD 0xFFFF
#if CFG_PWM_ENABLE_OLD_API
#include "hw/pwm_map.h"
/**
* Register structure for pwm driver.
* This array content all data and register pointer
* to manage pwm peripheral device.
*/
static PwmChannel pwm_map[PWM_CNT] =
{
{//PWM Channel 0
.duty_zero = false,
.pol = false,
.pwm_pin = BV(PWM0),
.mode_reg = &PWM_CMR0,
.duty_reg = &PWM_CDTY0,
.period_reg = &PWM_CPRD0,
.update_reg = &PWM_CUPD0,
},
{//PWM Channel 1
.duty_zero = false,
.pol = false,
.pwm_pin = BV(PWM1),
.mode_reg = &PWM_CMR1,
.duty_reg = &PWM_CDTY1,
.period_reg = &PWM_CPRD1,
.update_reg = &PWM_CUPD1,
},
{//PWM Channel 2
.duty_zero = false,
.pol = false,
.pwm_pin = BV(PWM2),
.mode_reg = &PWM_CMR2,
.duty_reg = &PWM_CDTY2,
.period_reg = &PWM_CPRD2,
.update_reg = &PWM_CUPD2,
},
{//PWM Channel 3
.duty_zero = false,
.pol = false,
.pwm_pin = BV(PWM3),
.mode_reg = &PWM_CMR3,
.duty_reg = &PWM_CDTY3,
.period_reg = &PWM_CPRD3,
.update_reg = &PWM_CUPD3,
}
};
/**
* Get preiod from select channel
*
* \a dev channel
*/
pwm_period_t pwm_hw_getPeriod(PwmDev dev)
{
return *pwm_map[dev].period_reg;
}
/**
* Set pwm waveform frequecy.
*
* \a freq in Hz
*/
void pwm_hw_setFrequency(PwmDev dev, uint32_t freq)
{
uint32_t period = 0;
for(int i = 0; i <= PWM_HW_MAX_PRESCALER_STEP; i++)
{
period = CPU_FREQ / (BV(i) * freq);
LOG_INFO("period[%ld], prescale[%d]\n", period, i);
if ((period < PWM_HW_MAX_PERIOD) && (period != 0))
{
//Clean previous channel prescaler, and set new
*pwm_map[dev].mode_reg &= ~PWM_CPRE_MCK_MASK;
*pwm_map[dev].mode_reg |= i;
//Set pwm period
*pwm_map[dev].period_reg = period;
break;
}
}
LOG_INFO("PWM ch[%d] period[%ld]\n", dev, period);
}
/**
* Set pwm duty cycle.
*
* \a duty value 0 - 2^16
*/
void pwm_hw_setDutyUnlock(PwmDev dev, uint16_t duty)
{
ASSERT(duty <= (uint16_t)*pwm_map[dev].period_reg);
/*
* If polarity flag is true we must invert
* PWM polarity.
*/
if (pwm_map[dev].pol)
{
duty = (uint16_t)*pwm_map[dev].period_reg - duty;
LOG_INFO("Inverted duty[%d], pol[%d]\n", duty, pwm_map[dev].pol);
}
/*
* WARNING: is forbidden to write 0 to duty cycle value,
* and so for duty = 0 we must enable PIO and clear output!
*/
if (!duty)
{
PWM_PIO_CODR = pwm_map[dev].pwm_pin;
PWM_PIO_PER = pwm_map[dev].pwm_pin;
pwm_map[dev].duty_zero = true;
}
else
{
PWM_PIO_PDR = pwm_map[dev].pwm_pin;
PWM_PIO_ABSR = pwm_map[dev].pwm_pin;
*pwm_map[dev].update_reg = duty;
pwm_map[dev].duty_zero = false;
}
PWM_ENA = BV(dev);
LOG_INFO("PWM ch[%d] duty[%d], period[%ld]\n", dev, duty, *pwm_map[dev].period_reg);
}
/**
* Enable select pwm channel
*/
void pwm_hw_enable(PwmDev dev)
{
if (!pwm_map[dev].duty_zero)
{
PWM_PIO_PDR = pwm_map[dev].pwm_pin;
PWM_PIO_ABSR = pwm_map[dev].pwm_pin;
}
}
/**
* Disable select pwm channel
*/
void pwm_hw_disable(PwmDev dev)
{
PWM_PIO_PER = pwm_map[dev].pwm_pin;
}
/**
* Set PWM polarity to select pwm channel
*/
void pwm_hw_setPolarity(PwmDev dev, bool pol)
{
pwm_map[dev].pol = pol;
LOG_INFO("Set pol[%d]\n", pwm_map[dev].pol);
}
/**
* Init pwm.
*/
void pwm_hw_init(void)
{
/*
* Init pwm:
* WARNING: is forbidden to write 0 to duty cycle value,
* and so for duty = 0 we must enable PIO and clear output!
* - clear PIO outputs
* - enable PIO outputs
* - Disable PIO and enable PWM functions
* - Power on PWM
*/
PWM_PIO_CODR = BV(PWM0) | BV(PWM1) | BV(PWM2) | BV(PWM3);
PWM_PIO_OER = BV(PWM0) | BV(PWM1) | BV(PWM2) | BV(PWM3);
PWM_PIO_PDR = BV(PWM0) | BV(PWM1) | BV(PWM2) | BV(PWM3);
PWM_PIO_ABSR = BV(PWM0) | BV(PWM1) | BV(PWM2) | BV(PWM3);
PMC_PCER |= BV(PWMC_ID);
/* Disable all channels. */
PWM_DIS = 0xFFFFFFFF;
/* Disable prescalers A and B */
PWM_MR = 0;
/*
* Set pwm mode:
* - set period alidned to left
* - set output waveform to start at high level
* - allow duty cycle modify at next period event
*/
for (int ch = 0; ch < PWM_CNT; ch++)
{
*pwm_map[ch].mode_reg = 0;
*pwm_map[ch].mode_reg = BV(PWM_CPOL);
}
}
#else
typedef struct PwmChannelRegs
{
reg32_t CMR;
reg32_t CDTY;
reg32_t CPRD;
reg32_t CCNT;
reg32_t CUPD;
} PwmChannelRegs;
/*
* Set pwm waveform frequecy.
*/
void pwm_hw_setFrequency(Pwm *ctx, pwm_freq_t freq)
{
uint32_t period = 0;
for(int i = 0; i <= PWM_HW_MAX_PRESCALER_STEP; i++)
{
period = CPU_FREQ / (BV(i) * freq);
LOG_INFO("period[%ld], prescale[%d]\n", period, i);
if ((period < PWM_HW_MAX_PERIOD) && (period != 0))
{
//Clear previous channel prescaler, and set new
ctx->hw->base->CMR &= ~PWM_CPRE_MCK_MASK;
ctx->hw->base->CMR |= i;
//Set pwm period
ATOMIC(
ctx->hw->base->CPRD = period;
ctx->hw->base->CDTY = period;
);
break;
}
}
LOG_INFO("PWM ch[%d] period[%ld]\n", ctx->ch, period);
}
pwm_hwreg_t pwm_hw_getPeriod(Pwm *ctx)
{
return ctx->hw->base->CPRD;
}
/*
* Set pwm duty cycle.
*
* duty value 0 - (2^16 - 1)
*/
void pwm_hw_setDuty(Pwm *ctx, pwm_hwreg_t hw_duty)
{
ASSERT(hw_duty <= ctx->hw->base->CPRD);
/*
* WARNING: is forbidden to write 0 or 1 to duty cycle value,
* and so for duty < 2 we must enable PIO and clear output!
*/
if (hw_duty < 2)
{
hw_duty = 2;
PWM_PIO_PER = ctx->hw->pwm_pin;
}
else
PWM_PIO_PDR = ctx->hw->pwm_pin;
ctx->hw->base->CUPD = hw_duty;
LOG_INFO("PWM ch[%d] duty[%d], period[%ld]\n", ctx->ch, hw_duty, ctx->hw->base->CPRD);
}
static PwmHardware pwm_channels[] =
{
{//PWM Channel 0
.pwm_pin = BV(PWM0),
.base = (volatile PwmChannelRegs *)&PWM_CMR0,
},
{//PWM Channel 1
.pwm_pin = BV(PWM1),
.base = (volatile PwmChannelRegs *)&PWM_CMR1,
},
{//PWM Channel 2
.pwm_pin = BV(PWM2),
.base = (volatile PwmChannelRegs *)&PWM_CMR2,
},
{//PWM Channel 3
.pwm_pin = BV(PWM3),
.base = (volatile PwmChannelRegs *)&PWM_CMR3,
},
};
/*
* Init pwm.
*/
void pwm_hw_init(Pwm *ctx, unsigned ch)
{
ctx->hw = &pwm_channels[ch];
/*
* Init pwm:
* - clear PIO outputs
* - enable PIO outputs
* - Enable PWM functions
* - Power on PWM
*/
PWM_PIO_CODR = ctx->hw->pwm_pin;
PWM_PIO_OER = ctx->hw->pwm_pin;
PWM_PIO_PER = ctx->hw->pwm_pin;
PWM_PIO_ABSR = ctx->hw->pwm_pin;
PMC_PCER |= BV(PWMC_ID);
/* Disable prescalers A and B */
PWM_MR = 0;
/*
* Set pwm mode:
* WARNING: is forbidden to write 0 or 1 to duty cycle value,
* and so for start we set duty to 2.
* Also:
* - set period aligned to left
* - set output waveform to start at high level
* - allow duty cycle modify at next period event
*/
ctx->hw->base->CDTY = 2;
ctx->hw->base->CMR = BV(PWM_CPOL);
PWM_ENA = BV(ch);
}
#endif

View file

@ -0,0 +1,103 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2008 Develer S.r.l. (http://www.develer.com/)
*
* -->
*
*
* \brief PWM hardware-specific definition
*
*
* \author Daniele Basile <asterix@develer.com>
*/
#ifndef DRV_PWM_AT91_H
#define DRV_PWM_AT91_H
#include <cfg/compiler.h>
#include <cfg/macros.h>
#include "cfg/cfg_pwm.h"
#include <io/arm.h>
#if CFG_PWM_ENABLE_OLD_API
#include "hw/pwm_map.h"
/**
* Type definition for pwm period.
*/
typedef uint16_t pwm_period_t;
/**
* Structur definition for pwm driver.
*/
typedef struct PwmChannel
{
bool duty_zero; ///< True if duty cyle is zero, false otherwise.
bool pol; ///< PWM polarty flag.
int pwm_pin; ///< PWM pin.
reg32_t *mode_reg; ///< PWM mode register.
reg32_t *duty_reg; ///< PWM duty cycle register.
reg32_t *period_reg; ///< PWM periodic register.
reg32_t *update_reg; ///< Update setting register for PWM.
} PwmChannel;
void pwm_hw_init(void);
void pwm_hw_setFrequency(PwmDev dev, uint32_t freq);
void pwm_hw_setDutyUnlock(PwmDev dev, uint16_t duty);
void pwm_hw_disable(PwmDev dev);
void pwm_hw_enable(PwmDev dev);
void pwm_hw_setPolarity(PwmDev dev, bool pol);
pwm_period_t pwm_hw_getPeriod(PwmDev dev);
#else
#include <drv/pwm.h>
typedef uint16_t pwm_hwreg_t;
struct PwmChannelRegs; //fwd decl
typedef struct PwmHardware
{
uint32_t pwm_pin; ///< PWM pin.
volatile struct PwmChannelRegs *base;
} PwmHardware;
pwm_hwreg_t pwm_hw_getPeriod(Pwm *ctx);
void pwm_hw_setFrequency(struct Pwm *ctx, pwm_freq_t freq);
void pwm_hw_setDuty(Pwm *ctx, pwm_hwreg_t duty);
void pwm_hw_init(struct Pwm *ctx, unsigned ch);
#endif
#endif /* DRV_ADC_AT91_H */

View file

@ -0,0 +1,56 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2007 Develer S.r.l. (http://www.develer.com/)
*
* -->
*
* \brief Low-level serial module for ARM (inplementation).
*
* \author Daniele Basile <asterix@develer.com>
*
* This module is automatically included so no need to include
* in test list.
* notest: arm
*
*/
#ifndef WIZ_AUTOGEN
#warning This file is deprecated, you should use ser_at91.c
#include <cpu/detect.h>
#if CPU_ARM_AT91
#include "ser_at91.c"
#elif CPU_ARM_LPC2378
#include "ser_lpc2.c"
/*#elif Add other ARM families here */
#else
#error Unknown CPU
#endif
#endif /* WIZ_AUTOGEN */

View file

@ -0,0 +1,49 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2007 Develer S.r.l. (http://www.develer.com/)
*
* -->
*
* \brief Low-level serial module for ARM (interface).
*
*
* \author Daniele Basile <asterix@develer.com>
*
*/
#include <cpu/detect.h>
#if CPU_ARM_AT91
#include "ser_at91.h"
#elif CPU_ARM_LPC2378
#include "ser_lpc2.h"
/*#elif Add other ARM families here */
#else
#error Unknown CPU
#endif

View file

@ -0,0 +1,918 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2003, 2004 Develer S.r.l. (http://www.develer.com/)
* Copyright 2000 Bernie Innocenti <bernie@codewiz.org>
*
* -->
*
* \brief ARM UART and SPI I/O driver
*
*
* \author Daniele Basile <asterix@develer.com>
*/
#include "hw/hw_ser.h" /* Required for bus macros overrides */
#include <hw/hw_cpufreq.h> /* CPU_FREQ */
#include "cfg/cfg_ser.h"
#include <cfg/debug.h>
#include <io/arm.h>
#include <cpu/attr.h>
#include <drv/ser.h>
#include <drv/ser_p.h>
#include <struct/fifobuf.h>
#define SERIRQ_PRIORITY 4 ///< default priority for serial irqs.
/**
* \name Overridable serial bus hooks
*
* These can be redefined in hw.h to implement
* special bus policies such as half-duplex, 485, etc.
*
*
* \code
* TXBEGIN TXCHAR TXEND TXOFF
* | __________|__________ | |
* | | | | | | | | |
* v v v v v v v v v
* ______ __ __ __ __ __ __ ________________
* \/ \/ \/ \/ \/ \/ \/
* ______/\__/\__/\__/\__/\__/\__/
*
* \endcode
*
* \{
*/
#ifndef SER_UART0_BUS_TXINIT
/**
* Default TXINIT macro - invoked in uart0_init()
*
* - Disable GPIO on USART0 tx/rx pins
*/
#if !CPU_ARM_SAM7S_LARGE && !CPU_ARM_SAM7X
#warning Check USART0 pins!
#endif
#define SER_UART0_BUS_TXINIT do { \
PIOA_PDR = BV(RXD0) | BV(TXD0); \
} while (0)
#endif
#ifndef SER_UART0_BUS_TXBEGIN
/**
* Invoked before starting a transmission
*/
#define SER_UART0_BUS_TXBEGIN
#endif
#ifndef SER_UART0_BUS_TXCHAR
/**
* Invoked to send one character.
*/
#define SER_UART0_BUS_TXCHAR(c) do { \
US0_THR = (c); \
} while (0)
#endif
#ifndef SER_UART0_BUS_TXEND
/**
* Invoked as soon as the txfifo becomes empty
*/
#define SER_UART0_BUS_TXEND
#endif
/* End USART0 macros */
#ifndef SER_UART1_BUS_TXINIT
/**
* Default TXINIT macro - invoked in uart1_init()
*
* - Disable GPIO on USART1 tx/rx pins
*/
#if !CPU_ARM_SAM7S_LARGE && !CPU_ARM_SAM7X
#warning Check USART1 pins!
#endif
#define SER_UART1_BUS_TXINIT do { \
PIOA_PDR = BV(RXD1) | BV(TXD1); \
} while (0)
#endif
#ifndef SER_UART1_BUS_TXBEGIN
/**
* Invoked before starting a transmission
*/
#define SER_UART1_BUS_TXBEGIN
#endif
#ifndef SER_UART1_BUS_TXCHAR
/**
* Invoked to send one character.
*/
#define SER_UART1_BUS_TXCHAR(c) do { \
US1_THR = (c); \
} while (0)
#endif
#ifndef SER_UART1_BUS_TXEND
/**
* Invoked as soon as the txfifo becomes empty
*/
#define SER_UART1_BUS_TXEND
#endif
/**
* \name Overridable SPI hooks
*
* These can be redefined in hw.h to implement
* special bus policies such as slave select pin handling, etc.
*
* \{
*/
#ifndef SER_SPI0_BUS_TXINIT
/**
* Default TXINIT macro - invoked in spi_init()
* The default is no action.
*/
#define SER_SPI0_BUS_TXINIT
#endif
#ifndef SER_SPI0_BUS_TXCLOSE
/**
* Invoked after the last character has been transmitted.
* The default is no action.
*/
#define SER_SPI0_BUS_TXCLOSE
#endif
#if CPU_ARM_SAM7X
#ifndef SER_SPI1_BUS_TXINIT
/**
* Default TXINIT macro - invoked in spi_init()
* The default is no action.
*/
#define SER_SPI1_BUS_TXINIT
#endif
#ifndef SER_SPI1_BUS_TXCLOSE
/**
* Invoked after the last character has been transmitted.
* The default is no action.
*/
#define SER_SPI1_BUS_TXCLOSE
#endif
#endif
/*\}*/
/* From the high-level serial driver */
extern struct Serial *ser_handles[SER_CNT];
/* TX and RX buffers */
static unsigned char uart0_txbuffer[CONFIG_UART0_TXBUFSIZE];
static unsigned char uart0_rxbuffer[CONFIG_UART0_RXBUFSIZE];
static unsigned char uart1_txbuffer[CONFIG_UART1_TXBUFSIZE];
static unsigned char uart1_rxbuffer[CONFIG_UART1_RXBUFSIZE];
static unsigned char spi0_txbuffer[CONFIG_SPI0_TXBUFSIZE];
static unsigned char spi0_rxbuffer[CONFIG_SPI0_RXBUFSIZE];
#if CPU_ARM_SAM7X
static unsigned char spi1_txbuffer[CONFIG_SPI1_TXBUFSIZE];
static unsigned char spi1_rxbuffer[CONFIG_SPI1_RXBUFSIZE];
#endif
/**
* Internal hardware state structure
*
* The \a sending variable is true while the transmission
* interrupt is retriggering itself.
*
* For the USARTs the \a sending flag is useful for taking specific
* actions before sending a burst of data, at the start of a trasmission
* but not before every char sent.
*
* For the SPI, this flag is necessary because the SPI sends and receives
* bytes at the same time and the SPI IRQ is unique for send/receive.
* The only way to start transmission is to write data in SPDR (this
* is done by spi_starttx()). We do this *only* if a transfer is
* not already started.
*/
struct ArmSerial
{
struct SerialHardware hw;
volatile bool sending;
};
static ISR_PROTO(uart0_irq_dispatcher);
static ISR_PROTO(uart1_irq_dispatcher);
static ISR_PROTO(spi0_irq_handler);
#if CPU_ARM_SAM7X
static ISR_PROTO(spi1_irq_handler);
#endif
/*
* Callbacks for USART0
*/
static void uart0_init(
UNUSED_ARG(struct SerialHardware *, _hw),
UNUSED_ARG(struct Serial *, ser))
{
US0_IDR = 0xFFFFFFFF;
/* Set the vector. */
AIC_SVR(US0_ID) = uart0_irq_dispatcher;
/* Initialize to level sensitive with defined priority. */
AIC_SMR(US0_ID) = AIC_SRCTYPE_INT_LEVEL_SENSITIVE | SERIRQ_PRIORITY;
PMC_PCER = BV(US0_ID);
/*
* - Reset USART0
* - Set serial param: mode Normal, 8bit data, 1bit stop, parity none
* - Enable both the receiver and the transmitter
* - Enable only the RX complete interrupt
*/
US0_CR = BV(US_RSTRX) | BV(US_RSTTX);
US0_MR = US_CHMODE_NORMAL | US_CHRL_8 | US_NBSTOP_1 | US_PAR_NO;
US0_CR = BV(US_RXEN) | BV(US_TXEN);
US0_IER = BV(US_RXRDY);
SER_UART0_BUS_TXINIT;
/* Enable the USART IRQ */
AIC_IECR = BV(US0_ID);
SER_STROBE_INIT;
}
static void uart0_cleanup(UNUSED_ARG(struct SerialHardware *, _hw))
{
US0_CR = BV(US_RSTRX) | BV(US_RSTTX) | BV(US_RXDIS) | BV(US_TXDIS) | BV(US_RSTSTA);
}
static void uart0_enabletxirq(struct SerialHardware *_hw)
{
struct ArmSerial *hw = (struct ArmSerial *)_hw;
/*
* WARNING: racy code here! The tx interrupt sets hw->sending to false
* when it runs with an empty fifo. The order of statements in the
* if-block matters.
*/
if (!hw->sending)
{
hw->sending = true;
/*
* - Enable the transmitter
* - Enable TX empty interrupt
*/
SER_UART0_BUS_TXBEGIN;
US0_IER = BV(US_TXEMPTY);
}
}
static void uart0_setbaudrate(UNUSED_ARG(struct SerialHardware *, _hw), unsigned long rate)
{
/* Compute baud-rate period */
US0_BRGR = CPU_FREQ / (16 * rate);
//DB(kprintf("uart0_setbaudrate(rate=%lu): period=%d\n", rate, period);)
}
static void uart0_setparity(UNUSED_ARG(struct SerialHardware *, _hw), int parity)
{
US0_MR &= ~US_PAR_MASK;
/* Set UART parity */
switch(parity)
{
case SER_PARITY_NONE:
{
/* Parity none. */
US0_MR |= US_PAR_NO;
break;
}
case SER_PARITY_EVEN:
{
/* Even parity. */
US0_MR |= US_PAR_EVEN;
break;
}
case SER_PARITY_ODD:
{
/* Odd parity. */
US0_MR |= US_PAR_ODD;
break;
}
default:
ASSERT(0);
}
}
/*
* Callbacks for USART1
*/
static void uart1_init(
UNUSED_ARG(struct SerialHardware *, _hw),
UNUSED_ARG(struct Serial *, ser))
{
US1_IDR = 0xFFFFFFFF;
/* Set the vector. */
AIC_SVR(US1_ID) = uart1_irq_dispatcher;
/* Initialize to level sensitive with defined priority. */
AIC_SMR(US1_ID) = AIC_SRCTYPE_INT_LEVEL_SENSITIVE | SERIRQ_PRIORITY;
PMC_PCER = BV(US1_ID);
/*
* - Reset USART1
* - Set serial param: mode Normal, 8bit data, 1bit stop, parity none
* - Enable both the receiver and the transmitter
* - Enable only the RX complete interrupt
*/
US1_CR = BV(US_RSTRX) | BV(US_RSTTX);
US1_MR = US_CHMODE_NORMAL | US_CHRL_8 | US_NBSTOP_1 | US_PAR_NO;
US1_CR = BV(US_RXEN) | BV(US_TXEN);
US1_IER = BV(US_RXRDY);
SER_UART1_BUS_TXINIT;
/* Enable the USART IRQ */
AIC_IECR = BV(US1_ID);
SER_STROBE_INIT;
}
static void uart1_cleanup(UNUSED_ARG(struct SerialHardware *, _hw))
{
US1_CR = BV(US_RSTRX) | BV(US_RSTTX) | BV(US_RXDIS) | BV(US_TXDIS) | BV(US_RSTSTA);
}
static void uart1_enabletxirq(struct SerialHardware *_hw)
{
struct ArmSerial *hw = (struct ArmSerial *)_hw;
/*
* WARNING: racy code here! The tx interrupt sets hw->sending to false
* when it runs with an empty fifo. The order of statements in the
* if-block matters.
*/
if (!hw->sending)
{
hw->sending = true;
/*
* - Enable the transmitter
* - Enable TX empty interrupt
*/
SER_UART1_BUS_TXBEGIN;
US1_IER = BV(US_TXEMPTY);
}
}
static void uart1_setbaudrate(UNUSED_ARG(struct SerialHardware *, _hw), unsigned long rate)
{
/* Compute baud-rate period */
US1_BRGR = CPU_FREQ / (16 * rate);
//DB(kprintf("uart0_setbaudrate(rate=%lu): period=%d\n", rate, period);)
}
static void uart1_setparity(UNUSED_ARG(struct SerialHardware *, _hw), int parity)
{
US1_MR &= ~US_PAR_MASK;
/* Set UART parity */
switch(parity)
{
case SER_PARITY_NONE:
{
/* Parity none. */
US1_MR |= US_PAR_NO;
break;
}
case SER_PARITY_EVEN:
{
/* Even parity. */
US1_MR |= US_PAR_EVEN;
break;
}
case SER_PARITY_ODD:
{
/* Odd parity. */
US1_MR |= US_PAR_ODD;
break;
}
default:
ASSERT(0);
}
}
/* SPI driver */
static void spi0_init(UNUSED_ARG(struct SerialHardware *, _hw), UNUSED_ARG(struct Serial *, ser))
{
/* Disable PIO on SPI pins */
PIOA_PDR = BV(SPI0_SPCK) | BV(SPI0_MOSI) | BV(SPI0_MISO);
/* Reset device */
SPI0_CR = BV(SPI_SWRST);
/*
* Set SPI to master mode, fixed peripheral select, chip select directly connected to a peripheral device,
* SPI clock set to MCK, mode fault detection disabled, loopback disable, NPCS0 active, Delay between CS = 0
*/
SPI0_MR = BV(SPI_MSTR) | BV(SPI_MODFDIS);
/*
* Set SPI mode.
* At reset clock division factor is set to 0, that is
* *forbidden*. Set SPI clock to minimum to keep it valid.
*/
SPI0_CSR0 = BV(SPI_NCPHA) | (255 << SPI_SCBR_SHIFT);
/* Disable all irqs */
SPI0_IDR = 0xFFFFFFFF;
/* Set the vector. */
AIC_SVR(SPI0_ID) = spi0_irq_handler;
/* Initialize to edge triggered with defined priority. */
AIC_SMR(SPI0_ID) = AIC_SRCTYPE_INT_EDGE_TRIGGERED | SERIRQ_PRIORITY;
/* Enable the USART IRQ */
AIC_IECR = BV(SPI0_ID);
PMC_PCER = BV(SPI0_ID);
/* Enable interrupt on tx buffer empty */
SPI0_IER = BV(SPI_TXEMPTY);
/* Enable SPI */
SPI0_CR = BV(SPI_SPIEN);
SER_SPI0_BUS_TXINIT;
SER_STROBE_INIT;
}
static void spi0_cleanup(UNUSED_ARG(struct SerialHardware *, _hw))
{
/* Disable SPI */
SPI0_CR = BV(SPI_SPIDIS);
/* Disable all irqs */
SPI0_IDR = 0xFFFFFFFF;
SER_SPI0_BUS_TXCLOSE;
/* Enable PIO on SPI pins */
PIOA_PER = BV(SPI0_SPCK) | BV(SPI0_MOSI) | BV(SPI0_MISO);
}
static void spi0_starttx(struct SerialHardware *_hw)
{
struct ArmSerial *hw = (struct ArmSerial *)_hw;
cpu_flags_t flags;
IRQ_SAVE_DISABLE(flags);
/* Send data only if the SPI is not already transmitting */
if (!hw->sending && !fifo_isempty(&ser_handles[SER_SPI0]->txfifo))
{
hw->sending = true;
SPI0_TDR = fifo_pop(&ser_handles[SER_SPI0]->txfifo);
}
IRQ_RESTORE(flags);
}
static void spi0_setbaudrate(UNUSED_ARG(struct SerialHardware *, _hw), unsigned long rate)
{
SPI0_CSR0 &= ~SPI_SCBR;
ASSERT((uint8_t)DIV_ROUND(CPU_FREQ, rate));
SPI0_CSR0 |= DIV_ROUND(CPU_FREQ, rate) << SPI_SCBR_SHIFT;
}
#if CPU_ARM_SAM7X
/* SPI driver */
static void spi1_init(UNUSED_ARG(struct SerialHardware *, _hw), UNUSED_ARG(struct Serial *, ser))
{
/* Disable PIO on SPI pins */
PIOA_PDR = BV(SPI1_SPCK) | BV(SPI1_MOSI) | BV(SPI1_MISO);
/* SPI1 pins are on B peripheral function! */
PIOA_BSR = BV(SPI1_SPCK) | BV(SPI1_MOSI) | BV(SPI1_MISO);
/* Reset device */
SPI1_CR = BV(SPI_SWRST);
/*
* Set SPI to master mode, fixed peripheral select, chip select directly connected to a peripheral device,
* SPI clock set to MCK, mode fault detection disabled, loopback disable, NPCS0 active, Delay between CS = 0
*/
SPI1_MR = BV(SPI_MSTR) | BV(SPI_MODFDIS);
/*
* Set SPI mode.
* At reset clock division factor is set to 0, that is
* *forbidden*. Set SPI clock to minimum to keep it valid.
*/
SPI1_CSR0 = BV(SPI_NCPHA) | (255 << SPI_SCBR_SHIFT);
/* Disable all irqs */
SPI1_IDR = 0xFFFFFFFF;
/* Set the vector. */
AIC_SVR(SPI1_ID) = spi1_irq_handler;
/* Initialize to edge triggered with defined priority. */
AIC_SMR(SPI1_ID) = AIC_SRCTYPE_INT_EDGE_TRIGGERED | SERIRQ_PRIORITY;
/* Enable the USART IRQ */
AIC_IECR = BV(SPI1_ID);
PMC_PCER = BV(SPI1_ID);
/* Enable interrupt on tx buffer empty */
SPI1_IER = BV(SPI_TXEMPTY);
/* Enable SPI */
SPI1_CR = BV(SPI_SPIEN);
SER_SPI1_BUS_TXINIT;
SER_STROBE_INIT;
}
static void spi1_cleanup(UNUSED_ARG(struct SerialHardware *, _hw))
{
/* Disable SPI */
SPI1_CR = BV(SPI_SPIDIS);
/* Disable all irqs */
SPI1_IDR = 0xFFFFFFFF;
SER_SPI1_BUS_TXCLOSE;
/* Enable PIO on SPI pins */
PIOA_PER = BV(SPI1_SPCK) | BV(SPI1_MOSI) | BV(SPI1_MISO);
}
static void spi1_starttx(struct SerialHardware *_hw)
{
struct ArmSerial *hw = (struct ArmSerial *)_hw;
cpu_flags_t flags;
IRQ_SAVE_DISABLE(flags);
/* Send data only if the SPI is not already transmitting */
if (!hw->sending && !fifo_isempty(&ser_handles[SER_SPI1]->txfifo))
{
hw->sending = true;
SPI1_TDR = fifo_pop(&ser_handles[SER_SPI1]->txfifo);
}
IRQ_RESTORE(flags);
}
static void spi1_setbaudrate(UNUSED_ARG(struct SerialHardware *, _hw), unsigned long rate)
{
SPI1_CSR0 &= ~SPI_SCBR;
ASSERT((uint8_t)DIV_ROUND(CPU_FREQ, rate));
SPI1_CSR0 |= DIV_ROUND(CPU_FREQ, rate) << SPI_SCBR_SHIFT;
}
#endif
static void spi_setparity(UNUSED_ARG(struct SerialHardware *, _hw), UNUSED_ARG(int, parity))
{
// nop
}
static bool tx_sending(struct SerialHardware* _hw)
{
struct ArmSerial *hw = (struct ArmSerial *)_hw;
return hw->sending;
}
// FIXME: move into compiler.h? Ditch?
#if COMPILER_C99
#define C99INIT(name,val) .name = val
#elif defined(__GNUC__)
#define C99INIT(name,val) name: val
#else
#warning No designated initializers, double check your code
#define C99INIT(name,val) (val)
#endif
/*
* High-level interface data structures
*/
static const struct SerialHardwareVT UART0_VT =
{
C99INIT(init, uart0_init),
C99INIT(cleanup, uart0_cleanup),
C99INIT(setBaudrate, uart0_setbaudrate),
C99INIT(setParity, uart0_setparity),
C99INIT(txStart, uart0_enabletxirq),
C99INIT(txSending, tx_sending),
};
static const struct SerialHardwareVT UART1_VT =
{
C99INIT(init, uart1_init),
C99INIT(cleanup, uart1_cleanup),
C99INIT(setBaudrate, uart1_setbaudrate),
C99INIT(setParity, uart1_setparity),
C99INIT(txStart, uart1_enabletxirq),
C99INIT(txSending, tx_sending),
};
static const struct SerialHardwareVT SPI0_VT =
{
C99INIT(init, spi0_init),
C99INIT(cleanup, spi0_cleanup),
C99INIT(setBaudrate, spi0_setbaudrate),
C99INIT(setParity, spi_setparity),
C99INIT(txStart, spi0_starttx),
C99INIT(txSending, tx_sending),
};
#if CPU_ARM_SAM7X
static const struct SerialHardwareVT SPI1_VT =
{
C99INIT(init, spi1_init),
C99INIT(cleanup, spi1_cleanup),
C99INIT(setBaudrate, spi1_setbaudrate),
C99INIT(setParity, spi_setparity),
C99INIT(txStart, spi1_starttx),
C99INIT(txSending, tx_sending),
};
#endif
static struct ArmSerial UARTDescs[SER_CNT] =
{
{
C99INIT(hw, /**/) {
C99INIT(table, &UART0_VT),
C99INIT(txbuffer, uart0_txbuffer),
C99INIT(rxbuffer, uart0_rxbuffer),
C99INIT(txbuffer_size, sizeof(uart0_txbuffer)),
C99INIT(rxbuffer_size, sizeof(uart0_rxbuffer)),
},
C99INIT(sending, false),
},
{
C99INIT(hw, /**/) {
C99INIT(table, &UART1_VT),
C99INIT(txbuffer, uart1_txbuffer),
C99INIT(rxbuffer, uart1_rxbuffer),
C99INIT(txbuffer_size, sizeof(uart1_txbuffer)),
C99INIT(rxbuffer_size, sizeof(uart1_rxbuffer)),
},
C99INIT(sending, false),
},
{
C99INIT(hw, /**/) {
C99INIT(table, &SPI0_VT),
C99INIT(txbuffer, spi0_txbuffer),
C99INIT(rxbuffer, spi0_rxbuffer),
C99INIT(txbuffer_size, sizeof(spi0_txbuffer)),
C99INIT(rxbuffer_size, sizeof(spi0_rxbuffer)),
},
C99INIT(sending, false),
},
#if CPU_ARM_SAM7X
{
C99INIT(hw, /**/) {
C99INIT(table, &SPI1_VT),
C99INIT(txbuffer, spi1_txbuffer),
C99INIT(rxbuffer, spi1_rxbuffer),
C99INIT(txbuffer_size, sizeof(spi1_txbuffer)),
C99INIT(rxbuffer_size, sizeof(spi1_rxbuffer)),
},
C99INIT(sending, false),
}
#endif
};
struct SerialHardware *ser_hw_getdesc(int unit)
{
ASSERT(unit < SER_CNT);
return &UARTDescs[unit].hw;
}
/**
* Serial 0 TX interrupt handler
*/
INLINE void uart0_irq_tx(void)
{
SER_STROBE_ON;
struct FIFOBuffer * const txfifo = &ser_handles[SER_UART0]->txfifo;
if (fifo_isempty(txfifo))
{
/*
* - Disable the TX empty interrupts
*/
US0_IDR = BV(US_TXEMPTY);
SER_UART0_BUS_TXEND;
UARTDescs[SER_UART0].sending = false;
}
else
{
char c = fifo_pop(txfifo);
SER_UART0_BUS_TXCHAR(c);
}
SER_STROBE_OFF;
}
/**
* Serial 0 RX complete interrupt handler.
*/
INLINE void uart0_irq_rx(void)
{
SER_STROBE_ON;
/* Should be read before US_CRS */
ser_handles[SER_UART0]->status |= US0_CSR & (SERRF_RXSROVERRUN | SERRF_FRAMEERROR);
US0_CR = BV(US_RSTSTA);
char c = US0_RHR;
struct FIFOBuffer * const rxfifo = &ser_handles[SER_UART0]->rxfifo;
if (fifo_isfull(rxfifo))
ser_handles[SER_UART0]->status |= SERRF_RXFIFOOVERRUN;
else
fifo_push(rxfifo, c);
SER_STROBE_OFF;
}
/**
* Serial IRQ dispatcher for USART0.
*/
static DECLARE_ISR(uart0_irq_dispatcher)
{
if (US0_CSR & BV(US_RXRDY))
uart0_irq_rx();
if (US0_CSR & BV(US_TXEMPTY))
uart0_irq_tx();
/* Inform hw that we have served the IRQ */
AIC_EOICR = 0;
}
/**
* Serial 1 TX interrupt handler
*/
INLINE void uart1_irq_tx(void)
{
SER_STROBE_ON;
struct FIFOBuffer * const txfifo = &ser_handles[SER_UART1]->txfifo;
if (fifo_isempty(txfifo))
{
/*
* - Disable the TX empty interrupts
*/
US1_IDR = BV(US_TXEMPTY);
SER_UART1_BUS_TXEND;
UARTDescs[SER_UART1].sending = false;
}
else
{
char c = fifo_pop(txfifo);
SER_UART1_BUS_TXCHAR(c);
}
SER_STROBE_OFF;
}
/**
* Serial 1 RX complete interrupt handler.
*/
INLINE void uart1_irq_rx(void)
{
SER_STROBE_ON;
/* Should be read before US_CRS */
ser_handles[SER_UART1]->status |= US1_CSR & (SERRF_RXSROVERRUN | SERRF_FRAMEERROR);
US1_CR = BV(US_RSTSTA);
char c = US1_RHR;
struct FIFOBuffer * const rxfifo = &ser_handles[SER_UART1]->rxfifo;
if (fifo_isfull(rxfifo))
ser_handles[SER_UART1]->status |= SERRF_RXFIFOOVERRUN;
else
fifo_push(rxfifo, c);
SER_STROBE_OFF;
}
/**
* Serial IRQ dispatcher for USART1.
*/
static DECLARE_ISR(uart1_irq_dispatcher)
{
if (US1_CSR & BV(US_RXRDY))
uart1_irq_rx();
if (US1_CSR & BV(US_TXEMPTY))
uart1_irq_tx();
/* Inform hw that we have served the IRQ */
AIC_EOICR = 0;
}
/**
* SPI0 interrupt handler
*/
static DECLARE_ISR(spi0_irq_handler)
{
SER_STROBE_ON;
char c = SPI0_RDR;
/* Read incoming byte. */
if (!fifo_isfull(&ser_handles[SER_SPI0]->rxfifo))
fifo_push(&ser_handles[SER_SPI0]->rxfifo, c);
/*
* FIXME
else
ser_handles[SER_SPI0]->status |= SERRF_RXFIFOOVERRUN;
*/
/* Send */
if (!fifo_isempty(&ser_handles[SER_SPI0]->txfifo))
SPI0_TDR = fifo_pop(&ser_handles[SER_SPI0]->txfifo);
else
UARTDescs[SER_SPI0].sending = false;
/* Inform hw that we have served the IRQ */
AIC_EOICR = 0;
SER_STROBE_OFF;
}
#if CPU_ARM_SAM7X
/**
* SPI1 interrupt handler
*/
static DECLARE_ISR(spi1_irq_handler)
{
SER_STROBE_ON;
char c = SPI1_RDR;
/* Read incoming byte. */
if (!fifo_isfull(&ser_handles[SER_SPI1]->rxfifo))
fifo_push(&ser_handles[SER_SPI1]->rxfifo, c);
/*
* FIXME
else
ser_handles[SER_SPI1]->status |= SERRF_RXFIFOOVERRUN;
*/
/* Send */
if (!fifo_isempty(&ser_handles[SER_SPI1]->txfifo))
SPI1_TDR = fifo_pop(&ser_handles[SER_SPI1]->txfifo);
else
UARTDescs[SER_SPI1].sending = false;
/* Inform hw that we have served the IRQ */
AIC_EOICR = 0;
SER_STROBE_OFF;
}
#endif

View file

@ -0,0 +1,82 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2003,2004 Develer S.r.l. (http://www.develer.com/)
* Copyright 2000 Bernie Innocenti <bernie@codewiz.org>
*
* -->
*
* \brief High level serial I/O API
*
* \author Daniele Basile <asterix@develer.com>
*/
#ifndef SER_AT91_H
#define SER_AT91_H
#include <cfg/macros.h> /* BV() */
#include <cfg/compiler.h> /* uint32_t */
#include <cpu/detect.h> /* CPU_* */
/** \name Serial Error/status flags. */
/*\{*/
typedef uint32_t serstatus_t;
/* Software errors */
#define SERRF_RXFIFOOVERRUN BV(0) /**< Rx FIFO buffer overrun */
#define SERRF_RXTIMEOUT BV(1) /**< Receive timeout */
#define SERRF_TXTIMEOUT BV(2) /**< Transmit timeout */
/*
* Hardware errors.
* These flags map directly to the ARM USART Channel Status Register (US_CSR).
*/
#define SERRF_RXSROVERRUN BV(5) /**< Rx shift register overrun */
#define SERRF_FRAMEERROR BV(6) /**< Stop bit missing */
#define SERRF_PARITYERROR BV(7) /**< Parity error */
#define SERRF_NOISEERROR 0 /**< Unsupported */
/*\}*/
/**
* \name Serial hw numbers
*
* \{
*/
enum
{
SER_UART0,
SER_UART1,
SER_SPI0,
#if CPU_ARM_SAM7X
SER_SPI1,
#endif
SER_CNT /**< Number of serial ports */
};
/*\}*/
#endif /* SER_AT91_H */

View file

@ -0,0 +1,487 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2010 Develer S.r.l. (http://www.develer.com/)
*
* -->
*
* \brief LPC23xx UART driver.
*
* \author Andrea Righi <arighi@develer.com>
*
* notest:arm
*/
#include "ser_lpc2.h"
#include "cfg/cfg_ser.h"
#include <cfg/macros.h> /* for BV() */
#include <cpu/power.h> /* cpu_relax() */
#include <drv/ser_p.h>
#include <drv/ser.h>
#include <drv/vic_lpc2.h> /* vic_handler_t */
#include <io/lpc23xx.h>
/* Register offsets */
#define RBR 0x00
#define THR 0x00
#define DLL 0x00
#define DLM 0x04
#define IER 0x04
#define IIR 0x08
#define FCR 0x08
#define LCR 0x0c
#define LSR 0x14
#define SCR 0x1c
#define ACR 0x20
#define ICR 0x24
#define FDR 0x28
#define TER 0x30
/* From the high-level serial driver */
extern struct Serial *ser_handles[SER_CNT];
struct LPC2Serial
{
struct SerialHardware hw;
bool sending;
int irq;
};
/* Forward declaration */
static struct LPC2Serial UARTDesc[SER_CNT];
struct uart_config
{
uint32_t base;
uint32_t pconp;
uint32_t pclksel0;
uint32_t pclksel0_mask;
uint32_t pclksel1;
uint32_t pclksel1_mask;
uint32_t pinsel0;
uint32_t pinsel0_mask;
uint32_t pinsel4;
uint32_t pinsel4_mask;
};
/* UART registers configuration */
static const struct uart_config uart_param[] =
{
/* UART0 */
{
.base = UART0_BASE_ADDR,
.pconp = BV(3),
.pclksel0 = BV(6),
.pclksel0_mask = BV(7) | BV(6),
.pclksel1 = 0,
.pclksel1_mask = 0,
.pinsel0 = BV(6) | BV(4),
.pinsel0_mask = BV(7) | BV(6) | BV(5) | BV(4),
.pinsel4 = 0,
.pinsel4_mask = 0,
},
/* UART1 */
{
.base = UART1_BASE_ADDR,
.pconp = BV(4),
.pclksel0 = BV(8),
.pclksel0_mask = BV(9) | BV(8),
.pclksel1 = 0,
.pclksel1_mask = 0,
.pinsel0 = 0,
.pinsel0_mask = 0,
.pinsel4 = BV(3) | BV(1),
.pinsel4_mask = BV(3) | BV(2) | BV(1) | BV(0),
},
/* UART2 */
{
.base = UART2_BASE_ADDR,
.pconp = BV(24),
.pclksel0 = 0,
.pclksel0_mask = 0,
.pclksel1 = BV(16),
.pclksel1_mask = BV(17) | BV(16),
.pinsel0 = 0,
.pinsel0_mask = 0,
.pinsel4 = BV(19) | BV(17),
.pinsel4_mask = BV(19) | BV(18) | BV(17) | BV(16),
},
/* UART3 */
{
.base = UART3_BASE_ADDR,
.pconp = BV(25),
.pclksel0 = 0,
.pclksel0_mask = 0,
.pclksel1 = BV(18),
.pclksel1_mask = BV(19) | BV(18),
.pinsel0 = BV(3) | BV(1),
.pinsel0_mask = BV(3) | BV(2) | BV(1) | BV(0),
.pinsel4 = 0,
.pinsel4_mask = 0,
},
};
static void lpc2_uartSetBaudRate(int port, unsigned long baud)
{
cpu_flags_t flags;
IRQ_SAVE_DISABLE(flags);
/* LCR: DLAB = 1 (enable divisor modify) */
*(reg8_t *)(uart_param[port].base + LCR) |= 0x80;
/* DLL */
*(reg8_t *)(uart_param[port].base + DLL) =
DIV_ROUND(CPU_FREQ, 16 * baud) & 0xFF;
/* DLM */
*(reg8_t *)(uart_param[port].base + DLM) =
(DIV_ROUND(CPU_FREQ, 16 * baud) >> 8) & 0xFF;
*(reg32_t *)(uart_param[port].base + LCR) &= ~0x80;
/* LCR: DLAB = 0 (disable divisor modify) */
*(reg8_t *)(uart_param[port].base + LCR) &= ~0x80;
IRQ_RESTORE(flags);
}
static void lpc2_uartSetParity(int port, int parity)
{
/* Set 8-bit word, one stop bit by default */
uint32_t config = BV(1) | BV(0);
cpu_flags_t flags;
IRQ_SAVE_DISABLE(flags);
switch(parity)
{
case SER_PARITY_NONE:
break;
case SER_PARITY_ODD:
config |= BV(3);
break;
case SER_PARITY_EVEN:
config |= BV(4) | BV(3);
break;
default:
ASSERT(0);
IRQ_RESTORE(flags);
return;
}
/* LCR */
*(reg8_t *)(uart_param[port].base + LCR) = config;
IRQ_RESTORE(flags);
}
static void lpc2_uartPutChar(uint32_t base, uint8_t c)
{
reg8_t *lsr = (reg8_t *)base + LSR;
reg8_t *thr = (reg8_t *)base + THR;
while (!(*lsr & BV(6)))
cpu_relax();
*thr = c;
}
void lpc2_uartInit(int port)
{
cpu_flags_t flags;
IRQ_SAVE_DISABLE(flags);
/* Power-on the device */
PCONP |= uart_param[port].pconp;
/* Set UART clk to CPU_FREQ */
PCLKSEL0 &= ~uart_param[port].pclksel0_mask;
PCLKSEL0 |= uart_param[port].pclksel0;
PCLKSEL1 &= ~uart_param[port].pclksel1_mask;
PCLKSEL1 |= uart_param[port].pclksel1;
/* LCR: 8bit, 1 stop bit, no parity, DLAB = 1 (enable divisor modify) */
*(reg8_t *)(uart_param[port].base + LCR) = 0x83;
/* DLL */
*(reg8_t *)(uart_param[port].base + DLL) =
DIV_ROUND(CPU_FREQ, 16 * CONFIG_KDEBUG_BAUDRATE) & 0xFF;
/* DLM */
*(reg8_t *)(uart_param[port].base + DLM) =
(DIV_ROUND(CPU_FREQ, 16 * CONFIG_KDEBUG_BAUDRATE) >> 8) & 0xFF;
/* FDR */
*(reg32_t *)(uart_param[port].base + FDR) = 0x10;
/* Assign TX pin to UART0*/
PINSEL0 &= ~uart_param[port].pinsel0_mask;
PINSEL0 |= uart_param[port].pinsel0;
PINSEL4 &= ~uart_param[port].pinsel4_mask;
PINSEL4 |= uart_param[port].pinsel4;
/* LCR: set 8bit, 1 stop bit, no parity, DLAB = 0 (disable divisor modify) */
*(reg8_t *)(uart_param[port].base + LCR) = 0x03;
/* TER: Enable transmitter */
*(reg8_t *)(uart_param[port].base + TER) = BV(7);
/* IER: Enable RBR interrupt */
*(reg8_t *)(uart_param[port].base + IER) = BV(0);
IRQ_RESTORE(flags);
}
static bool tx_sending(struct SerialHardware *_hw)
{
struct LPC2Serial *hw = (struct LPC2Serial *)_hw;
return hw->sending;
}
INLINE bool lpc2_uartRxReady(int port)
{
/* LSR: check Receiver Data Ready (RDR) bit */
return *(reg8_t *)(uart_param[port].base + LSR) & BV(0) ? true : false;
}
static void uart_irq_rx(int port)
{
struct FIFOBuffer *rxfifo = &ser_handles[port]->rxfifo;
char c;
while (lpc2_uartRxReady(port))
{
/* RBR: read a character from the Receiver Buffer Register */
c = *(reg8_t *)(uart_param[port].base + RBR);
if (fifo_isfull(rxfifo))
ser_handles[port]->status |= SERRF_RXFIFOOVERRUN;
else
fifo_push(rxfifo, c);
}
}
INLINE bool lpc2_uartTxReady(int port)
{
/* LSR: check Transmitter Holding Register Empty (THRE) bit */
return *(reg8_t *)(uart_param[port].base + LSR) & BV(5) ? true : false;
}
static void uart_irq_tx(int port)
{
struct FIFOBuffer *txfifo = &ser_handles[port]->txfifo;
while (lpc2_uartTxReady(port))
{
/*
* Disable TX empty interrupts if there're no more
* characters to transmit.
*/
if (fifo_isempty(txfifo))
{
/* IER: Disable THRE interrupt */
*(reg8_t *)(uart_param[port].base + IER) &= ~BV(1);
UARTDesc[port].sending = false;
break;
}
/* THR: put a character to the Transmit Holding Register */
*(reg8_t *)(uart_param[port].base + THR) = fifo_pop(txfifo);
}
}
static void uart_common_irq_handler(int port)
{
/* IIR: identify the interrupt source */
uint32_t status = *(reg32_t *)(uart_param[port].base + IIR) >> 1 & 0x7;
/* Receiver Data Ready (RDR) */
if (status == 0x02)
uart_irq_rx(port);
/* Transmit Holding Register Empty (THRE) */
else if (status == 0x01)
uart_irq_tx(port);
/* Signal the VIC we have completed the ISR */
VICVectAddr = 0;
}
static void lpc2_uartIRQEnable(int port, vic_handler_t handler)
{
vic_setVector(UARTDesc[port].irq, handler);
vic_enable(UARTDesc[port].irq);
}
static void lpc2_uartIRQDisable(int port)
{
vic_disable(UARTDesc[port].irq);
}
/* UART class definition */
#define UART_PORT(port) \
/* UART TX and RX buffers */ \
static unsigned char \
uart ## port ## _txbuffer[CONFIG_UART ## port ## _TXBUFSIZE]; \
static unsigned char \
uart ## port ## _rxbuffer[CONFIG_UART ## port ## _RXBUFSIZE]; \
\
/* UART interrupt handler */ \
static DECLARE_ISR(uart ## port ## _irq_handler) \
{ \
uart_common_irq_handler(port); \
} \
\
/* UART public methods */ \
static void \
uart ## port ## _txStart(struct SerialHardware *_hw) \
{ \
struct FIFOBuffer *txfifo = &ser_handles[port]->txfifo; \
struct LPC2Serial *hw = (struct LPC2Serial *)_hw; \
\
if (hw->sending) \
return; \
lpc2_uartPutChar(UART ## port ## _BASE_ADDR, fifo_pop(txfifo)); \
if (!fifo_isempty(txfifo)) \
{ \
hw->sending = true; \
/* IER: Enable THRE interrupt */ \
*(reg8_t *)(uart_param[port].base + IER) |= BV(1); \
} \
} \
\
static void \
uart ## port ## _setbaudrate(UNUSED_ARG(struct SerialHardware *, hw), \
unsigned long baud) \
{ \
lpc2_uartSetBaudRate(port, baud); \
} \
\
static void \
uart ## port ## _setparity(UNUSED_ARG(struct SerialHardware *, hw), \
int parity) \
{ \
lpc2_uartSetParity(port, parity); \
} \
\
static void \
uart ## port ## _cleanup(struct SerialHardware *_hw) \
{ \
struct LPC2Serial *hw = (struct LPC2Serial *)_hw; \
\
hw->sending = false; \
lpc2_uartIRQDisable(port); \
} \
\
static void \
uart ## port ## _init(UNUSED_ARG(struct SerialHardware *, hw), \
UNUSED_ARG(struct Serial *, ser)) \
{ \
lpc2_uartInit(port); \
lpc2_uartIRQEnable(port, uart ## port ## _irq_handler); \
} \
\
/* UART operations */ \
static const struct SerialHardwareVT UART ## port ## _VT = \
{ \
.init = uart ## port ## _init, \
.cleanup = uart ## port ## _cleanup, \
.setBaudrate = uart ## port ## _setbaudrate, \
.setParity = uart ## port ## _setparity, \
.txStart = uart ## port ## _txStart, \
.txSending = tx_sending, \
};
/* UART port instances */
UART_PORT(0)
UART_PORT(1)
UART_PORT(2)
UART_PORT(3)
static struct LPC2Serial UARTDesc[SER_CNT] =
{
{
.hw = {
.table = &UART0_VT,
.txbuffer = uart0_txbuffer,
.rxbuffer = uart0_rxbuffer,
.txbuffer_size = sizeof(uart0_txbuffer),
.rxbuffer_size = sizeof(uart0_rxbuffer),
},
.sending = false,
.irq = INT_UART0,
},
{
.hw = {
.table = &UART1_VT,
.txbuffer = uart1_txbuffer,
.rxbuffer = uart1_rxbuffer,
.txbuffer_size = sizeof(uart1_txbuffer),
.rxbuffer_size = sizeof(uart1_rxbuffer),
},
.sending = false,
.irq = INT_UART1,
},
{
.hw = {
.table = &UART2_VT,
.txbuffer = uart2_txbuffer,
.rxbuffer = uart2_rxbuffer,
.txbuffer_size = sizeof(uart2_txbuffer),
.rxbuffer_size = sizeof(uart2_rxbuffer),
},
.sending = false,
.irq = INT_UART2,
},
{
.hw = {
.table = &UART3_VT,
.txbuffer = uart3_txbuffer,
.rxbuffer = uart3_rxbuffer,
.txbuffer_size = sizeof(uart3_txbuffer),
.rxbuffer_size = sizeof(uart3_rxbuffer),
},
.sending = false,
.irq = INT_UART3,
},
};
struct SerialHardware *ser_hw_getdesc(int port)
{
ASSERT(port >= 0 && port < SER_CNT);
return &UARTDesc[port].hw;
}

View file

@ -0,0 +1,73 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2010 Develer S.r.l. (http://www.develer.com/)
*
* -->
*
* \brief LPC23xx UART driver.
*
* \author Andrea Righi <arighi@develer.com>
*/
#ifndef SER_LPC2_H
#define SER_LPC2_H
#include <cfg/cfg_debug.h>
#include <io/lpc23xx.h>
/* Serial hardware numbers */
enum
{
SER_UART0,
SER_UART1,
SER_UART2,
SER_UART3,
SER_CNT //< Number of serial ports
};
/* Software errors */
#define SERRF_RXFIFOOVERRUN BV(0) //< Rx FIFO buffer overrun
#define SERRF_RXTIMEOUT BV(1) //< Receive timeout
#define SERRF_TXTIMEOUT BV(2) //< Transmit timeout
/*
* Hardware errors.
*/
#define SERRF_RXSROVERRUN 0 //< Input overrun
#define SERRF_FRAMEERROR 0 //< Stop bit missing
#define SERRF_PARITYERROR 0 //< Parity error
#define SERRF_NOISEERROR 0 //< Noise error
/* Serial error/status flags */
typedef uint32_t serstatus_t;
void lpc2_uartInit(int port);
#endif /* SER_LPC2_H */

View file

@ -0,0 +1,170 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2008 Develer S.r.l. (http://www.develer.com/)
*
* -->
*
* \brief SPI driver with DMA.
*
* \author Francesco Sacchi <batt@develer.com>
* \author Luca Ottaviano <lottaviano@develer.com>
*/
#include <drv/spi_dma.h>
#include "cfg/cfg_spi_dma.h"
#include "hw/hw_spi_dma.h"
#include <io/at91sam7.h>
#include <io/kfile.h>
#include <struct/fifobuf.h>
#include <struct/kfile_fifo.h>
#include <drv/timer.h>
#include <cpu/attr.h>
#include <cpu/power.h>
#include <string.h> /* memset */
void spi_dma_setclock(uint32_t rate)
{
SPI0_CSR0 &= ~SPI_SCBR;
ASSERT((uint8_t)DIV_ROUND(CPU_FREQ, rate));
SPI0_CSR0 |= DIV_ROUND(CPU_FREQ, rate) << SPI_SCBR_SHIFT;
}
static int spi_dma_flush(UNUSED_ARG(struct KFile *, fd))
{
/* Wait for DMA to finish */
while (!(SPI0_SR & BV(SPI_TXBUFE)))
cpu_relax();
/* Wait until last bit has been shifted out */
while (!(SPI0_SR & BV(SPI_TXEMPTY)))
cpu_relax();
return 0;
}
static size_t spi_dma_write(struct KFile *fd, const void *_buf, size_t size)
{
SPI0_PTCR = BV(PDC_TXTDIS);
SPI0_TPR = (reg32_t)_buf;
SPI0_TCR = size;
SPI0_PTCR = BV(PDC_TXTEN);
spi_dma_flush(fd);
return size;
}
/*
* Dummy buffer used to transmit 0xff chars while receiving data.
* This buffer is completetly constant and the compiler should allocate it
* in flash memory.
*/
static const uint8_t tx_dummy_buf[CONFIG_SPI_DMA_MAX_RX] = { [0 ... (CONFIG_SPI_DMA_MAX_RX - 1)] = 0xFF };
static size_t spi_dma_read(UNUSED_ARG(struct KFile *, fd), void *_buf, size_t size)
{
size_t count, total_rx = 0;
uint8_t *buf = (uint8_t *)_buf;
while (size)
{
count = MIN(size, (size_t)CONFIG_SPI_DMA_MAX_RX);
SPI0_PTCR = BV(PDC_TXTDIS) | BV(PDC_RXTDIS);
SPI0_RPR = (reg32_t)buf;
SPI0_RCR = count;
SPI0_TPR = (reg32_t)tx_dummy_buf;
SPI0_TCR = count;
/* Avoid reading the previous sent char */
*buf = SPI0_RDR;
/* Start transfer */
SPI0_PTCR = BV(PDC_RXTEN) | BV(PDC_TXTEN);
/* wait for transfer to finish */
while (!(SPI0_SR & BV(SPI_ENDRX)))
cpu_relax();
size -= count;
total_rx += count;
buf += count;
}
SPI0_PTCR = BV(PDC_RXTDIS) | BV(PDC_TXTDIS);
return total_rx;
}
#define SPI_DMA_IRQ_PRIORITY 4
void spi_dma_init(SpiDma *spi)
{
/* Disable PIO on SPI pins */
PIOA_PDR = BV(SPI0_SPCK) | BV(SPI0_MOSI) | BV(SPI0_MISO);
/* Reset device */
SPI0_CR = BV(SPI_SWRST);
/*
* Set SPI to master mode, fixed peripheral select, chip select directly connected to a peripheral device,
* SPI clock set to MCK, mode fault detection disabled, loopback disable, NPCS0 active, Delay between CS = 0
*/
SPI0_MR = BV(SPI_MSTR) | BV(SPI_MODFDIS);
/*
* Set SPI mode.
* At reset clock division factor is set to 0, that is
* *forbidden*. Set SPI clock to minimum to keep it valid.
*/
SPI0_CSR0 = BV(SPI_NCPHA) | (255 << SPI_SCBR_SHIFT);
/* Disable all irqs */
SPI0_IDR = 0xFFFFFFFF;
/* Enable SPI clock. */
PMC_PCER = BV(SPI0_ID);
/* Enable SPI */
SPI0_CR = BV(SPI_SPIEN);
DB(spi->fd._type = KFT_SPIDMA);
spi->fd.write = spi_dma_write;
spi->fd.read = spi_dma_read;
spi->fd.flush = spi_dma_flush;
SPI_DMA_STROBE_INIT();
}

View file

@ -0,0 +1,72 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2008 Develer S.r.l. (http://www.develer.com/)
*
* -->
*
* \brief SPI driver with DMA.
*
* \note Only one copy of SpiDmaAt91 is allowed for each application.
*
* \author Francesco Sacchi <batt@develer.com>
* \author Luca Ottaviano <lottaviano@develer.com>
*/
#ifndef DRV_SPI_DMA_AT91_H
#define DRV_SPI_DMA_AT91_H
#include <io/kfile.h>
typedef struct SpiDmaAt91
{
KFile fd;
} SpiDmaAt91;
#define KFT_SPIDMAAT91 MAKE_ID('S', 'P', 'I', 'A')
INLINE SpiDmaAt91 * SPIDMAAT91_CAST(KFile *fd)
{
ASSERT(fd->_type == KFT_SPIDMAAT91);
return (SpiDmaAt91 *)fd;
}
/**
* Init DMA SPI driver.
* \param spi A pointer to a SpiDmaAt91 structure.
*/
void spi_dma_init(SpiDmaAt91 *spi);
/**
* Set the clock rate for SPI bus.
*
* \param rate The rate you want to set for SPI.
*/
void spi_dma_setclock(uint32_t rate);
#endif /* DRV_SPI_DMA_AT91_H */

View file

@ -0,0 +1,54 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2008 Develer S.r.l. (http://www.develer.com/)
*
* -->
*
* \brief Low-level stepper timer module for ARM (inplementation).
*
*
* \author Daniele Basile <asterix@develer.com>
*
* This module is automatically included so no need to include
* in test list.
* notest: arm
*/
#ifndef WIZ_AUTOGEN
#warning This file is deprecated, you should use stepper_at91.c
#include <cpu/detect.h>
#if CPU_ARM_AT91
#include "stepper_at91.c"
/*#elif Add other ARM families here */
#else
#error Unknown CPU
#endif
#endif /* WIZ_AUTOGEN */

View file

@ -0,0 +1,47 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2008 Develer S.r.l. (http://www.develer.com/)
*
* -->
*
* \brief Low-level stepper timer module for ARM (inplementation).
*
*
* \author Daniele Basile <asterix@develer.com>
*
*/
#include <cpu/detect.h>
#if CPU_ARM_AT91
#include "stepper_at91.h"
/*#elif Add other ARM families here */
#else
#error Unknown CPU
#endif

View file

@ -0,0 +1,417 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2008 Develer S.r.l. (http://www.develer.com/)
* All Rights Reserved.
* -->
*
* \brief Stepper driver interface implementation.
*
* This module use the three timer on the at91 family, to generate a
* six periodic variable pwm waveform. The pulse width is fix, and could
* change by setting the STEPPER_DELAY_ON_COMPARE_C define, but you make
* an attention to do this, becouse the pulse width is not exactly
* STEPPER_DELAY_ON_COMPARE_C. The pulse width depend also to latency
* time of cpu to serve an interrupt, this generate an pwm waveform affect
* to noise. This noise not effect the period but only the pulse width,
* becouse the raising edge is generate by hardware comply with the our
* period settings.
*
* Note: is most important to set STEPPER_DELAY_ON_COMPARE_C value minor
* than a interrupt time service, becouse the falling edge must be happen
* inside to inerrupt service to guarantee a correct functionaly of pwm
* generator.
*
*
*
* \author Daniele Basile <asterix@develer.com>
*/
#include "stepper_at91.h"
#include "cfg/cfg_stepper.h"
#include <cfg/macros.h>
#include <cfg/debug.h>
#include <cpu/types.h>
#include <cpu/irq.h>
#include <io/arm.h>
/*
* Delay to set C compare to clear output
* on select TIO output
*/
#define STEPPER_DELAY_ON_COMPARE_C 20
/*
* Forward declaration for interrupt handler
*/
static ISR_PROTO(stepper_tc0_irq);
static ISR_PROTO(stepper_tc1_irq);
static ISR_PROTO(stepper_tc2_irq);
///< Static array of timer counter struct for stepper.
static struct TimerCounter stepper_timers[CONFIG_TC_STEPPER_MAX_NUM] =
{
{ //Timer Counter settings for TIOA0 output pin
.timer_id = TC0_ID,
.blk_ctrl_set = TC_NONEXC0,
.chl_mode_reg = &TC0_CMR,
.chl_ctrl_reg = &TC0_CCR,
.comp_effect_mask = TC_ACPA_MASK,
.comp_effect_set = TC_ACPA_SET_OUTPUT,
.comp_effect_clear = TC_ACPA_CLEAR_OUTPUT,
.comp_effect_c_mask = TC_ACPC_MASK,
.comp_effect_c_clear = TC_ACPC_CLEAR_OUTPUT,
.ext_event_set = TC_EEVT_XC0,
.comp_reg = &TC0_RA,
.comp_c_reg = &TC0_RC,
.count_val_reg = &TC0_CV,
.irq_enable_reg = &TC0_IER,
.irq_disable_reg = &TC0_IDR,
.irq_set_mask = BV(TC_CPAS),
.irq_mask_reg = &TC0_IMR,
.isr = stepper_tc0_irq,
.status_reg = &TC0_SR,
.tio_pin = TIOA0,
.callback = NULL,
.motor = NULL,
},
{ //Timer Counter settings for TIOB0 output pin
.timer_id = TC0_ID,
.blk_ctrl_set = TC_NONEXC0,
.chl_mode_reg = &TC0_CMR,
.chl_ctrl_reg = &TC0_CCR,
.comp_reg = &TC0_RB,
.comp_c_reg = &TC0_RC,
.count_val_reg = &TC0_CV,
.comp_effect_mask = TC_BCPB_MASK,
.comp_effect_set = TC_BCPB_SET_OUTPUT,
.comp_effect_clear = TC_BCPB_CLEAR_OUTPUT,
.comp_effect_c_mask = TC_BCPC_MASK,
.comp_effect_c_clear = TC_BCPC_CLEAR_OUTPUT,
.ext_event_set = TC_EEVT_XC0,
.irq_enable_reg = &TC0_IER,
.irq_disable_reg = &TC0_IDR,
.irq_set_mask = BV(TC_CPBS),
.irq_mask_reg = &TC0_IMR,
.isr = stepper_tc0_irq,
.status_reg = &TC0_SR,
.tio_pin = TIOB0,
.callback = NULL,
.motor = NULL,
},
{ //Timer Counter settings for TIOA1 output pin
.timer_id = TC1_ID,
.blk_ctrl_set = TC_NONEXC1,
.chl_mode_reg = &TC1_CMR,
.chl_ctrl_reg = &TC1_CCR,
.comp_reg = &TC1_RA,
.comp_c_reg = &TC1_RC,
.count_val_reg = &TC1_CV,
.comp_effect_mask = TC_ACPA_MASK,
.comp_effect_set = TC_ACPA_SET_OUTPUT,
.comp_effect_clear = TC_ACPA_CLEAR_OUTPUT,
.comp_effect_c_mask = TC_ACPC_MASK,
.comp_effect_c_clear = TC_ACPC_CLEAR_OUTPUT,
.ext_event_set = TC_EEVT_XC1,
.irq_enable_reg = &TC1_IER,
.irq_disable_reg = &TC1_IDR,
.irq_set_mask = BV(TC_CPAS),
.irq_mask_reg = &TC1_IMR,
.isr = stepper_tc1_irq,
.status_reg = &TC1_SR,
.tio_pin = TIOA1,
.callback = NULL,
.motor = NULL,
},
{ //Timer Counter settings for TIOB1 output pin
.timer_id = TC1_ID,
.blk_ctrl_set = TC_NONEXC1,
.chl_mode_reg = &TC1_CMR,
.chl_ctrl_reg = &TC1_CCR,
.comp_reg = &TC1_RB,
.comp_c_reg = &TC1_RC,
.count_val_reg = &TC1_CV,
.comp_effect_mask = TC_BCPB_MASK,
.comp_effect_set = TC_BCPB_SET_OUTPUT,
.comp_effect_clear = TC_BCPB_CLEAR_OUTPUT,
.comp_effect_c_mask = TC_BCPC_MASK,
.comp_effect_c_clear = TC_BCPC_CLEAR_OUTPUT,
.ext_event_set = TC_EEVT_XC1,
.irq_enable_reg = &TC1_IER,
.irq_disable_reg = &TC1_IDR,
.irq_set_mask = BV(TC_CPBS),
.irq_mask_reg = &TC1_IMR,
.isr = stepper_tc1_irq,
.status_reg = &TC1_SR,
.tio_pin = TIOB1,
.callback = NULL,
.motor = NULL,
},
{ //Timer Counter settings for TIOA2 output pin
.timer_id = TC2_ID,
.blk_ctrl_set = TC_NONEXC2,
.chl_mode_reg = &TC2_CMR,
.chl_ctrl_reg = &TC2_CCR,
.comp_reg = &TC2_RA,
.comp_c_reg = &TC2_RC,
.count_val_reg = &TC2_CV,
.comp_effect_mask = TC_ACPA_MASK,
.comp_effect_set = TC_ACPA_SET_OUTPUT,
.comp_effect_clear = TC_ACPA_CLEAR_OUTPUT,
.comp_effect_c_mask = TC_ACPC_MASK,
.comp_effect_c_clear = TC_ACPC_CLEAR_OUTPUT,
.ext_event_set = TC_EEVT_XC2,
.irq_enable_reg = &TC2_IER,
.irq_disable_reg = &TC2_IDR,
.irq_set_mask = BV(TC_CPAS),
.irq_mask_reg = &TC2_IMR,
.isr = stepper_tc2_irq,
.status_reg = &TC2_SR,
.tio_pin = TIOA2,
.callback = NULL,
.motor = NULL,
},
{ //Timer Counter settings for TIOB2 output pin
.timer_id = TC2_ID,
.blk_ctrl_set = TC_NONEXC2,
.chl_mode_reg = &TC2_CMR,
.chl_ctrl_reg = &TC2_CCR,
.comp_reg = &TC2_RB,
.comp_c_reg = &TC2_RC,
.count_val_reg = &TC2_CV,
.comp_effect_mask = TC_BCPB_MASK,
.comp_effect_set = TC_BCPB_SET_OUTPUT,
.comp_effect_clear = TC_BCPB_CLEAR_OUTPUT,
.comp_effect_c_mask = TC_BCPC_MASK,
.comp_effect_c_clear = TC_BCPC_CLEAR_OUTPUT,
.ext_event_set = TC_EEVT_XC2,
.irq_enable_reg = &TC2_IER,
.irq_disable_reg = &TC2_IDR,
.irq_set_mask = BV(TC_CPBS),
.irq_mask_reg = &TC2_IMR,
.isr = stepper_tc2_irq,
.status_reg = &TC2_SR,
.tio_pin = TIOB2,
.callback = NULL,
.motor = NULL,
}
};
/**
* Generic TIO interrupt handler.
*/
INLINE void stepper_tc_tio_irq(struct TimerCounter * t)
{
//
*t->chl_mode_reg &= ~t->comp_effect_c_mask;
*t->chl_mode_reg |= t->comp_effect_c_clear;
/*
* Cleat TIO output on c register compare.
* This generate an pulse with variable lenght, this
* depend to delay that interrupt is realy service.
*/
*t->comp_c_reg = *t->count_val_reg + STEPPER_DELAY_ON_COMPARE_C;
//Call the associate callback
t->callback(t->motor);
*t->chl_mode_reg &= ~t->comp_effect_c_mask;
}
/*
* Interrupt handler for timer counter TCKL0
*/
DECLARE_ISR(stepper_tc0_irq)
{
/*
* Warning: when we read the status_reg register, we reset it.
* That mean if is occur an interrupt event we can read only
* the last that has been occur. To not miss an interrupt event
* we save the status_reg register and then we read it.
*/
uint32_t status_reg = TC0_SR & TC0_IMR;
if (status_reg & BV(TC_CPAS))
stepper_tc_tio_irq(&stepper_timers[TC_TIOA0]);
if (status_reg & BV(TC_CPBS))
stepper_tc_tio_irq(&stepper_timers[TC_TIOB0]);
/* Inform hw that we have served the IRQ */
AIC_EOICR = 0;
}
/*
* Interrupt handler for timer counter TCKL1
*/
DECLARE_ISR(stepper_tc1_irq)
{
/*
* Warning: when we read the status_reg register, we reset it.
* That mean if is occur an interrupt event we can read only
* the last that has been occur. To not miss an interrupt event
* we save the status_reg register and then we read it.
*/
uint32_t status_reg = TC1_SR & TC1_IMR;
if (status_reg & BV(TC_CPAS))
stepper_tc_tio_irq(&stepper_timers[TC_TIOA1]);
if (status_reg & BV(TC_CPBS))
stepper_tc_tio_irq(&stepper_timers[TC_TIOB1]);
/* Inform hw that we have served the IRQ */
AIC_EOICR = 0;
}
/*
* Interrupt handler for timer counter TCKL2
*/
DECLARE_ISR(stepper_tc2_irq)
{
/*
* Warning: when we read the status_reg register, we reset it.
* That mean if is occur an interrupt event we can read only
* the last that has been occur. To not miss an interrupt event
* we save the status_reg register and then we read it.
*/
uint32_t status_reg = TC2_SR & TC2_IMR;
if (status_reg & BV(TC_CPAS))
stepper_tc_tio_irq(&stepper_timers[TC_TIOA2]);
if (status_reg & BV(TC_CPBS))
stepper_tc_tio_irq(&stepper_timers[TC_TIOB2]);
/* Inform hw that we have served the IRQ */
AIC_EOICR = 0;
}
/**
* Timer couter setup.
*
* This function apply to select timer couter all needed settings.
* Every settings are stored in stepper_timers[].
*/
void stepper_tc_setup(int index, stepper_isr_t callback, struct Stepper *motor)
{
ASSERT(index < CONFIG_TC_STEPPER_MAX_NUM);
motor->timer = &stepper_timers[index];
//Disable PIO controller and enable TIO function
TIO_PIO_PDR = BV(motor->timer->tio_pin);
TIO_PIO_ABSR = BV(motor->timer->tio_pin);
/*
* Sets timer counter in waveform mode.
* We set as default:
* - Waveform mode 00 (see datasheet for more detail.)
* - Master clock prescaler to STEPPER_MCK_PRESCALER
* - Set none external event
* - Clear pin output on comp_reg
* - None effect on reg C compare
*/
*motor->timer->chl_mode_reg = BV(TC_WAVE);
*motor->timer->chl_mode_reg |= motor->timer->ext_event_set;
*motor->timer->chl_mode_reg &= ~TC_WAVSEL_MASK;
*motor->timer->chl_mode_reg |= TC_WAVSEL_UP;
*motor->timer->chl_mode_reg |= STEPPER_MCK_PRESCALER;
*motor->timer->chl_mode_reg |= motor->timer->comp_effect_clear;
*motor->timer->chl_mode_reg &= ~motor->timer->comp_effect_c_mask;
//Reset comp_reg and C compare register
*motor->timer->comp_reg = 0;
*motor->timer->comp_c_reg = 0;
//Register interrupt vector
cpu_flags_t flags;
IRQ_SAVE_DISABLE(flags);
/*
* Warning: To guarantee a correct management of interrupt event, we must
* trig the interrupt on level sensitive. This becouse, we have only a common
* line for interrupt request, and if we have at the same time two interrupt
* request could be that the is service normaly but the second will never
* been detected and interrupt will stay active but never serviced.
*/
AIC_SVR(motor->timer->timer_id) = motor->timer->isr;
AIC_SMR(motor->timer->timer_id) = AIC_SRCTYPE_INT_LEVEL_SENSITIVE;
AIC_IECR = BV(motor->timer->timer_id);
// Disable interrupt on select timer counter
stepper_tc_irq_disable(motor->timer);
IRQ_RESTORE(flags);
//Register callback
motor->timer->callback = callback;
motor->timer->motor = motor;
}
/**
* Timer counter init.
*/
void stepper_tc_init(void)
{
STEPPER_STROBE_INIT;
ASSERT(CONFIG_NUM_STEPPER_MOTORS <= CONFIG_TC_STEPPER_MAX_NUM);
/*
* Enable timer counter:
* - power on all timer counter
* - disable all interrupt
* - disable all external event/timer source
*/
for (int i = 0; i < CONFIG_TC_STEPPER_MAX_NUM; i++)
{
PMC_PCER = BV(stepper_timers[i].timer_id);
*stepper_timers[i].irq_disable_reg = 0xFFFFFFFF;
TC_BMR = stepper_timers[i].blk_ctrl_set;
}
/*
* Enable timer counter and start it.
*/
for (int i = 0; i < CONFIG_TC_STEPPER_MAX_NUM; i++)
*stepper_timers[i].chl_ctrl_reg = (BV(TC_CLKEN) | BV(TC_SWTRG));
}

View file

@ -0,0 +1,185 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2008 Develer S.r.l. (http://www.develer.com/)
* All Rights Reserved.
* -->
*
* \brief Stepper hardware-specific definitions
*
*
* \author Daniele Basile <asterix@develer.com>
*/
#include <cfg/compiler.h>
#include <cfg/macros.h>
#include <drv/stepper.h>
#include <io/arm.h>
/**
* Setting master clock prescaler for all timer couter
*
* You could choise one of these:
* - TC_CLKS_MCK2: Selects MCK / 2
* - TC_CLKS_MCK8: Selects MCK / 8
* - TC_CLKS_MCK32: Selects MCK / 32
* - TC_CLKS_MCK128: Selects MCK / 128
* - TC_CLKS_MCK1024: Selects MCK / 1024
*/
#if STEPPER_PRESCALER_LOG2 == 1
#define STEPPER_MCK_PRESCALER TC_CLKS_MCK2
#elif STEPPER_PRESCALER_LOG2 == 3
#define STEPPER_MCK_PRESCALER TC_CLKS_MCK8
#elif STEPPER_PRESCALER_LOG2 == 5
#define STEPPER_MCK_PRESCALER TC_CLKS_MCK32
#elif STEPPER_PRESCALER_LOG2 == 7
#define STEPPER_MCK_PRESCALER TC_CLKS_MCK128
#elif STEPPER_PRESCALER_LOG2 == 10
#define STEPPER_MCK_PRESCALER TC_CLKS_MCK1024
#else
#error Unsupported stepper prescaler value.
#endif
/**
* Timer counter hw enumeration.
*/
enum
{
TC_TIOA0 = 0,
TC_TIOB0,
TC_TIOA1,
TC_TIOB1,
TC_TIOA2,
TC_TIOB2,
TC_CNT
};
/**
* IRQ callback function type definition.
*/
typedef void (*irq_t)(void);
/**
* Timer contex structure.
*/
typedef struct TimerCounter
{
int timer_id; ///< Timer counter ID
uint32_t blk_ctrl_set; ///< Control block setting for this timer
reg32_t *chl_mode_reg; ///< Channel mode register
reg32_t *chl_ctrl_reg; ///< Channel control register
reg32_t *comp_reg; ///< Compare register
reg32_t *comp_c_reg; ///< C compare register
reg32_t *count_val_reg; ///< Current timer counter value
uint32_t comp_effect_mask; ///< Bit mask for TIO register compare effects
uint32_t comp_effect_set; ///< Set TIO on register compare event
uint32_t comp_effect_clear; ///< Clear TIO on register compare event
uint32_t comp_effect_c_mask; ///< Bit mask for TIO on C register compare effects
uint32_t comp_effect_c_clear; ///< Clear TIO on C register compare event
uint32_t ext_event_set; ///< Setting for extern event trigger for TIOB
reg32_t *irq_enable_reg; ///< Enable interrupt register
reg32_t *irq_disable_reg; ///< Disable interrupt register
uint32_t irq_set_mask; ///< IRQ flag bit for select TIO
reg32_t *irq_mask_reg; ///< IRQ mask register
irq_t isr; ///< IRQ handler
reg32_t *status_reg; ///< Timer status register
int tio_pin; ///< Timer I/O pin
stepper_isr_t callback; ///< Interrupt callback pointer
struct Stepper *motor; ///< Stepper context structure
} TimerCounter;
/**
* Enable interrupt for timer counter compare event.
*/
INLINE void stepper_tc_irq_enable(struct TimerCounter *timer)
{
*timer->irq_enable_reg = timer->irq_set_mask;
}
/**
* Disable interrupt for timer counter compare event.
*/
INLINE void stepper_tc_irq_disable(struct TimerCounter *timer)
{
*timer->irq_disable_reg = timer->irq_set_mask;
}
/**
* Set delay for next interrupt compare event.
*/
INLINE void stepper_tc_setDelay(struct TimerCounter *timer, stepper_time_t delay)
{
*timer->comp_reg += delay;
}
/**
* Set delay for next interrupt compare event.
*/
INLINE void stepper_tc_resetTimer(struct TimerCounter *timer)
{
*timer->comp_reg = 0;
}
/**
* Programm timer counter to generate a pulse on select TIO output.
*/
INLINE void FAST_FUNC stepper_tc_doPulse(struct TimerCounter *timer)
{
*timer->chl_mode_reg &= ~timer->comp_effect_mask;
*timer->chl_mode_reg |= timer->comp_effect_set;
}
/**
* Programm timer counter to not generate a pulse on select TIO output.
*/
INLINE void FAST_FUNC stepper_tc_skipPulse(struct TimerCounter *timer)
{
*timer->chl_mode_reg &= ~timer->comp_effect_mask;
}
void stepper_tc_setup(int index, stepper_isr_t callback, struct Stepper *motor);
void stepper_tc_init(void);
/*
* Test the hardware timer counter on board.
* This test generate a square waveform through irq, setting
* the timer register.
*/
void stepper_timer_test_brute(void);
/*
* Test the timer driver structure.
* This test generate a square waveform through irq.
* The irq callback is programmable, and all timer setting
* are save in one data structure. Every pulse is generate through
* a call of this irq callback.
*/
void stepper_timer_test_prestepper(struct Stepper *local_motor, struct StepperConfig *local_cfg, int index);

View file

@ -0,0 +1,174 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2008 Develer S.r.l. (http://www.develer.com/)
* All Rights Reserved.
* -->
*
* \brief Low level test for stepper driver interface implementation.
*
*
* \author Daniele Basile <asterix@develer.com>
*/
#include "stepper_at91.h"
#include "cfg/cfg_stepper.h"
#include <cfg/macros.h>
#include <cfg/debug.h>
#include <cpu/types.h>
#include <cpu/irq.h>
#include <io/arm.h>
#warning FIXME:This test is incomplete.. you MUST review..
#if 0
static void stepper_test_irq_schedule(struct Stepper *motor, stepper_time_t delay)
{
stepper_tc_doPulse(motor->timer);
stepper_tc_setDelay(motor->timer, delay);
}
static void stepper_test_irq(struct Stepper *motor)
{
stepper_test_irq_schedule(motor, 300);
}
/*
* Test a timer couter driver
*/
void stepper_timer_test_prestepper(struct Stepper *local_motor, struct StepperConfig *local_cfg, int index)
{
local_cfg->pulse = 300;
local_motor->cfg = local_cfg;
stepper_tc_init(index, &stepper_test_irq, local_motor);
stepper_tc_irq_enable(local_motor->timer);
}
bool su = true;
bool sub = true;
uint16_t periodo_st0 = 100;
uint16_t periodo_st1 = 233;
static void tc_irq(void) __attribute__ ((interrupt));
static void tc_irq(void)
{
uint32_t status_reg = TC2_SR & TC2_IMR;
if (status_reg & BV(TC_CPAS))
{
TC2_CMR &= ~TC_ACPA_MASK;
if (su)
{
TC2_CMR |= TC_ACPA_CLEAR_OUTPUT;
TC2_RA += periodo_st0;
}
else
{
TC2_CMR |= TC_ACPA_SET_OUTPUT;
TC2_RA += periodo_st1;
}
su = !su;
}
if (status_reg & BV(TC_CPBS))
{
TC2_CMR &= ~TC_BCPB_MASK ;
if (sub)
{
TC2_CMR |= TC_BCPB_CLEAR_OUTPUT;
TC2_RB += periodo_st0;
}
else
{
TC2_CMR |= TC_BCPB_SET_OUTPUT;
TC2_RB += periodo_st1;
}
sub = !sub;
}
/* Inform hw that we have served the IRQ */
AIC_EOICR = 0;
}
/*
* Test a timer couter hardware
*/
void stepper_timer_test_brute(void)
{
PIOA_PDR |= BV(26) | BV(27);
PIOA_BSR |= BV(26) | BV(27);
// Power on TCLK0
PMC_PCER |= BV(TC2_ID);// | BV(TC1_ID) | BV(TC2_ID);
TC_BCR = 1;
TC_BMR |= TC_NONEXC2;
// Select waveform mode
TC2_CMR = BV(TC_WAVE);
TC2_CMR |= TC_EEVT_XC2;
TC2_CMR |= TC_WAVSEL_UP;
TC2_CMR |= TC_CLKS_MCK8;
//Set waveform on TIOA and TIOB
TC2_CMR |= TC_ACPA_SET_OUTPUT;
TC2_CMR |= TC_BCPB_SET_OUTPUT;
//Reset all comp_reg register
TC2_RA = 0;
TC2_RB = 0;
cpuflags_t flags;
IRQ_SAVE_DISABLE(flags);
/* Set the vector. */
AIC_SVR(TC2_ID) = tc_irq;
/* Initialize to edge triggered with defined priority. */
AIC_SMR(TC2_ID) = AIC_SRCTYPE_INT_EDGE_TRIGGERED;
/* Enable the USART IRQ */
AIC_IECR = BV(TC2_ID);
IRQ_RESTORE(flags);
// Disable all interrupt
TC2_IDR = 0xFFFFFFFF;
//Enable interrupt on RA, RB
TC2_IER = BV(TC_CPAS) | BV(TC_CPBS);
//Enable timer and trig it
TC2_CCR = BV(TC_CLKEN) | BV(TC_SWTRG);
}
#endif

View file

@ -0,0 +1,176 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2007 Develer S.r.l. (http://www.develer.com/)
*
* -->
*
*
* \author Francesco Sacchi <batt@develer.com>
*
* \brief System IRQ handler for Atmel AT91 ARM7 processors.
*
* In Atmel AT91 ARM7TDMI processors, there are various
* peripheral interrupt sources.
* In general, every source has its own interrupt vector, so it
* is possible to assign a specific handler for each interrupt
* independently.
* However, there are a few sources called "system sources" that
* share a common IRQ line and vector, called "system IRQ".
* So a unique system IRQ dispatcher is implemented here.
* This module also contains an interface to manage every source
* independently. It is possible to assign to every system IRQ
* a specific IRQ handler.
*
* \see sysirq_setHandler
* \see sysirq_setEnable
*/
#include "sysirq_at91.h"
#include <io/arm.h>
#include <cpu/irq.h>
#include <cpu/types.h>
#include <cfg/module.h>
#include <cfg/macros.h>
/**
* Enable/disable the Periodic Interrupt Timer
* interrupt.
*/
INLINE void pit_setEnable(bool enable)
{
if (enable)
PIT_MR |= BV(PITIEN);
else
PIT_MR &= ~BV(PITIEN);
}
/**
* Table containing all system irqs.
*/
static SysIrq sysirq_tab[] =
{
/* PIT, Periodic Interval Timer (System timer)*/
{
.enabled = false,
.setEnable = pit_setEnable,
.handler = NULL,
},
/* TODO: add other system sources here */
};
STATIC_ASSERT(countof(sysirq_tab) == SYSIRQ_CNT);
/**
* System IRQ dispatcher.
* This is the entry point for all system IRQs in AT91.
* This function checks for interrupt enable state of
* various sources (system timer, etc..) and calls
* the corresponding handler.
*
* \note On AT91SAM7, all system IRQs (timer included) are handled
* by the sysirq_dispatcher, so we can't differentiate between
* context-switch and non-context-switch ISR inside this
* class of IRQs.
*/
static DECLARE_ISR_CONTEXT_SWITCH(sysirq_dispatcher)
{
unsigned int i;
for (i = 0; i < countof(sysirq_tab); i++)
{
if (sysirq_tab[i].enabled
&& sysirq_tab[i].handler)
sysirq_tab[i].handler();
}
/* Inform hw that we have served the IRQ */
AIC_EOICR = 0;
}
#define SYSIRQ_PRIORITY 0 ///< default priority for system irqs.
MOD_DEFINE(sysirq);
/**
* Init system IRQ handling.
* \note all system interrupts are disabled.
*/
void sysirq_init(void)
{
cpu_flags_t flags;
IRQ_SAVE_DISABLE(flags);
/* Disable all system interrupts */
for (unsigned i = 0; i < countof(sysirq_tab); i++)
sysirq_tab[i].setEnable(false);
/* Set the vector. */
AIC_SVR(SYSC_ID) = sysirq_dispatcher;
/* Initialize to edge triggered with defined priority. */
AIC_SMR(SYSC_ID) = AIC_SRCTYPE_INT_EDGE_TRIGGERED | SYSIRQ_PRIORITY;
/* Clear pending interrupt */
AIC_ICCR = BV(SYSC_ID);
/* Enable the system IRQ */
AIC_IECR = BV(SYSC_ID);
IRQ_RESTORE(flags);
MOD_INIT(sysirq);
}
/**
* Helper function used to set handler for system IRQ \a irq.
*/
void sysirq_setHandler(sysirq_t irq, sysirq_handler_t handler)
{
ASSERT(irq < SYSIRQ_CNT);
sysirq_tab[irq].handler = handler;
}
/**
* Helper function used to enable/disable system IRQ \a irq.
*/
void sysirq_setEnable(sysirq_t irq, bool enable)
{
ASSERT(irq < SYSIRQ_CNT);
sysirq_tab[irq].setEnable(enable);
sysirq_tab[irq].enabled = enable;
}
/**
* Helper function used to get system IRQ \a irq state.
*/
bool sysirq_enabled(sysirq_t irq)
{
ASSERT(irq < SYSIRQ_CNT);
return sysirq_tab[irq].enabled;
}

View file

@ -0,0 +1,72 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2007 Develer S.r.l. (http://www.develer.com/)
*
* -->
*
*
* \author Francesco Sacchi <batt@develer.com>
*
* \brief System irq handler for Atmel AT91 ARM7 processors (interface).
*/
#ifndef DRV_AT91_SYSIRQ_H
#define DRV_AT91_SYSIRQ_H
#include <cfg/compiler.h>
typedef void (* sysirq_handler_t)(void); ///< Type for system irq handler.
typedef void (* sysirq_setEnable_t)(bool); ///< Type for system irq enable/disable function.
/**
* Structure used to define a system interrupt source.
*/
typedef struct SysIrq
{
bool enabled; ///< Getter for irq enable/disable state.
sysirq_setEnable_t setEnable; ///< Setter for irq enable/disable state.
sysirq_handler_t handler; ///< IRQ handler.
} SysIrq;
/**
* System IRQ ID list.
*/
typedef enum sysirq_t
{
SYSIRQ_PIT, ///< Periodic Interval Timer
/* TODO: add all system irqs */
SYSIRQ_CNT
} sysirq_t;
void sysirq_init(void);
void sysirq_setHandler(sysirq_t irq, sysirq_handler_t handler);
void sysirq_setEnable(sysirq_t irq, bool enable);
bool sysirq_enabled(sysirq_t irq);
#endif /* ARCH_ARM_SYSIRQ_H */

View file

@ -0,0 +1,56 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2007 Develer S.r.l. (http://www.develer.com/)
*
* -->
*
*
* \author Francesco Sacchi <batt@develer.com>
*
* \brief Low-level timer module for ARM (inplementation).
*
* This module is automatically included so no need to include
* in test list.
* notest: arm
*/
#ifndef WIZ_AUTOGEN
#warning This file is deprecated, you should use timer_at91.c
#include <cpu/detect.h>
#include <cfg/cfg_arch.h>
#if CPU_ARM_AT91
#include "timer_at91.c"
/*#elif Add other ARM families here */
#else
#error Unknown CPU
#endif
#endif /* WIZ_AUTOGEN */

View file

@ -0,0 +1,48 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2007 Develer S.r.l. (http://www.develer.com/)
*
* -->
*
*
* \author Francesco Sacchi <batt@develer.com>
*
* \brief Low-level timer module for ARM (interface).
*/
#include <cpu/detect.h>
#if CPU_ARM_AT91
#include "timer_at91.h"
#elif CPU_ARM_LPC2
#include "timer_lpc2.h"
/*#elif Add other ARM families here */
#else
#error Unknown CPU
#endif

View file

@ -0,0 +1,80 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2007 Develer S.r.l. (http://www.develer.com/)
*
* -->
*
* \author Francesco Sacchi <batt@develer.com>
*
* \brief Low-level timer module for Atmel AT91 (inplementation).
*/
#include "timer_at91.h"
#include <io/arm.h>
#include "sysirq_at91.h"
#include <cfg/macros.h> // BV()
#include <cfg/module.h>
#include <cpu/irq.h>
#include <cpu/types.h>
/** HW dependent timer initialization */
#if (CONFIG_TIMER == TIMER_ON_PIT)
ISR_PROTO_CONTEXT_SWITCH(timer_handler);
void timer_hw_init(void)
{
sysirq_init();
cpu_flags_t flags;
MOD_CHECK(sysirq);
IRQ_SAVE_DISABLE(flags);
PIT_MR = TIMER_HW_CNT;
/* Register system interrupt handler. */
sysirq_setHandler(SYSIRQ_PIT, timer_handler);
/* Enable interval timer and interval timer interrupts */
PIT_MR |= BV(PITEN);
sysirq_setEnable(SYSIRQ_PIT, true);
/* Reset counters, this is needed to start timer and interrupt flags */
uint32_t dummy = PIVR;
(void) dummy;
IRQ_RESTORE(flags);
}
#else
#error Unimplemented value for CONFIG_TIMER
#endif /* CONFIG_TIMER */

View file

@ -0,0 +1,108 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2007 Develer S.r.l. (http://www.develer.com/)
*
* -->
*
* \author Francesco Sacchi <batt@develer.com>
*
* \brief Low-level timer module for Atmel AT91 (interface).
*/
#ifndef DRV_AT91_TIMER_H
#define DRV_AT91_TIMER_H
#include <hw/hw_cpufreq.h> /* CPU_FREQ */
#include "cfg/cfg_timer.h" /* CONFIG_TIMER */
#include <cfg/compiler.h> /* uint8_t */
#include <cfg/macros.h> /* BV */
#include <io/arm.h>
/**
* \name Values for CONFIG_TIMER.
*
* Select which hardware timer interrupt to use for system clock and softtimers.
*
* $WIZ$ timer_select = "TIMER_ON_PIT", "TIMER_DEFAULT"
*/
#define TIMER_ON_PIT 1 ///< System timer on Periodic interval timer
#define TIMER_DEFAULT TIMER_ON_PIT ///< Default system timer
/*
* Hardware dependent timer initialization.
*/
#if (CONFIG_TIMER == TIMER_ON_PIT)
/*
* On ARM all system IRQs are handled by the sysirq_dispatcher, so the actual
* timer handler can be treated like any other normal routine.
*/
#define DEFINE_TIMER_ISR void timer_handler(void); \
void timer_handler(void)
#define TIMER_TICKS_PER_SEC 1000
#define TIMER_HW_CNT (CPU_FREQ / (16 * TIMER_TICKS_PER_SEC) - 1)
/** Frequency of the hardware high-precision timer. */
#define TIMER_HW_HPTICKS_PER_SEC (CPU_FREQ / 16)
/** Type of time expressed in ticks of the hardware high-precision timer */
typedef uint32_t hptime_t;
#define SIZEOF_HPTIME_T 4
INLINE void timer_hw_irq(void)
{
/* Reset counters, this is needed to reset timer and interrupt flags */
uint32_t dummy = PIVR;
(void) dummy;
}
INLINE bool timer_hw_triggered(void)
{
return PIT_SR & BV(PITS);
}
INLINE hptime_t timer_hw_hpread(void)
{
/* In the upper part of PIT_PIIR there is unused data */
return PIIR & CPIV_MASK;
}
#else
#error Unimplemented value for CONFIG_TIMER
#endif /* CONFIG_TIMER */
void timer_hw_init(void);
#endif /* DRV_TIMER_AT91_H */

View file

@ -0,0 +1,81 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2010 Develer S.r.l. (http://www.develer.com/)
*
* -->
*
* \author Francesco Sacchi <batt@develer.com>
*
* \brief Low-level timer module for LPC2xxx (implementation).
*
* notest:arm
*/
#include "cfg/cfg_timer.h"
#include <cfg/macros.h> // BV()
#include <cfg/debug.h> // BV()
#include <drv/vic_lpc2.h>
#include <io/lpc23xx.h>
#include "timer_lpc2.h"
/** HW dependent timer initialization */
#if (CONFIG_TIMER == TIMER0_COMPARE0)
#define TIMER0_ID 4
void timer_hw_init(void)
{
/* Power on timer0 */
PCONP |= BV(1);
/* Set TIMER0 clk to CPU_FREQ */
PCLKSEL0 &= ~0x0C;
PCLKSEL0 |= 0x04;
/* reset prescaler counter */
T0PR = 0;
/* Set match register 0 */
T0MR0 = TIMER_HW_CNT;
/* IRQ and reset counter on compare match 0 */
T0MCR &= ~0x03;
T0MCR |= 0x03;
/* Reset timer0 counter and prescaler */
T0TCR = 0x02;
vic_setVector(TIMER0_ID, timer_handler);
vic_enable(TIMER0_ID);
/* Start timer0 */
T0TCR = 0x01;
}
#else
#error Unimplemented value for CONFIG_TIMER
#endif /* CONFIG_TIMER */

View file

@ -0,0 +1,103 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2010 Develer S.r.l. (http://www.develer.com/)
*
* -->
*
* \author Francesco Sacchi <batt@develer.com>
*
* \brief Low-level timer module for NXP LPC2xxx (interface).
*/
#ifndef DRV_LPC2_TIMER_H
#define DRV_LPC2_TIMER_H
#include <hw/hw_cpufreq.h> /* CPU_FREQ */
#include "cfg/cfg_timer.h" /* CONFIG_TIMER */
#include <cfg/compiler.h> /* uint8_t */
#include <cfg/macros.h> /* BV */
#include <io/lpc23xx.h>
/**
* \name Values for CONFIG_TIMER.
*
* Select which hardware timer interrupt to use for system clock and softtimers.
*
* $WIZ$ timer_select = "TIMER0_COMPARE0", "TIMER_DEFAULT"
*/
#define TIMER0_COMPARE0 0 ///< System timer on Timer0 Compare match0
#define TIMER_DEFAULT TIMER0_COMPARE0 ///< Default system timer
/*
* Hardware dependent timer initialization.
*/
#if (CONFIG_TIMER == TIMER0_COMPARE0)
ISR_PROTO_CONTEXT_SWITCH(timer_handler);
#define DEFINE_TIMER_ISR DECLARE_ISR_CONTEXT_SWITCH(timer_handler)
#define TIMER_TICKS_PER_SEC 1000
#define TIMER_HW_CNT (CPU_FREQ / TIMER_TICKS_PER_SEC - 1)
/** Frequency of the hardware high-precision timer. */
#define TIMER_HW_HPTICKS_PER_SEC (CPU_FREQ)
/** Type of time expressed in ticks of the hardware high-precision timer */
typedef uint32_t hptime_t;
#define SIZEOF_HPTIME_T 4
INLINE void timer_hw_irq(void)
{
/* Reset The match0 irq flag */
T0IR = 0x01;
/* Signal the VIC we have completed the ISR */
VICVectAddr = 0;
}
INLINE bool timer_hw_triggered(void)
{
return true;
}
INLINE hptime_t timer_hw_hpread(void)
{
return T0TC;
}
#else
#error Unimplemented value for CONFIG_TIMER
#endif /* CONFIG_TIMER */
void timer_hw_init(void);
#endif /* DRV_LPC2_TIMER_H */

View file

@ -0,0 +1,55 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2008 Develer S.r.l. (http://www.develer.com/)
*
* -->
*
* \brief Low-level TWI module for ARM (inplementation).
*
*
* \author Daniele Basile <asterix@develer.com>
*
* This module is automatically included so no need to include
* in test list.
* notest: arm
*
*/
#ifndef WIZ_AUTOGEN
#warning This file is deprecated, you should use twi_at91.c
#include <cpu/detect.h>
#if CPU_ARM_AT91
#include "twi_at91.c"
/*#elif Add other ARM families here */
#else
#error Unknown CPU
#endif
#endif /* WIZ_AUTOGEN */

View file

@ -0,0 +1,47 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2008 Develer S.r.l. (http://www.develer.com/)
*
* -->
*
* \brief Low-level TWI module for ARM (interface).
*
*
* \author Daniele Basile <asterix@develer.com>
*
*/
#include <cpu/detect.h>
#if CPU_ARM_AT91
#include "twi_at91.h"
/*#elif Add other ARM families here */
#else
#error Unknown CPU
#endif

View file

@ -0,0 +1,267 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2008 Develer S.r.l. (http://www.develer.com/)
*
* -->
*
* \brief Driver for the AT91 ARM TWI (implementation)
*
*
* \author Francesco Sacchi <batt@develer.com>
*/
#include "twi_at91.h"
#include "cfg/cfg_i2c.h"
#include <cfg/compiler.h>
#include <cfg/debug.h>
#include <cfg/macros.h>
#include <cfg/module.h>
#include <drv/timer.h>
#include <io/arm.h>
/**
* Timeout for ACK slave waiting.
*/
#define TWI_TIMEOUT ms_to_ticks(50)
/**
* Send \a size bytes over the twi line to slave \a id.
* If the device requires internal addressing before writing, \a byte1 \a byte2 and \a byte3 can
* be specified. Internal addressign bytes not used *must* be set to TWI_NO_IADDR. If 1 or 2 bytes
* are required for internal addressing you *must* first use \a byte1 and than \a byte2.
* \note Atmel TWI implementation is broken so it was not possible to supply a better
* interface. Additionally NACK handling is also broken, so if the i2c device reply nack
* this function will return after TWI_TIMEOUT.
* \return true if ok, false on slave timeout.
*/
bool twi_write(uint8_t id, twi_iaddr_t byte1, twi_iaddr_t byte2, twi_iaddr_t byte3, const void *_buf, size_t size)
{
uint8_t addr_size = 0;
const uint8_t *buf = (const uint8_t *)_buf;
ticks_t start;
/* At least 1 byte *must* be transmitted, thanks to crappy hw implementation */
ASSERT(size >= 1);
/* Check internal byte address presence */
if (byte1 != TWI_NO_IADDR)
addr_size++;
if (byte2 != TWI_NO_IADDR)
{
ASSERT(addr_size == 1);
addr_size++;
}
if (byte3 != TWI_NO_IADDR)
{
ASSERT(addr_size == 2);
addr_size++;
}
start = timer_clock();
/* Wait tx buffer empty */
while (!(TWI_SR & BV(TWI_TXRDY)))
{
if (timer_clock() - start > TWI_TIMEOUT)
return false;
}
/* Set slave address and (optional) internal slave addresses */
TWI_MMR = (uint32_t)id << TWI_DADR_SHIFT | (uint32_t)addr_size << TWI_IADRSZ_SHIFT;
TWI_IADR = ((uint32_t)(byte3 & 0xff) << 16) | ((uint32_t)(byte2 & 0xff) << 8) | ((uint32_t)(byte1 & 0xff));
while (size--)
{
/* Send data */
TWI_THR = *buf++;
start = timer_clock();
/* Wait tx buffer empty */
while (!(TWI_SR & BV(TWI_TXRDY)))
{
if (timer_clock() - start > TWI_TIMEOUT)
return false;
}
}
/* Wait transmit complete bit */
start = timer_clock();
while (!(TWI_SR & BV(TWI_TXCOMP)))
{
if (timer_clock() - start > TWI_TIMEOUT)
return false;
}
return true;
}
/**
* Read \a size bytes from the twi line from slave \a id.
* If the device requires internal addressing before reading, \a byte1 \a byte2 and \a byte3 must
* be specified. Internal addressign bytes not used *must* be set to TWI_NO_IADDR. If 1 or 2 bytes
* are required for internal addressing you *must* first use \a byte1 and than \a byte2.
* \note Atmel TWI implementation is broken so it was not possible to supply a better
* interface. Additionally NACK handling is also broken, so if the i2c device reply nack
* this function will return after TWI_TIMEOUT.
* \return true if ok, false on slave timeout.
*/
bool twi_read(uint8_t id, twi_iaddr_t byte1, twi_iaddr_t byte2, twi_iaddr_t byte3, void *_buf, size_t size)
{
uint8_t addr_size = 0;
uint8_t *buf = (uint8_t *)_buf;
bool stopped = false;
ticks_t start;
/* At least 1 byte *must* be transmitted, thanks to crappy twi implementation */
ASSERT(size >= 1);
/* Check internal byte address presence */
if (byte1 != TWI_NO_IADDR)
addr_size++;
if (byte2 != TWI_NO_IADDR)
{
ASSERT(addr_size == 1);
addr_size++;
}
if (byte3 != TWI_NO_IADDR)
{
ASSERT(addr_size == 2);
addr_size++;
}
/* Wait tx buffer empty */
start = timer_clock();
while (!(TWI_SR & BV(TWI_TXRDY)))
{
if (timer_clock() - start > TWI_TIMEOUT)
return false;
}
/* Set slave address and (optional) internal slave addresses */
TWI_MMR = ((uint32_t)id << TWI_DADR_SHIFT) | BV(TWI_MREAD) | ((uint32_t)addr_size << TWI_IADRSZ_SHIFT);
TWI_IADR = ((uint32_t)(byte3 & 0xff) << 16) | ((uint32_t)(byte2 & 0xff) << 8) | ((uint32_t)(byte1 & 0xff));
/*
* Start reception.
* Kludge: if we want to receive only 1 byte, the stop but *must* be set here
* (thanks to crappy twi implementation again).
*/
if (size == 1)
{
TWI_CR = BV(TWI_START) | BV(TWI_STOP);
stopped = true;
}
else
TWI_CR = BV(TWI_START);
while (size--)
{
/* If we are at the last byte, inform the crappy hw that we
want to stop the reception. */
if (!size && !stopped)
TWI_CR = BV(TWI_STOP);
/* Wait until a byte is received */
start = timer_clock();
while (!(TWI_SR & BV(TWI_RXRDY)))
{
if (timer_clock() - start > TWI_TIMEOUT)
{
TWI_CR = BV(TWI_STOP);
return false;
}
}
*buf++ = TWI_RHR;
}
/* Wait transmit complete bit */
start = timer_clock();
while (!(TWI_SR & BV(TWI_TXCOMP)))
{
if (timer_clock() - start > TWI_TIMEOUT)
return false;
}
return true;
}
MOD_DEFINE(twi);
/**
* Init the (broken) sam7 twi driver.
*/
void twi_init(void)
{
/* Disable PIO on TWI pins */
PIOA_PDR = BV(TWD) | BV(TWCK);
/* Enable oper drain on TWI pins */
PIOA_MDER = BV(TWD);
/* Disable all irqs */
TWI_IDR = 0xFFFFFFFF;
TWI_CR = BV(TWI_SWRST);
/* Enable master mode */
TWI_CR = BV(TWI_MSEN);
PMC_PCER = BV(TWI_ID);
/*
* Compute twi clock.
* CLDIV = ((Tlow * 2^CKDIV) -3) * Tmck
* CHDIV = ((THigh * 2^CKDIV) -3) * Tmck
* Only CLDIV is computed since CLDIV = CHDIV (50% duty cycle)
*/
uint16_t cldiv, ckdiv = 0;
while ((cldiv = ((CPU_FREQ / (2 * CONFIG_I2C_FREQ)) - 3) / (1 << ckdiv)) > 255)
ckdiv++;
/* Atmel errata states that ckdiv *must* be less than 5 for unknown reason */
ASSERT(ckdiv < 5);
TWI_CWGR = ((uint32_t)ckdiv << TWI_CKDIV_SHIFT) | (cldiv << TWI_CLDIV_SHIFT) | (cldiv << TWI_CHDIV_SHIFT);
TRACEMSG("TWI_CWGR [%08lx]", TWI_CWGR);
MOD_INIT(twi);
}

View file

@ -0,0 +1,52 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2003, 2004, 2005 Develer S.r.l. (http://www.develer.com/)
*
* -->
*
* \brief Driver for the AT91 ARM TWI (implementation)
*
* \author Francesco Sacchi <batt@develer.com>
*/
#ifndef DRV_AT91_TWI_H
#define DRV_AT91_TWI_H
#include <cfg/compiler.h>
typedef int16_t twi_iaddr_t;
#define TWI_NO_IADDR (-1)
void twi_init(void);
bool twi_read(uint8_t id, twi_iaddr_t byte1, twi_iaddr_t byte2, twi_iaddr_t byte3, void *_buf, size_t len);
bool twi_write(uint8_t id, twi_iaddr_t byte1, twi_iaddr_t byte2, twi_iaddr_t byte3, const void *_buf, size_t len);
#endif /* DRV_AT91_TWI_H */

View file

@ -0,0 +1,51 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2010 Develer S.r.l. (http://www.develer.com/)
*
* -->
*
* \author Francesco Sacchi <batt@develer.com>
*
* \brief Vectored Interrupt Controller VIC driver.
*
* notest:arm
*/
#include "vic_lpc2.h"
#include <cfg/log.h>
void NORETURN vic_defaultHandler(void)
{
IRQ_DISABLE;
LOG_ERR("Unhandled IRQ\n"
"VICIRQStatus %08lX\n"
"VICFIQStatus %08lX\n", VICIRQStatus, VICFIQStatus);
while (1)
PAUSE;
}

View file

@ -0,0 +1,78 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2010 Develer S.r.l. (http://www.develer.com/)
*
* -->
*
* \author Francesco Sacchi <batt@develer.com>
*
* \brief Vectored Interrupt Controller VIC driver.
*/
#ifndef DRV_VIC_LPC2_H
#define DRV_VIC_LPC2_H
#include <cfg/compiler.h>
#include <cpu/irq.h>
#if CPU_ARM_LPC2378
#include <io/lpc23xx.h>
#define vic_vector(i) (*(&VICVectAddr0 + i))
#define vic_priority(i) (*(&VICVectCntl0 + i))
#define VIC_SRC_CNT 32
#define vic_enable(i) do { ASSERT(i < VIC_SRC_CNT); VICIntEnable = BV(i); } while (0)
#define vic_disable(i) do { ASSERT(i < VIC_SRC_CNT); VICIntEnClr = BV(i); } while (0)
typedef void vic_handler_t(void);
void vic_defaultHandler(void);
INLINE void vic_init(void)
{
IRQ_DISABLE;
/* Assign all sources to IRQ (not to FIQ) */
VICIntSelect = 0;
/* Disable all sw interrupts */
VICSoftIntClr = 0xFFFFFFFF;
/* Disable all interrupts */
VICIntEnClr = 0xFFFFFFFF;
for (int i = 0; i < VIC_SRC_CNT; i++)
vic_vector(i) = (reg32_t)vic_defaultHandler;
}
INLINE void vic_setVector(int id, vic_handler_t *handler)
{
ASSERT(id < VIC_SRC_CNT);
vic_vector(id) = (reg32_t)handler;
}
#else
#error Unknown CPU
#endif
#endif /* DRV_VIC_LPC2_H */

View file

@ -0,0 +1,50 @@
/**
* \file
* <!--
* This file is part of BeRTOS.
*
* Bertos 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 2 of the License, or
* (at your option) any later version.
*
* This program 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, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* As a special exception, you may use this file as part of a free software
* library without restriction. Specifically, if other files instantiate
* templates or use macros or inline functions from this file, or you compile
* this file and link it with other files to produce an executable, this
* file does not by itself cause the resulting executable to be covered by
* the GNU General Public License. This exception does not however
* invalidate any other reasons why the executable file might be covered by
* the GNU General Public License.
*
* Copyright 2009 Develer S.r.l. (http://www.develer.com/)
*
* -->
*
* \brief Watchdog interface for ARM architecture.
*
*
* \author Luca Ottaviano <lottaviano@develer.com>
*
*/
#ifndef DRV_WDT_ARM_H
#define DRV_WDT_ARM_H
#include <cfg/compiler.h> // INLINE
#warning TODO: This module is not implemented for at91 CPUs
INLINE void wdt_start(uint32_t _timeout) { (void) _timeout; /* implement me */ }
INLINE void wdt_stop(void) { /*implement me */ }
INLINE void wdt_reset(void) { /* implement me */ }
#endif //DRV_WDT_ARM_H