bsps/mcf5206elite: Move libcpu content to bsps

This patch is a part of the BSP source reorganization.

Update #3285.
This commit is contained in:
Sebastian Huber
2018-03-26 12:20:45 +02:00
parent 3cf2bf633f
commit 2190bc61bf
7 changed files with 5 additions and 33 deletions

View File

@@ -46,12 +46,11 @@ libbsp_a_SOURCES += nvram/nvram.c
libbsp_a_SOURCES += ../../../../../../bsps/shared/cache/nocache.c
libbsp_a_SOURCES += ../../../../../../bsps/m68k/shared/m68kidle.c
libbsp_a_SOURCES += ../../../../../../bsps/m68k/shared/memProbe.c
libbsp_a_LIBADD = \
../../../libcpu/@RTEMS_CPU@/mcf5206/clock.rel \
../../../libcpu/@RTEMS_CPU@/mcf5206/mcfuart.rel \
../../../libcpu/@RTEMS_CPU@/mcf5206/timer.rel \
../../../libcpu/@RTEMS_CPU@/mcf5206/mbus.rel
libbsp_a_SOURCES += ../../../../../../bsps/m68k/mcf5206elite/dev/ckinit.c
libbsp_a_SOURCES += ../../../../../../bsps/m68k/mcf5206elite/dev/mcfmbus.c
libbsp_a_SOURCES += ../../../../../../bsps/m68k/mcf5206elite/dev/mcfuart.c
libbsp_a_SOURCES += ../../../../../../bsps/m68k/mcf5206elite/dev/timer.c
libbsp_a_SOURCES += ../../../../../../bsps/m68k/mcf5206elite/dev/timerisr.S
include $(top_srcdir)/../../../../automake/local.am
include $(srcdir)/../../../../../../bsps/m68k/mcf5206elite/headers.am

View File

@@ -4,33 +4,6 @@ include $(top_srcdir)/../../../automake/compile.am
noinst_PROGRAMS =
if mcf5206
# mcf5206/include
## mcf5206/clock
noinst_PROGRAMS += mcf5206/clock.rel
mcf5206_clock_rel_SOURCES = mcf5206/clock/ckinit.c
mcf5206_clock_rel_CPPFLAGS = $(AM_CPPFLAGS)
mcf5206_clock_rel_LDFLAGS = $(RTEMS_RELLDFLAGS)
## mcf5206/mcfuart
noinst_PROGRAMS += mcf5206/mcfuart.rel
mcf5206_mcfuart_rel_SOURCES = mcf5206/console/mcfuart.c
mcf5206_mcfuart_rel_CPPFLAGS = $(AM_CPPFLAGS)
mcf5206_mcfuart_rel_LDFLAGS = $(RTEMS_RELLDFLAGS)
## mcf5206/mbus
noinst_PROGRAMS += mcf5206/mbus.rel
mcf5206_mbus_rel_SOURCES = mcf5206/mbus/mcfmbus.c
mcf5206_mbus_rel_CPPFLAGS = $(AM_CPPFLAGS)
mcf5206_mbus_rel_LDFLAGS = $(RTEMS_RELLDFLAGS)
## mcf5206/timer
noinst_PROGRAMS += mcf5206/timer.rel
mcf5206_timer_rel_SOURCES = mcf5206/timer/timer.c mcf5206/timer/timerisr.S
mcf5206_timer_rel_CPPFLAGS = $(AM_CPPFLAGS)
mcf5206_timer_rel_LDFLAGS = $(RTEMS_RELLDFLAGS)
endif
if mcf5272
## mcf5272/include
## clock

View File

@@ -1,113 +0,0 @@
/*
* Clock Driver for MCF5206eLITE board
*
* This driver initailizes timer1 on the MCF5206E as the
* main system clock
*/
/*
* Author: Victor V. Vengerov <vvv@oktet.ru>
*
* Based on work:
* David Fiddes, D.J@fiddes.surfaid.org
* http://www.calm.hw.ac.uk/davidf/coldfire/
*
* COPYRIGHT (c) 1989-1998.
* On-Line Applications Research Corporation (OAR).
*
* The license and distribution terms for this file may be
* found in the file LICENSE in this distribution or at
* http://www.rtems.org/license/LICENSE.
*/
#include <stdlib.h>
#include <bsp.h>
#include <rtems/libio.h>
#include <rtems/clockdrv.h>
#include "mcf5206/mcf5206e.h"
/*
* Clock_driver_ticks is a monotonically increasing counter of the
* number of clock ticks since the driver was initialized.
*/
volatile uint32_t Clock_driver_ticks;
rtems_isr (*rtems_clock_hook)(rtems_vector_number) = NULL;
static rtems_isr
Clock_isr (rtems_vector_number vector)
{
/* Clear pending interrupt... */
*MCF5206E_TER(MBAR,1) = MCF5206E_TER_REF | MCF5206E_TER_CAP;
/* Announce the clock tick */
Clock_driver_ticks++;
rtems_clock_tick();
if (rtems_clock_hook != NULL)
rtems_clock_hook(vector);
}
void
Clock_exit(void)
{
/* disable all timer1 interrupts */
*MCF5206E_IMR(MBAR) |= MCF5206E_INTR_BIT(MCF5206E_INTR_TIMER_1);
/* reset timer1 */
*MCF5206E_TMR(MBAR,1) = MCF5206E_TMR_ICLK_STOP;
/* clear pending */
*MCF5206E_TER(MBAR,1) = MCF5206E_TER_REF | MCF5206E_TER_CAP;
}
static void
Install_clock(rtems_isr_entry clock_isr)
{
Clock_driver_ticks = 0;
/* Configure timer1 interrupts */
*MCF5206E_ICR(MBAR,MCF5206E_INTR_TIMER_1) =
MCF5206E_ICR_AVEC |
((BSP_INTLVL_TIMER1 << MCF5206E_ICR_IL_S) & MCF5206E_ICR_IL) |
((BSP_INTPRIO_TIMER1 << MCF5206E_ICR_IP_S) & MCF5206E_ICR_IP);
/* Register the interrupt handler */
set_vector(clock_isr, BSP_INTVEC_TIMER1, 1);
/* Reset timer 1 */
*MCF5206E_TMR(MBAR, 1) = MCF5206E_TMR_RST;
*MCF5206E_TMR(MBAR, 1) = MCF5206E_TMR_ICLK_STOP;
*MCF5206E_TMR(MBAR, 1) = MCF5206E_TMR_RST;
*MCF5206E_TCN(MBAR, 1) = 0; /* Reset counter */
*MCF5206E_TER(MBAR, 1) = MCF5206E_TER_REF | MCF5206E_TER_CAP;
/* Set Timer 1 prescaler so that it counts in microseconds */
*MCF5206E_TMR(MBAR, 1) =
(((BSP_SYSTEM_FREQUENCY/1000000 - 1) << MCF5206E_TMR_PS_S) &
MCF5206E_TMR_PS) |
MCF5206E_TMR_CE_NONE | MCF5206E_TMR_ORI | MCF5206E_TMR_FRR |
MCF5206E_TMR_RST;
/* Set the timer timeout value from the BSP config */
*MCF5206E_TRR(MBAR, 1) = rtems_configuration_get_microseconds_per_tick() - 1;
/* Feed system frequency to the timer */
*MCF5206E_TMR(MBAR, 1) |= MCF5206E_TMR_ICLK_MSCLK;
/* Enable timer 1 interrupts */
*MCF5206E_IMR(MBAR) &= ~MCF5206E_INTR_BIT(MCF5206E_INTR_TIMER_1);
/* Register the driver exit procedure so we can shutdown */
atexit(Clock_exit);
}
rtems_device_driver
Clock_initialize(rtems_device_major_number major,
rtems_device_minor_number minor,
void *pargp)
{
Install_clock (Clock_isr);
return RTEMS_SUCCESSFUL;
}

