m68k/mcf5206elite: Remove obsolete BSP family

Updates #5031
This commit is contained in:
Joel Sherrill
2025-02-05 15:15:25 -06:00
committed by Gedare Bloom
parent 7f86974bf3
commit 23a4dc74cd
31 changed files with 0 additions and 5412 deletions

View File

@@ -1,107 +0,0 @@
MCF5206eLITE
============
Copyright (C) 2000,2001 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.
This board support package works with MCF5206eLITE evaluation board with
Motorola Coldfire MCF5206e CPU.
Many thanks to Balanced Audio Technology (http://www.balanced.com),
company which donates MCF5206eLITE evaluation board, P&E Coldfire BDM
interface and provides support for development of this BSP and generic
MCF5206 CPU code.
Decisions made at compile time include:
Decisions to be made a link-edit time are:
- The size of memory allocator heap. By default, all available
memory allocated for the heap. To specify amount of memory
available for heap:
LDFLAGS += -Wl,--defsym -Wl,HeapSize=xxx
- The frequency of system clock oscillator. By default, this frequency
is 54MHz. To select other clock frequency for your application, put
line like this in application Makefile:
LDFLAGS += -qclock=40000000
- Select between RAM or ROM images. By default, RAM image generated
which may be loaded starting from address 0x30000000 to the RAM.
To prepare image intended to be stored in ROM, put the following
line to the application Makefile:
LDFLAGS += -qflash
You may select other memory configuration providing your own
linker script.
```
BSP NAME: mcf5206elite
BOARD: MCF5206eLITE Evaluation Board
BUS: none
CPU FAMILY: Motorola ColdFire
COPROCESSORS: none
MODE: not applicable
DEBUG MONITOR: none (Hardware provides BDM)
```
PERIPHERALS
-----------
```
TIMERS: PIT, Watchdog(disabled)
RESOLUTION: one microsecond
SERIAL PORTS: 2 UART
REAL-TIME CLOCK: DS1307
NVRAM: DS1307
DMA: 2 general purpose
VIDEO: none
SCSI: none
NETWORKING: none
I2C BUS: MCF5206e MBUS module
```
DRIVER INFORMATION
------------------
```
CLOCK DRIVER: Programmable Interval Timer
IOSUPP DRIVER: UART 1
SHMSUPP: none
TIMER DRIVER: yes
I2C DRIVER: yes
```
STDIO
-----
```
PORT: UART 1
ELECTRICAL: EIA-232
BAUD: 19200
BITS PER CHARACTER: 8
PARITY: None
STOP BITS: 1
```
Board description
-----------------
clock rate: 54 MHz default (other oscillator can be installed)
bus width: 16-bit PROM, 32-bit external SRAM
ROM: Flash memory device AM29LV800BB, 1 MByte, 3 wait states,
chip select 0
RAM: Static RAM 2xMCM69F737TQ, 1 MByte, 1 wait state, chip select 2
Host System
-----------
RedHat 6.2 (Linux 2.2.14), RedHat 7.0 (Linux 2.2.17)
Verification
------------
Single processor tests: passed
Multi-processort tests: not applicable
Timing tests: passed

View File

@@ -1,8 +0,0 @@
#
# mcf5206elite RTEMS Test Database
#
# Format is one line per test that is _NOT_ built.
#
exclude: fsdosfsname01
exclude: dl05

View File

@@ -1,20 +0,0 @@
#
# Config file for a MCF5206eLITE board BSP
#
# Author: Victor V. Vengerov <vvv@oktet.ru>
#
RTEMS_CPU=m68k
include $(RTEMS_ROOT)/make/custom/default.cfg
# This contains the compiler options necessary to select the CPU model
# and (hopefully) optimize for it.
CPU_CFLAGS = -mcpu=5206
# optimize flag: typically -O2
CFLAGS_OPTIMIZE_V = -O2 -g -fomit-frame-pointer
# The following two lines enable compiling and linking on per element.
CFLAGS_OPTIMIZE_V += -ffunction-sections -fdata-sections
LDFLAGS = -Wl,--gc-sections

View File

@@ -1,431 +0,0 @@
/*
* Console driver for Motorola MCF5206E UART modules
*/
/*
* Copyright (C) 2000 OKTET Ltd., St.-Petersburg, Russia
* Author: Victor V. Vengerov <vvv@oktet.ru>
*
* 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 <termios.h>
#include <bsp.h>
#include <rtems/libio.h>
#include <rtems/console.h>
#include "mcf5206/mcf5206e.h"
#include "mcf5206/mcfuart.h"
/* Descriptor structures for two on-chip UART channels */
static mcfuart uart[2];
/* Console operations mode:
* 0 - raw (non-termios) polled input/output
* 1 - termios-based polled input/output
* 2 - termios-based interrupt-driven input/output
*/
int console_mode = 2;
#define CONSOLE_MODE_RAW (0)
#define CONSOLE_MODE_POLL (1)
#define CONSOLE_MODE_INT (2)
/* Wrapper functions for MCF UART generic driver */
/* console_poll_read --
* wrapper for poll read function
*
* PARAMETERS:
* minor - minor device number
*
* RETURNS:
* character code readed from UART, or -1 if there is no characters
* available
*/
static int
console_poll_read(int minor)
{
return mcfuart_poll_read(&uart[minor]);
}
/* console_interrupt_write --
* wrapper for interrupt write function
*
* PARAMETERS:
* minor - minor device number
* buf - output buffer
* len - output buffer length
*
* RETURNS:
* result code
*/
static ssize_t
console_interrupt_write(int minor, const char *buf, size_t len)
{
return mcfuart_interrupt_write(&uart[minor], buf, len);
}
/* console_poll_write --
* wrapper for polling mode write function
*
* PARAMETERS:
* minor - minor device number
* buf - output buffer
* len - output buffer length
*
* RETURNS:
* result code
*/
static ssize_t
console_poll_write(int minor, const char *buf, size_t len)
{
return mcfuart_poll_write(&uart[minor], buf, len);
}
/* console_set_attributes --
* wrapper for hardware-dependent termios attributes setting
*
* PARAMETERS:
* minor - minor device number
* t - pointer to the termios structure
*
* RETURNS:
* result code
*/
static int
console_set_attributes(int minor, const struct termios *t)
{
return mcfuart_set_attributes(&uart[minor], t);
}
/* console_stop_remote_tx --
* wrapper for stopping data flow from remote party.
*
* PARAMETERS:
* minor - minor device number
*
* RETURNS:
* result code
*/
static int
console_stop_remote_tx(int minor)
{
if (minor < sizeof(uart)/sizeof(uart[0]))
return mcfuart_stop_remote_tx(&uart[minor]);
else
return RTEMS_INVALID_NUMBER;
}
/* console_start_remote_tx --
* wrapper for resuming data flow from remote party.
*
* PARAMETERS:
* minor - minor device number
*
*/
static int
console_start_remote_tx(int minor)
{
if (minor < sizeof(uart)/sizeof(uart[0]))
return mcfuart_start_remote_tx(&uart[minor]);
else
return RTEMS_INVALID_NUMBER;
}
/* console_first_open --
* wrapper for UART controller initialization functions
*
* PARAMETERS:
* major - major device number
* minor - minor device number
* arg - libio device open argument
*
* RETURNS:
* error code
*/
static int
console_first_open(int major, int minor, void *arg)
{
rtems_libio_open_close_args_t *args = arg;
rtems_status_code sc;
uint8_t intvec;
switch (minor) {
case 0: intvec = BSP_INTVEC_UART1; break;
case 1: intvec = BSP_INTVEC_UART2; break;
default:
return RTEMS_INVALID_NUMBER;
}
if (console_mode != CONSOLE_MODE_INT) {
intvec = 0;
}
sc = mcfuart_init(
&uart[minor], /* uart */
args->iop->data1, /* tty */
intvec, /* interrupt vector number */
minor+1);
if (sc == RTEMS_SUCCESSFUL)
sc = mcfuart_reset(&uart[minor]);
return sc;
}
/* console_last_close --
* wrapper for UART controller close function
*
* PARAMETERS:
* major - major device number
* minor - minor device number
* arg - libio device close argument
*
* RETURNS:
* error code
*/
static int
console_last_close(int major, int minor, void *arg)
{
return mcfuart_disable(&uart[minor]);
}
/* console_initialize --
* This routine initializes the console IO drivers and register devices
* in RTEMS I/O system.
*
* PARAMETERS:
* major - major console device number
* minor - minor console device number (not used)
* arg - device initialize argument
*
* RETURNS:
* RTEMS error code (RTEMS_SUCCESSFUL if device initialized successfuly)
*/
rtems_device_driver console_initialize(
rtems_device_major_number major,
rtems_device_minor_number minor,
void *arg)
{
rtems_status_code status;
/*
* Set up TERMIOS
*/
if (console_mode != CONSOLE_MODE_RAW)
rtems_termios_initialize ();
/*
* Register the devices
*/
status = rtems_io_register_name ("/dev/console", major, 0);
if (status != RTEMS_SUCCESSFUL)
rtems_fatal_error_occurred (status);
status = rtems_io_register_name ("/dev/aux", major, 1);
if (status != RTEMS_SUCCESSFUL)
rtems_fatal_error_occurred (status);
if (console_mode == CONSOLE_MODE_RAW) {
rtems_status_code sc;
sc = mcfuart_init(&uart[0], /* uart */
NULL, /* tty */
0, /* interrupt vector number */
1); /* UART channel number */
if (sc == RTEMS_SUCCESSFUL)
sc = mcfuart_reset(&uart[0]);
sc = mcfuart_init(&uart[1], /* uart */
NULL, /* tty */
0, /* interrupt vector number */
2); /* UART channel number */
if (sc == RTEMS_SUCCESSFUL)
sc = mcfuart_reset(&uart[1]);
return sc;
}
return RTEMS_SUCCESSFUL;
}
/* console_open --
* Open console device driver. Pass appropriate termios callback
* functions to termios library.
*
* PARAMETERS:
* major - major device number for console devices
* minor - minor device number for console
* arg - device opening argument
*
* RETURNS:
* RTEMS error code
*/
rtems_device_driver
console_open(rtems_device_major_number major,
rtems_device_minor_number minor,
void *arg)
{
static const rtems_termios_callbacks intr_callbacks = {
console_first_open, /* firstOpen */
console_last_close, /* lastClose */
NULL, /* pollRead */
console_interrupt_write, /* write */
console_set_attributes, /* setAttributes */
console_stop_remote_tx, /* stopRemoteTx */
console_start_remote_tx, /* startRemoteTx */
TERMIOS_IRQ_DRIVEN /* outputUsesInterrupts */
};
static const rtems_termios_callbacks poll_callbacks = {
console_first_open, /* firstOpen */
console_last_close, /* lastClose */
console_poll_read, /* pollRead */
console_poll_write, /* write */
console_set_attributes, /* setAttributes */
console_stop_remote_tx, /* stopRemoteTx */
console_start_remote_tx, /* startRemoteTx */
TERMIOS_POLLED /* outputUsesInterrupts */
};
switch (console_mode) {
case CONSOLE_MODE_RAW:
return RTEMS_SUCCESSFUL;
case CONSOLE_MODE_INT:
return rtems_termios_open(major, minor, arg, &intr_callbacks);
case CONSOLE_MODE_POLL:
return rtems_termios_open(major, minor, arg, &poll_callbacks);
default:
rtems_fatal_error_occurred(0xC07A1310);
}
return RTEMS_INTERNAL_ERROR;
}
/* console_close --
* Close console device.
*
* PARAMETERS:
* major - major device number for console devices
* minor - minor device number for console
* arg - device close argument
*
* RETURNS:
* RTEMS error code
*/
rtems_device_driver
console_close(rtems_device_major_number major,
rtems_device_minor_number minor,
void *arg)
{
if (console_mode != CONSOLE_MODE_RAW)
return rtems_termios_close (arg);
else
return RTEMS_SUCCESSFUL;
}
/* console_read --
* Read from the console device
*
* PARAMETERS:
* major - major device number for console devices
* minor - minor device number for console
* arg - device read argument
*
* RETURNS:
* RTEMS error code
*/
rtems_device_driver
console_read(rtems_device_major_number major,
rtems_device_minor_number minor,
void *arg)
{
if (console_mode != CONSOLE_MODE_RAW) {
return rtems_termios_read (arg);
} else {
rtems_libio_rw_args_t *argp = arg;
char *buf = argp->buffer;
int count = argp->count;
int n = 0;
int c;
while (n < count) {
do {
c = mcfuart_poll_read(&uart[minor]);
} while (c == -1);
if (c == '\r')
c = '\n';
*(buf++) = c;
n++;
if (c == '\n')
break;
}
argp->bytes_moved = n;
return RTEMS_SUCCESSFUL;
}
}
/* console_write --
* Write to the console device
*
* PARAMETERS:
* major - major device number for console devices
* minor - minor device number for console
* arg - device write argument
*
* RETURNS:
* RTEMS error code
*/
rtems_device_driver
console_write(rtems_device_major_number major,
rtems_device_minor_number minor,
void *arg
)
{
if (console_mode != CONSOLE_MODE_RAW) {
return rtems_termios_write (arg);
} else {
rtems_libio_rw_args_t *argp = arg;
char cr = '\r';
char *buf = argp->buffer;
int count = argp->count;
int i;
for (i = 0; i < count; i++) {
if (*buf == '\n')
mcfuart_poll_write(&uart[minor], &cr, 1);
mcfuart_poll_write(&uart[minor], buf, 1);
buf++;
}
argp->bytes_moved = count;
return RTEMS_SUCCESSFUL;
}
}
/* console_control --
* Handle console device I/O control (IOCTL)
*
* PARAMETERS:
* major - major device number for console devices
* minor - minor device number for console
* arg - device ioctl argument
*
* RETURNS:
* RTEMS error code
*/
rtems_device_driver
console_control(rtems_device_major_number major,
rtems_device_minor_number minor,
void *arg)
{
if (console_mode != CONSOLE_MODE_RAW) {
return rtems_termios_ioctl (arg);
} else {
return RTEMS_SUCCESSFUL;
}
}

View File

@@ -1,127 +0,0 @@
/* SPDX-License-Identifier: BSD-2-Clause */
/*
* 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).
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/
#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);
}
static 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);
}
void _Clock_Initialize( void )
{
Install_clock (Clock_isr);
}

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,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,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

View File

@@ -1,320 +0,0 @@
/* I2C bus common (driver-independent) primitives implementation.
*
* 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 <bsp.h>
#include <i2c.h>
#include <rtems/score/sysstate.h>
/* i2c_transfer_sema_done_func --
* This function called from I2C driver layer to signal that I2C
* transfer is finished. This function resumes of task execution which
* has invoked blocking I2C primitive.
*
* PARAMETERS:
* arg - done function argument; it is RTEMS semaphore ID.
*/
static void
i2c_transfer_sema_done_func(void * arg)
{
rtems_id sema = *(rtems_id *)arg;
rtems_semaphore_release(sema);
}
/* i2c_transfer_poll_done_func --
* This function called from I2C driver layer to signal that I2C
* transfer is finished. This function set the flag polled by waiting
* function.
*
* PARAMETERS:
* arg - done function argument; address of poll_done_flag
*/
static void
i2c_transfer_poll_done_func(void *arg)
{
bool *poll_done_flag = (bool *)arg;
*poll_done_flag = true;
}
/* i2c_transfer_wait_sema --
* Initiate I2C bus transfer and block on temporary created semaphore
* until this transfer will be finished.
*
* PARAMETERS:
* bus - I2C bus number
* msg - pointer to transfer messages array
* nmsg - number of messages in transfer
*
* RETURNS:
* RTEMS_SUCCESSFUL, if tranfer finished successfully,
* or RTEMS status code if semaphore operations has failed.
*/
static i2c_message_status
i2c_transfer_wait_sema(i2c_bus_number bus, i2c_message *msg, int nmsg)
{
rtems_status_code sc;
rtems_id sema;
sc = rtems_semaphore_create(
rtems_build_name('I', '2', 'C', 'S'),
0,
RTEMS_COUNTING_SEMAPHORE | RTEMS_NO_INHERIT_PRIORITY |
RTEMS_NO_PRIORITY_CEILING | RTEMS_LOCAL,
0,
&sema
);
if (sc != RTEMS_SUCCESSFUL)
return I2C_RESOURCE_NOT_AVAILABLE;
sc = i2c_transfer(bus, nmsg, msg,
i2c_transfer_sema_done_func, &sema);
if (sc != RTEMS_SUCCESSFUL)
{
rtems_semaphore_delete(sema);
return sc;
}
rtems_semaphore_obtain(sema, RTEMS_WAIT, RTEMS_NO_TIMEOUT);
sc = rtems_semaphore_delete(sema);
return sc;
}
/* i2c_transfer_wait_poll --
* Initiate I2C bus transfer and wait by poll transaction done flag until
* this transfer will be finished.
*
* PARAMETERS:
* bus - I2C bus number
* msg - pointer to transfer messages array
* nmsg - number of messages in transfer
*
* RETURNS:
* RTEMS_SUCCESSFUL
*/
static rtems_status_code
i2c_transfer_wait_poll(i2c_bus_number bus, i2c_message *msg, int nmsg)
{
/*
* this looks nasty, but is correct:
* we wait in this function, until the poll_done_flag is
* set deep inside the i2c_poll() function
*/
volatile bool poll_done_flag;
rtems_status_code sc;
poll_done_flag = false;
sc = i2c_transfer(bus, nmsg, msg,
i2c_transfer_poll_done_func,(void *)&poll_done_flag);
if (sc != RTEMS_SUCCESSFUL)
return sc;
while (poll_done_flag == false)
{
i2c_poll(bus);
}
return RTEMS_SUCCESSFUL;
}
/* i2c_transfer_wait --
* Initiate I2C bus transfer and block until this transfer will be
* finished. This function wait the semaphore if system in
* SYSTEM_STATE_UP state, or poll done flag in other states.
*
* PARAMETERS:
* bus - I2C bus number
* msg - pointer to transfer messages array
* nmsg - number of messages in transfer
*
* RETURNS:
* I2C_SUCCESSFUL, if tranfer finished successfully,
* I2C_RESOURCE_NOT_AVAILABLE, if semaphore operations has failed,
* value of status field of first error-finished message in transfer,
* if something wrong.
*/
i2c_message_status
i2c_transfer_wait(i2c_bus_number bus, i2c_message *msg, int nmsg)
{
rtems_status_code sc;
int i;
if (_System_state_Is_up(_System_state_Get()))
{
sc = i2c_transfer_wait_sema(bus, msg, nmsg);
}
else
{
sc = i2c_transfer_wait_poll(bus, msg, nmsg);
}
if (sc != RTEMS_SUCCESSFUL)
return I2C_RESOURCE_NOT_AVAILABLE;
for (i = 0; i < nmsg; i++)
{
if (msg[i].status != I2C_SUCCESSFUL)
{
return msg[i].status;
}
}
return I2C_SUCCESSFUL;
}
/* i2c_write --
* Send single message over specified I2C bus to addressed device and
* wait while transfer is finished.
*
* PARAMETERS:
* bus - I2C bus number
* addr - address of I2C device
* buf - data to be sent to device
* size - data buffer size
*
* RETURNS:
* transfer status
*/
i2c_message_status
i2c_write(i2c_bus_number bus, i2c_address addr, void *buf, int size)
{
i2c_message msg;
msg.addr = addr;
msg.flags = I2C_MSG_WR;
if (addr > 0xff)
msg.flags |= I2C_MSG_ADDR_10;
msg.status = 0;
msg.len = size;
msg.buf = buf;
return i2c_transfer_wait(bus, &msg, 1);
}
/* i2c_wrbyte --
* Send single one-byte long message over specified I2C bus to
* addressed device and wait while transfer is finished.
*
* PARAMETERS:
* bus - I2C bus number
* addr - address of I2C device
* cmd - byte message to be sent to device
*
* RETURNS:
* transfer status
*/
i2c_message_status
i2c_wrbyte(i2c_bus_number bus, i2c_address addr, uint8_t cmd)
{
i2c_message msg;
uint8_t data = cmd;
msg.addr = addr;
msg.flags = I2C_MSG_WR;
if (addr > 0xff)
msg.flags |= I2C_MSG_ADDR_10;
msg.status = 0;
msg.len = sizeof(data);
msg.buf = &data;
return i2c_transfer_wait(bus, &msg, 1);
}
/* i2c_read --
* receive single message over specified I2C bus from addressed device.
* This call will wait while transfer is finished.
*
* PARAMETERS:
* bus - I2C bus number
* addr - address of I2C device
* buf - buffer for received message
* size - receive buffer size
*
* RETURNS:
* transfer status
*/
i2c_message_status
i2c_read(i2c_bus_number bus, i2c_address addr, void *buf, int size)
{
i2c_message msg;
msg.addr = addr;
msg.flags = 0;
if (addr > 0xff)
msg.flags |= I2C_MSG_ADDR_10;
msg.status = 0;
msg.len = size;
msg.buf = buf;
return i2c_transfer_wait(bus, &msg, 1);
}
/* i2c_wrrd --
* Send message over I2C bus to specified device and receive message
* from the same device during single transfer.
*
* PARAMETERS:
* bus - I2C bus number
* addr - address of I2C device
* bufw - data to be sent to device
* sizew - send data buffer size
* bufr - buffer for received message
* sizer - receive buffer size
*
* RETURNS:
* transfer status
*/
i2c_message_status
i2c_wrrd(i2c_bus_number bus, i2c_address addr, void *bufw, int sizew,
void *bufr, int sizer)
{
i2c_message msg[2];
msg[0].addr = addr;
msg[0].flags = I2C_MSG_WR | I2C_MSG_ERRSKIP;
if (addr > 0xff)
msg[0].flags |= I2C_MSG_ADDR_10;
msg[0].status = 0;
msg[0].len = sizew;
msg[0].buf = bufw;
msg[1].addr = addr;
msg[1].flags = 0;
if (addr > 0xff)
msg[1].flags |= I2C_MSG_ADDR_10;
msg[1].status = 0;
msg[1].len = sizer;
msg[1].buf = bufr;
return i2c_transfer_wait(bus, msg, 2);
}
/* i2c_wbrd --
* Send one-byte message over I2C bus to specified device and receive
* message from the same device during single transfer.
*
* PARAMETERS:
* bus - I2C bus number
* addr - address of I2C device
* cmd - one-byte message to be sent over I2C bus
* bufr - buffer for received message
* sizer - receive buffer size
*
* RETURNS:
* transfer status
*/
i2c_message_status
i2c_wbrd(i2c_bus_number bus, i2c_address addr, uint8_t cmd,
void *bufr, int sizer)
{
i2c_message msg[2];
uint8_t bufw = cmd;
msg[0].addr = addr;
msg[0].flags = I2C_MSG_WR | I2C_MSG_ERRSKIP;
if (addr > 0xff)
msg[0].flags |= I2C_MSG_ADDR_10;
msg[0].status = 0;
msg[0].len = sizeof(bufw);
msg[0].buf = &bufw;
msg[1].addr = addr;
msg[1].flags = I2C_MSG_ERRSKIP;
if (addr > 0xff)
msg[1].flags |= I2C_MSG_ADDR_10;
msg[1].status = 0;
msg[1].len = sizer;
msg[1].buf = bufr;
return i2c_transfer_wait(bus, msg, 2);
}

View File

@@ -1,262 +0,0 @@
/* I2C driver for MCF5206eLITE board. I2C bus accessed through on-chip
* MCF5206e MBUS controller.
*
* The purpose of this module is to perform I2C driver initialization
* and serialize I2C transfers.
*
* 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 <rtems.h>
#include <bsp.h>
#include <stdlib.h>
#include <string.h>
#include "i2c.h"
#include "i2cdrv.h"
#include "mcf5206/mcfmbus.h"
#ifndef I2C_NUMBER_OF_BUSES
#define I2C_NUMBER_OF_BUSES (1)
#endif
#ifndef I2C_SELECT_BUS
#define I2C_SELECT_BUS(bus)
#endif
/*
* Few I2C transfers may be posted simultaneously, but MBUS driver is able
* to process it one-by-one. To serialize transfers, function i2c_transfer
* put transfer information to the queue and initiate new transfers if MBUS
* driver is not busy. When driver is busy, next transfer is dequeued
* when current active transfer is finished.
*/
/*
* i2c_qel - I2C transfers queue element; contain information about
* delayed transfer
*/
typedef struct i2c_qel {
i2c_bus_number bus; /* I2C bus number */
i2c_message *msg; /* pointer to the transfer' messages array */
int nmsg; /* number of messages in transfer */
i2c_transfer_done done; /* transfer done callback function */
void * done_arg_ptr; /* arbitrary arg pointer to done callback */
} i2c_qel;
/* Memory for I2C transfer queue. This queue represented like a ring buffer */
static i2c_qel *tqueue;
/* Maximum number of elements in transfer queue */
static int tqueue_size;
/* Position of next free element in a ring buffer */
static volatile int tqueue_head;
/* Position of the first element in transfer queue */
static volatile int tqueue_tail;
/* MBus I2C bus controller busy flag */
static volatile bool mbus_busy;
/* MBus I2C bus controller descriptor */
static mcfmbus mbus;
/* Clock rate selected for each of bus */
static int i2cdrv_bus_clock_div[I2C_NUMBER_OF_BUSES];
/* Currently selected I2C bus clock rate */
static int i2cdrv_bus_clock_div_current;
/* Forward function declaration */
static void i2cdrv_unload(void);
/* i2cdrv_done --
* Callback function which is called from MBus low-level driver when
* transfer is finished.
*/
static void
i2cdrv_done(void * arg_ptr)
{
rtems_interrupt_level level;
i2c_qel *qel = tqueue + tqueue_tail;
qel->done(qel->done_arg_ptr);
rtems_interrupt_disable(level);
tqueue_tail = (tqueue_tail + 1) % tqueue_size;
mbus_busy = false;
rtems_interrupt_enable(level);
i2cdrv_unload();
}
/* i2cdrv_unload --
* If MBUS controller is not busy and transfer waiting in a queue,
* initiate processing of the next transfer in queue.
*/
static void
i2cdrv_unload(void)
{
rtems_interrupt_level level;
i2c_qel *qel;
rtems_status_code sc;
rtems_interrupt_disable(level);
if (!mbus_busy && (tqueue_head != tqueue_tail))
{
mbus_busy = true;
rtems_interrupt_enable(level);
qel = tqueue + tqueue_tail;
I2C_SELECT_BUS(qel->bus);
if (i2cdrv_bus_clock_div[qel->bus] != i2cdrv_bus_clock_div_current)
{
i2cdrv_bus_clock_div_current = i2cdrv_bus_clock_div[qel->bus];
mcfmbus_select_clock_divider(&mbus, i2cdrv_bus_clock_div_current);
}
sc = mcfmbus_i2c_transfer(&mbus, qel->nmsg, qel->msg,
i2cdrv_done,qel);
if (sc != RTEMS_SUCCESSFUL)
{
int i;
for (i = 0; i < qel->nmsg; i++)
{
qel->msg[i].status = I2C_RESOURCE_NOT_AVAILABLE;
}
i2cdrv_done(qel);
}
}
else
{
rtems_interrupt_enable(level);
}
}
/* i2c_transfer --
* Initiate multiple-messages transfer over specified I2C bus or
* put request into queue if bus or some other resource is busy. (This
* is non-blocking function).
*
* PARAMETERS:
* bus - I2C bus number
* nmsg - number of messages
* msg - pointer to messages array
* done - function which is called when transfer is finished
* done_arg_ptr - arbitrary argument pointer passed to done funciton
*
* RETURNS:
* RTEMS_SUCCESSFUL if transfer initiated successfully, or error
* code if something failed.
*/
rtems_status_code
i2c_transfer(i2c_bus_number bus, int nmsg, i2c_message *msg,
i2c_transfer_done done, void * done_arg_ptr)
{
i2c_qel qel;
rtems_interrupt_level level;
if (bus >= I2C_NUMBER_OF_BUSES)
{
return RTEMS_INVALID_NUMBER;
}
if (msg == NULL)
{
return RTEMS_INVALID_ADDRESS;
}
qel.bus = bus;
qel.msg = msg;
qel.nmsg = nmsg;
qel.done = done;
qel.done_arg_ptr = done_arg_ptr;
rtems_interrupt_disable(level);
if ((tqueue_head + 1) % tqueue_size == tqueue_tail)
{
rtems_interrupt_enable(level);
return RTEMS_TOO_MANY;
}
memcpy(tqueue + tqueue_head, &qel, sizeof(qel));
tqueue_head = (tqueue_head + 1) % tqueue_size;
rtems_interrupt_enable(level);
i2cdrv_unload();
return RTEMS_SUCCESSFUL;
}
/* i2cdrv_initialize --
* I2C driver initialization (rtems I/O driver primitive)
*/
rtems_device_driver
i2cdrv_initialize(rtems_device_major_number major,
rtems_device_minor_number minor,
void *arg)
{
int i;
rtems_status_code sc;
mbus_busy = false;
tqueue_tail = tqueue_head = 0;
tqueue_size = 32;
tqueue = calloc(tqueue_size, sizeof(i2c_qel));
sc = mcfmbus_initialize(&mbus, MBAR);
if (sc != RTEMS_SUCCESSFUL)
return sc;
for (i = 0; i < I2C_NUMBER_OF_BUSES; i++)
{
sc = i2c_select_clock_rate(i, 4096);
if (sc != RTEMS_SUCCESSFUL)
return sc;
}
i2cdrv_bus_clock_div_current = -1;
return RTEMS_SUCCESSFUL;
}
/* i2c_select_clock_rate --
* select I2C bus clock rate for specified bus. Some bus controller do not
* allow to select arbitrary clock rate; in this case nearest possible
* slower clock rate is selected.
*
* PARAMETERS:
* bus - I2C bus number
* bps - data transfer rate for this bytes in bits per second
*
* RETURNS:
* RTEMS_SUCCESSFUL, if operation performed successfully,
* RTEMS_INVALID_NUMBER, if wrong bus number is specified,
* RTEMS_UNSATISFIED, if bus do not support data transfer rate selection
* or specified data transfer rate could not be used.
*/
rtems_status_code
i2c_select_clock_rate(i2c_bus_number bus, int bps)
{
int div;
if (bus >= I2C_NUMBER_OF_BUSES)
return RTEMS_INVALID_NUMBER;
if (bps == 0)
return RTEMS_UNSATISFIED;
div = BSP_SYSTEM_FREQUENCY / bps;
i2cdrv_bus_clock_div[bus] = div;
return RTEMS_SUCCESSFUL;
}
/* i2c_poll --
* Poll I2C bus controller for events and hanle it. This function is
* used when I2C driver operates in poll-driven mode.
*
* PARAMETERS:
* bus - bus number to be polled
*
* RETURNS:
* none
*/
void
i2c_poll(i2c_bus_number bus)
{
mcfmbus_poll(&mbus);
}

View File

@@ -1,201 +0,0 @@
/**
* @file
*
* @ingroup RTEMSBSPsM68kMCF5206Elite
*
* @brief Global BSP definitions.
*/
/*
* Board Support Package for MCF5206eLITE evaluation board
* BSP definitions
*
* 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.
*/
#ifndef LIBBSP_M68K_MCF5206ELITE_BSP_H
#define LIBBSP_M68K_MCF5206ELITE_BSP_H
/**
* @defgroup RTEMSBSPsM68kMCF5206Elite MCF5206eLite
*
* @ingroup RTEMSBSPsM68k
*
* @brief MCF5206eLite Board Support Package.
*
* @{
*/
#include "mcf5206/mcf5206e.h"
/*** Board resources allocation ***/
/*
* To achieve some compatibility with dBUG monitor, we use the same
* memory resources allocation as it is used in dBUG.
*
* If this definitions will be changed, change the linker script also.
*/
/* Memory mapping */
/* CS0: Boot Flash */
#define BSP_MEM_ADDR_FLASH (0xFFE00000)
#define BSP_MEM_SIZE_FLASH (1*1024*1024)
#define BSP_MEM_MASK_FLASH (MCF5206E_CSMR_MASK_1M)
/* CS2: External SRAM */
#define BSP_MEM_ADDR_ESRAM (0x30000000)
#define BSP_MEM_SIZE_ESRAM (1*1024*1024)
#define BSP_MEM_MASK_ESRAM (MCF5206E_CSMR_MASK_1M)
/* CS3: General-Purpose I/O register */
#define BSP_MEM_ADDR_GPIO (0x40000000)
#define BSP_MEM_SIZE_GPIO (64*1024)
#define BSP_MEM_MASK_GPIO (MCF5206E_CSMR_MASK_64K)
/* DRAM0: Dynamic RAM */
#define BSP_MEM_ADDR_DRAM (0x00000000)
#define BSP_MEM_SIZE_DRAM (16*1024*1024)
#define BSP_MEM_MASK_DRAM (MCF5206E_DCMR_MASK_16M)
/* On-chip SRAM */
#define BSP_MEM_ADDR_SRAM (0x20000000)
#define BSP_MEM_SIZE_SRAM (8*1024)
/* On-chip peripherial registers */
#define BSP_MEM_ADDR_IMM (0x10000000)
#define BSP_MEM_SIZE_IMM (1*1024)
#define MBAR BSP_MEM_ADDR_IMM
/* Interrupt vector assignment */
#define BSP_INTVEC_AVEC1 (25)
#define BSP_INTLVL_AVEC1 (1)
#define BSP_INTPRIO_AVEC1 (3)
#define BSP_INTVEC_AVEC2 (26)
#define BSP_INTLVL_AVEC2 (2)
#define BSP_INTPRIO_AVEC2 (3)
#define BSP_INTVEC_AVEC3 (27)
#define BSP_INTLVL_AVEC3 (3)
#define BSP_INTPRIO_AVEC3 (3)
#define BSP_INTVEC_AVEC4 (28)
#define BSP_INTLVL_AVEC4 (4)
#define BSP_INTPRIO_AVEC4 (3)
#define BSP_INTVEC_AVEC5 (29)
#define BSP_INTLVL_AVEC5 (5)
#define BSP_INTPRIO_AVEC5 (3)
#define BSP_INTVEC_AVEC6 (30)
#define BSP_INTLVL_AVEC6 (6)
#define BSP_INTPRIO_AVEC6 (3)
#define BSP_INTVEC_AVEC7 (31)
#define BSP_INTLVL_AVEC7 (7)
#define BSP_INTPRIO_AVEC7 (3)
#define BSP_INTVEC_TIMER1 (BSP_INTVEC_AVEC5)
#define BSP_INTLVL_TIMER1 (BSP_INTLVL_AVEC5)
#define BSP_INTPRIO_TIMER1 (2)
#define BSP_INTVEC_TIMER2 (BSP_INTVEC_AVEC6)
#define BSP_INTLVL_TIMER2 (BSP_INTLVL_AVEC6)
#define BSP_INTPRIO_TIMER2 (2)
#define BSP_INTVEC_MBUS (BSP_INTVEC_AVEC4)
#define BSP_INTLVL_MBUS (BSP_INTLVL_AVEC4)
#define BSP_INTPRIO_MBUS (2)
#define BSP_INTVEC_UART1 (64)
#define BSP_INTLVL_UART1 (4)
#define BSP_INTPRIO_UART1 (0)
#define BSP_INTVEC_UART2 (65)
#define BSP_INTLVL_UART2 (4)
#define BSP_INTPRIO_UART2 (1)
#define BSP_INTVEC_DMA0 (66)
#define BSP_INTLVL_DMA0 (3)
#define BSP_INTPRIO_DMA0 (1)
#define BSP_INTVEC_DMA1 (67)
#define BSP_INTLVL_DMA1 (3)
#define BSP_INTPRIO_DMA1 (2)
/* Location of DS1307 Real-Time Clock/NVRAM chip */
#define DS1307_I2C_BUS_NUMBER (0)
#ifndef ASM
#include <bspopts.h>
#include <rtems.h>
#include <bsp/default-initial-extension.h>
#ifdef __cplusplus
extern "C" {
#endif
/* System frequency */
#define BSP_SYSTEM_FREQUENCY ((unsigned int)&_SYS_CLOCK_FREQUENCY)
extern char _SYS_CLOCK_FREQUENCY; /* Don't use this variable directly!!! */
/* MBUS I2C bus clock default frequency */
#define BSP_MBUS_FREQUENCY (16000)
/* Number of I2C buses supported in this board */
#define I2C_NUMBER_OF_BUSES (1)
/* I2C bus selection */
#define I2C_SELECT_BUS(bus)
/*
* Simple spin delay in microsecond units for device drivers.
* This is very dependent on the clock speed of the target.
*/
#define rtems_bsp_delay( microseconds ) \
{ register uint32_t _delay=(microseconds); \
register uint32_t _tmp=123; \
__asm__ volatile( "0: \
nbcd %0 ; \
nbcd %0 ; \
dbf %1,0b" \
: "=d" (_tmp), "=d" (_delay) \
: "0" (_tmp), "1" (_delay) ); \
}
extern rtems_isr_entry M68Kvec[]; /* vector table address */
extern rtems_isr (*rtems_clock_hook)(rtems_vector_number);
/* functions */
rtems_isr_entry set_vector(
rtems_isr_entry handler,
rtems_vector_number vector,
int type
);
/*
* Prototypes for BSP methods that cross file boundaries
*/
void Init5206e(void);
#ifdef __cplusplus
}
#endif
#endif /* ASM */
/** @} */
#endif

View File

@@ -1 +0,0 @@
#include <bsp/irq-default.h>

View File

@@ -1,41 +0,0 @@
/*
* This file contains the definitions for Dallas Semiconductor
* DS1307/DS1308 serial real-time clock/NVRAM.
*
* 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.
*/
#ifndef __RTC_DS1307__
#define __RTC_DS1307__
#define DS1307_I2C_ADDRESS (0xD0) /* I2C bus address assigned to DS1307 */
#define DS1307_SECOND (0x00)
#define DS1307_SECOND_HALT (0x80) /* High bit is a Clock Halt bit */
#define DS1307_MINUTE (0x01)
#define DS1307_HOUR (0x02)
#define DS1307_HOUR_12 (0x40) /* 12-hour mode */
#define DS1307_HOUR_PM (0x20) /* PM in 12-hour mode */
#define DS1307_DAY_OF_WEEK (0x03)
#define DS1307_DAY (0x04)
#define DS1307_MONTH (0x05)
#define DS1307_YEAR (0x06)
#define DS1307_CONTROL (0x07)
#define DS1307_CONTROL_OUT (0x80) /* Output control */
#define DS1307_CONTROL_SQWE (0x10) /* Sqware Wave Enable */
#define DS1307_CONTROL_RS_1 (0x00) /* Rate select: 1 Hz */
#define DS1307_CONTROL_RS_4096 (0x01) /* Rate select: 4096 Hz */
#define DS1307_CONTROL_RS_8192 (0x02) /* Rate select: 8192 Hz */
#define DS1307_CONTROL_RS_32768 (0x03) /* Rate select; 32768 Hz */
#define DS1307_NVRAM_START (0x08) /* Start location of non-volatile memory */
#define DS1307_NVRAM_END (0x3F) /* End location of non-volatile memory */
#define DS1307_NVRAM_SIZE (56) /* Size of non-volatile memory */
#endif /* __RTC_DS1307__ */

View File

@@ -1,243 +0,0 @@
/*
* Generic I2C bus interface for RTEMS
*
* 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.
*/
#ifndef __RTEMS__I2C_H__
#define __RTEMS__I2C_H__
#include <rtems.h>
#include <bsp.h>
/* This header file define the generic interface to i2c buses available in
* system. This interface may be used by user applications or i2c-device
* drivers (like RTC, NVRAM, etc).
*
* Functions i2c_initialize and i2c_transfer declared in this header usually
* implemented in particular board support package. Usually this
* implementation is a simple wrapper or multiplexor to I2C controller
* driver which is available in system. It may be generic "software
* controller" I2C driver which control SDA and SCL signals directly (if SDA
* and SCL is general-purpose I/O pins), or driver for hardware I2C
* controller (standalone or integrated with processors: MBus controller in
* ColdFire processors, I2C controller in PowerQUICC and so on).
*
* i2c_transfer is a very generic low-level function. Higher-level function
* i2c_write, i2c_read, i2c_wrrd, i2c_wbrd is defined here too.
*/
/* I2C Bus Number type */
typedef uint32_t i2c_bus_number;
/* I2C device address */
typedef uint16_t i2c_address;
/* I2C error codes generated during message transfer */
typedef enum i2c_message_status {
I2C_SUCCESSFUL = 0,
I2C_TIMEOUT,
I2C_NO_DEVICE,
I2C_ARBITRATION_LOST,
I2C_NO_ACKNOWLEDGE,
I2C_NO_DATA,
I2C_RESOURCE_NOT_AVAILABLE
} i2c_message_status;
/* I2C Message */
typedef struct i2c_message {
i2c_address addr; /* I2C slave device address */
uint16_t flags; /* message flags (see below) */
i2c_message_status status; /* message transfer status code */
uint16_t len; /* Number of bytes to read or write */
uint8_t *buf; /* pointer to data array */
} i2c_message;
/* I2C message flag */
#define I2C_MSG_ADDR_10 (0x01) /* 10-bit address */
#define I2C_MSG_WR (0x02) /* transfer direction for this message
from master to slave */
#define I2C_MSG_ERRSKIP (0x04) /* Skip message if last transfered message
is failed */
/* Type for function which is called when transfer over I2C bus is finished */
typedef void (*i2c_transfer_done) (void *arg);
/* i2c_initialize --
* I2C driver initialization. This function usually called on device
* driver initialization state, before initialization task. All I2C
* buses are initialized; reasonable slow data transfer rate is
* selected for each bus.
*
* PARAMETERS:
* major - I2C device major number
* minor - I2C device minor number
* arg - RTEMS driver initialization argument
*
* RETURNS:
* RTEMS status code
*/
rtems_device_driver
i2c_initialize(rtems_device_major_number major,
rtems_device_minor_number minor,
void *arg);
/* i2c_select_clock_rate --
* select I2C bus clock rate for specified bus. Some bus controller do not
* allow to select arbitrary clock rate; in this case nearest possible
* slower clock rate is selected.
*
* PARAMETERS:
* bus - I2C bus number
* bps - data transfer rate for this bytes in bits per second
*
* RETURNS:
* RTEMS_SUCCESSFUL, if operation performed successfully,
* RTEMS_INVALID_NUMBER, if wrong bus number is specified,
* RTEMS_UNSATISFIED, if bus do not support data transfer rate selection
* or specified data transfer rate could not be used.
*/
rtems_status_code
i2c_select_clock_rate(i2c_bus_number bus, int bps);
/* i2c_transfer --
* Initiate multiple-messages transfer over specified I2C bus or
* put request into queue if bus or some other resource is busy. (This
* is non-blocking function).
*
* PARAMETERS:
* bus - I2C bus number
* 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 if something failed.
*/
rtems_status_code
i2c_transfer(i2c_bus_number bus, int nmsg, i2c_message *msg,
i2c_transfer_done done, void * done_arg_ptr);
/* i2c_transfer_wait --
* Initiate I2C bus transfer and block until this transfer will be
* finished. This function wait the semaphore if system in
* SYSTEM_STATE_UP state, or poll done flag in other states.
*
* PARAMETERS:
* bus - I2C bus number
* msg - pointer to transfer messages array
* nmsg - number of messages in transfer
*
* RETURNS:
* I2C_SUCCESSFUL, if transfer finished successfully,
* I2C_RESOURCE_NOT_AVAILABLE, if semaphore operations has failed,
* value of status field of first error-finished message in transfer,
* if something wrong.
*/
i2c_message_status
i2c_transfer_wait(i2c_bus_number bus, i2c_message *msg, int nmsg);
/* i2c_poll --
* Poll I2C bus controller for events and hanle it. This function is
* used when I2C driver operates in poll-driven mode.
*
* PARAMETERS:
* bus - bus number to be polled
*
* RETURNS:
* none
*/
void
i2c_poll(i2c_bus_number bus);
/* i2c_write --
* Send single message over specified I2C bus to addressed device and
* wait while transfer is finished.
*
* PARAMETERS:
* bus - I2C bus number
* addr - address of I2C device
* buf - data to be sent to device
* size - data buffer size
*
* RETURNS:
* transfer status
*/
i2c_message_status
i2c_write(i2c_bus_number bus, i2c_address addr, void *buf, int size);
/* i2c_wrbyte --
* Send single one-byte long message over specified I2C bus to
* addressed device and wait while transfer is finished.
*
* PARAMETERS:
* bus - I2C bus number
* addr - address of I2C device
* cmd - byte message to be sent to device
*
* RETURNS:
* transfer status
*/
i2c_message_status
i2c_wrbyte(i2c_bus_number bus, i2c_address addr, uint8_t cmd);
/* i2c_read --
* receive single message over specified I2C bus from addressed device.
* This call will wait while transfer is finished.
*
* PARAMETERS:
* bus - I2C bus number
* addr - address of I2C device
* buf - buffer for received message
* size - receive buffer size
*
* RETURNS:
* transfer status
*/
i2c_message_status
i2c_read(i2c_bus_number bus, i2c_address addr, void *buf, int size);
/* i2c_wrrd --
* Send message over I2C bus to specified device and receive message
* from the same device during single transfer.
*
* PARAMETERS:
* bus - I2C bus number
* addr - address of I2C device
* bufw - data to be sent to device
* sizew - send data buffer size
* bufr - buffer for received message
* sizer - receive buffer size
*
* RETURNS:
* transfer status
*/
i2c_message_status
i2c_wrrd(i2c_bus_number bus, i2c_address addr, void *bufw, int sizew,
void *bufr, int sizer);
/* i2c_wbrd --
* Send one-byte message over I2C bus to specified device and receive
* message from the same device during single transfer.
*
* PARAMETERS:
* bus - I2C bus number
* addr - address of I2C device
* cmd - one-byte message to be sent over I2C bus
* bufr - buffer for received message
* sizer - receive buffer size
*
* RETURNS:
* transfer status
*/
i2c_message_status
i2c_wbrd(i2c_bus_number bus, i2c_address addr, uint8_t cmd,
void *bufr, int sizer);
#endif

View File

@@ -1,35 +0,0 @@
/*
* i2cdrv.h -- I2C bus driver prototype and definitions
*
* 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.
*/
#ifndef __I2CDRV_H__
#define __I2CDRV_H__
#ifdef __cplusplus
extern "C" {
#endif
#define I2C_DRIVER_TABLE_ENTRY \
{ i2cdrv_initialize, NULL, NULL, NULL, NULL, NULL }
/* i2cdrv_initialize --
* I2C driver initialization (rtems I/O driver primitive)
*/
rtems_device_driver
i2cdrv_initialize(rtems_device_major_number major,
rtems_device_minor_number minor,
void *arg);
#ifdef __cplusplus
}
#endif
#endif /* __I2CDRV_H__ */

View File

@@ -1,71 +0,0 @@
/*
* nvram.h -- DS1307-based non-volatile memory device driver.
*
* This driver support file-like operations to 56-bytes long non-volatile
* memory of DS1307 I2C real-time clock chip.
*
* 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.
*/
#ifndef __DRIVER__NVRAM_H__
#define __DRIVER__NVRAM_H__
#ifdef __cplusplus
extern "C" {
#endif
#define NVRAM_DRIVER_TABLE_ENTRY \
{ nvram_driver_initialize, nvram_driver_open, nvram_driver_close, \
nvram_driver_read, nvram_driver_write, NULL }
/* nvram_driver_initialize --
* Non-volatile memory device driver initialization.
*/
rtems_device_driver
nvram_driver_initialize(rtems_device_major_number major,
rtems_device_minor_number minor,
void *arg);
/* nvram_driver_open --
* Non-volatile memory device driver open primitive.
*/
rtems_device_driver
nvram_driver_open(rtems_device_major_number major,
rtems_device_minor_number minor,
void *arg);
/* nvram_driver_close --
* Non-volatile memory device driver close primitive.
*/
rtems_device_driver
nvram_driver_close(rtems_device_major_number major,
rtems_device_minor_number minor,
void *arg);
/* nvram_driver_read --
* Non-volatile memory device driver read primitive.
*/
rtems_device_driver
nvram_driver_read(rtems_device_major_number major,
rtems_device_minor_number minor,
void *arg);
/* nvram_driver_write --
* Non-volatile memory device driver write primitive.
*/
rtems_device_driver
nvram_driver_write(rtems_device_major_number major,
rtems_device_minor_number minor,
void *arg);
#ifdef __cplusplus
}
#endif
#endif /* __VFDDRV_H__ */

View File

@@ -1,37 +0,0 @@
/*
* @file
* @ingroup m68k_mcf5206elite
* @brief Implementations for interrupt mechanisms for Time Test 27
*/
/*
* 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.
*/
#ifndef _RTEMS_TMTEST27
#error "This is an RTEMS internal file you must not include directly."
#endif
#ifndef __tm27_h
#define __tm27_h
/*
* Stuff for Time Test 27
* Don't bother with hardware -- just use a software-interrupt
*/
#define MUST_WAIT_FOR_INTERRUPT 0
#define TM27_USE_VECTOR_HANDLER
#define Install_tm27_vector( handler ) set_vector( (handler), 34, 1 )
#define Cause_tm27_intr() asm volatile ("trap #2");
#define Clear_tm27_intr() /* empty */
#define Lower_tm27_intr() /* empty */
#endif

View File

@@ -1,173 +0,0 @@
/*
* DS1307-based Non-Volatile memory device driver
*
* DS1307 chip is a I2C Real-Time Clock. It contains 56 bytes of
* non-volatile RAM storage. This driver provide file-like interface to
* this memory.
*
* 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 <rtems.h>
#include <rtems/libio.h>
#include <errno.h>
#include <string.h>
#include <bsp.h>
#include <nvram.h>
#include <i2c.h>
#include <ds1307.h>
/* nvram_driver_initialize --
* Non-volatile memory device driver initialization.
*/
rtems_device_driver
nvram_driver_initialize(rtems_device_major_number major,
rtems_device_minor_number minor,
void *arg)
{
rtems_status_code sc;
i2c_message_status status;
i2c_bus_number bus = DS1307_I2C_BUS_NUMBER;
i2c_address addr = DS1307_I2C_ADDRESS;
int try = 0;
do {
status = i2c_wrbyte(bus, addr, 0);
if (status == I2C_NO_DEVICE)
break;
try++;
} while ((try < 15) && (status != I2C_SUCCESSFUL));
if (status == I2C_SUCCESSFUL)
{
sc = rtems_io_register_name("/dev/nvram", major, 0);
if (sc != RTEMS_SUCCESSFUL)
{
errno = EIO;
return RTEMS_UNSATISFIED;
}
else
return RTEMS_SUCCESSFUL;
}
else
{
errno = ENODEV;
return RTEMS_UNSATISFIED;
}
}
/* nvram_driver_open --
* Non-volatile memory device driver open primitive.
*/
rtems_device_driver
nvram_driver_open(rtems_device_major_number major,
rtems_device_minor_number minor,
void *arg)
{
return RTEMS_SUCCESSFUL;
}
/* nvram_driver_close --
* Non-volatile memory device driver close primitive.
*/
rtems_device_driver
nvram_driver_close(rtems_device_major_number major,
rtems_device_minor_number minor,
void *arg)
{
return RTEMS_SUCCESSFUL;
}
/* nvram_driver_read --
* Non-volatile memory device driver read primitive.
*/
rtems_device_driver
nvram_driver_read(rtems_device_major_number major,
rtems_device_minor_number minor,
void *arg)
{
rtems_libio_rw_args_t *args = arg;
uint32_t count;
i2c_bus_number bus = DS1307_I2C_BUS_NUMBER;
i2c_address addr = DS1307_I2C_ADDRESS;
i2c_message_status status;
if (args->offset >= DS1307_NVRAM_SIZE)
{
count = 0;
}
else if (args->offset + args->count >= DS1307_NVRAM_SIZE)
{
count = DS1307_NVRAM_SIZE - args->offset;
}
else
{
count = args->count;
}
if (count > 0)
{
int try = 0;
do {
status = i2c_wbrd(bus, addr, DS1307_NVRAM_START + args->offset,
args->buffer, count);
try++;
} while ((try < 15) && (status != I2C_SUCCESSFUL));
if (status != I2C_SUCCESSFUL)
{
errno = EIO;
return RTEMS_UNSATISFIED;
}
}
args->bytes_moved = count;
return RTEMS_SUCCESSFUL;
}
/* nvram_driver_write --
* Non-volatile memory device driver write primitive.
*/
rtems_device_driver
nvram_driver_write(rtems_device_major_number major,
rtems_device_minor_number minor,
void *arg)
{
rtems_libio_rw_args_t *args = arg;
uint32_t count;
i2c_bus_number bus = DS1307_I2C_BUS_NUMBER;
i2c_address addr = DS1307_I2C_ADDRESS;
i2c_message_status status;
if (args->offset >= DS1307_NVRAM_SIZE)
{
count = 0;
}
else if (args->offset + args->count >= DS1307_NVRAM_SIZE)
{
count = DS1307_NVRAM_SIZE - args->offset;
}
else
{
count = args->count;
}
if (count > 0)
{
int try = 0;
do {
uint8_t buf[DS1307_NVRAM_SIZE + 1];
buf[0] = DS1307_NVRAM_START + args->offset;
memcpy(buf+1, args->buffer, count);
status = i2c_write(bus, addr, buf, count+1);
try++;
} while ((try < 15) && (status != I2C_SUCCESSFUL));
if (status != I2C_SUCCESSFUL)
{
errno = EIO;
return RTEMS_UNSATISFIED;
}
}
args->bytes_moved = count;
return RTEMS_SUCCESSFUL;
}

View File

@@ -1,206 +0,0 @@
/*
* This file interfaces with the real-time clock found in a
* Dallas Semiconductor DS1307/DS1308 serial real-time clock chip.
* This RTC have I2C bus interface. BSP have to provide I2C bus primitives
* to make this driver working. getRegister and setRegister primitives is
* not used here to avoid multiple transactions over I2C bus (each transaction
* require significant time and error when date/time information red may
* occurs). ulControlPort contains I2C bus number; ulDataPort contains
* RTC I2C device address.
*
* Year 2000 Note:
*
* This chip only uses a two digit field to store the year. This code
* uses the RTEMS Epoch as a pivot year. This lets us map the two digit
* year field as follows:
*
* + two digit years 00-87 are mapped to 2000-2087
* + two digit years 88-99 are mapped to 1988-1999
*/
/*
* 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 <rtems.h>
#include <libchip/rtc.h>
#include <string.h>
#include "ds1307.h"
#include "i2c.h"
/* Convert from/to Binary-Coded Decimal representation */
#define From_BCD( _x ) ((((_x) >> 4) * 10) + ((_x) & 0x0F))
#define To_BCD( _x ) ((((_x) / 10) << 4) + ((_x) % 10))
/* ds1307_initialize --
* Initialize DS1307 real-time clock chip. If RTC is halted, this
* function resume counting.
*
* PARAMETERS:
* minor -- minor RTC device number
*/
static void ds1307_initialize(int minor)
{
i2c_message_status status;
int try;
uint8_t sec;
i2c_bus_number bus;
i2c_address addr;
bus = RTC_Table[minor].ulCtrlPort1;
addr = RTC_Table[minor].ulDataPort;
/* Read SECONDS register */
try = 0;
do {
status = i2c_wbrd(bus, addr, 0, &sec, sizeof(sec));
try++;
} while ((status != I2C_SUCCESSFUL) && (try < 15));
/* If clock is halted, reset and start the clock */
if ((sec & DS1307_SECOND_HALT) != 0) {
uint8_t start[8];
memset(start, 0, sizeof(start));
start[0] = DS1307_SECOND;
try = 0;
do {
status = i2c_write(bus, addr, start, 2);
} while ((status != I2C_SUCCESSFUL) && (try < 15));
}
}
/* ds1307_get_time --
* read current time from DS1307 real-time clock chip and convert it
* to the rtems_time_of_day structure.
*
* PARAMETERS:
* minor -- minor RTC device number
* time -- place to put return value (date and time)
*
* RETURNS:
* 0, if time obtained successfully
* -1, if error occured
*/
static int ds1307_get_time(int minor, rtems_time_of_day *time)
{
i2c_bus_number bus;
i2c_address addr;
uint8_t info[8];
uint32_t v1, v2;
i2c_message_status status;
int try;
if (time == NULL)
return -1;
bus = RTC_Table[minor].ulCtrlPort1;
addr = RTC_Table[minor].ulDataPort;
memset(time, 0, sizeof(rtems_time_of_day));
try = 0;
do {
status = i2c_wbrd(bus, addr, 0, info, sizeof(info));
try++;
} while ((status != I2C_SUCCESSFUL) && (try < 10));
if (status != I2C_SUCCESSFUL) {
return -1;
}
v1 = info[DS1307_YEAR];
v2 = From_BCD(v1);
if (v2 < 88)
time->year = 2000 + v2;
else
time->year = 1900 + v2;
v1 = info[DS1307_MONTH] & ~0xE0;
time->month = From_BCD(v1);
v1 = info[DS1307_DAY] & ~0xC0;
time->day = From_BCD(v1);
v1 = info[DS1307_HOUR];
if (v1 & DS1307_HOUR_12) {
v2 = v1 & ~0xE0;
if (v1 & DS1307_HOUR_PM) {
time->hour = From_BCD(v2) + 12;
} else {
time->hour = From_BCD(v2);
}
} else {
v2 = v1 & ~0xC0;
time->hour = From_BCD(v2);
}
v1 = info[DS1307_MINUTE] & ~0x80;
time->minute = From_BCD(v1);
v1 = info[DS1307_SECOND];
v2 = v1 & ~0x80;
time->second = From_BCD(v2);
return 0;
}
/* ds1307_set_time --
* set time to the DS1307 real-time clock chip
*
* PARAMETERS:
* minor -- minor RTC device number
* time -- new date and time to be written to DS1307
*
* RETURNS:
* 0, if time obtained successfully
* -1, if error occured
*/
static int ds1307_set_time(int minor, const rtems_time_of_day *time)
{
i2c_bus_number bus;
i2c_address addr;
uint8_t info[8];
i2c_message_status status;
int try;
if (time == NULL)
return -1;
bus = RTC_Table[minor].ulCtrlPort1;
addr = RTC_Table[minor].ulDataPort;
if (time->year >= 2088)
rtems_fatal_error_occurred(RTEMS_INVALID_NUMBER);
info[0] = DS1307_SECOND;
info[1 + DS1307_YEAR] = To_BCD(time->year % 100);
info[1 + DS1307_MONTH] = To_BCD(time->month);
info[1 + DS1307_DAY] = To_BCD(time->day);
info[1 + DS1307_HOUR] = To_BCD(time->hour);
info[1 + DS1307_MINUTE] = To_BCD(time->minute);
info[1 + DS1307_SECOND] = To_BCD(time->second);
info[1 + DS1307_DAY_OF_WEEK] = 1; /* Do not set day of week */
try = 0;
do {
status = i2c_write(bus, addr, info, 8);
try++;
} while ((status != I2C_SUCCESSFUL) && (try < 10));
if (status != I2C_SUCCESSFUL)
return -1;
else
return 0;
}
/* Driver function table */
rtc_fns ds1307_fns = {
ds1307_initialize,
ds1307_get_time,
ds1307_set_time
};

View File

@@ -1,80 +0,0 @@
/*
* This file contains the RTC driver table for Motorola MCF5206eLITE
* ColdFire evaluation board.
*
* 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 <i2c.h>
#include <libchip/rtc.h>
#include <ds1307.h>
/* Forward function declaration */
bool mcf5206elite_ds1307_probe(int minor);
extern rtc_fns ds1307_fns;
/* The following table configures the RTC drivers used in this BSP */
rtc_tbl RTC_Table[] = {
{
"/dev/rtc", /* sDeviceName */
RTC_CUSTOM, /* deviceType */
&ds1307_fns, /* pDeviceFns */
mcf5206elite_ds1307_probe, /* deviceProbe */
NULL, /* pDeviceParams */
0x00, /* ulCtrlPort1, for DS1307-I2C bus number */
DS1307_I2C_ADDRESS, /* ulDataPort, for DS1307-I2C device addr */
NULL, /* getRegister - not applicable to DS1307 */
NULL /* setRegister - not applicable to DS1307 */
}
};
/* Some information used by the RTC driver */
#define NUM_RTCS (sizeof(RTC_Table)/sizeof(rtc_tbl))
size_t RTC_Count = NUM_RTCS;
/* mcf5206elite_ds1307_probe --
* RTC presence probe function. Return TRUE, if device is present.
* Device presence checked by probe access to RTC device over I2C bus.
*
* PARAMETERS:
* minor - minor RTC device number
*
* RETURNS:
* TRUE, if RTC device is present
*/
bool
mcf5206elite_ds1307_probe(int minor)
{
int try = 0;
i2c_message_status status;
rtc_tbl *rtc;
i2c_bus_number bus;
i2c_address addr;
if (minor >= NUM_RTCS)
return false;
rtc = RTC_Table + minor;
bus = rtc->ulCtrlPort1;
addr = rtc->ulDataPort;
do {
status = i2c_wrbyte(bus, addr, 0);
if (status == I2C_NO_DEVICE)
return false;
try++;
} while ((try < 15) && (status != I2C_SUCCESSFUL));
if (status == I2C_SUCCESSFUL)
return true;
else
return false;
}

View File

@@ -1,351 +0,0 @@
#! /bin/sh -p
#
# Run rtems tests on the Motorola MCF5206eLITE Coldfire Evaluation board
# using gdb configured with P&E Micro Background Debug Mode debugging
# interface.
#
# This program generates a gdb script to run each test, intercept
# serial port output and put log into output file.
#
# Author: Victor V. Vengerov <vvv@oktet.ru>
# Copyright (C) 2000 OKTET Ltd., St.-Petersburg, Russia
#
# Partially based on runtest script for powerpc psim.
#
# COPYRIGHT (c) 1989-1999.
# 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.
#
# progname=`basename $0`
progname=${0##*/} # fast basename hack for ksh, bash
USAGE=\
"usage: $progname [ -opts ] test [ test ... ]
-s ttydevice -- specify serial device to be used to capture test
output
-r baud -- set serial port baud rate (19200 by default)
-b bdmdevice -- specify BDM device to be used to control the target
-g gdbname -- specify name of gdb program to be used
-v -- verbose output
-d -- don't remove temporary files (for debugging only)
-i -- use interrupt driven console I/O when test is running
(many tests failed when interrupt driven console
input/output is used due undetermenistic tests
behaviour)
-p -- use termios poll console I/O
-l logdir -- specify log directory (default is 'logdir')
Specify test as 'test' or 'test.exe'.
All multiprocessing tests *must* be specified simply as 'mp01', etc.
"
# export everything
set -a
# log an error to stderr
prerr()
{
echo "$*" >&2
}
fatal() {
[ "$1" ] && prerr $*
prerr "$USAGE"
exit 1
}
warn() {
[ "$1" ] && prerr $*
}
# run at normal and signalled exit
test_exit()
{
exit_code=$1
rm -f ${logfile}.tmp*
[ "$gdb_pid" ] && kill -9 $gdb_pid
[ "$serial_pid" ] && kill -9 $serial_pid
exit $exit_code
}
#
# process the options
#
# defaults for getopt vars
#
# max_run_time is defaulted to 5 minutes
#
verbose=""
serial_device=/dev/ttyS0
bdm_device=/dev/bdmcf0
gdbprog=true
for i in rtems bdm-rtems bdm bdm-elf bdm-coff ; do
if m68k-$i-gdb --version > /dev/null 2>&1 ; then
gdbprog=m68k-$i-gdb ;
break ;
fi
done
logdir=log
max_run_time=$((5 * 60))
sizeof_ram=$((1 * 1024 * 1024))
debugging="no"
baudrate="19200"
console_mode=0
while getopts vdips:r:b:l: OPT
do
case "$OPT" in
v)
verbose="yes";;
d)
debugging="yes";;
s)
serial_device="$OPTARG";;
r)
baudrate="$OPTARG";;
b)
bdm_device="$OPTARG";;
l)
logdir="$OPTARG";;
s)
gdbprog="$OPTARG";;
p)
console_mode=1;;
i)
console_mode=2;;
*)
fatal;;
esac
done
let $((shiftcount = $OPTIND - 1))
shift $shiftcount
args=$*
#
# Run the tests
#
tests="$args"
if [ ! "$tests" ]
then
set -- `echo *.exe`
tests="$*"
fi
[ -d $logdir ] ||
mkdir $logdir || fatal "could not create log directory ($logdir)"
# where the tmp files go
trap "test_exit" 1 2 3 13 14 15
for tfile in $tests
do
tname=`basename $tfile .exe`
cpus="1"
TEST_TYPE="single"
case "$tname" in
# size is no longer interactive.
capture* | monitor* | termios* | fileio* | pppd*)
warn "Skipping $tname; it is interactive"
continue
;;
*-node2*)
warn "Skipping $tname; 'runtest' runs both nodes when for *-node1"
continue
;;
*-node1*)
warn "Running both nodes associated with $tname"
tname=`echo $tname | sed 's/-node.*//'`
TEST_TYPE="mp"
;;
minimum*|stackchk*|*fatal*|malloctest*)
continue
;;
esac
if [ "$TEST_TYPE" = "mp" ] ; then
fatal "MP tests not supported for this board"
fi
if [ $TEST_TYPE = "single" ] ; then
logfile=$logdir/${tname}
infofile=${logfile}.info
scriptfile=${logfile}.ss
gdblogfile=${logfile}.gdb
rm -f ${logfile}.tmp*
date=`date`
echo "Starting $tname at $date"
# Set serial port parameters
if ! stty -F ${serial_device} raw cs8 -cstopb cread crtscts \
ispeed ${baudrate} ospeed ${baudrate} \
> /dev/null 2> /dev/null ; then
fatal "Serial port couldn't be configured"
fi
# Flush serial port
cat ${serial_device} > /dev/null &
serial_pid=$!
sleep 1s
kill ${serial_pid}
# Capture serial port
cat ${serial_device} > $logfile &
serial_pid=$!
cat > "${scriptfile}" <<EOF
target bdm $bdm_device
set \$mbar = 0x10000001
set \$csar0 = \$mbar - 1 + 0x064
set \$csmr0 = \$mbar - 1 + 0x068
set \$cscr0 = \$mbar - 1 + 0x06E
set \$csar1 = \$mbar - 1 + 0x070
set \$csmr1 = \$mbar - 1 + 0x074
set \$cscr1 = \$mbar - 1 + 0x07A
set \$csar2 = \$mbar - 1 + 0x07C
set \$csmr2 = \$mbar - 1 + 0x080
set \$cscr2 = \$mbar - 1 + 0x086
set \$csar3 = \$mbar - 1 + 0x088
set \$csmr3 = \$mbar - 1 + 0x08C
set \$cscr3 = \$mbar - 1 + 0x092
set \$csar4 = \$mbar - 1 + 0x094
set \$csmr4 = \$mbar - 1 + 0x098
set \$cscr4 = \$mbar - 1 + 0x09E
set \$csar5 = \$mbar - 1 + 0x0A0
set \$csmr5 = \$mbar - 1 + 0x0A4
set \$cscr5 = \$mbar - 1 + 0x0AA
set \$csar6 = \$mbar - 1 + 0x0AC
set \$csmr6 = \$mbar - 1 + 0x0B0
set \$cscr6 = \$mbar - 1 + 0x0B6
set \$csar7 = \$mbar - 1 + 0x0B8
set \$csmr7 = \$mbar - 1 + 0x0BC
set \$cscr7 = \$mbar - 1 + 0x0C2
#
set *((short*) \$csar0) = 0xffe0
set *((int*) \$csmr0) = 0x000f0000
set *((short*) \$cscr0) = 0x1da3
set *((short*) \$csar1) = 0x5000
set *((int*) \$csmr1) = 0x00000000
set *((short*) \$cscr1) = 0x3d43
set *((short*) \$csar2) = 0x3000
set *((int*) \$csmr2) = 0x000f0000
set *((short*) \$cscr2) = 0x1903
set *((short*) \$csar3) = 0x4000
set *((int*) \$csmr3) = 0x000f0000
set *((short*) \$cscr3) = 0x0083
#
load
# Many tests not working properly when interrupt driven console I/O is used.
set console_mode=$console_mode
set \$pc=start
set \$sp=0x20001ffc
#
break bsp_cleanup
commands
shell kill $serial_pid
quit
end
#
break _stop
commands
shell kill $serial_pid
quit 1
end
#
continue
quit 2
EOF
${gdbprog} -x "${scriptfile}" "${tfile}" > "${gdblogfile}" 2>&1 &
gdb_pid=$!
{
time_run=0
while [ $time_run -lt $max_run_time ] ; do
sleep 10s
if kill -0 $gdb_pid 2> /dev/null ; then
time_run=$((time_run+10)) ;
else
exit 0
fi
done
kill -2 $serial_pid 2> /dev/null
kill -2 $gdb_pid 2> /dev/null
{
sleep 5s ;
if kill -0 $gdb_pid 2> /dev/null ; then
kill -9 $gdb_pid 2> /dev/null ;
fi
if kill -0 $serial_pid 2> /dev/null ; then
kill -9 $serial_pid 2> /dev/null ;
fi
} &
} &
wait $gdb_pid
gdb_status=$?
{
if kill -0 $serial_pid 2> /dev/null ; then
kill $serial_pid 2> /dev/null ;
fi
sleep 5s ;
if kill -0 $serial_pid 2> /dev/null ; then
kill -9 $serial_pid 2> /dev/null ;
fi
} &
if [ $gdb_status -ge 128 ] ; then
ran_too_long="yes" ;
else
ran_too_long="no"
fi
if [ $gdb_status -ne 0 ] ; then
test_failed="yes" ;
else
test_failed="no"
fi
gdb_pid=""
serial_pid=""
fi
# Create the info files
{
echo "$date"
echo "Test run on: `uname -n`"
echo "Host Information:"
echo `uname -a`
echo
echo "Serial port: ${serial_device}"
echo "Baud rate: ${baudrate}"
echo "BDM port: ${bdm_device}"
echo "gdb: `type -path ${gdbprog}`"
cat ${logfile}
if [ "$test_failed" = "yes" ] ; then
echo -e "\\n\\nTest did not finish normally"
if [ "$ran_too_long" = "yes" ] ; then
echo "Test killed after $max_run_time seconds"
fi
fi
echo
date;
} > ${infofile}
if [ "${debugging}" = "no" ] ; then
rm -f ${scriptfile}
rm -f ${gdblogfile}
fi
done
echo "Tests completed at " `date`
test_exit 0

View File

@@ -1,217 +0,0 @@
#
# GDB Init script for the Coldfire 5206e processor.
#
# The main purpose of this script is to perform minimum initialization of
# processor so code can be loaded. Also, exception handling is performed.
#
# Copyright (C) OKTET Ltd., St.-Petersburg, Russia
# Author: Victor V. Vengerov <vvv@oktet.ru>
#
# This script partially based on gdb scripts written by
# Eric Norum, <eric@norum.ca>
#
# 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.
#
define addresses
set $mbar = 0x10000001
set $simr = $mbar - 1 + 0x003
set $icr1 = $mbar - 1 + 0x014
set $icr2 = $mbar - 1 + 0x015
set $icr3 = $mbar - 1 + 0x016
set $icr4 = $mbar - 1 + 0x017
set $icr5 = $mbar - 1 + 0x018
set $icr6 = $mbar - 1 + 0x019
set $icr7 = $mbar - 1 + 0x01A
set $icr8 = $mbar - 1 + 0x01B
set $icr9 = $mbar - 1 + 0x01C
set $icr10 = $mbar - 1 + 0x01D
set $icr11 = $mbar - 1 + 0x01E
set $icr12 = $mbar - 1 + 0x01F
set $icr13 = $mbar - 1 + 0x020
set $imr = $mbar - 1 + 0x036
set $ipr = $mbar - 1 + 0x03A
set $rsr = $mbar - 1 + 0x040
set $sypcr = $mbar - 1 + 0x041
set $swivr = $mbar - 1 + 0x042
set $swsr = $mbar - 1 + 0x043
set $dcrr = $mbar - 1 + 0x046
set $dctr = $mbar - 1 + 0x04A
set $dcar0 = $mbar - 1 + 0x04C
set $dcmr0 = $mbar - 1 + 0x050
set $dccr0 = $mbar - 1 + 0x057
set $dcar1 = $mbar - 1 + 0x058
set $dcmr1 = $mbar - 1 + 0x05C
set $dccr1 = $mbar - 1 + 0x063
set $csar0 = $mbar - 1 + 0x064
set $csmr0 = $mbar - 1 + 0x068
set $cscr0 = $mbar - 1 + 0x06E
set $csar1 = $mbar - 1 + 0x070
set $csmr1 = $mbar - 1 + 0x074
set $cscr1 = $mbar - 1 + 0x07A
set $csar2 = $mbar - 1 + 0x07C
set $csmr2 = $mbar - 1 + 0x080
set $cscr2 = $mbar - 1 + 0x086
set $csar3 = $mbar - 1 + 0x088
set $csmr3 = $mbar - 1 + 0x08C
set $cscr3 = $mbar - 1 + 0x092
set $csar4 = $mbar - 1 + 0x094
set $csmr4 = $mbar - 1 + 0x098
set $cscr4 = $mbar - 1 + 0x09E
set $csar5 = $mbar - 1 + 0x0A0
set $csmr5 = $mbar - 1 + 0x0A4
set $cscr5 = $mbar - 1 + 0x0AA
set $csar6 = $mbar - 1 + 0x0AC
set $csmr6 = $mbar - 1 + 0x0B0
set $cscr6 = $mbar - 1 + 0x0B6
set $csar7 = $mbar - 1 + 0x0B8
set $csmr7 = $mbar - 1 + 0x0BC
set $cscr7 = $mbar - 1 + 0x0C2
set $dmcr = $mbar - 1 + 0x0C6
set $par = $mbar - 1 + 0x0CA
set $tmr1 = $mbar - 1 + 0x100
set $trr1 = $mbar - 1 + 0x104
set $tcr1 = $mbar - 1 + 0x108
set $tcn1 = $mbar - 1 + 0x10C
set $ter1 = $mbar - 1 + 0x111
set $tmr2 = $mbar - 1 + 0x120
set $trr2 = $mbar - 1 + 0x124
set $tcr2 = $mbar - 1 + 0x128
set $tcn2 = $mbar - 1 + 0x12C
set $ter2 = $mbar - 1 + 0x131
end
#
# Setup CSAR0 for the FLASH ROM.
#
define setup-cs
set *((short*) $csar0) = 0xffe0
set *((int*) $csmr0) = 0x000f0000
set *((short*) $cscr0) = 0x1da3
set *((short*) $csar1) = 0x5000
set *((int*) $csmr1) = 0x00000000
set *((short*) $cscr1) = 0x3d43
set *((short*) $csar2) = 0x3000
set *((int*) $csmr2) = 0x000f0000
set *((short*) $cscr2) = 0x1903
set *((short*) $csar3) = 0x4000
set *((int*) $csmr3) = 0x000f0000
set *((short*) $cscr3) = 0x0083
end
#
# Setup the DRAM controller.
#
define setup-dram
set *((short*) $dcrr) = 24
set *((short*) $dctr) = 0x0000
set *((short*) $dcar0) = 0x0000
set *((long*) $dcmr0) = 0x000e0000
set *((char*) $dccr0) = 0x07
set *((short*) $dcar1) = 0x0000
set *((long*) $dcmr1) = 0x00000000
set *((char*) $dccr1) = 0x00
end
#
# Wake up the board
#
define initboard
addresses
setup-cs
# setup-dram
end
define ss
si
x/i $pc
end
#
# Display exception information
#
define exception-info
set $excpc = *(unsigned int *)($sp+4)
set $excfmt = (*(unsigned int *)$sp >> 28) & 0x0f
set $excfs = ((*(unsigned int *)$sp >> 24) & 0x0c) | \
((*(unsigned int *)$sp >> 16) & 0x03)
set $excvec = (*(unsigned int *)$sp >> 18) & 0xff
set $excsr = *(unsigned int *)$sp & 0xffff
printf "EXCEPTION -- SR:0x%X PC:0x%X FRAME:0x%X VECTOR:%d\n", \
$excsr, $excpc, $sp, $excvec
if $excvec == 2
printf "Access error exception"
end
if $excvec == 3
printf "Address error exception"
end
if $excvec == 4
printf "Illegal instruction exception"
end
if $excvec == 8
printf "Privelege violation exception"
end
if $excvec == 9
printf "Trace exception"
end
if $excvec == 10
printf "Unimplemented LINE-A opcode exception"
end
if $excvec == 11
printf "Unimplemented LINE-F opcode exception"
end
if $excvec == 12
printf "Debug interrupt"
end
if $excvec == 14
printf "Format error exception"
end
if $excfs == 0x04
printf " on instruction fetch"
end
if $excfs == 0x08
printf " on operand write"
end
if $excfs == 0x09
printf " on write to write-protected space"
end
if $excfs == 0x0c
printf " on operand read"
end
printf "\n"
x/4i $excpc
set $pc=$excpc
set $sp=$sp+8
end
target bdm /dev/bdmcf0
initboard
load
set $pc=start
set $sp=0x20001ffc
b bsp_cleanup
b _stop
b _unexp_exception
commands
silent
exception-info
end
b _unexp_int
b _reserved_int
b _spurious_int