View File

@@ -1,519 +0,0 @@
/*
* Generic UART Serial driver for Motorola Coldfire processors
*/
/*
* Copyright (C) 2000 OKTET Ltd., St.-Petersburg, Russian Fed.
* Author: Victor V. Vengerov <vvv@oktet.ru>
*
* COPYRIGHT (c) 1989-2000.
* On-Line Applications Research Corporation (OAR).
*
* The license and distribution terms for this file may be
* found in the file LICENSE in this distribution or at
* http://www.rtems.org/license/LICENSE.
*/
#include <rtems.h>
#include <termios.h>
#include <rtems/libio.h>
#include "mcf5206/mcfuart.h"
/*
* int_driven_uart -- mapping between interrupt vector number and
* UART descriptor structures
*/
static struct {
mcfuart *uart;
int vec;
} int_driven_uart[2];
/* Forward function declarations */
static rtems_isr
mcfuart_interrupt_handler(rtems_vector_number vec);
/*
* mcfuart_init --
* This function verifies the input parameters and perform initialization
* of the Motorola Coldfire on-chip UART descriptor structure.
*
* PARAMETERS:
* uart - pointer to the UART channel descriptor structure
* tty - pointer to termios structure
* int_driven - interrupt-driven (1) or polled (0) I/O mode
* chn - channel number (0/1)
* rx_buf - pointer to receive buffer
* rx_buf_len - receive buffer length
*
* RETURNS:
* RTEMS_SUCCESSFUL if all parameters are valid, or error code
*/
rtems_status_code
mcfuart_init(
mcfuart *uart,
void *tty,
uint8_t intvec,
uint32_t chn
)
{
if (uart == NULL)
return RTEMS_INVALID_ADDRESS;
if ((chn <= 0) || (chn > MCF5206E_UART_CHANNELS))
return RTEMS_INVALID_NUMBER;
uart->chn = chn;
uart->intvec = intvec;
uart->tty = tty;
return RTEMS_SUCCESSFUL;
}
/* mcfuart_set_baudrate --
* Program the UART timer to specified baudrate
*
* PARAMETERS:
* uart - pointer to UART descriptor structure
* baud - termios baud rate (B50, B9600, etc...)
*
* RETURNS:
* none
*/
static void
mcfuart_set_baudrate(mcfuart *uart, speed_t baud)
{
uint32_t div;
uint32_t rate;
switch (baud) {
case B50: rate = 50; break;
case B75: rate = 75; break;
case B110: rate = 110; break;
case B134: rate = 134; break;
case B150: rate = 150; break;
case B200: rate = 200; break;
case B300: rate = 300; break;
case B600: rate = 600; break;
case B1200: rate = 1200; break;
case B2400: rate = 2400; break;
case B4800: rate = 4800; break;
case B9600: rate = 9600; break;
case B19200: rate = 19200; break;
case B38400: rate = 38400; break;
case B57600: rate = 57600; break;
#ifdef B115200
case B115200: rate = 115200; break;
#endif
#ifdef B230400
case B230400: rate = 230400; break;
#endif
default: rate = 9600; break;
}
div = SYSTEM_CLOCK_FREQUENCY / (rate * 32);
*MCF5206E_UBG1(MBAR,uart->chn) = (uint8_t)((div >> 8) & 0xff);
*MCF5206E_UBG2(MBAR,uart->chn) = (uint8_t)(div & 0xff);
}
/*
* mcfuart_reset --
* This function perform the hardware initialization of Motorola
* Coldfire processor on-chip UART controller using parameters
* filled by the mcfuart_init function.
*
* PARAMETERS:
* uart - pointer to UART channel descriptor structure
*
* RETURNS:
* RTEMS_SUCCESSFUL if channel is initialized successfully, error
* code in other case
*
* ALGORITHM:
* This function in general follows to algorith described in MCF5206e
* User's Manual, 12.5 UART Module Initialization Sequence
*/
rtems_status_code mcfuart_reset(mcfuart *uart)
{
register uint32_t chn;
rtems_status_code rc;
if (uart == NULL)
return RTEMS_INVALID_ADDRESS;
chn = uart->chn;
/* Reset the receiver and transmitter */
*MCF5206E_UCR(MBAR,chn) = MCF5206E_UCR_MISC_RESET_RX;
*MCF5206E_UCR(MBAR,chn) = MCF5206E_UCR_MISC_RESET_TX;
/*
* Program the vector number for a UART module interrupt, or
* disable UART interrupts if polled I/O. Enable the desired
* interrupt sources.
*/
if (uart->intvec != 0) {
int_driven_uart[chn - 1].uart = uart;
int_driven_uart[chn - 1].vec = uart->intvec;
rc = rtems_interrupt_catch(mcfuart_interrupt_handler, uart->intvec,
&uart->old_handler);
if (rc != RTEMS_SUCCESSFUL)
return rc;
*MCF5206E_UIVR(MBAR,chn) = uart->intvec;
*MCF5206E_UIMR(MBAR,chn) = MCF5206E_UIMR_FFULL;
*MCF5206E_UACR(MBAR,chn) = MCF5206E_UACR_IEC;
*MCF5206E_IMR(MBAR) &= ~MCF5206E_INTR_BIT(uart->chn == 1 ?
MCF5206E_INTR_UART_1 :
MCF5206E_INTR_UART_2);
} else {
*MCF5206E_UIMR(MBAR,chn) = 0;
}
/* Select the receiver and transmitter clock. */
mcfuart_set_baudrate(uart, B19200); /* dBUG defaults (unfortunately,
it is differ to termios default */
*MCF5206E_UCSR(MBAR,chn) = MCF5206E_UCSR_RCS_TIMER | MCF5206E_UCSR_TCS_TIMER;
/* Mode Registers 1,2 - set termios defaults (8N1) */
*MCF5206E_UCR(MBAR,chn) = MCF5206E_UCR_MISC_RESET_MR;
*MCF5206E_UMR(MBAR,chn) =
/* MCF5206E_UMR1_RXRTS | */
MCF5206E_UMR1_PM_NO_PARITY |
MCF5206E_UMR1_BC_8;
*MCF5206E_UMR(MBAR,chn) =
MCF5206E_UMR2_CM_NORMAL |
/* MCF5206E_UMR2_TXCTS | */
MCF5206E_UMR2_SB_1;
/* Enable Receiver and Transmitter */
*MCF5206E_UCR(MBAR,chn) = MCF5206E_UCR_MISC_RESET_ERR;
*MCF5206E_UCR(MBAR,chn) = MCF5206E_UCR_TC_ENABLE;
*MCF5206E_UCR(MBAR,chn) = MCF5206E_UCR_RC_ENABLE;
return RTEMS_SUCCESSFUL;
}
/*
* mcfuart_disable --
* This function disable the operations on Motorola Coldfire UART
* controller
*
* PARAMETERS:
* uart - pointer to UART channel descriptor structure
*
* RETURNS:
* RTEMS_SUCCESSFUL if UART closed successfuly, or error code in
* other case
*/
rtems_status_code mcfuart_disable(mcfuart *uart)
{
rtems_status_code rc;
*MCF5206E_UCR(MBAR,uart->chn) =
MCF5206E_UCR_TC_DISABLE |
MCF5206E_UCR_RC_DISABLE;
if (uart->intvec != 0) {
*MCF5206E_IMR(MBAR) |= MCF5206E_INTR_BIT(uart->chn == 1 ?
MCF5206E_INTR_UART_1 :
MCF5206E_INTR_UART_2);
rc = rtems_interrupt_catch(uart->old_handler, uart->intvec, NULL);
int_driven_uart[uart->chn - 1].uart = NULL;
int_driven_uart[uart->chn - 1].vec = 0;
if (rc != RTEMS_SUCCESSFUL)
return rc;
}
return RTEMS_SUCCESSFUL;
}
/*
* mcfuart_set_attributes --
* This function parse the termios attributes structure and perform
* the appropriate settings in hardware.
*
* PARAMETERS:
* uart - pointer to the UART descriptor structure
* t - pointer to termios parameters
*
* RETURNS:
* RTEMS_SUCCESSFUL
*/
int mcfuart_set_attributes(mcfuart *uart, const struct termios *t)
{
int level;
speed_t baud;
uint8_t umr1, umr2;
baud = cfgetospeed(t);
umr1 = 0;
umr2 = MCF5206E_UMR2_CM_NORMAL;
/* Set flow control */
if ((t->c_cflag & CRTSCTS) != 0) {
umr1 |= MCF5206E_UMR1_RXRTS;
umr2 |= MCF5206E_UMR2_TXCTS;
}
/* Set character size */
switch (t->c_cflag & CSIZE) {
case CS5: umr1 |= MCF5206E_UMR1_BC_5; break;
case CS6: umr1 |= MCF5206E_UMR1_BC_6; break;
case CS7: umr1 |= MCF5206E_UMR1_BC_7; break;
case CS8: umr1 |= MCF5206E_UMR1_BC_8; break;
}
/* Set number of stop bits */
if ((t->c_cflag & CSTOPB) != 0) {
if ((t->c_cflag & CSIZE) == CS5) {
umr2 |= MCF5206E_UMR2_SB5_2;
} else {
umr2 |= MCF5206E_UMR2_SB_2;
}
} else {
if ((t->c_cflag & CSIZE) == CS5) {
umr2 |= MCF5206E_UMR2_SB5_1;
} else {
umr2 |= MCF5206E_UMR2_SB_1;
}
}
/* Set parity mode */
if ((t->c_cflag & PARENB) != 0) {
if ((t->c_cflag & PARODD) != 0) {
umr1 |= MCF5206E_UMR1_PM_ODD;
} else {
umr1 |= MCF5206E_UMR1_PM_EVEN;
}
} else {
umr1 |= MCF5206E_UMR1_PM_NO_PARITY;
}
rtems_interrupt_disable(level);
*MCF5206E_UCR(MBAR,uart->chn) =
MCF5206E_UCR_TC_DISABLE | MCF5206E_UCR_RC_DISABLE;
mcfuart_set_baudrate(uart, baud);
*MCF5206E_UCR(MBAR,uart->chn) = MCF5206E_UCR_MISC_RESET_MR;
*MCF5206E_UMR(MBAR,uart->chn) = umr1;
*MCF5206E_UMR(MBAR,uart->chn) = umr2;
if ((t->c_cflag & CREAD) != 0) {
*MCF5206E_UCR(MBAR,uart->chn) =
MCF5206E_UCR_TC_ENABLE | MCF5206E_UCR_RC_ENABLE;
} else {
*MCF5206E_UCR(MBAR,uart->chn) = MCF5206E_UCR_TC_ENABLE;
}
rtems_interrupt_enable(level);
return RTEMS_SUCCESSFUL;
}
/*
* mcfuart_poll_read --
* This function tried to read character from MCF UART and perform
* error handling. When parity or framing error occured, return
* value dependent on termios input mode flags:
* - received character, if IGNPAR == 1
* - 0, if IGNPAR == 0 and PARMRK == 0
* - 0xff and 0x00 on next poll_read invocation, if IGNPAR == 0 and
* PARMRK == 1
*
* PARAMETERS:
* uart - pointer to UART descriptor structure
*
* RETURNS:
* code of received character or -1 if no characters received.
*/
int mcfuart_poll_read(mcfuart *uart)
{
uint8_t usr;
int ch;
if (uart->parerr_mark_flag == true) {
uart->parerr_mark_flag = false;
return 0;
}
usr = *MCF5206E_USR(MBAR,uart->chn);
if ((usr & MCF5206E_USR_RXRDY) != 0) {
if (((usr & (MCF5206E_USR_FE | MCF5206E_USR_PE)) != 0) &&
!(uart->c_iflag & IGNPAR)) {
ch = *MCF5206E_URB(MBAR,uart->chn); /* Clear error bits */
if (uart->c_iflag & PARMRK) {
uart->parerr_mark_flag = true;
ch = 0xff;
} else {
ch = 0;
}
} else {
ch = *MCF5206E_URB(MBAR,uart->chn);
}
} else
ch = -1;
return ch;
}
/*
* mcfuart_poll_write --
* This function transmit buffer byte-by-byte in polling mode.
*
* PARAMETERS:
* uart - pointer to the UART descriptor structure
* buf - pointer to transmit buffer
* len - transmit buffer length
*
* RETURNS:
* 0
*/
ssize_t mcfuart_poll_write(mcfuart *uart, const char *buf, size_t len)
{
size_t retval = len;
while (len--) {
while ((*MCF5206E_USR(MBAR, uart->chn) & MCF5206E_USR_TXRDY) == 0);
*MCF5206E_UTB(MBAR, uart->chn) = *buf++;
}
return retval;
}
/* mcfuart_interrupt_handler --
* UART interrupt handler routine
*
* PARAMETERS:
* vec - interrupt vector number
*
* RETURNS:
* none
*/
static rtems_isr mcfuart_interrupt_handler(rtems_vector_number vec)
{
mcfuart *uart;
register uint8_t usr;
register uint8_t uisr;
register int chn;
register int bp = 0;
/* Find UART descriptor from vector number */
if (int_driven_uart[0].vec == vec)
uart = int_driven_uart[0].uart;
else if (int_driven_uart[1].vec == vec)
uart = int_driven_uart[1].uart;
else
return;
chn = uart->chn;
uisr = *MCF5206E_UISR(MBAR, chn);
if (uisr & MCF5206E_UISR_DB) {
*MCF5206E_UCR(MBAR, chn) = MCF5206E_UCR_MISC_RESET_BRK;
}
/* Receiving */
while (1) {
char buf[32];
usr = *MCF5206E_USR(MBAR,chn);
if ((bp < sizeof(buf) - 1) && ((usr & MCF5206E_USR_RXRDY) != 0)) {
/* Receive character and handle frame/parity errors */
if (((usr & (MCF5206E_USR_FE | MCF5206E_USR_PE)) != 0) &&
!(uart->c_iflag & IGNPAR)) {
if (uart->c_iflag & PARMRK) {
buf[bp++] = 0xff;
buf[bp++] = 0x00;
} else {
buf[bp++] = 0x00;
}
} else {
buf[bp++] = *MCF5206E_URB(MBAR, chn);
}
/* Reset error condition if any errors has been detected */
if (usr & (MCF5206E_USR_RB | MCF5206E_USR_FE |
MCF5206E_USR_PE | MCF5206E_USR_OE)) {
*MCF5206E_UCR(MBAR, chn) = MCF5206E_UCR_MISC_RESET_ERR;
}
} else {
if (bp != 0)
rtems_termios_enqueue_raw_characters(uart->tty, buf, bp);
break;
}
}
/* Transmitting */
while (1) {
if ((*MCF5206E_USR(MBAR, chn) & MCF5206E_USR_TXRDY) == 0)
break;
if (uart->tx_buf != NULL) {
if (uart->tx_ptr >= uart->tx_buf_len) {
register int dequeue = uart->tx_buf_len;
*MCF5206E_UIMR(MBAR, uart->chn) = MCF5206E_UIMR_FFULL;
uart->tx_buf = NULL;
uart->tx_ptr = uart->tx_buf_len = 0;
rtems_termios_dequeue_characters(uart->tty, dequeue);
} else {
*MCF5206E_UTB(MBAR, chn) = uart->tx_buf[uart->tx_ptr++];
}
}
else
break;
}
}
/* mcfuart_interrupt_write --
* This function initiate transmitting of the buffer in interrupt mode.
*
* PARAMETERS:
* uart - pointer to the UART descriptor structure
* buf - pointer to transmit buffer
* len - transmit buffer length
*
* RETURNS:
* 0
*/
ssize_t mcfuart_interrupt_write(
mcfuart *uart,
const char *buf,
size_t len
)
{
if (len > 0) {
uart->tx_buf = buf;
uart->tx_buf_len = len;
uart->tx_ptr = 0;
*MCF5206E_UIMR(MBAR, uart->chn) =
MCF5206E_UIMR_FFULL | MCF5206E_UIMR_TXRDY;
while (((*MCF5206E_USR(MBAR,uart->chn) & MCF5206E_USR_TXRDY) != 0) &&
(uart->tx_ptr < uart->tx_buf_len)) {
*MCF5206E_UTB(MBAR,uart->chn) = uart->tx_buf[uart->tx_ptr++];
}
}
return 0;
}
/* mcfuart_stop_remote_tx --
* This function stop data flow from remote device.
*
* PARAMETERS:
* uart - pointer to the UART descriptor structure
*
* RETURNS:
* RTEMS_SUCCESSFUL
*/
int mcfuart_stop_remote_tx(mcfuart *uart)
{
*MCF5206E_UOP0(MBAR, uart->chn) = 1;
return RTEMS_SUCCESSFUL;
}
/* mcfuart_start_remote_tx --
* This function resume data flow from remote device.
*
* PARAMETERS:
* uart - pointer to the UART descriptor structure
*
* RETURNS:
* RTEMS_SUCCESSFUL
*/
int mcfuart_start_remote_tx(mcfuart *uart)
{
*MCF5206E_UOP1(MBAR, uart->chn) = 1;
return RTEMS_SUCCESSFUL;
}