View File

@@ -1,229 +0,0 @@
/*
* MCF5206e hardware startup routines
*
* This is where the real hardware setup is done. A minimal stack
* has been provided by the start.S code. No normal C or RTEMS
* functions can be called from here.
*
* This initialization code based on hardware settings of dBUG
* monitor. This must be changed if you like to run it immediately
* after reset.
*/
/*
* 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 "mcf5206/mcf5206e.h"
extern void CopyDataClearBSSAndStart(unsigned long ramsize);
extern void INTERRUPT_VECTOR(void);
#define m68k_set_srambar( _rambar0 ) \
__asm__ volatile ( "movec %0,%%rambar0\n\t" \
"nop\n\t" \
: : "d" (_rambar0) )
#define m68k_set_mbar( _mbar ) \
__asm__ volatile ( "movec %0,%%mbar\n\t" \
"nop\n\t" \
: : "d" (_mbar) )
#define mcf5206e_enable_cache() \
m68k_set_cacr( MCF5206E_CACR_CENB )
#define mcf5206e_disable_cache() \
__asm__ volatile ( "nop\n\t" \
"movec %0,%%cacr\n\t" \
"nop\n\t" \
"movec %0,%%cacr\n\t" \
"nop\n\t" \
: : "d" (MCF5206E_CACR_CINV) )
/*
* Initialize MCF5206e on-chip modules
*/
void Init5206e(void)
{
/* Set Module Base Address register */
m68k_set_mbar((MBAR & MCF5206E_MBAR_BA) | MCF5206E_MBAR_V);
/* Set System Protection Control Register (SYPCR):
* Bus Monitor Enable, Bus Monitor Timing = 1024 clocks,
* Software watchdog disabled
*/
*MCF5206E_SYPCR(MBAR) = MCF5206E_SYPCR_BME |
MCF5206E_SYPCR_BMT_1024;
/* Set Pin Assignment Register (PAR):
* Output Timer 0 (not DREQ) on *TOUT[0] / *DREQ[1]
* Input Timer 0 (not DREQ) on *TIN[0] / *DREQ[0]
* IRQ, not IPL
* UART2 RTS signal (not \RSTO)
* PST/DDATA (not PPIO)
* *WE (not CS/A)
*/
*MCF5206E_PAR(MBAR) = MCF5206E_PAR_PAR9_TOUT |
MCF5206E_PAR_PAR8_TIN0 |
MCF5206E_PAR_PAR7_UART2 |
MCF5206E_PAR_PAR6_IRQ |
MCF5206E_PAR_PAR5_PST |
MCF5206E_PAR_PAR4_DDATA |
MCF5206E_PAR_WE0_WE1_WE2_WE3;
/* Set SIM Configuration Register (SIMR):
* Disable software watchdog timer and bus timeout monitor when
* internal freeze signal is asserted.
*/
*MCF5206E_SIMR(MBAR) = MCF5206E_SIMR_FRZ0 | MCF5206E_SIMR_FRZ1;
/* Set Interrupt Mask Register: Disable all interrupts */
*MCF5206E_IMR(MBAR) = 0xFFFF;
/* Assign Interrupt Control Registers as it is defined in bsp.h */
*MCF5206E_ICR(MBAR,MCF5206E_INTR_EXT_IPL1) =
(BSP_INTLVL_AVEC1 << MCF5206E_ICR_IL_S) |
(BSP_INTPRIO_AVEC1 << MCF5206E_ICR_IP_S) |
MCF5206E_ICR_AVEC;
*MCF5206E_ICR(MBAR,MCF5206E_INTR_EXT_IPL2) =
(BSP_INTLVL_AVEC2 << MCF5206E_ICR_IL_S) |
(BSP_INTPRIO_AVEC2 << MCF5206E_ICR_IP_S) |
MCF5206E_ICR_AVEC;
*MCF5206E_ICR(MBAR,MCF5206E_INTR_EXT_IPL3) =
(BSP_INTLVL_AVEC3 << MCF5206E_ICR_IL_S) |
(BSP_INTPRIO_AVEC3 << MCF5206E_ICR_IP_S) |
MCF5206E_ICR_AVEC;
*MCF5206E_ICR(MBAR,MCF5206E_INTR_EXT_IPL4) =
(BSP_INTLVL_AVEC4 << MCF5206E_ICR_IL_S) |
(BSP_INTPRIO_AVEC4 << MCF5206E_ICR_IP_S) |
MCF5206E_ICR_AVEC;
*MCF5206E_ICR(MBAR,MCF5206E_INTR_EXT_IPL5) =
(BSP_INTLVL_AVEC5 << MCF5206E_ICR_IL_S) |
(BSP_INTPRIO_AVEC5 << MCF5206E_ICR_IP_S) |
MCF5206E_ICR_AVEC;
*MCF5206E_ICR(MBAR,MCF5206E_INTR_EXT_IPL6) =
(BSP_INTLVL_AVEC6 << MCF5206E_ICR_IL_S) |
(BSP_INTPRIO_AVEC6 << MCF5206E_ICR_IP_S) |
MCF5206E_ICR_AVEC;
*MCF5206E_ICR(MBAR,MCF5206E_INTR_EXT_IPL7) =
(BSP_INTLVL_AVEC7 << MCF5206E_ICR_IL_S) |
(BSP_INTPRIO_AVEC7 << MCF5206E_ICR_IP_S) |
MCF5206E_ICR_AVEC;
*MCF5206E_ICR(MBAR,MCF5206E_INTR_TIMER_1) =
(BSP_INTLVL_TIMER1 << MCF5206E_ICR_IL_S) |
(BSP_INTPRIO_TIMER1 << MCF5206E_ICR_IP_S) |
MCF5206E_ICR_AVEC;
*MCF5206E_ICR(MBAR,MCF5206E_INTR_TIMER_2) =
(BSP_INTLVL_TIMER2 << MCF5206E_ICR_IL_S) |
(BSP_INTPRIO_TIMER2 << MCF5206E_ICR_IP_S) |
MCF5206E_ICR_AVEC;
*MCF5206E_ICR(MBAR,MCF5206E_INTR_MBUS) =
(BSP_INTLVL_MBUS << MCF5206E_ICR_IL_S) |
(BSP_INTPRIO_MBUS << MCF5206E_ICR_IP_S) |
MCF5206E_ICR_AVEC;
*MCF5206E_ICR(MBAR,MCF5206E_INTR_UART_1) =
(BSP_INTLVL_UART1 << MCF5206E_ICR_IL_S) |
(BSP_INTPRIO_UART1 << MCF5206E_ICR_IP_S);
*MCF5206E_ICR(MBAR,MCF5206E_INTR_UART_2) =
(BSP_INTLVL_UART2 << MCF5206E_ICR_IL_S) |
(BSP_INTPRIO_UART2 << MCF5206E_ICR_IP_S);
*MCF5206E_ICR(MBAR,MCF5206E_INTR_DMA_0) =
(BSP_INTLVL_DMA0 << MCF5206E_ICR_IL_S) |
(BSP_INTPRIO_DMA0 << MCF5206E_ICR_IP_S) |
MCF5206E_ICR_AVEC;
*MCF5206E_ICR(MBAR,MCF5206E_INTR_DMA_1) =
(BSP_INTLVL_DMA1 << MCF5206E_ICR_IL_S) |
(BSP_INTPRIO_DMA1 << MCF5206E_ICR_IP_S) |
MCF5206E_ICR_AVEC;
/* Software Watchdog timer (not used now) */
*MCF5206E_SWIVR(MBAR) = 0x0F; /* Uninitialized interrupt */
*MCF5206E_SWSR(MBAR) = MCF5206E_SWSR_KEY1;
*MCF5206E_SWSR(MBAR) = MCF5206E_SWSR_KEY2;
/* Configuring Chip Selects */
/* CS2: SRAM memory */
*MCF5206E_CSAR(MBAR,2) = BSP_MEM_ADDR_ESRAM >> 16;
*MCF5206E_CSMR(MBAR,2) = BSP_MEM_MASK_ESRAM;
*MCF5206E_CSCR(MBAR,2) = MCF5206E_CSCR_WS1 |
MCF5206E_CSCR_PS_32 |
MCF5206E_CSCR_AA |
MCF5206E_CSCR_EMAA |
MCF5206E_CSCR_WR |
MCF5206E_CSCR_RD;
/* CS3: GPIO on eLITE board */
*MCF5206E_CSAR(MBAR,3) = BSP_MEM_ADDR_GPIO >> 16;
*MCF5206E_CSMR(MBAR,3) = BSP_MEM_MASK_GPIO;
*MCF5206E_CSCR(MBAR,3) = MCF5206E_CSCR_WS15 |
MCF5206E_CSCR_PS_16 |
MCF5206E_CSCR_AA |
MCF5206E_CSCR_EMAA |
MCF5206E_CSCR_WR |
MCF5206E_CSCR_RD;
{
uint32_t *inttab = (uint32_t*)&INTERRUPT_VECTOR;
uint32_t *intvec = (uint32_t*)BSP_MEM_ADDR_ESRAM;
register int i;
for (i = 0; i < 256; i++) {
*(intvec++) = *(inttab++);
}
}
m68k_set_vbr(BSP_MEM_ADDR_ESRAM);
/* CS0: Flash EEPROM */
*MCF5206E_CSAR(MBAR,0) = BSP_MEM_ADDR_FLASH >> 16;
*MCF5206E_CSCR(MBAR,0) = MCF5206E_CSCR_WS3 |
MCF5206E_CSCR_AA |
MCF5206E_CSCR_PS_16 |
MCF5206E_CSCR_EMAA |
MCF5206E_CSCR_WR |
MCF5206E_CSCR_RD;
*MCF5206E_CSMR(MBAR,0) = BSP_MEM_MASK_FLASH;
/*
* Invalidate the cache and disable it
*/
mcf5206e_disable_cache();
/*
* Setup ACRs so that if cache turned on, periphal accesses
* are not messed up. (Non-cacheable, serialized)
*/
m68k_set_acr0 ( 0
| MCF5206E_ACR_BASE(BSP_MEM_ADDR_ESRAM)
| MCF5206E_ACR_MASK(BSP_MEM_MASK_ESRAM)
| MCF5206E_ACR_EN
| MCF5206E_ACR_SM_ANY
);
m68k_set_acr1 ( 0
| MCF5206E_ACR_BASE(BSP_MEM_ADDR_FLASH)
| MCF5206E_ACR_MASK(BSP_MEM_MASK_FLASH)
| MCF5206E_ACR_EN
| MCF5206E_ACR_SM_ANY
);
mcf5206e_enable_cache();
/*
* Copy data, clear BSS, switch stacks and call boot_card()
*/
CopyDataClearBSSAndStart (BSP_MEM_SIZE_ESRAM - 0x400);
}

View File

@@ -1,215 +0,0 @@
/*
* This file contains GNU linker directives for an MCF5206eLITE
* evaluation board.
*
* Variations in memory size and allocation can be made by
* overriding some values with linker command-line arguments.
*
* Copyright (C) 2000 OKTET Ltd., St.-Petersburg, Russia
* Author: Victor V. Vengerov <vvv@oktet.ru>
*
* This file based on work:
* David Fiddes, D.J.Fiddes@hw.ac.uk
* http://www.calm.hw.ac.uk/davidf/coldfire/
*
* 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.
*/
/*
* Declare some sizes.
* XXX: The assignment of ". += XyzSize;" fails in older gld's if the
* number used there is not constant. If this happens to you, edit
* the lines marked XXX below to use a constant value.
*/
/*
* Declare system clock frequency.
*/
_SYS_CLOCK_FREQUENCY = DEFINED(_SYS_CLOCK_FREQUENCY) ?
_SYS_CLOCK_FREQUENCY : 54000000;
/*
* Declare size of heap.
* A heap size of 0 means "Use all available memory for the heap".
* Initial stack located in on-chip SRAM and not declared there.
*/
HeapSize = DEFINED(HeapSize) ? HeapSize : 0x0;
RamBase = DEFINED(RamBase) ? RamBase : 0x30000000;
RamSize = DEFINED(RamSize) ? RamSize : 0x00100000;
RamEnd = RamBase + RamSize;
/*
* Setup the memory map of the MCF5206eLITE evaluation board
*
* The "rom" section is in USER Flash on the board
* The "ram" section is placed in USER RAM starting at 10000h
*
*/
MEMORY
{
ram : ORIGIN = 0x30000000, LENGTH = 0x00100000
rom : ORIGIN = 0xFFE20000, LENGTH = 128k
}
MBase = 0x10000000;
ENTRY(start)
STARTUP(start.o)
/* Interrupt Vector table located at start of external static RAM */
_VBR = 0x30000000;
SECTIONS
{
/*
* Dynamic RAM
*/
ram : {
RamBase = .;
RamBase = .;
/* Reserve space for interrupt table */
. += 0x400;
} >ram
/*
* Text, data and bss segments
*/
.text : {
CREATE_OBJECT_SYMBOLS
*(.text*)
/*
* C++ constructors/destructors
*/
*(.gnu.linkonce.t.*)
/*
* Initialization and finalization code.
*/
. = ALIGN (16);
PROVIDE (_init = .);
*crti.o(.init)
*(.init)
*crtn.o(.init)
. = ALIGN (16);
PROVIDE (_fini = .);
*crti.o(.fini)
*(.fini)
*crtn.o(.fini)
/*
* Special FreeBSD sysctl sections.
*/
. = ALIGN (16);
__start_set_sysctl_set = .;
*(set_sysctl_*);
__stop_set_sysctl_set = ABSOLUTE(.);
*(set_domain_*);
*(set_pseudo_*);
/*
* C++ constructors/destructors
*/
. = ALIGN (16);
*crtbegin.o(.ctors)
*(.ctors)
*crtend.o(.ctors)
*crtbegin.o(.dtors)
*(.dtors)
*crtend.o(.dtors)
/*
* Exception frame info
*/
. = ALIGN (16);
*(.eh_frame)
/*
* Read-only data
*/
. = ALIGN (16);
_rodata_start = .;
*(.rodata*)
KEEP (*(SORT(.rtemsroset.*)))
*(.gnu.linkonce.r*)
. = ALIGN (16);
PROVIDE (etext = .);
} > ram
.tdata : {
_TLS_Data_begin = .;
*(.tdata .tdata.* .gnu.linkonce.td.*)
_TLS_Data_end = .;
} >ram
.tbss : {
_TLS_BSS_begin = .;
*(.tbss .tbss.* .gnu.linkonce.tb.*) *(.tcommon)
_TLS_BSS_end = .;
} >ram
_TLS_Data_size = _TLS_Data_end - _TLS_Data_begin;
_TLS_Data_begin = _TLS_Data_size != 0 ? _TLS_Data_begin : _TLS_BSS_begin;
_TLS_Data_end = _TLS_Data_size != 0 ? _TLS_Data_end : _TLS_BSS_begin;
_TLS_BSS_size = _TLS_BSS_end - _TLS_BSS_begin;
_TLS_Size = _TLS_BSS_end - _TLS_Data_begin;
_TLS_Alignment = MAX (ALIGNOF (.tdata), ALIGNOF (.tbss));
.data BLOCK (0x4) : {
copy_start = .;
*(.shdata)
. = ALIGN (0x10);
*(.data*)
KEEP (*(SORT(.rtemsrwset.*)))
. = ALIGN (0x10);
*(.gcc_exc)
*(.gcc_except_table*)
*(.jcr)
. = ALIGN (0x10);
*(.gnu.linkonce.d*)
. = ALIGN (0x10);
_edata = .;
copy_end = .;
} > ram
.bss BLOCK (0x4) :
{
clear_start = . ;
*(.shbss)
*(.dynbss)
*(.bss* .gnu.linkonce.b.*)
*(COMMON)
. = ALIGN(0x10);
_end = .;
clear_end = .;
} > ram
.noinit (NOLOAD) : {
*(SORT_BY_NAME (SORT_BY_ALIGNMENT (.noinit*)))
} >ram
.rtemsstack (NOLOAD) : {
*(SORT(.rtemsstack.*))
WorkAreaBase = .;
} > ram
.stab 0 (NOLOAD) :
{
*(.stab)
}
.stabstr 0 (NOLOAD) :
{
*(.stabstr)
}
/* Addition to let linker know about custom section for GDB pretty-printing support. */
.debug_gdb_scripts 0 : { *(.debug_gdb_scripts) }
}