View File

@@ -1,565 +0,0 @@
/*
* MCF5206e MBUS module (I2C bus) driver
*/
/*
* Copyright (C) 2000 OKTET Ltd., St.-Petersburg, Russia
* Author: Victor V. Vengerov <vvv@oktet.ru>
*
* The license and distribution terms for this file may be
* found in the file LICENSE in this distribution or at
* http://www.rtems.org/license/LICENSE.
*/
#include "mcf5206/mcfmbus.h"
#include "mcf5206/mcf5206e.h"
#include "i2c.h"
/* Events of I2C machine */
typedef enum i2c_event {
EVENT_NONE, /* Spurious event */
EVENT_TRANSFER, /* Start new transfer */
EVENT_NEXTMSG, /* Start processing of next message in transfer */
EVENT_ACK, /* Sending finished with ACK */
EVENT_NACK, /* Sending finished with NACK */
EVENT_TIMEOUT, /* Timeout occured */
EVENT_DATA_RECV, /* Data received */
EVENT_ARB_LOST, /* Arbitration lost */
EVENT_SLAVE /* Addressed as a slave */
} i2c_event;
static mcfmbus *mbus;
/*** Auxillary primitives ***/
/* Change state of finite state machine */
#define next_state(bus,new_state) \
do { \
(bus)->state = (new_state); \
} while (0)
/* Initiate start condition on the I2C bus */
#define mcfmbus_start(bus) \
do { \
*MCF5206E_MBCR((bus)->base) |= MCF5206E_MBCR_MSTA; \
} while (0)
/* Initiate stop condition on the I2C bus */
#define mcfmbus_stop(bus) \
do { \
*MCF5206E_MBCR((bus)->base) &= ~MCF5206E_MBCR_MSTA; \
} while (0)
/* Initiate repeat start condition on the I2C bus */
#define mcfmbus_rstart(bus) \
do { \
*MCF5206E_MBCR((bus)->base) |= MCF5206E_MBCR_RSTA; \
} while (0)
/* Send byte to the bus */
#define mcfmbus_send(bus,byte) \
do { \
*MCF5206E_MBDR((bus)->base) = (byte); \
} while (0)
/* Set transmit mode */
#define mcfmbus_tx_mode(bus) \
do { \
*MCF5206E_MBCR((bus)->base) |= MCF5206E_MBCR_MTX; \
} while (0)
/* Set receive mode */
#define mcfmbus_rx_mode(bus) \
do { \
*MCF5206E_MBCR((bus)->base) &= ~MCF5206E_MBCR_MTX; \
(void)*MCF5206E_MBDR((bus)->base); \
} while (0)
/* Transmit acknowledge when byte received */
#define mcfmbus_send_ack(bus) \
do { \
*MCF5206E_MBCR((bus)->base) &= ~MCF5206E_MBCR_TXAK; \
} while (0)
/* DO NOT transmit acknowledge when byte received */
#define mcfmbus_send_nack(bus) \
do { \
*MCF5206E_MBCR((bus)->base) |= MCF5206E_MBCR_TXAK; \
} while (0)
#define mcfmbus_error(bus,err_status) \
do { \
do { \
(bus)->cmsg->status = (err_status); \
(bus)->cmsg++; \
} while (((bus)->cmsg - (bus)->msg < (bus)->nmsg) && \
((bus)->cmsg->flags & I2C_MSG_ERRSKIP)); \
bus->cmsg--; \
} while (0)
/* mcfmbus_get_event --
* Read MBUS module status register, determine interrupt reason and
* return appropriate event.
*
* PARAMETERS:
* bus - pointer to MBUS module descriptor structure
*
* RETURNS:
* event code
*/
static i2c_event
mcfmbus_get_event(mcfmbus *bus)
{
i2c_event event;
uint8_t status, control;
rtems_interrupt_level level;
rtems_interrupt_disable(level);
status = *MCF5206E_MBSR(bus->base);
control = *MCF5206E_MBCR(bus->base);
if (status & MCF5206E_MBSR_MIF) { /* Interrupt occured */
if (status & MCF5206E_MBSR_MAAS) {
event = EVENT_SLAVE;
*MCF5206E_MBCR(bus->base) = control; /* To clear Addressed As Slave
condition */
} else if (status & MCF5206E_MBSR_MAL) { /* Arbitration lost */
*MCF5206E_MBSR(bus->base) = status & ~MCF5206E_MBSR_MAL;
event = EVENT_ARB_LOST;
}
else if (control & MCF5206E_MBCR_MTX) { /* Trasmit mode */
if (status & MCF5206E_MBSR_RXAK)
event = EVENT_NACK;
else
event = EVENT_ACK;
} else { /* Received */
event = EVENT_DATA_RECV;
}
/* Clear interrupt condition */
*MCF5206E_MBSR(bus->base) &= ~MCF5206E_MBSR_MIF;
} else {
event = EVENT_NONE;
}
rtems_interrupt_enable(level);
return event;
}
static void mcfmbus_machine_error(mcfmbus *bus, i2c_event event)
{
}
/* mcfmbus_machine --
* finite state machine for I2C bus protocol
*
* PARAMETERS:
* bus - pointer to ColdFire MBUS descriptor structure
* event - I2C event
*
* RETURNS:
* none
*/
static void mcfmbus_machine(mcfmbus *bus, i2c_event event)
{
uint8_t b;
switch (bus->state) {
case STATE_IDLE:
switch (event) {
case EVENT_NEXTMSG: /* Start new message processing */
bus->cmsg++;
/* FALLTHRU */
case EVENT_TRANSFER: /* Initiate new transfer */
if (bus->cmsg - bus->msg >= bus->nmsg) {
mcfmbus_stop(bus);
next_state(bus, STATE_IDLE);
bus->msg = bus->cmsg = NULL;
bus->nmsg = bus->byte = 0;
bus->done((void *)bus->done_arg_ptr);
break;
}
/* Initiate START or REPEATED START condition on the bus */
if (event == EVENT_TRANSFER) {
mcfmbus_start(bus);
} else { /* (event == EVENT_NEXTMSG) */
mcfmbus_rstart(bus);
}
bus->byte = 0;
mcfmbus_tx_mode(bus);
/* Initiate slave address sending */
if (bus->cmsg->flags & I2C_MSG_ADDR_10) {
i2c_address a = bus->cmsg->addr;
b = 0xf0 | (((a >> 8) & 0x03) << 1);
if (bus->cmsg->flags & I2C_MSG_WR) {
mcfmbus_send(bus, b);
next_state(bus, STATE_ADDR_1_W);
} else {
mcfmbus_send(bus, b | 1);
next_state(bus, STATE_ADDR_1_R);
}
} else {
b = (bus->cmsg->addr & ~0x01);
if (bus->cmsg->flags & I2C_MSG_WR) {
next_state(bus, STATE_SENDING);
} else {
next_state(bus, STATE_ADDR_7);
b |= 1;
}
mcfmbus_send(bus, b);
}
break;
default:
mcfmbus_machine_error(bus, event);
break;
}
break;
case STATE_ADDR_7:
switch (event) {
case EVENT_ACK:
mcfmbus_rx_mode(bus);
if (bus->cmsg->len <= 1)
mcfmbus_send_nack(bus);
else
mcfmbus_send_ack(bus);
next_state(bus, STATE_RECEIVING);
break;
case EVENT_NACK:
mcfmbus_error(bus, I2C_NO_DEVICE);
next_state(bus, STATE_IDLE);
mcfmbus_machine(bus, EVENT_NEXTMSG);
break;
case EVENT_ARB_LOST:
mcfmbus_error(bus, I2C_ARBITRATION_LOST);
next_state(bus, STATE_IDLE);
mcfmbus_machine(bus, EVENT_NEXTMSG);
break;
default:
mcfmbus_machine_error(bus, event);
break;
}
break;
case STATE_ADDR_1_R:
case STATE_ADDR_1_W:
switch (event) {
case EVENT_ACK: {
uint8_t b = (bus->cmsg->addr & 0xff);
mcfmbus_send(bus, b);
if (bus->state == STATE_ADDR_1_W) {
next_state(bus, STATE_SENDING);
} else {
i2c_address a;
mcfmbus_rstart(bus);
mcfmbus_tx_mode(bus);
a = bus->cmsg->addr;
b = 0xf0 | (((a >> 8) & 0x03) << 1) | 1;
mcfmbus_send(bus, b);
next_state(bus, STATE_ADDR_7);
}
break;
}
case EVENT_NACK:
mcfmbus_error(bus, I2C_NO_DEVICE);
next_state(bus, STATE_IDLE);
mcfmbus_machine(bus, EVENT_NEXTMSG);
break;
case EVENT_ARB_LOST:
mcfmbus_error(bus, I2C_ARBITRATION_LOST);
next_state(bus, STATE_IDLE);
mcfmbus_machine(bus, EVENT_NEXTMSG);
break;
default:
mcfmbus_machine_error(bus, event);
break;
}
break;
case STATE_SENDING:
switch (event) {
case EVENT_ACK:
if (bus->byte == bus->cmsg->len) {
next_state(bus, STATE_IDLE);
mcfmbus_machine(bus, EVENT_NEXTMSG);
} else {
mcfmbus_send(bus, bus->cmsg->buf[bus->byte++]);
next_state(bus, STATE_SENDING);
}
break;
case EVENT_NACK:
if (bus->byte == 0) {
mcfmbus_error(bus, I2C_NO_DEVICE);
} else {
mcfmbus_error(bus, I2C_NO_ACKNOWLEDGE);
}
next_state(bus, STATE_IDLE);
mcfmbus_machine(bus, EVENT_NEXTMSG);
break;
case EVENT_ARB_LOST:
mcfmbus_error(bus, I2C_ARBITRATION_LOST);
next_state(bus, STATE_IDLE);
mcfmbus_machine(bus, EVENT_NEXTMSG);
break;
default:
mcfmbus_machine_error(bus, event);
break;
}
break;
case STATE_RECEIVING:
switch (event) {
case EVENT_DATA_RECV:
if (bus->cmsg->len - bus->byte <= 2) {
mcfmbus_send_nack(bus);
if (bus->cmsg->len - bus->byte <= 1) {
if (bus->cmsg - bus->msg + 1 == bus->nmsg)
mcfmbus_stop(bus);
else
mcfmbus_rstart(bus);
}
} else {
mcfmbus_send_ack(bus);
}
bus->cmsg->buf[bus->byte++] = *MCF5206E_MBDR(bus->base);
if (bus->cmsg->len == bus->byte) {
next_state(bus,STATE_IDLE);
mcfmbus_machine(bus, EVENT_NEXTMSG);
} else {
next_state(bus,STATE_RECEIVING);
}
break;
case EVENT_ARB_LOST:
mcfmbus_error(bus, I2C_ARBITRATION_LOST);
next_state(bus, STATE_IDLE);
mcfmbus_machine(bus, EVENT_NEXTMSG);
break;
default:
mcfmbus_machine_error(bus, event);
break;
}
break;
}
}
/* mcfmbus_interrupt_handler --
* MBUS module interrupt handler routine
*
* PARAMETERS:
* vector - interrupt vector number (not used)
*
* RETURNS:
* none
*/
static rtems_isr mcfmbus_interrupt_handler(rtems_vector_number vector)
{
i2c_event event;
event = mcfmbus_get_event(mbus);
mcfmbus_machine(mbus, event);
}
/* mcfmbus_poll --
* MBUS module poll routine; used to poll events when I2C driver
* operates in poll-driven mode.
*
* PARAMETERS:
* none
*
* RETURNS:
* none
*/
void
mcfmbus_poll(mcfmbus *bus)
{
i2c_event event;
event = mcfmbus_get_event(bus);
if (event != EVENT_NONE)
mcfmbus_machine(bus, event);
}
/* mcfmbus_select_clock_divider --
* Select divider for system clock which is used for I2C bus clock
* generation. Not each divider can be selected for I2C bus; this
* function select nearest larger or equal divider.
*
* PARAMETERS:
* i2c_bus - pointer to the bus descriptor structure
* divider - system frequency divider for I2C serial clock.
* RETURNS:
* RTEMS_SUCCESSFUL, if operation performed successfully, or
* RTEMS error code when failed.
*/
rtems_status_code
mcfmbus_select_clock_divider(mcfmbus *i2c_bus, int divider)
{
int i;
int mbc;
struct {
int divider;
int mbc;
} dividers[] ={
{ 20, 0x20 }, { 22, 0x21 }, { 24, 0x22 }, { 26, 0x23 },
{ 28, 0x00 }, { 30, 0x01 }, { 32, 0x25 }, { 34, 0x02 },
{ 36, 0x26 }, { 40, 0x03 }, { 44, 0x04 }, { 48, 0x05 },
{ 56, 0x06 }, { 64, 0x2a }, { 68, 0x07 }, { 72, 0x2B },
{ 80, 0x08 }, { 88, 0x09 }, { 96, 0x2D }, { 104, 0x0A },
{ 112, 0x2E }, { 128, 0x0B }, { 144, 0x0C }, { 160, 0x0D },
{ 192, 0x0E }, { 224, 0x32 }, { 240, 0x0F }, { 256, 0x33 },
{ 288, 0x10 }, { 320, 0x11 }, { 384, 0x12 }, { 448, 0x36 },
{ 480, 0x13 }, { 512, 0x37 }, { 576, 0x14 }, { 640, 0x15 },
{ 768, 0x16 }, { 896, 0x3A }, { 960, 0x17 }, { 1024, 0x3B },
{ 1152, 0x18 }, { 1280, 0x19 }, { 1536, 0x1A }, { 1792, 0x3E },
{ 1920, 0x1B }, { 2048, 0x3F }, { 2304, 0x1C }, { 2560, 0x1D },
{ 3072, 0x1E }, { 3840, 0x1F }
};
if (i2c_bus == NULL)
return RTEMS_INVALID_ADDRESS;
for (i = 0, mbc = -1; i < sizeof(dividers)/sizeof(dividers[0]); i++) {
mbc = dividers[i].mbc;
if (dividers[i].divider >= divider) {
break;
}
}
*MCF5206E_MFDR(i2c_bus->base) = mbc;
return RTEMS_SUCCESSFUL;
}
/* mcfmbus_initialize --
* Initialize ColdFire MBUS I2C bus controller.
*
* PARAMETERS:
* i2c_bus - pointer to the bus descriptor structure
* base - ColdFire internal peripherial base address
*
* RETURNS:
* RTEMS_SUCCESSFUL, or RTEMS error code when initialization failed.
*/
rtems_status_code mcfmbus_initialize(mcfmbus *i2c_bus, uint32_t base)
{
rtems_interrupt_level level;
rtems_status_code sc;
if (mbus != NULL) /* Check if already initialized */
return RTEMS_RESOURCE_IN_USE;
if (i2c_bus == NULL)
return RTEMS_INVALID_ADDRESS;
i2c_bus->base = base;
i2c_bus->state = STATE_IDLE;
i2c_bus->msg = NULL;
i2c_bus->cmsg = NULL;
i2c_bus->nmsg = 0;
i2c_bus->byte = 0;
sc = rtems_interrupt_catch(
mcfmbus_interrupt_handler,
24 + ((*MCF5206E_ICR(base, MCF5206E_INTR_MBUS) & MCF5206E_ICR_IL) >>
MCF5206E_ICR_IL_S),
&i2c_bus->oldisr
);
if (sc != RTEMS_SUCCESSFUL)
return sc;
mbus = i2c_bus;
rtems_interrupt_disable(level);
*MCF5206E_IMR(base) &= ~MCF5206E_INTR_BIT(MCF5206E_INTR_MBUS);
*MCF5206E_MBCR(base) = 0;
*MCF5206E_MBSR(base) = 0;
*MCF5206E_MBDR(base) = 0x1F; /* Maximum possible divider is 3840 */
*MCF5206E_MBCR(base) = MCF5206E_MBCR_MEN | MCF5206E_MBCR_MIEN;
rtems_interrupt_enable(level);
return RTEMS_SUCCESSFUL;
}
/* mcfmbus_i2c_transfer --
* Initiate multiple-messages transfer over I2C bus via ColdFire MBUS
* controller.
*
* PARAMETERS:
* bus - pointer to MBUS controller descriptor
* nmsg - number of messages
* msg - pointer to messages array
* done - function which is called when transfer is finished
* done_arg_ptr - arbitrary argument ptr passed to done funciton
*
* RETURNS:
* RTEMS_SUCCESSFUL if transfer initiated successfully, or error
* code when failed.
*/
rtems_status_code mcfmbus_i2c_transfer(
mcfmbus *bus,
int nmsg,
i2c_message *msg,
i2c_transfer_done done,
void *done_arg_ptr
)
{
if (bus != mbus)
return RTEMS_NOT_CONFIGURED;
bus->done = done;
bus->done_arg_ptr = (uintptr_t) done_arg_ptr;
bus->cmsg = bus->msg = msg;
bus->nmsg = nmsg;
bus->byte = 0;
bus->state = STATE_IDLE;
mcfmbus_machine(bus, EVENT_TRANSFER);
return RTEMS_SUCCESSFUL;
}
/* mcfmbus_i2c_done --
* Close ColdFire MBUS I2C bus controller and release all resources.
*
* PARAMETERS:
* bus - pointer to MBUS controller descriptor
*
* RETURNS:
* RTEMS_SUCCESSFUL, if transfer initiated successfully, or error
* code when failed.
*/
rtems_status_code mcfmbus_i2c_done(mcfmbus *i2c_bus)
{
rtems_status_code sc;
uint32_t base;
if (mbus == NULL)
return RTEMS_NOT_CONFIGURED;
if (mbus != i2c_bus)
return RTEMS_INVALID_ADDRESS;
base = i2c_bus->base;
*MCF5206E_IMR(base) |= MCF5206E_INTR_BIT(MCF5206E_INTR_MBUS);
*MCF5206E_MBCR(base) = 0;
sc = rtems_interrupt_catch(
i2c_bus->oldisr,
24 + ((*MCF5206E_ICR(base, MCF5206E_INTR_MBUS) & MCF5206E_ICR_IL) >>
MCF5206E_ICR_IL_S),
NULL
);
return sc;
}