View File

@@ -1,212 +0,0 @@
/*
* This file contains GNU linker directives for an MCF5206eLITE
* evaluation board.
*
* Variations in memory size and allocation can be made by
* overriding some values with linker command-line arguments.
*
* Copyright (C) 2000 OKTET Ltd., St.-Petersburg, Russia
* Author: Victor V. Vengerov <vvv@oktet.ru>
*
* This file based on work:
* David Fiddes, D.J.Fiddes@hw.ac.uk
* http://www.calm.hw.ac.uk/davidf/coldfire/
*
* 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.
*/
/*
* Declare some sizes.
* XXX: The assignment of ". += XyzSize;" fails in older gld's if the
* number used there is not constant. If this happens to you, edit
* the lines marked XXX below to use a constant value.
*/
/*
* Declare size of heap.
* A heap size of 0 means "Use all available memory for the heap".
* Initial stack located in on-chip SRAM and not declared there.
*/
HeapSize = DEFINED(HeapSize) ? HeapSize : 0x0;
/*
* Declare system clock frequency.
*/
_SYS_CLOCK_FREQUENCY = DEFINED(_SYS_CLOCK_FREQUENCY) ? _SYS_CLOCK_FREQUENCY : 54000000;
/*
* Setup the memory map of the MCF5206eLITE evaluation board
*
* The "rom" section is in USER Flash on the board
* The "ram" section is placed in USER RAM starting at 10000h
*
*/
MEMORY
{
ram : ORIGIN = 0x30000000, LENGTH = 0x00100000
rom : ORIGIN = 0xFFE00000, LENGTH = 0x00100000
}
MBase = 0x10000000;
ENTRY(start)
STARTUP(start.o)
/* Interrupt Vector table located at start of external static RAM */
_VBR = 0x30000000;
SECTIONS
{
/*
* Flash ROM
*/
rom : {
_RomBase = .;
} >rom
/*
* Dynamic RAM
*/
ram : {
RamBase = .;
RamBase = .;
} >ram
/*
* Text, data and bss segments
*/
.text : AT(0x30020000) {
CREATE_OBJECT_SYMBOLS
*(.text*)
/*
* C++ constructors/destructors
*/
*(.gnu.linkonce.t.*)
/*
* Initialization and finalization code.
*/
. = ALIGN (16);
PROVIDE (_init = .);
*crti.o(.init)
*(.init)
*crtn.o(.init)
. = ALIGN (16);
PROVIDE (_fini = .);
*crti.o(.fini)
*(.fini)
*crtn.o(.fini)
/*
* Special FreeBSD sysctl sections.
*/
. = ALIGN (16);
__start_set_sysctl_set = .;
*(set_sysctl_*);
__stop_set_sysctl_set = ABSOLUTE(.);
*(set_domain_*);
*(set_pseudo_*);
/*
* C++ constructors/destructors
*/
. = ALIGN (16);
*crtbegin.o(.ctors)
*(.ctors)
*crtend.o(.ctors)
*crtbegin.o(.dtors)
*(.dtors)
*crtend.o(.dtors)
/*
* Exception frame info
*/
. = ALIGN (16);
*(.eh_frame)
/*
* Read-only data
*/
. = ALIGN (16);
_rodata_start = . ;
*(.rodata)
KEEP (*(SORT(.rtemsroset.*)))
*(.gnu.linkonce.r*)
. = ALIGN (16);
PROVIDE (etext = .);
} >rom
.tdata : {
_TLS_Data_begin = .;
*(.tdata .tdata.* .gnu.linkonce.td.*)
_TLS_Data_end = .;
} >rom
.tbss : {
_TLS_BSS_begin = .;
*(.tbss .tbss.* .gnu.linkonce.tb.*) *(.tcommon)
_TLS_BSS_end = .;
} >rom
_TLS_Data_size = _TLS_Data_end - _TLS_Data_begin;
_TLS_Data_begin = _TLS_Data_size != 0 ? _TLS_Data_begin : _TLS_BSS_begin;
_TLS_Data_end = _TLS_Data_size != 0 ? _TLS_Data_end : _TLS_BSS_begin;
_TLS_BSS_size = _TLS_BSS_end - _TLS_BSS_begin;
_TLS_Size = _TLS_BSS_end - _TLS_Data_begin;
_TLS_Alignment = MAX (ALIGNOF (.tdata), ALIGNOF (.tbss));
.data 0x30000400 : AT(LOADADDR(.text) + SIZEOF(.text)) {
copy_start = .;
. = ALIGN (0x10);
*(.shdata)
. = ALIGN (0x10);
*(.data)
KEEP (*(SORT(.rtemsrwset.*)))
. = ALIGN (0x10);
*(.gcc_exc)
*(.gcc_except_table*)
. = ALIGN (0x10);
*(.gnu.linkonce.d*)
. = ALIGN (0x10);
_edata = .;
copy_end = .;
} >ram
.bss BLOCK (0x4) :
{
clear_start = . ;
*(.shbss)
*(.dynbss)
*(.bss* .gnu.linkonce.b.*)
*(COMMON)
. = ALIGN(0x10);
_end = .;
clear_end = .;
} > ram
.noinit (NOLOAD) : {
*(SORT_BY_NAME (SORT_BY_ALIGNMENT (.noinit*)))
} >ram
.rtemsstack (NOLOAD) : {
*(SORT(.rtemsstack.*))
WorkAreaBase = .;
} > ram
.stab 0 (NOLOAD) :
{
*(.stab)
}
.stabstr 0 (NOLOAD) :
{
*(.stabstr)
}
}