View File

@@ -1,158 +0,0 @@
/**
* @file
* @brief Timer Init
*
* This module initializes TIMER 2 for on the MCF5206E for benchmarks.
*/
/*
* Copyright (C) 2000 OKTET Ltd., St.-Petersburg, Russia
* Author: Victor V. Vengerov <vvv@oktet.ru>
*
* Based on work:
* Author:
* David Fiddes, D.J@fiddes.surfaid.org
* http://www.calm.hw.ac.uk/davidf/coldfire/
*
* COPYRIGHT (c) 1989-1998.
* On-Line Applications Research Corporation (OAR).
*
* The license and distribution terms for this file may be
* found in the file LICENSE in this distribution or at
* http://www.rtems.org/license/LICENSE.
*/
#include <rtems.h>
#include <bsp.h>
#include <rtems/btimer.h>
#include "mcf5206/mcf5206e.h"
#define TRR2_VAL 65530
uint32_t Timer_interrupts;
bool benchmark_timer_find_average_overhead;
/* External assembler interrupt handler routine */
extern rtems_isr timerisr(rtems_vector_number vector);
/* benchmark_timer_initialize --
* Initialize timer 2 for accurate time measurement.
*
* PARAMETERS:
* none
*
* RETURNS:
* none
*/
void
benchmark_timer_initialize(void)
{
/* Catch timer2 interrupts */
set_vector(timerisr, BSP_INTVEC_TIMER2, 0);
/* Initialize interrupts for timer2 */
*MCF5206E_ICR(MBAR, MCF5206E_INTR_TIMER_2) =
MCF5206E_ICR_AVEC |
((BSP_INTLVL_TIMER2 << MCF5206E_ICR_IL_S) & MCF5206E_ICR_IL) |
((BSP_INTPRIO_TIMER2 << MCF5206E_ICR_IP_S) & MCF5206E_ICR_IP);
/* Enable interrupts from timer2 */
*MCF5206E_IMR(MBAR) &= ~MCF5206E_INTR_BIT(MCF5206E_INTR_TIMER_2);
/* Reset Timer */
*MCF5206E_TMR(MBAR, 2) = MCF5206E_TMR_RST;
*MCF5206E_TMR(MBAR, 2) = MCF5206E_TMR_ICLK_STOP;
*MCF5206E_TMR(MBAR, 2) = MCF5206E_TMR_RST;
*MCF5206E_TCN(MBAR, 2) = 0; /* Zero timer counter */
Timer_interrupts = 0; /* Clear timer ISR counter */
*MCF5206E_TER(MBAR, 2) = MCF5206E_TER_REF | MCF5206E_TER_CAP; /*clr pend*/
*MCF5206E_TRR(MBAR, 2) = TRR2_VAL - 1;
*MCF5206E_TMR(MBAR, 2) =
(((BSP_SYSTEM_FREQUENCY / 1000000) << MCF5206E_TMR_PS_S) &
MCF5206E_TMR_PS) |
MCF5206E_TMR_CE_NONE | MCF5206E_TMR_ORI | MCF5206E_TMR_FRR |
MCF5206E_TMR_RST;
*MCF5206E_TMR(MBAR, 2) |= MCF5206E_TMR_ICLK_MSCLK;
}
/*
* The following controls the behavior of benchmark_timer_read().
*
* FIND_AVG_OVERHEAD * instructs the routine to return the "raw" count.
*
* AVG_OVEREHAD is the overhead for starting and stopping the timer. It
* is usually deducted from the number returned.
*
* LEAST_VALID is the lowest number this routine should trust. Numbers
* below this are "noise" and zero is returned.
*/
#define AVG_OVERHEAD 0 /* It typically takes 2.0 microseconds */
/* (Y countdowns) to start/stop the timer. */
/* This value is in microseconds. */
#define LEAST_VALID 1 /* Don't trust a clicks value lower than this */
/* benchmark_timer_read --
* Read timer value in microsecond units since timer start.
*
* PARAMETERS:
* none
*
* RETURNS:
* number of microseconds since timer has been started
*/
benchmark_timer_t
benchmark_timer_read( void )
{
uint16_t clicks;
uint32_t total;
/*
* Read the timer and see how many clicks it has been since counter
* rolled over.
*/
clicks = *MCF5206E_TCN(MBAR, 2);
/* Stop Timer... */
*MCF5206E_TMR(MBAR, 2) = MCF5206E_TMR_ICLK_STOP |
MCF5206E_TMR_RST;
/*
* Total is calculated by taking into account the number of timer
* overflow interrupts since the timer was initialized and clicks
* since the last interrupts.
*/
total = (Timer_interrupts * TRR2_VAL) + clicks;
if ( benchmark_timer_find_average_overhead == 1 )
return total; /* in XXX microsecond units */
if ( total < LEAST_VALID )
return 0; /* below timer resolution */
/*
* Return the count in microseconds
*/
return (total - AVG_OVERHEAD);
}
/* benchmark_timer_disable_subtracting_average_overhead --
* This routine is invoked by the "Check Timer" (tmck) test in the
* RTEMS Timing Test Suite. It makes the benchmark_timer_read routine not
* subtract the overhead required to initialize and read the benchmark
* timer.
*
* PARAMETERS:
* find_flag - boolean flag, true if overhead must not be subtracted.
*
* RETURNS:
* none
*/
void
benchmark_timer_disable_subtracting_average_overhead(bool find_flag)
{
benchmark_timer_find_average_overhead = find_flag;
}

View File

@@ -1,48 +0,0 @@
/**
* @file
* @brief Handle MCF5206 TIMER2 interrupts
*
* All code in this routine is pure overhead which can perturb the
* accuracy of RTEMS' timing test suite.
*
* See also: benchmark_timer_read()
*
* To reduce overhead this is best to be the "rawest" hardware interupt
* handler you can write. This should be the only interrupt which can
* occur during the measured time period.
*
* An external counter, Timer_interrupts, is incremented.
*/
/*
* Copyright (C) 2000 OKTET Ltd., St.-Petersburg, Russia
* Author: Victor V. Vengerov <vvv@oktet.ru>
*
* This file based on work:
* Author:
* David Fiddes, D.J@fiddes.surfaid.org
* http://www.calm.hw.ac.uk/davidf/coldfire/
*
* COPYRIGHT (c) 1989-1998.
* On-Line Applications Research Corporation (OAR).
*
* The license and distribution terms for this file may be
* found in the file LICENSE in this distribution or at
* http://www.rtems.org/license/LICENSE.
*/
#include <rtems/asm.h>
#include <bsp.h>
#include "mcf5206/mcf5206e.h"
BEGIN_CODE
PUBLIC(timerisr)
SYM(timerisr):
move.l a0, a7@-
move.l #MCF5206E_TER(BSP_MEM_ADDR_IMM, 2), a0
move.b # (MCF5206E_TER_REF + MCF5206E_TER_CAP), (a0)
addq.l #1,SYM(Timer_interrupts) | increment timer value
move.l a7@+, a0
rte
END_CODE
END