View File

@@ -1,416 +0,0 @@
/*
* MCF5206eLITE startup code
*
* This file contains the entry point for the application.
* The name of this entry point is compiler dependent.
* It jumps to the BSP which is responsible for performing
* all initialization.
*/
/*
* 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/asm.h>
#include "bsp.h"
BEGIN_CODE
/* Initial stack situated in on-chip static memory */
#define INITIAL_STACK BSP_MEM_ADDR_SRAM+BSP_MEM_SIZE_SRAM-4
PUBLIC (INTERRUPT_VECTOR)
SYM(INTERRUPT_VECTOR):
.long INITIAL_STACK | 00: initial SSP
.long start | 01: Initial PC
.long _unexp_exception | 02: Access Error
.long _unexp_exception | 03: Address Error
.long _unexp_exception | 04: Illegal Instruction
.long _reserved_int | 05: Reserved
.long _reserved_int | 06: Reserved
.long _reserved_int | 07: Reserved
.long _unexp_exception | 08: Priveledge Violation
.long _unexp_exception | 09: Trace
.long _unexp_exception | 0A: Unimplemented A-Line
.long _unexp_exception | 0B: Unimplemented F-Line
.long _unexp_exception | 0C: Debug interrupt
.long _reserved_int | 0D: Reserved
.long _unexp_exception | 0E: Format error
.long _unexp_exception | 0F: Uninitialized interrupt
.long _reserved_int | 10: Reserved
.long _reserved_int | 11: Reserved
.long _reserved_int | 12: Reserved
.long _reserved_int | 13: Reserved
.long _reserved_int | 14: Reserved
.long _reserved_int | 15: Reserved
.long _reserved_int | 16: Reserved
.long _reserved_int | 17: Reserved
.long _spurious_int | 18: Spurious interrupt
.long _avec1_int | 19: Autovector Level 1
.long _avec2_int | 1A: Autovector Level 2
.long _avec3_int | 1B: Autovector Level 3
.long _avec4_int | 1C: Autovector Level 4
.long _avec5_int | 1D: Autovector Level 5
.long _avec6_int | 1E: Autovector Level 6
.long _avec7_int | 1F: Autovector Level 7
.long _unexp_exception | 20: TRAP #0
.long _unexp_exception | 21: TRAP #1
.long _unexp_exception | 22: TRAP #2
.long _unexp_exception | 23: TRAP #3
.long _unexp_exception | 24: TRAP #4
.long _unexp_exception | 25: TRAP #5
.long _unexp_exception | 26: TRAP #6
.long _unexp_exception | 27: TRAP #7
.long _unexp_exception | 28: TRAP #8
.long _unexp_exception | 29: TRAP #9
.long _unexp_exception | 2A: TRAP #10
.long _unexp_exception | 2B: TRAP #11
.long _unexp_exception | 2C: TRAP #12
.long _unexp_exception | 2D: TRAP #13
.long _unexp_exception | 2E: TRAP #14
.long _unexp_exception | 2F: TRAP #15
.long _reserved_int | 30: Reserved
.long _reserved_int | 31: Reserved
.long _reserved_int | 32: Reserved
.long _reserved_int | 33: Reserved
.long _reserved_int | 34: Reserved
.long _reserved_int | 35: Reserved
.long _reserved_int | 36: Reserved
.long _reserved_int | 37: Reserved
.long _reserved_int | 38: Reserved
.long _reserved_int | 39: Reserved
.long _reserved_int | 3A: Reserved
.long _reserved_int | 3B: Reserved
.long _reserved_int | 3C: Reserved
.long _reserved_int | 3D: Reserved
.long _reserved_int | 3E: Reserved
.long _reserved_int | 3F: Reserved
.long _unexp_int | 40-FF: User defined interrupts
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int | 50:
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int | 60:
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int | 70:
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int | 80:
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int | 90:
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int | A0:
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int | B0:
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int | C0:
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int | D0:
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int | E0:
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int | F0:
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
.long _unexp_int
PUBLIC(start)
SYM(start):
move.w #0x2700,sr | First turn off all interrupts!
move.l #(BSP_MEM_ADDR_SRAM + MCF5206E_RAMBAR_V),d0
movec d0,rambar0 | ...so we have a stack
move.l #(INITIAL_STACK),sp | Set up stack again (may be we are
| going here from monitor or with
| BDM interface assistance)
/*
* Remainder of the startup code is handled by C code
*/
jmp SYM(Init5206e) | Start C code (which never returns)
/***************************************************************************
Function : CopyDataClearBSSAndStart
Description : Copy DATA segment, clear BSS segment, initialize heap,
initialise real stack, start C program. Assume that DATA and BSS sizes
are multiples of 4.
***************************************************************************/
PUBLIC (CopyDataClearBSSAndStart)
SYM(CopyDataClearBSSAndStart):
lea copy_start,a0 | Get start of DATA in RAM
lea SYM(etext),a2 | Get start of DATA in ROM
cmpl a0,a2 | Are they the same?
beq.s NOCOPY | Yes, no copy necessary
lea copy_end,a1 | Get end of DATA in RAM
bra.s COPYLOOPTEST | Branch into copy loop
COPYLOOP:
movel a2@+,a0@+ | Copy word from ROM to RAM
COPYLOOPTEST:
cmpl a1,a0 | Done?
bcs.s COPYLOOP | No, skip
NOCOPY:
lea clear_start,a0 | Get start of BSS
lea clear_end,a1 | Get end of BSS
clrl d0 | Value to set
bra.s ZEROLOOPTEST | Branch into clear loop
ZEROLOOP:
movel d0,a0@+ | Clear a word
ZEROLOOPTEST:
cmpl a1,a0 | Done?
bcs.s ZEROLOOP | No, skip
move 4(a7),d0
/*
* Right : Now we're ready to boot RTEMS
*/
move.l #_ISR_Stack_area_end,sp | Use configuration defined stack
clrl d0 | Pass in null to all boot_card() params
movel d0,a7@- | command line
jsr SYM(boot_card) | Call C boot_card function to startup RTEMS
# Wait forever
_stop:
nop
stop #0x2700
jmp _stop
# The following labelled nops is a placeholders for breakpoints
_unexp_exception:
nop
jmp _stop
_unexp_int:
nop
jmp _stop
_reserved_int:
nop
jmp _stop
_spurious_int:
nop
jmp _stop
_avec1_int:
nop
jmp _unexp_int
_avec2_int:
nop
jmp _unexp_int
_avec3_int:
nop
jmp _unexp_int
_avec4_int:
nop
jmp _unexp_int
_avec5_int:
nop
jmp _unexp_int
_avec6_int:
nop
jmp _unexp_int
_avec7_int:
nop
jmp _unexp_int
END_CODE
END

View File

@@ -1,18 +0,0 @@
SPDX-License-Identifier: CC-BY-SA-4.0 OR BSD-2-Clause
actions:
- get-string: null
- split: null
- env-append: null
build-type: option
copyrights:
- Copyright (C) 2020 embedded brains GmbH & Co. KG
default:
- enabled-by: true
value:
- -mcpu=5206
description: |
ABI flags
enabled-by: true
links: []
name: ABI_FLAGS
type: build

View File

@@ -1,71 +0,0 @@
SPDX-License-Identifier: CC-BY-SA-4.0 OR BSD-2-Clause
arch: m68k
bsp: mcf5206elite
build-type: bsp
cflags: []
copyrights:
- Copyright (C) 2020 embedded brains GmbH & Co. KG
cppflags: []
enabled-by: true
family: mcf5206elite
includes: []
install:
- destination: ${BSP_INCLUDEDIR}
source:
- bsps/m68k/mcf5206elite/include/bsp.h
- bsps/m68k/mcf5206elite/include/ds1307.h
- bsps/m68k/mcf5206elite/include/i2c.h
- bsps/m68k/mcf5206elite/include/i2cdrv.h
- bsps/m68k/mcf5206elite/include/nvram.h
- destination: ${BSP_INCLUDEDIR}/bsp
source:
- bsps/m68k/mcf5206elite/include/bsp/irq.h
- destination: ${BSP_LIBDIR}
source:
- bsps/m68k/mcf5206elite/start/gdbinit
- bsps/m68k/mcf5206elite/start/linkcmds
- bsps/m68k/mcf5206elite/start/linkcmds.flash
links:
- role: build-dependency
uid: ../grp
- role: build-dependency
uid: abi
- role: build-dependency
uid: start
- role: build-dependency
uid: tstmcf5206elite
- role: build-dependency
uid: ../../obj
- role: build-dependency
uid: ../../objirqdflt
- role: build-dependency
uid: ../../objmem
- role: build-dependency
uid: ../../opto2
- role: build-dependency
uid: ../../bspopts
source:
- bsps/m68k/mcf5206elite/console/console.c
- bsps/m68k/mcf5206elite/dev/ckinit.c
- bsps/m68k/mcf5206elite/dev/mcfmbus.c
- bsps/m68k/mcf5206elite/dev/mcfuart.c
- bsps/m68k/mcf5206elite/dev/timer.c
- bsps/m68k/mcf5206elite/dev/timerisr.S
- bsps/m68k/mcf5206elite/i2c/i2c.c
- bsps/m68k/mcf5206elite/i2c/i2cdrv.c
- bsps/m68k/mcf5206elite/nvram/nvram.c
- bsps/m68k/mcf5206elite/rtc/ds1307.c
- bsps/m68k/mcf5206elite/rtc/todcfg.c
- bsps/m68k/mcf5206elite/start/init5206e.c
- bsps/m68k/shared/m68kidle.c
- bsps/m68k/shared/memProbe.c
- bsps/shared/cache/nocache.c
- bsps/shared/dev/getentropy/getentropy-cpucounter.c
- bsps/shared/dev/rtc/rtc-support.c
- bsps/shared/dev/serial/printk-dummy.c
- bsps/shared/start/bspreset-loop.c
- bsps/shared/start/bspstart-empty.c
- bsps/shared/start/gettargethash-default.c
- bsps/shared/start/sbrk.c
- bsps/shared/start/setvec.c
type: build

View File

@@ -1,14 +0,0 @@
SPDX-License-Identifier: CC-BY-SA-4.0 OR BSD-2-Clause
asflags: []
build-type: start-file
copyrights:
- Copyright (C) 2020 embedded brains GmbH & Co. KG
cppflags: []
enabled-by: true
includes: []
install-path: ${BSP_LIBDIR}
links: []
source:
- bsps/m68k/mcf5206elite/start/start.S
target: start.o
type: build

View File

@@ -1,16 +0,0 @@
SPDX-License-Identifier: CC-BY-SA-4.0 OR BSD-2-Clause
actions:
- set-test-state:
reason: null
state: exclude
tests:
- dl05
- fsdosfsname01
build-type: option
copyrights:
- Copyright (C) 2020 embedded brains GmbH & Co. KG
default: []
description: ''
enabled-by: true
links: []
type: build