summaryrefslogtreecommitdiffstats
path: root/c/src/lib/libbsp/sparc/shared/can
diff options
context:
space:
mode:
authorJoel Sherrill <joel.sherrill@OARcorp.com>2007-09-06 13:27:25 +0000
committerJoel Sherrill <joel.sherrill@OARcorp.com>2007-09-06 13:27:25 +0000
commit226455f9fffef4c88b67aeef113a97dcaabd4b00 (patch)
tree8771eee8053655a1c09977a68efd2ba35ee173c5 /c/src/lib/libbsp/sparc/shared/can
parent2007-09-06 Daniel Hellstrom <daniel@gaisler.com> (diff)
downloadrtems-226455f9fffef4c88b67aeef113a97dcaabd4b00.tar.bz2
2007-09-06 Daniel Hellstrom <daniel@gaisler.com>
New drivers: PCI, b1553BRM, SpaceWire(GRSPW), CAN (GRCAN,OC_CAN), Raw UART. * shared/1553/b1553brm.c, shared/1553/b1553brm_pci.c, shared/1553/b1553brm_rasta.c, shared/can/grcan.c, shared/can/grcan_rasta.c, shared/can/occan.c, shared/can/occan_pci.c, shared/spw/grspw.c, shared/spw/grspw_pci.c, shared/spw/grspw_rasta.c, shared/uart/apbuart.c, shared/uart/apbuart_pci.c, shared/uart/apbuart_rasta.c: New files missed in previous commit.
Diffstat (limited to 'c/src/lib/libbsp/sparc/shared/can')
-rw-r--r--c/src/lib/libbsp/sparc/shared/can/grcan.c1706
-rw-r--r--c/src/lib/libbsp/sparc/shared/can/grcan_rasta.c99
-rw-r--r--c/src/lib/libbsp/sparc/shared/can/occan.c1922
-rw-r--r--c/src/lib/libbsp/sparc/shared/can/occan_pci.c64
4 files changed, 3791 insertions, 0 deletions
diff --git a/c/src/lib/libbsp/sparc/shared/can/grcan.c b/c/src/lib/libbsp/sparc/shared/can/grcan.c
new file mode 100644
index 0000000000..2482414165
--- /dev/null
+++ b/c/src/lib/libbsp/sparc/shared/can/grcan.c
@@ -0,0 +1,1706 @@
+/*
+ * GRCAN driver
+ *
+ * COPYRIGHT (c) 2007.
+ * Gaisler Research.
+ *
+ * The license and distribution terms for this file may be
+ * found in the file LICENSE in this distribution or at
+ * http://www.rtems.com/license/LICENSE.
+ *
+ *
+ * 2007-06-13, Daniel Hellstrom <daniel@gaisler.com>
+ * New driver in sparc shared directory. Parts taken
+ * from rasta grhcan driver.
+ *
+ */
+
+#include <bsp.h>
+#include <rtems/libio.h>
+#include <stdlib.h>
+#include <stdio.h>
+#include <string.h>
+#include <assert.h>
+#include <sched.h>
+#include <ctype.h>
+#include <rtems/bspIo.h>
+
+#include <grcan.h>
+#include <ambapp.h>
+#include <pci.h>
+
+#define WRAP_AROUND_TX_MSGS 1
+#define WRAP_AROUND_RX_MSGS 2
+#define GRCAN_MSG_SIZE sizeof(struct grcan_msg)
+#define BLOCK_SIZE (16*4)
+
+/* Default Maximium buffer size for statically allocated buffers */
+#ifndef TX_BUF_SIZE
+#define TX_BUF_SIZE (BLOCK_SIZE*16)
+#endif
+
+/* Make receiver buffers bigger than transmitt */
+#ifndef RX_BUF_SIZE
+#define RX_BUF_SIZE ((3*BLOCK_SIZE)*16)
+#endif
+
+#ifndef IRQ_GLOBAL_DISABLE
+ #define IRQ_GLOBAL_DISABLE() sparc_disable_interrupts()
+#endif
+
+#ifndef IRQ_GLOBAL_ENABLE
+ #define IRQ_GLOBAL_ENABLE() sparc_enable_interrupts()
+#endif
+
+#ifndef IRQ_CLEAR_PENDING
+ #define IRQ_CLEAR_PENDING(irqno)
+#endif
+
+#ifndef IRQ_UNMASK
+ #define IRQ_UNMASK(irqno)
+#endif
+
+#ifndef IRQ_MASK
+ #define IRQ_MASK(irqno)
+#endif
+
+#ifndef GRCAN_PREFIX
+ #define GRCAN_PREFIX(name) grcan##name
+#endif
+
+#ifndef MEMAREA_TO_HW
+ #define MEMAREA_TO_HW(x) (x)
+#endif
+
+/* default name to /dev/grcan0 */
+#if !defined(GRCAN_DEVNAME) || !defined(GRCAN_DEVNAME_NO)
+ #undef GRCAN_DEVNAME
+ #undef GRCAN_DEVNAME_NO
+ #define GRCAN_DEVNAME "/dev/grcan0"
+ #define GRCAN_DEVNAME_NO(devstr,no) ((devstr)[10]='0'+(no))
+#endif
+
+#ifndef GRCAN_REG_INT
+ #define GRCAN_REG_INT(handler,irqno,arg) set_vector(handler,irqno+0x10,1)
+#endif
+
+#ifndef GRCAN_DEFAULT_BAUD
+ /* default to 500kbits/s */
+ #define GRCAN_DEFAULT_BAUD 500000
+#endif
+
+/* Uncomment for debug output */
+/****************** DEBUG Definitions ********************/
+#define DBG_IOCTRL 1
+#define DBG_TX 2
+#define DBG_RX 4
+
+#define DEBUG_FLAGS (DBG_IOCTRL | DBG_RX | DBG_TX )
+/*#define DEBUG
+#define DEBUGFUNCS*/
+
+#include <debug_defs.h>
+
+/*
+#ifdef DEBUG
+#include <debug_defs.h>
+#else
+void silentdbg_init(void);
+void silentdbg_printf(char *fmt, ...);
+void silentdbg_int_printf(char *fmt, ...);
+void silentdbg_get_buf(char *buf, int max);
+int silentdbg_print_buf(int max);
+ extern int DEBUG_printf(const char *fmt, ...);
+ #define DBG(fmt, args...) do { silentdbg_printf(" : %03d @ %18s()]:" fmt , __LINE__,__FUNCTION__,## args); } while(0)
+ #define DBG2(fmt) do { silentdbg_printf(" : %03d @ %18s()]:" fmt , __LINE__,__FUNCTION__); } while(0)
+ #define DBGC(c,fmt, args...) do { if (DEBUG_FLAGS & c) { silentdbg_printf(" : %03d @ %18s()]:" fmt , __LINE__,__FUNCTION__,## args); }} while(0)
+ #ifdef DEBUGFUNCS
+ #define FUNCDBG() do { silentdbg_printf("%s\n\r",__FUNCTION__); } while(0)
+ #define FUNCDBG_INT()
+ #else
+ #define FUNCDBG()
+ #define FUNCDBG_INT() do { silentdbg_int_printf("%s\n\r",__FUNCTION__); } while(0)
+ #endif
+
+#endif
+*/
+/*********************************************************/
+
+/* grcan needs to have it buffers aligned to 1k boundaries */
+#define BUFFER_ALIGNMENT_NEEDS 1024
+
+#ifdef STATICALLY_ALLOCATED_TX_BUFFER
+static unsigned int tx_circbuf[GRCAN_MAX_CORES][TX_BUF_SIZE]
+ __attribute__ ((aligned(BUFFER_ALIGNMENT_NEEDS)));
+#define STATIC_TX_BUF_SIZE TX_BUF_SIZE
+#define STATIC_TX_BUF_ADDR(core) (&tx_circbuf[(core)][0])
+#endif
+
+#ifdef STATICALLY_ALLOCATED_RX_BUFFER
+static unsigned int rx_circbuf[GRCAN_MAX_CORES][RX_BUF_SIZE]
+ __attribute__ ((aligned(BUFFER_ALIGNMENT_NEEDS)));
+#define STATIC_RX_BUF_SIZE RX_BUF_SIZE
+#define STATIC_RX_BUF_ADDR(core) (&rx_circbuf[(core)][0])
+#endif
+
+/*
+ * If USE_AT697_RAM is defined the RAM on the AT697 board will be used for DMA buffers (but rx message queue is always in AT697 ram).
+ * USE_AT697_DMA specifies whether the messages will be fetched using DMA or PIO.
+ *
+ * RASTA_PCI_BASE is the base address of the GRPCI AHB slave
+ *
+ * GRCAN_BUF_SIZE must be set to the size (in bytes) of the GRCAN DMA buffers.
+ *
+ * RX_QUEUE_SIZE defines the number of messages that fits in the RX message queue. On RX interrupts the messages in the DMA buffer
+ * are copied into the message queue (using dma if the rx buf is not in the AT697 ram).
+ */
+
+/*#define USE_AT697_RAM 1 */
+#define USE_AT697_DMA 1
+#define RASTA_PCI_BASE 0xe0000000
+#define GRCAN_BUF_SIZE 4096
+#define RX_QUEUE_SIZE 1024
+
+#define INDEX(x) ( x&(RX_QUEUE_SIZE-1) )
+
+/* pa(x)
+ *
+ * x: address in AT697 address space
+ *
+ * returns the address in the RASTA address space that can be used to access x with dma.
+ *
+*/
+#ifdef USE_AT697_RAM
+static inline unsigned int pa(unsigned int addr) {
+ return ((addr & 0x0fffffff) | RASTA_PCI_BASE);
+}
+#else
+static inline unsigned int pa(unsigned int addr) {
+ return ((addr & 0x0fffffff) | 0x40000000);
+}
+#endif
+
+struct grcan_msg {
+ unsigned int head[2];
+ unsigned char data[8];
+};
+
+struct grcan_config {
+ struct grcan_timing timing;
+ struct grcan_selection selection;
+ int abort;
+ int silent;
+};
+
+struct grcan_priv {
+ unsigned int baseaddr, ram_base;
+ struct grcan_regs *regs;
+ int irq;
+ int minor;
+ int open;
+ int started;
+ unsigned int channel;
+ int flushing;
+ unsigned int corefreq_hz;
+
+ /* Circular DMA buffers */
+ void *_rx;
+ void *_tx;
+ struct grcan_msg *rx;
+ struct grcan_msg *tx;
+ unsigned int rxbuf_size; /* requested RX buf size in bytes */
+ unsigned int txbuf_size; /* requested TX buf size in bytes */
+
+ int txblock, rxblock;
+ int txcomplete, rxcomplete;
+ int txerror, rxerror;
+
+ struct grcan_filter sfilter;
+ struct grcan_filter afilter;
+ int config_changed; /* 0=no changes, 1=changes ==> a Core reset is needed */
+ struct grcan_config config;
+ struct grcan_stats stats;
+
+ rtems_id rx_sem, tx_sem, txempty_sem, dev_sem;
+};
+
+static int grcan_core_cnt;
+struct grcan_priv *grcans;
+static amba_confarea_type *amba_bus;
+static unsigned int ram_base;
+struct grcan_device_info *grcan_cores;
+static int grcan_core_cnt;
+
+static rtems_device_driver grcan_initialize(rtems_device_major_number major, rtems_device_minor_number minor, void *arg);
+static rtems_device_driver grcan_open(rtems_device_major_number major, rtems_device_minor_number minor, void *arg);
+static rtems_device_driver grcan_close(rtems_device_major_number major, rtems_device_minor_number minor, void *arg);
+static rtems_device_driver grcan_read(rtems_device_major_number major, rtems_device_minor_number minor, void *arg);
+static rtems_device_driver grcan_write(rtems_device_major_number major, rtems_device_minor_number minor, void *arg);
+static rtems_device_driver grcan_ioctl(rtems_device_major_number major, rtems_device_minor_number minor, void *arg);
+
+#define GRCAN_DRIVER_TABLE_ENTRY { grcan_initialize, grcan_open, grcan_close, grcan_read, grcan_write, grcan_ioctl }
+
+static unsigned int grcan_hw_read_try(
+ struct grcan_priv *pDev,
+ struct grcan_regs *regs,
+ CANMsg *buffer,
+ int max);
+
+static unsigned int grcan_hw_write_try(
+ struct grcan_priv *pDev,
+ struct grcan_regs *regs,
+ CANMsg *buffer,
+ int count);
+
+static void grcan_hw_config(
+ struct grcan_regs *regs,
+ struct grcan_config *conf);
+
+static void grcan_hw_accept(
+ struct grcan_regs *regs,
+ struct grcan_filter *afilter);
+
+static void grcan_hw_sync(
+ struct grcan_regs *regs,
+ struct grcan_filter *sfilter);
+
+#ifndef GRCAN_DONT_DECLARE_IRQ_HANDLER
+static rtems_isr grcan_interrupt_handler(rtems_vector_number v);
+#endif
+
+static void grcan_interrupt(struct grcan_priv *pDev);
+
+#ifdef GRCAN_REG_BYPASS_CACHE
+#define READ_REG(address) _grcan_read_nocache((unsigned int)(address))
+#else
+#define READ_REG(address) (*(unsigned int *)(address))
+#endif
+
+#ifdef GRCAN_DMA_BYPASS_CACHE
+#define READ_DMA_WORD(address) _grcan_read_nocache((unsigned int)(address))
+#define READ_DMA_BYTE(address) _grcan_read_nocache_byte((unsigned int)(address))
+static unsigned char __inline__ _grcan_read_nocache_byte(unsigned int address)
+{
+ unsigned char tmp;
+ asm(" lduba [%1]1, %0 "
+ : "=r"(tmp)
+ : "r"(address)
+ );
+ return tmp;
+}
+#else
+#define READ_DMA_WORD(address) (*(unsigned int *)(address))
+#define READ_DMA_BYTE(address) (*(unsigned char *)(address))
+#endif
+
+#if defined(GRCAN_REG_BYPASS_CACHE) || defined(GRCAN_DMA_BYPASS_CACHE)
+static unsigned int __inline__ _grcan_read_nocache(unsigned int address)
+{
+ unsigned int tmp;
+ asm(" lda [%1]1, %0 "
+ : "=r"(tmp)
+ : "r"(address)
+ );
+ return tmp;
+}
+#endif
+
+
+static rtems_driver_address_table grcan_driver = GRCAN_DRIVER_TABLE_ENTRY;
+
+static void __inline__ grcan_hw_reset(struct grcan_regs *regs)
+{
+ regs->ctrl = GRCAN_CTRL_RESET;
+}
+
+static rtems_device_driver grcan_start(struct grcan_priv *pDev)
+{
+ unsigned int tmp;
+ FUNCDBG();
+
+ /* Check that memory has been allocated successfully */
+ if ( !pDev->tx || !pDev->rx )
+ return RTEMS_NO_MEMORY;
+
+ /* Configure FIFO configuration register
+ * and Setup timing
+ */
+ if ( pDev->config_changed ){
+ grcan_hw_config(pDev->regs,&pDev->config);
+ pDev->config_changed = 0;
+ }
+
+ /* Setup receiver */
+ pDev->regs->rx0addr = MEMAREA_TO_HW((unsigned int)pDev->rx);
+ pDev->regs->rx0size = pDev->rxbuf_size;
+
+ /* Setup Transmitter */
+ pDev->regs->tx0addr = MEMAREA_TO_HW((unsigned int)pDev->tx);
+ pDev->regs->tx0size = pDev->txbuf_size;
+
+ /* Setup acceptance filters */
+ grcan_hw_accept(pDev->regs,&pDev->afilter);
+
+ /* Sync filters */
+ grcan_hw_sync(pDev->regs,&pDev->sfilter);
+
+ /* Clear status bits */
+ tmp = READ_REG(&pDev->regs->stat);
+ pDev->regs->stat = 0;
+
+ /* Setup IRQ handling */
+
+ /* Clear all IRQs */
+ tmp = READ_REG(&pDev->regs->pir);
+ pDev->regs->picr = 0x1ffff;
+
+ /* unmask TxLoss|TxErrCntr|RxErrCntr|TxAHBErr|RxAHBErr|OR|OFF|PASS */
+ pDev->regs->imr = 0x1601f;
+
+ /* Enable routing of the IRQs */
+ IRQ_GLOBAL_DISABLE();
+ IRQ_UNMASK(pDev->irq+GRCAN_IRQ_TXSYNC);
+ IRQ_UNMASK(pDev->irq+GRCAN_IRQ_RXSYNC);
+ IRQ_UNMASK(pDev->irq+GRCAN_IRQ_IRQ);
+ IRQ_GLOBAL_ENABLE();
+
+ /* Reset some software data */
+ /*pDev->txerror = 0;
+ pDev->rxerror = 0;*/
+
+ /* Enable receiver/transmitter */
+ pDev->regs->rx0ctrl = GRCAN_RXCTRL_ENABLE;
+ pDev->regs->tx0ctrl = GRCAN_TXCTRL_ENABLE;
+
+ /* Enable HurriCANe core */
+ pDev->regs->ctrl = GRCAN_CTRL_ENABLE;
+
+ /* Leave transmitter disabled, it is enabled when
+ * trying to send something.
+ */
+ return RTEMS_SUCCESSFUL;
+}
+
+static void grcan_stop(struct grcan_priv *pDev)
+{
+ FUNCDBG();
+
+ /* Mask all IRQs */
+ pDev->regs->imr = 0;
+ IRQ_MASK(pDev->irq+GRCAN_IRQ_TXSYNC);
+ IRQ_MASK(pDev->irq+GRCAN_IRQ_RXSYNC);
+ IRQ_MASK(pDev->irq+GRCAN_IRQ_IRQ);
+
+ /* Disable receiver & transmitter */
+ pDev->regs->rx0ctrl = 0;
+ pDev->regs->tx0ctrl = 0;
+
+ /* Reset semaphores to the initial state and wakeing
+ * all threads waiting for an IRQ. The threads that
+ * get woken up must check for RTEMS_UNSATISFIED in
+ * order to determine that they should return to
+ * user space with error status.
+ */
+ rtems_semaphore_flush(pDev->rx_sem);
+ rtems_semaphore_flush(pDev->tx_sem);
+ rtems_semaphore_flush(pDev->txempty_sem);
+}
+
+static void grcan_hw_config(
+ struct grcan_regs *regs,
+ struct grcan_config *conf
+ )
+{
+ unsigned int config=0;
+
+ /* Reset HurriCANe Core */
+ regs->ctrl = 0;
+
+ if ( conf->silent )
+ config |= GRCAN_CFG_SILENT;
+
+ if ( conf->abort )
+ config |= GRCAN_CFG_ABORT;
+
+ if ( conf->selection.selection )
+ config |= GRCAN_CFG_SELECTION;
+
+ if ( conf->selection.enable0 )
+ config |= GRCAN_CFG_ENABLE0;
+
+ if ( conf->selection.enable1 )
+ config |= GRCAN_CFG_ENABLE1;
+
+ /* Timing */
+ config |= (conf->timing.bpr<<GRCAN_CFG_BPR_BIT) & GRCAN_CFG_BPR;
+ config |= (conf->timing.rsj<<GRCAN_CFG_RSJ_BIT) & GRCAN_CFG_RSJ;
+ config |= (conf->timing.ps1<<GRCAN_CFG_PS1_BIT) & GRCAN_CFG_PS1;
+ config |= (conf->timing.ps2<<GRCAN_CFG_PS2_BIT) & GRCAN_CFG_PS2;
+ config |= (conf->timing.scaler<<GRCAN_CFG_SCALER_BIT) & GRCAN_CFG_SCALER;
+
+ /* Write configuration */
+ regs->conf = config;
+
+ /* Enable HurriCANe Core */
+ regs->ctrl = GRCAN_CTRL_ENABLE;
+}
+
+static void grcan_hw_accept(
+ struct grcan_regs *regs,
+ struct grcan_filter *afilter
+ )
+{
+ /* Disable Sync mask totaly (if we change scode or smask
+ * in an unfortunate way we may trigger a sync match)
+ */
+ regs->rx0mask = 0xffffffff;
+
+ /* Set Sync Filter in a controlled way */
+ regs->rx0code = afilter->code;
+ regs->rx0mask = afilter->mask;
+}
+
+static void grcan_hw_sync(
+ struct grcan_regs *regs,
+ struct grcan_filter *sfilter
+ )
+{
+ /* Disable Sync mask totaly (if we change scode or smask
+ * in an unfortunate way we may trigger a sync match)
+ */
+ regs->smask = 0xffffffff;
+
+ /* Set Sync Filter in a controlled way */
+ regs->scode = sfilter->code;
+ regs->smask = sfilter->mask;
+}
+
+static unsigned int grcan_hw_rxavail(
+ unsigned int rp,
+ unsigned int wp,
+ unsigned int size
+ )
+{
+ if ( rp == wp ) {
+ /* read pointer and write pointer is equal only
+ * when RX buffer is empty.
+ */
+ return 0;
+ }
+
+ if ( wp > rp ) {
+ return (wp-rp)/GRCAN_MSG_SIZE;
+ }else{
+ return (size-(rp-wp))/GRCAN_MSG_SIZE;
+ }
+}
+
+static unsigned int grcan_hw_txspace(
+ unsigned int rp,
+ unsigned int wp,
+ unsigned int size
+ )
+{
+ unsigned int left;
+
+ if ( rp == wp ) {
+ /* read pointer and write pointer is equal only
+ * when TX buffer is empty.
+ */
+ return size/GRCAN_MSG_SIZE-WRAP_AROUND_TX_MSGS;
+ }
+
+ /* size - 4 - abs(read-write) */
+ if ( wp > rp ) {
+ left = size-(wp-rp);
+ }else{
+ left = rp-wp;
+ }
+
+ return left/GRCAN_MSG_SIZE-WRAP_AROUND_TX_MSGS;
+}
+
+static int grcan_hw_rx_ongoing(struct grcan_regs *regs)
+{
+ return READ_REG(&regs->rx0ctrl) & GRCAN_RXCTRL_ONGOING;
+};
+
+static int grcan_hw_tx_ongoing(struct grcan_regs *regs)
+{
+ return READ_REG(&regs->tx0ctrl) & GRCAN_TXCTRL_ONGOING;
+};
+
+static int grcan_calc_timing(
+ unsigned int baud, /* The requested BAUD to calculate timing for */
+ unsigned int core_hz, /* Frequency in Hz of GRCAN Core */
+ struct grcan_timing *timing /* result is placed here */
+ )
+{
+ return -1; /* not implemented yet */
+}
+
+static unsigned int grcan_hw_read_try(
+ struct grcan_priv *pDev,
+ struct grcan_regs *regs,
+ CANMsg *buffer,
+ int max
+ )
+{
+ int i,j;
+ CANMsg *dest;
+ struct grcan_msg *source,tmp;
+ unsigned int wp,rp,size,rxmax,addr,trunk_msg_cnt;
+
+ FUNCDBG();
+
+ wp = READ_REG(&regs->rx0wr);
+ rp = READ_REG(&regs->rx0rd);
+
+ /*
+ * Due to hardware wrap around simplification write pointer will
+ * never reach the read pointer, at least a gap of 8 bytes.
+ * The only time they are equal is when the read pointer has
+ * reached the write pointer (empty buffer)
+ *
+ */
+ if ( wp != rp ){
+ /* Not empty, we have received chars...
+ * Read as much as possible from DMA buffer
+ */
+ size = READ_REG(&regs->rx0size);
+
+ /* Get number of bytes available in RX buffer */
+ trunk_msg_cnt = grcan_hw_rxavail(rp,wp,size);
+
+ /* truncate size if user space buffer hasn't room for
+ * all received chars.
+ */
+ if ( trunk_msg_cnt > max )
+ trunk_msg_cnt = max;
+
+ /* Read until i is 0 */
+ i=trunk_msg_cnt;
+
+ addr = (unsigned int)pDev->rx;
+ source = (struct grcan_msg *)(addr + rp);
+ dest = buffer;
+ rxmax = addr + (size-GRCAN_MSG_SIZE);
+
+ /* Read as many can messages as possible */
+ while(i>0){
+ /* Read CAN message from DMA buffer */
+ tmp.head[0] = READ_DMA_WORD(&source->head[0]);
+ tmp.head[1] = READ_DMA_WORD(&source->head[1]);
+ /* Convert one grcan CAN message to one "software" CAN message */
+ dest->extended = tmp.head[0]>>31;
+ dest->rtr = (tmp.head[0] >>30) & 0x1;
+ if ( dest->extended ){
+ dest->id = tmp.head[0] & 0x3fffffff;
+ }else{
+ dest->id = (tmp.head[0] >>18) & 0xfff;
+ }
+ dest->len = tmp.head[1] >> 28;
+ for(j=0; j<dest->len; j++)
+ dest->data[j] = READ_DMA_BYTE(&source->data[j]);
+
+ /* wrap around if neccessary */
+ source = ( (unsigned int)source >= rxmax ) ? (struct grcan_msg *)addr : source+1;
+ dest++; /* straight user buffer */
+ i--;
+ }
+ /* Increment Hardware READ pointer (mark read byte as read)
+ * ! wait for registers to be safely re-configurable
+ */
+ regs->rx0ctrl = 0; /* DISABLE RX CHANNEL */
+ i=0;
+ while( grcan_hw_rx_ongoing(regs) && (i<1000) ){
+ i++;
+ }
+ regs->rx0rd = (unsigned int)source-addr;
+ regs->rx0ctrl = GRCAN_RXCTRL_ENABLE; /* ENABLE_RX_CHANNEL */
+ return trunk_msg_cnt;
+ }
+ return 0;
+}
+
+static unsigned int grcan_hw_write_try(
+ struct grcan_priv *pDev,
+ struct grcan_regs *regs,
+ CANMsg *buffer,
+ int count
+ )
+{
+ unsigned int rp, wp, size, txmax, addr, ret;
+ struct grcan_msg *dest;
+ CANMsg *source;
+ int space_left;
+ unsigned int tmp;
+ int i;
+
+ DBGC(DBG_TX,"\n");
+ /*FUNCDBG();*/
+
+ rp = READ_REG(&regs->tx0rd);
+ wp = READ_REG(&regs->tx0wr);
+ size = READ_REG(&regs->tx0size);
+
+ space_left = grcan_hw_txspace(rp,wp,size);
+
+ /* is circular fifo full? */
+ if ( space_left < 1 )
+ return 0;
+
+ /* Truncate size */
+ if ( space_left > count )
+ space_left = count;
+ ret = space_left;
+
+ addr = (unsigned int)pDev->tx;
+
+ dest = (struct grcan_msg *)(addr + wp);
+ source = (CANMsg *)buffer;
+ txmax = addr + (size-GRCAN_MSG_SIZE);
+
+ while ( space_left>0 ) {
+ /* Convert and write CAN message to DMA buffer */
+ if ( source->extended ){
+ tmp = (1<<31) | (source->id & 0x3fffffff);
+ }else{
+ tmp = (source->id&0xfff)<<18;
+ }
+ if ( source->rtr )
+ tmp|=(1<<30);
+ dest->head[0] = tmp;
+ dest->head[1] = source->len<<28;
+ for ( i=0; i<source->len; i++)
+ dest->data[i] = source->data[i];
+ source++; /* straight user buffer */
+ dest = ((unsigned int)dest >= txmax) ? (struct grcan_msg *)addr : dest+1;
+ space_left--;
+ }
+
+ /* Update write pointer
+ * ! wait for registers to be safely re-configurable
+ */
+ regs->tx0ctrl = 0; /* DISABLE TX CHANNEL */
+ i=0;
+ while( (grcan_hw_tx_ongoing(regs)) && i<1000 ){
+ i++;
+ printk("ongoing tx\n");
+ }
+ regs->tx0wr = (unsigned int)dest - addr; /* Update write pointer */
+ regs->tx0ctrl = GRCAN_TXCTRL_ENABLE; /* ENABLE_TX_CHANNEL */
+ return ret;
+}
+
+static int grcan_wait_rxdata(
+ struct grcan_priv *pDev,
+ int min
+ )
+{
+ unsigned int wp, rp, size, irq;
+ unsigned int irq_trunk, dataavail;
+ int wait;
+
+ FUNCDBG();
+
+ size = READ_REG(&pDev->regs->rx0size);
+ rp = READ_REG(&pDev->regs->rx0rd);
+ wp = READ_REG(&pDev->regs->rx0wr);
+
+ /**** Calculate IRQ Pointer ****/
+ irq = wp + min*GRCAN_MSG_SIZE;
+ /* wrap irq around */
+ if ( irq >= size ){
+ irq_trunk = irq-size;
+ }else
+ irq_trunk = irq;
+
+ /*** block until receive IRQ received
+ * Set up a valid IRQ point so that an IRQ is received
+ * when one or more messages are received
+ */
+ IRQ_GLOBAL_DISABLE();
+
+ /* init IRQ HW */
+ pDev->regs->rx0irq = irq_trunk;
+
+ /* Clear pending Rx IRQ */
+ pDev->regs->picr = GRCAN_RXIRQ_IRQ;
+
+ wp = READ_REG(&pDev->regs->rx0wr);
+
+ /* Calculate messages available */
+ dataavail = grcan_hw_rxavail(rp,wp,size);
+
+ if ( dataavail < min ){
+ /* Still empty, proceed with sleep - Turn on IRQ (unmask irq) */
+ pDev->regs->imr = READ_REG(&pDev->regs->imr) | GRCAN_RXIRQ_IRQ;
+ wait=1;
+ }else{
+ /* enough message has been received, abort sleep - don't unmask interrupt */
+ wait=0;
+ }
+ IRQ_GLOBAL_ENABLE();
+
+ /* Wait for IRQ to fire only if has been triggered */
+ if ( wait ){
+ if ( rtems_semaphore_obtain(pDev->rx_sem, RTEMS_WAIT, RTEMS_NO_TIMEOUT) == RTEMS_UNSATISFIED )
+ return -1; /* Device driver has been closed or stopped, return with error status */
+ }
+
+ return 0;
+}
+
+/* Wait until min bytes available in TX circular buffer.
+ * The IRQ RxIrq is used to pin point the location of
+ *
+ * min must be at least WRAP_AROUND_TX_BYTES bytes less
+ * than max buffer for this algo to work.
+ *
+ */
+static int grcan_wait_txspace(
+ struct grcan_priv *pDev,
+ int min
+ )
+{
+ int wait;
+ unsigned int irq, rp, wp, size, space_left;
+ unsigned int irq_trunk;
+
+ DBGC(DBG_TX,"\n");
+ /*FUNCDBG();*/
+
+ size = READ_REG(&pDev->regs->tx0size);
+ wp = READ_REG(&pDev->regs->tx0wr);
+
+ IRQ_GLOBAL_DISABLE();
+
+ rp = READ_REG(&pDev->regs->tx0rd);
+
+ /**** Calculate IRQ Pointer ****/
+ irq = rp + min*GRCAN_MSG_SIZE;
+ /* wrap irq around */
+ if ( irq >= size ){
+ irq_trunk = irq - size;
+ }else
+ irq_trunk = irq;
+
+ /* trigger HW to do a IRQ when enough room in buffer */
+ pDev->regs->tx0irq = irq_trunk;
+
+ /* Clear pending Tx IRQ */
+ pDev->regs->picr = GRCAN_TXIRQ_IRQ;
+
+ /* One problem, if HW already gone past IRQ place the IRQ will
+ * never be received resulting in a thread hang. We check if so
+ * before proceeding.
+ *
+ * has the HW already gone past the IRQ generation place?
+ * == does min fit info tx buffer?
+ */
+ rp = READ_REG(&pDev->regs->tx0rd);
+
+ space_left = grcan_hw_txspace(rp,wp,size);
+
+ if ( space_left < min ){
+ /* Still too full, proceed with sleep - Turn on IRQ (unmask irq) */
+ pDev->regs->imr = READ_REG(&pDev->regs->imr) | GRCAN_TXIRQ_IRQ;
+ wait=1;
+ }else{
+ /* There are enough room in buffer, abort wait - don't unmask interrupt */
+ wait=0;
+ }
+ IRQ_GLOBAL_ENABLE();
+
+ /* Wait for IRQ to fire only if it has been triggered */
+ if ( wait ){
+ if ( rtems_semaphore_obtain(pDev->tx_sem, RTEMS_WAIT, RTEMS_NO_TIMEOUT) ==
+ RTEMS_UNSATISFIED ){
+ /* Device driver has flushed us, this may be due to another thread has
+ * closed the device, this is to avoid deadlock */
+ return -1;
+ }
+ }
+
+ /* At this point the TxIRQ has been masked, we ned not to mask it */
+ return 0;
+}
+
+static int grcan_tx_flush(struct grcan_priv *pDev)
+{
+ int wait;
+ unsigned int rp, wp;
+ FUNCDBG();
+
+ /* loop until all data in circular buffer has been read by hw.
+ * (write pointer != read pointer )
+ *
+ * Hardware doesn't update write pointer - we do
+ */
+ while ( (wp=READ_REG(&pDev->regs->tx0wr)) != (rp=READ_REG(&pDev->regs->tx0rd)) ) {
+ /* Wait for TX empty IRQ */
+ IRQ_GLOBAL_DISABLE();
+ /* Clear pending TXEmpty IRQ */
+ pDev->regs->picr = GRCAN_TXEMPTY_IRQ;
+
+ if ( wp != READ_REG(&pDev->regs->tx0rd) ) {
+ /* Still not empty, proceed with sleep - Turn on IRQ (unmask irq) */
+ pDev->regs->imr = READ_REG(&pDev->regs->imr) | GRCAN_TXEMPTY_IRQ;
+ wait = 1;
+ }else{
+ /* TX fifo is empty */
+ wait = 0;
+ }
+ IRQ_GLOBAL_ENABLE();
+ if ( !wait )
+ break;
+
+ /* Wait for IRQ to wake us */
+ if ( rtems_semaphore_obtain(pDev->txempty_sem, RTEMS_WAIT, RTEMS_NO_TIMEOUT) ==
+ RTEMS_UNSATISFIED ) {
+ return -1;
+ }
+ }
+ return 0;
+}
+
+static int grcan_alloc_buffers(struct grcan_priv *pDev, int rx, int tx)
+{
+ FUNCDBG();
+
+ if ( tx ) {
+#ifdef STATIC_TX_BUF_ADDR
+ pDev->_tx = STATIC_TX_BUF_ADDR(pDev->minor);
+ if ( pDev->txbuf_size > STATIC_TX_BUF_SIZE ){
+ pDev->txbuf_size = STATIC_TX_BUF_SIZE;
+ return -1;
+ }
+ /* Assume aligned buffer */
+ pDev->tx = (struct grcan_msg *)pDev->_tx;
+#else
+ pDev->_tx = malloc(pDev->txbuf_size + BUFFER_ALIGNMENT_NEEDS);
+ if ( !pDev->_tx )
+ return -1;
+
+ /* Align TX buffer */
+ pDev->tx = (struct grcan_msg *)
+ (((unsigned int)pDev->_tx + (BUFFER_ALIGNMENT_NEEDS-1)) &
+ ~(BUFFER_ALIGNMENT_NEEDS-1));
+#endif
+ }
+
+ if ( rx ) {
+#ifdef STATIC_RX_BUF_ADDR
+ pDev->_rx = STATIC_RX_BUF_ADDR(pDev->minor);
+ if ( pDev->rxbuf_size > STATIC_RX_BUF_SIZE ){
+ pDev->rxbuf_size = STATIC_RX_BUF_SIZE;
+ return -1;
+ }
+ /* Assume aligned buffer */
+ pDev->rx = (struct grcan_msg *)pDev->_rx;
+#else
+ pDev->_rx = malloc(pDev->rxbuf_size + BUFFER_ALIGNMENT_NEEDS);
+ if ( !pDev->_rx )
+ return -1;
+
+ /* Align TX buffer */
+ pDev->rx = (struct grcan_msg *)
+ (((unsigned int)pDev->_rx + (BUFFER_ALIGNMENT_NEEDS-1)) &
+ ~(BUFFER_ALIGNMENT_NEEDS-1));
+#endif
+ }
+ return 0;
+}
+
+static void grcan_free_buffers(struct grcan_priv *pDev, int rx, int tx)
+{
+ FUNCDBG();
+
+#ifndef STATIC_TX_BUF_ADDR
+ if ( tx && pDev->_tx ){
+ free(pDev->_tx);
+ pDev->_tx = NULL;
+ pDev->tx = NULL;
+ }
+#endif
+#ifndef STATIC_RX_BUF_ADDR
+ if ( rx && pDev->_rx ){
+ free(pDev->_rx);
+ pDev->_rx = NULL;
+ pDev->rx = NULL;
+ }
+#endif
+}
+
+#if 0
+static char *almalloc(int sz)
+{
+ char *tmp;
+ tmp = calloc(1,2*sz);
+ tmp = (char *) (((int)tmp+sz) & ~(sz -1));
+ return(tmp);
+}
+#endif
+
+static rtems_device_driver grcan_initialize(
+ rtems_device_major_number major,
+ rtems_device_minor_number unused,
+ void *arg
+ )
+{
+ int minor;
+ struct grcan_priv *pDev;
+ amba_apb_device dev;
+ rtems_status_code status;
+ char fs_name[20];
+ unsigned int sys_freq_hz;
+
+ printk("grcan_initialize()\n\r");
+
+ FUNCDBG();
+
+ /* find GRCAN cores */
+ if ( !grcan_cores ) {
+ grcan_core_cnt = amba_get_number_apbslv_devices(amba_bus,VENDOR_GAISLER,GAISLER_GRHCAN);
+ DBG("GRCAN: Using AMBA Plug&Play, found %d cores\n",grcan_core_cnt);
+ if ( grcan_core_cnt < 1 )
+ return RTEMS_UNSATISFIED;
+ }
+
+#ifdef GRCAN_MAX_CORENR
+ /* limit number of cores */
+ if ( grcan_core_cnt > GRCAN_MAX_CORENR )
+ grcan_core_cnt = GRCAN_MAX_CORENR;
+#endif
+
+ /* Allocate memory for cores */
+ grcans = malloc(grcan_core_cnt * sizeof(struct grcan_priv));
+ if ( !grcans )
+ return RTEMS_NO_MEMORY;
+ memset(grcans,0,grcan_core_cnt * sizeof(struct grcan_priv));
+
+ /* make a local copy of device name */
+ strcpy(fs_name,GRCAN_DEVNAME);
+
+ /* Detect System Frequency from initialized timer */
+#ifndef SYS_FREQ_HZ
+#if defined(LEON3)
+ /* LEON3: find timer address via AMBA Plug&Play info */
+ {
+ amba_apb_device gptimer;
+ LEON3_Timer_Regs_Map *tregs;
+
+ if (amba_find_apbslv (&amba_conf, VENDOR_GAISLER, GAISLER_GPTIMER, &gptimer)
+ == 1) {
+ tregs = (LEON3_Timer_Regs_Map *) gptimer.start;
+ sys_freq_hz = (tregs->scaler_reload + 1) * 1000 * 1000;
+ DBG("GRCAN: detected %dHZ system frequency\n\r", sys_freq_hz);
+ } else {
+ sys_freq_hz = 40000000; /* Default to 40MHz */
+ printk("GRCAN: Failed to detect system frequency\n\r");
+ }
+ }
+#elif defined(LEON2)
+ /* LEON2: use hardcoded address to get to timer */
+ {
+ LEON_Register_Map *regs = (LEON_Register_Map *) 0x80000000;
+
+ sys_freq_hz = (regs->Scaler_Reload + 1) * 1000 * 1000;
+ }
+#else
+#error CPU not supported by driver
+#endif
+#else
+ /* Use hardcoded frequency */
+ sys_freq_hz = SYS_FREQ_HZ;
+#endif
+
+ for(minor=0; minor<grcan_core_cnt; minor++){
+
+ pDev = &grcans[minor];
+ pDev->minor = minor;
+ pDev->open = 0;
+ pDev->corefreq_hz = sys_freq_hz;
+ GRCAN_DEVNAME_NO(fs_name,minor);
+
+ /* Find core address & IRQ */
+ if ( !grcan_cores ) {
+ amba_find_next_apbslv(amba_bus,VENDOR_GAISLER,GAISLER_GRHCAN,&dev,minor);
+ pDev->irq = dev.irq;
+ pDev->regs = (struct grcan_regs *)dev.start;
+ }else{
+ pDev->irq = grcan_cores[minor].irq;
+ pDev->regs = (struct grcan_regs *)grcan_cores[minor].base_address;
+ }
+
+ DBG("Registering GRCAN core at [0x%x] irq %d, minor %d as %s\n",pDev->regs,pDev->irq,minor,fs_name);
+ printk("Registering GRCAN core at [0x%x] irq %d, minor %d as %s\n\r",pDev->regs,pDev->irq,minor,fs_name);
+
+ status = rtems_io_register_name(fs_name, major, 0);
+ if (status != RTEMS_SUCCESSFUL)
+ rtems_fatal_error_occurred(status);
+
+ /* Reset Hardware before attaching IRQ handler */
+ grcan_hw_reset(pDev->regs);
+
+ /* Register interrupt handler */
+ GRCAN_REG_INT(GRCAN_PREFIX(_interrupt_handler), pDev->irq+GRCAN_IRQ_IRQ, pDev);
+ /*
+ GRCAN_REG_INT(grcan_interrupt_handler, pDev->irq+GRCAN_IRQ_TXSYNC, pDev);
+ GRCAN_REG_INT(grcan_interrupt_handler, pDev->irq+GRCAN_IRQ_RXSYNC, pDev);
+ */
+
+ /* RX Semaphore created with count = 0 */
+ if ( rtems_semaphore_create(rtems_build_name('G', 'C', 'R', '0'+minor),
+ 0,
+ RTEMS_FIFO|RTEMS_SIMPLE_BINARY_SEMAPHORE|RTEMS_NO_INHERIT_PRIORITY|\
+ RTEMS_LOCAL|RTEMS_NO_PRIORITY_CEILING,
+ 0,
+ &pDev->rx_sem) != RTEMS_SUCCESSFUL )
+ return RTEMS_INTERNAL_ERROR;
+
+ /* TX Semaphore created with count = 0 */
+ if ( rtems_semaphore_create(rtems_build_name('G', 'C', 'T', '0'+minor),
+ 0,
+ RTEMS_FIFO|RTEMS_SIMPLE_BINARY_SEMAPHORE|RTEMS_NO_INHERIT_PRIORITY|\
+ RTEMS_LOCAL|RTEMS_NO_PRIORITY_CEILING,
+ 0,
+ &pDev->tx_sem) != RTEMS_SUCCESSFUL )
+ return RTEMS_INTERNAL_ERROR;
+
+ /* TX Empty Semaphore created with count = 0 */
+ if ( rtems_semaphore_create(rtems_build_name('G', 'C', 'E', '0'+minor),
+ 0,
+ RTEMS_FIFO|RTEMS_SIMPLE_BINARY_SEMAPHORE|RTEMS_NO_INHERIT_PRIORITY|\
+ RTEMS_LOCAL|RTEMS_NO_PRIORITY_CEILING,
+ 0,
+ &pDev->txempty_sem) != RTEMS_SUCCESSFUL )
+ return RTEMS_INTERNAL_ERROR;
+
+ /* Device Semaphore created with count = 1 */
+ if ( rtems_semaphore_create(rtems_build_name('G', 'C', 'A', '0'+minor),
+ 1,
+ RTEMS_FIFO|RTEMS_SIMPLE_BINARY_SEMAPHORE|RTEMS_NO_INHERIT_PRIORITY|\
+ RTEMS_LOCAL|RTEMS_NO_PRIORITY_CEILING,
+ 0,
+ &pDev->dev_sem) != RTEMS_SUCCESSFUL )
+ return RTEMS_INTERNAL_ERROR;
+ }
+
+ return RTEMS_SUCCESSFUL;
+}
+
+static rtems_device_driver grcan_open(rtems_device_major_number major, rtems_device_minor_number minor, void *arg) {
+ struct grcan_priv *pDev;
+ rtems_device_driver ret;
+
+ FUNCDBG();
+
+ if ( (minor < 0) || (minor>=grcan_core_cnt) ) {
+ DBG("Wrong minor %d\n", minor);
+ return RTEMS_INVALID_NUMBER;
+ }
+
+ pDev = &grcans[minor];
+
+ /* Wait until we get semaphore */
+ if ( rtems_semaphore_obtain(pDev->dev_sem, RTEMS_WAIT, RTEMS_NO_TIMEOUT) !=
+ RTEMS_SUCCESSFUL ){
+ return RTEMS_INTERNAL_ERROR;
+ }
+
+ /* is device busy/taken? */
+ if ( pDev->open ) {
+ ret=RTEMS_RESOURCE_IN_USE;
+ goto out;
+ }
+
+ /* Mark device taken */
+ pDev->open = 1;
+
+ pDev->txblock = pDev->rxblock = 1;
+ pDev->txcomplete = pDev->rxcomplete = 0;
+ pDev->started = 0;
+ pDev->config_changed = 1;
+ pDev->config.silent = 0;
+ pDev->config.abort = 0;
+ pDev->config.selection.selection = 0;
+ pDev->config.selection.enable0 = 0;
+ pDev->config.selection.enable1 = 1;
+ pDev->flushing = 0;
+ pDev->rx = pDev->_rx = NULL;
+ pDev->tx = pDev->_tx = NULL;
+ pDev->txbuf_size = TX_BUF_SIZE;
+ pDev->rxbuf_size = RX_BUF_SIZE;
+ printk("Defaulting to rxbufsize: %d, txbufsize: %d\n",RX_BUF_SIZE,TX_BUF_SIZE);
+
+ /* Default to accept all messages */
+ pDev->afilter.mask = 0x00000000;
+ pDev->afilter.code = 0x00000000;
+
+ /* Default to disable sync messages (only trigger when id is set to all ones) */
+ pDev->sfilter.mask = 0xffffffff;
+ pDev->sfilter.code = 0x00000000;
+
+ /* Calculate default timing register values */
+ grcan_calc_timing(GRCAN_DEFAULT_BAUD,pDev->corefreq_hz,&pDev->config.timing);
+
+ if ( grcan_alloc_buffers(pDev,1,1) ) {
+ ret=RTEMS_NO_MEMORY;
+ goto out;
+ }
+
+ /* Clear statistics */
+ memset(&pDev->stats,0,sizeof(struct grcan_stats));
+
+ ret = RTEMS_SUCCESSFUL;
+out:
+ rtems_semaphore_release(pDev->dev_sem);
+ return ret;
+}
+
+static rtems_device_driver grcan_close(rtems_device_major_number major, rtems_device_minor_number minor, void *arg)
+{
+ struct grcan_priv *pDev = &grcans[minor];
+
+ FUNCDBG();
+
+ if ( pDev->started )
+ grcan_stop(pDev);
+
+ grcan_hw_reset(pDev->regs);
+
+ grcan_free_buffers(pDev,1,1);
+
+ /* Mark Device as closed */
+ pDev->open = 0;
+
+ return RTEMS_SUCCESSFUL;
+}
+
+static rtems_device_driver grcan_read(rtems_device_major_number major, rtems_device_minor_number minor, void *arg)
+{
+ struct grcan_priv *pDev = &grcans[minor];
+ rtems_libio_rw_args_t *rw_args;
+ CANMsg *dest;
+ unsigned int count, left;
+ int req_cnt;
+
+ rw_args = (rtems_libio_rw_args_t *) arg;
+ dest = (CANMsg *) rw_args->buffer;
+ req_cnt = rw_args->count / sizeof(CANMsg);
+
+ FUNCDBG();
+
+ if ( (!dest) || (req_cnt<1) )
+ return RTEMS_INVALID_NAME;
+
+ if ( !pDev->started )
+ return RTEMS_RESOURCE_IN_USE;
+
+/* FUNCDBG("grcan_read [%i,%i]: buf: 0x%x len: %i\n",major, minor, (unsigned int)rw_args->buffer,rw_args->count);*/
+
+ count = grcan_hw_read_try(pDev,pDev->regs,dest,req_cnt);
+ if ( !( pDev->rxblock && pDev->rxcomplete && (count!=req_cnt) ) ){
+ if ( count > 0 ) {
+ /* Successfully received messages (at least one) */
+ rw_args->bytes_moved = count * sizeof(CANMsg);
+ return RTEMS_SUCCESSFUL;
+ }
+
+ /* nothing read, shall we block? */
+ if ( !pDev->rxblock ) {
+ /* non-blocking mode */
+ rw_args->bytes_moved = 0;
+ return RTEMS_TIMEOUT;
+ }
+ }
+
+ while(count == 0 || (pDev->rxcomplete && (count!=req_cnt)) ){
+
+ if ( !pDev->rxcomplete ){
+ left = 1; /* return as soon as there is one message available */
+ }else{
+ left = req_cnt - count; /* return as soon as all data are available */
+
+ /* never wait for more than the half the maximum size of the receive buffer
+ * Why? We need some time to copy buffer before to catch up with hw, otherwise
+ * we would have to copy everything when the data has been received.
+ */
+ if ( left > ((pDev->rxbuf_size/GRCAN_MSG_SIZE)/2) ){
+ left = (pDev->rxbuf_size/GRCAN_MSG_SIZE)/2;
+ }
+ }
+
+ if ( grcan_wait_rxdata(pDev,left) ) {
+ /* The wait has been aborted, probably due to
+ * the device driver has been closed by another
+ * thread.
+ */
+ rw_args->bytes_moved = count * sizeof(CANMsg);
+ return RTEMS_UNSATISFIED;
+ }
+
+ /* Try read bytes from circular buffer */
+ count += grcan_hw_read_try(
+ pDev,
+ pDev->regs,
+ dest+count,
+ req_cnt-count);
+ }
+ /* no need to unmask IRQ as IRQ Handler do that for us. */
+ rw_args->bytes_moved = count * sizeof(CANMsg);
+ return RTEMS_SUCCESSFUL;
+}
+
+static rtems_device_driver grcan_write(rtems_device_major_number major, rtems_device_minor_number minor, void *arg)
+{
+ struct grcan_priv *pDev = &grcans[minor];
+ rtems_libio_rw_args_t *rw_args;
+ CANMsg *source;
+ unsigned int count, left;
+ int req_cnt;
+
+ DBGC(DBG_TX,"\n");
+ /*FUNCDBG();*/
+
+ if ( !pDev->started || pDev->config.silent || pDev->flushing )
+ return RTEMS_RESOURCE_IN_USE;
+
+ rw_args = (rtems_libio_rw_args_t *) arg;
+ req_cnt = rw_args->count / sizeof(CANMsg);
+ source = (CANMsg *) rw_args->buffer;
+
+ /* check proper length and buffer pointer */
+ if (( req_cnt < 1) || (source == NULL) ){
+ return RTEMS_INVALID_NAME;
+ }
+
+ count = grcan_hw_write_try(pDev,pDev->regs,source,req_cnt);
+ if ( !(pDev->txblock && pDev->txcomplete && (count!=req_cnt)) ) {
+ if ( count > 0 ) {
+ /* Successfully transmitted chars (at least one char) */
+ rw_args->bytes_moved = count * sizeof(CANMsg);
+ return RTEMS_SUCCESSFUL;
+ }
+
+ /* nothing written, shall we block? */
+ if ( !pDev->txblock ) {
+ /* non-blocking mode */
+ rw_args->bytes_moved = 0;
+ return RTEMS_TIMEOUT;
+ }
+ }
+
+ /* if in txcomplete mode we need to transmit all chars */
+ while((count == 0) || (pDev->txcomplete && (count!=req_cnt)) ){
+ /*** block until room to fit all or as much of transmit buffer as possible IRQ comes
+ * Set up a valid IRQ point so that an IRQ is received
+ * when we can put a chunk of data into transmit fifo
+ */
+ if ( !pDev->txcomplete ){
+ left = 1; /* wait for anything to fit buffer */
+ }else{
+ left = req_cnt - count; /* wait for all data to fit in buffer */
+
+ /* never wait for more than the half the maximum size of the transmitt buffer
+ * Why? We need some time to fill buffer before hw catches up.
+ */
+ if ( left > ((pDev->txbuf_size/GRCAN_MSG_SIZE)/2) ){
+ left = (pDev->txbuf_size/GRCAN_MSG_SIZE)/2;
+ }
+ }
+
+ /* Wait until more room in transmit buffer */
+ if ( grcan_wait_txspace(pDev,left) ){
+ /* The wait has been aborted, probably due to
+ * the device driver has been closed by another
+ * thread. To avoid deadlock we return directly
+ * with error status.
+ */
+ rw_args->bytes_moved = count * sizeof(CANMsg);
+ return RTEMS_UNSATISFIED;
+ }
+
+ if ( pDev->txerror ){
+ /* Return number of bytes sent, compare write pointers */
+ pDev->txerror = 0;
+#if 0
+#error HANDLE AMBA error
+#endif
+ }
+
+ /* Try read bytes from circular buffer */
+ count += grcan_hw_write_try(
+ pDev,
+ pDev->regs,
+ source+count,
+ req_cnt-count);
+ }
+ /* no need to unmask IRQ as IRQ Handler do that for us. */
+
+ rw_args->bytes_moved = count * sizeof(CANMsg);
+ return RTEMS_SUCCESSFUL;
+}
+
+static rtems_device_driver grcan_ioctl(rtems_device_major_number major, rtems_device_minor_number minor, void *arg)
+{
+ struct grcan_priv *pDev = &grcans[minor];
+ rtems_libio_ioctl_args_t *ioarg = (rtems_libio_ioctl_args_t *)arg;
+ unsigned int *data = ioarg->buffer;
+ struct grcan_timing timing;
+ unsigned int speed;
+ struct grcan_selection *selection;
+ int tmp,ret;
+ rtems_device_driver status;
+ struct grcan_stats *stats;
+ struct grcan_filter *filter;
+
+ FUNCDBG();
+
+ if (!ioarg)
+ return RTEMS_INVALID_NAME;
+
+ ioarg->ioctl_return = 0;
+ switch(ioarg->command) {
+ case GRCAN_IOC_START:
+ if ( pDev->started )
+ return RTEMS_RESOURCE_IN_USE; /* EBUSY */
+
+ if ( (status=grcan_start(pDev)) != RTEMS_SUCCESSFUL ){
+ return status;
+ }
+ /* Read and write are now open... */
+ pDev->started = 1;
+ break;
+
+ case GRCAN_IOC_STOP:
+ if ( !pDev->started )
+ return RTEMS_RESOURCE_IN_USE;
+
+ grcan_stop(pDev);
+ pDev->started = 0;
+ break;
+
+ case GRCAN_IOC_ISSTARTED:
+ if ( !pDev->started )
+ return RTEMS_RESOURCE_IN_USE;
+ break;
+
+ case GRCAN_IOC_FLUSH:
+ if ( !pDev->started || pDev->flushing || pDev->config.silent )
+ return RTEMS_RESOURCE_IN_USE;
+
+ pDev->flushing = 1;
+ tmp = grcan_tx_flush(pDev);
+ pDev->flushing = 0;
+ if ( tmp ) {
+ /* The wait has been aborted, probably due to
+ * the device driver has been closed by another
+ * thread.
+ */
+ return RTEMS_UNSATISFIED;
+ }
+ break;
+
+#if 0
+ /* Set physical link */
+ case GRCAN_IOC_SET_LINK:
+#ifdef REDUNDANT_CHANNELS
+ if ( pDev->started )
+ return RTEMS_RESOURCE_IN_USE; /* EBUSY */
+
+ /* switch HW channel */
+ pDev->channel = (unsigned int)ioargs->buffer;
+#else
+ return RTEMS_NOT_IMPLEMENTED;
+#endif
+ break;
+#endif
+
+ case GRCAN_IOC_SET_SILENT:
+ if ( pDev->started )
+ return RTEMS_RESOURCE_IN_USE;
+ pDev->config.silent = (int)ioarg->buffer;
+ pDev->config_changed = 1;
+ break;
+
+ case GRCAN_IOC_SET_ABORT:
+ if ( pDev->started )
+ return RTEMS_RESOURCE_IN_USE;
+ pDev->config.abort = (int)ioarg->buffer;
+ /* This Configuration parameter doesn't need HurriCANe reset
+ * ==> no pDev->config_changed = 1;
+ */
+ break;
+
+ case GRCAN_IOC_SET_SELECTION:
+ if ( pDev->started )
+ return RTEMS_RESOURCE_IN_USE;
+
+ selection = (struct grcan_selection *)ioarg->buffer;
+ if ( !selection )
+ return RTEMS_INVALID_NAME;
+
+ pDev->config.selection = *selection;
+ pDev->config_changed = 1;
+ break;
+
+ case GRCAN_IOC_SET_RXBLOCK:
+ pDev->rxblock = (int)ioarg->buffer;
+ break;
+
+ case GRCAN_IOC_SET_TXBLOCK:
+ pDev->txblock = (int)ioarg->buffer;
+ break;
+
+ case GRCAN_IOC_SET_TXCOMPLETE:
+ pDev->txcomplete = (int)ioarg->buffer;
+ break;
+
+ case GRCAN_IOC_SET_RXCOMPLETE:
+ pDev->rxcomplete = (int)ioarg->buffer;
+ break;
+
+ case GRCAN_IOC_GET_STATS:
+ stats = (struct grcan_stats *)ioarg->buffer;
+ if ( !stats )
+ return RTEMS_INVALID_NAME;
+ *stats = pDev->stats;
+ break;
+
+ case GRCAN_IOC_CLR_STATS:
+ IRQ_GLOBAL_DISABLE();
+ memset(&pDev->stats,0,sizeof(struct grcan_stats));
+ IRQ_GLOBAL_ENABLE();
+ break;
+
+ case GRCAN_IOC_SET_SPEED:
+
+ /* cannot change speed during run mode */
+ if ( pDev->started )
+ return RTEMS_RESOURCE_IN_USE; /* EBUSY */
+
+ /* get speed rate from argument */
+ speed = (unsigned int)ioarg->buffer;
+ ret = grcan_calc_timing(pDev->corefreq_hz,speed,&timing);
+ if ( ret )
+ return RTEMS_INVALID_NAME; /* EINVAL */
+
+ /* save timing/speed */
+ pDev->config.timing = timing;
+ pDev->config_changed = 1;
+ break;
+
+ case GRCAN_IOC_SET_BTRS:
+ /* Set BTR registers manually
+ * Read GRCAN/HurriCANe Manual.
+ */
+ if ( pDev->started )
+ return RTEMS_RESOURCE_IN_USE; /* EBUSY */
+
+ if ( !ioarg->buffer )
+ return RTEMS_INVALID_NAME;
+
+ pDev->config.timing = *(struct grcan_timing *)ioarg->buffer;
+ pDev->config_changed = 1;
+ break;
+
+ case GRCAN_IOC_SET_AFILTER:
+ filter = (struct grcan_filter *)ioarg->buffer;
+ if ( !filter ){
+ /* Disable filtering - let all messages pass */
+ pDev->afilter.mask = 0x0;
+ pDev->afilter.code = 0x0;
+ }else{
+ /* Save filter */
+ pDev->afilter = *filter;
+ }
+ /* Set hardware acceptance filter */
+ grcan_hw_accept(pDev->regs,&pDev->afilter);
+ break;
+
+ case GRCAN_IOC_SET_SFILTER:
+ filter = (struct grcan_filter *)ioarg->buffer;
+ if ( !filter ){
+ /* disable TX/RX SYNC filtering */
+ pDev->sfilter.mask = 0xffffffff;
+ pDev->sfilter.mask = 0;
+
+ /* disable Sync interrupt */
+ pDev->regs->imr = READ_REG(&pDev->regs->imr) & ~(GRCAN_RXSYNC_IRQ|GRCAN_TXSYNC_IRQ);
+ }else{
+ /* Save filter */
+ pDev->sfilter = *filter;
+
+ /* Enable Sync interrupt */
+ pDev->regs->imr = READ_REG(&pDev->regs->imr) | (GRCAN_RXSYNC_IRQ|GRCAN_TXSYNC_IRQ);
+ }
+ /* Set Sync RX/TX filter */
+ grcan_hw_sync(pDev->regs,&pDev->sfilter);
+ break;
+
+ case GRCAN_IOC_GET_STATUS:
+ if ( !data )
+ return RTEMS_INVALID_NAME;
+ /* Read out the statsu register from the GRCAN core */
+ data[0] = READ_REG(&pDev->regs->stat);
+ break;
+
+ default:
+ return RTEMS_NOT_DEFINED;
+ }
+ return RTEMS_SUCCESSFUL;
+}
+
+#ifndef GRCAN_DONT_DECLARE_IRQ_HANDLER
+/* Find what device caused the IRQ */
+static rtems_isr grcan_interrupt_handler(rtems_vector_number v)
+{
+ int minor=0;
+ while ( minor < grcan_core_cnt ){
+ if ( grcans[minor].irq == (v+0x10) ){
+ grcan_interrupt(&grcans[minor]);
+ break;
+ }
+ }
+}
+#endif
+
+/* Handle the IRQ */
+static void grcan_interrupt(struct grcan_priv *pDev)
+{
+ unsigned int status = READ_REG(&pDev->regs->pimsr);
+ unsigned int canstat = READ_REG(&pDev->regs->stat);
+
+ /* Spurious IRQ call? */
+ if ( !status && !canstat )
+ return;
+
+ FUNCDBG();
+
+ /* Increment number of interrupts counter */
+ pDev->stats.ints++;
+
+ if ( (status & GRCAN_ERR_IRQ) || (canstat & GRCAN_STAT_PASS) ){
+ /* Error-Passive interrupt */
+ pDev->stats.passive_cnt++;
+ }
+
+ if ( (status & GRCAN_OFF_IRQ) || (canstat & GRCAN_STAT_OFF) ){
+ /* Bus-off condition interrupt
+ * The link is brought down by hardware, we wake all threads
+ * that is blocked in read/write calls and stop futher calls
+ * to read/write until user has called ioctl(fd,START,0).
+ */
+ pDev->started = 0;
+ grcan_stop(pDev); /* this mask all IRQ sources */
+ status=0x1ffff; /* clear all interrupts */
+ goto out;
+ }
+
+ if ( (status & GRCAN_OR_IRQ) || (canstat & GRCAN_STAT_OR) ){
+ /* Over-run during reception interrupt */
+ pDev->stats.overrun_cnt++;
+ }
+
+ if ( (status & GRCAN_RXAHBERR_IRQ) ||
+ (status & GRCAN_TXAHBERR_IRQ) ||
+ (canstat & GRCAN_STAT_AHBERR) ){
+ /* RX or Tx AHB Error interrupt */
+ printk("AHBERROR: status: 0x%x, canstat: 0x%x\n",status,canstat);
+ pDev->stats.ahberr_cnt++;
+ }
+
+ if ( status & GRCAN_TXLOSS_IRQ ) {
+ pDev->stats.txloss_cnt++;
+ }
+
+ if ( status & GRCAN_RXIRQ_IRQ ){
+ /* RX IRQ pointer interrupt */
+ /*printk("RxIrq 0x%x\n",status);*/
+ pDev->regs->imr = READ_REG(&pDev->regs->imr) & ~GRCAN_RXIRQ_IRQ;
+ rtems_semaphore_release(pDev->rx_sem);
+ }
+
+ if ( status & GRCAN_TXIRQ_IRQ ){
+ /* TX IRQ pointer interrupt */
+ pDev->regs->imr = READ_REG(&pDev->regs->imr) & ~GRCAN_TXIRQ_IRQ;
+ rtems_semaphore_release(pDev->tx_sem);
+ }
+
+ if ( status & GRCAN_TXSYNC_IRQ ){
+ /* TxSync message transmitted interrupt */
+ pDev->stats.txsync_cnt++;
+ }
+
+ if ( status & GRCAN_RXSYNC_IRQ ){
+ /* RxSync message received interrupt */
+ pDev->stats.rxsync_cnt++;
+ }
+
+ if ( status & GRCAN_TXEMPTY_IRQ ){
+ pDev->regs->imr = READ_REG(&pDev->regs->imr) & ~GRCAN_TXEMPTY_IRQ;
+ rtems_semaphore_release(pDev->txempty_sem);
+ }
+
+out:
+ /* Clear IRQs */
+ pDev->regs->picr = status;
+}
+
+static int grcan_register_internal(void)
+{
+ rtems_status_code r;
+ rtems_device_major_number m;
+
+ if ((r = rtems_io_register_driver(0, &grcan_driver, &m)) !=
+ RTEMS_SUCCESSFUL) {
+ switch(r) {
+ case RTEMS_TOO_MANY:
+ DBG2("failed RTEMS_TOO_MANY\n");
+ break;
+ case RTEMS_INVALID_NUMBER:
+ DBG2("failed RTEMS_INVALID_NUMBER\n");
+ break;
+ case RTEMS_RESOURCE_IN_USE:
+ DBG2("failed RTEMS_RESOURCE_IN_USE\n");
+ break;
+ default:
+ DBG("failed %i\n",r);
+ break;
+ }
+ return 1;
+ }
+ DBG("Registered GRCAN on major %d\n",m);
+ return 0;
+}
+
+
+/* Use custom addresses and IRQs to find hardware */
+int GRCAN_PREFIX(_register_abs)(struct grcan_device_info *devices, int dev_cnt)
+{
+ FUNCDBG();
+
+ if ( !devices || (dev_cnt<0) )
+ return 1;
+ grcan_cores = devices;
+ grcan_core_cnt = dev_cnt;
+
+ amba_bus = NULL;
+ return grcan_register_internal();
+}
+
+/* Use prescanned AMBA Plug&Play information to find all GRCAN cores */
+int GRCAN_PREFIX(_register)(amba_confarea_type *abus)
+{
+ FUNCDBG();
+
+ if ( !abus )
+ return 1;
+ amba_bus = abus;
+ grcan_cores = NULL;
+ grcan_core_cnt = 0;
+ return grcan_register_internal();
+}
diff --git a/c/src/lib/libbsp/sparc/shared/can/grcan_rasta.c b/c/src/lib/libbsp/sparc/shared/can/grcan_rasta.c
new file mode 100644
index 0000000000..5f6701fa4c
--- /dev/null
+++ b/c/src/lib/libbsp/sparc/shared/can/grcan_rasta.c
@@ -0,0 +1,99 @@
+
+#include <rasta.h>
+
+/* PCI frequency */
+#define SYS_FREQ_HZ 33000000
+
+/*#define USE_AT697_RAM 1 */
+
+/* memarea_to_hw(x)
+ *
+ * x: address in AT697 address space
+ *
+ * returns the address in the RASTA address space that can be used to access x with dma.
+ *
+*/
+#ifdef USE_AT697_RAM
+static inline unsigned int memarea_to_hw(unsigned int addr) {
+ return ((addr & 0x0fffffff) | RASTA_PCI_BASE);
+}
+#else
+static inline unsigned int memarea_to_hw(unsigned int addr) {
+ return ((addr & 0x0fffffff) | RASTA_LOCAL_SRAM);
+}
+#endif
+
+#define MEMAREA_TO_HW(x) memarea_to_hw(x)
+
+#define IRQ_CLEAR_PENDING(irqno)
+#define IRQ_UNMASK(irqno)
+#define IRQ_MASK(irqno)
+
+#define IRQ_GLOBAL_DISABLE() sparc_disable_interrupts()
+#define IRQ_GLOBAL_ENABLE() sparc_enable_interrupts()
+
+#define GRCAN_REG_INT(handler,irqno,arg) \
+ if ( grcan_rasta_int_reg ) \
+ grcan_rasta_int_reg(handler,irqno,arg);
+
+void (*grcan_rasta_int_reg)(void *handler, int irq, void *arg) = 0;
+
+#define GRCAN_PREFIX(name) grcan_rasta##name
+
+/* We provide our own handler */
+#define GRCAN_DONT_DECLARE_IRQ_HANDLER
+
+#define GRCAN_REG_BYPASS_CACHE
+#define GRCAN_DMA_BYPASS_CACHE
+
+#define GRCAN_MAX_CORES 1
+
+/* Custom Statically allocated memory */
+#undef STATICALLY_ALLOCATED_TX_BUFFER
+#undef STATICALLY_ALLOCATED_RX_BUFFER
+
+#define STATIC_TX_BUF_SIZE 4096
+#define STATIC_RX_BUF_SIZE 4096
+#define TX_BUF_SIZE 4096
+#define RX_BUF_SIZE 4096
+
+#define STATIC_TX_BUF_ADDR(core) \
+ (grcan_rasta_rambase+(core)*(STATIC_TX_BUF_SIZE+STATIC_RX_BUF_SIZE))
+
+#define STATIC_RX_BUF_ADDR(core) \
+ (grcan_rasta_rambase+(core)*(STATIC_TX_BUF_SIZE+STATIC_RX_BUF_SIZE)+STATIC_RX_BUF_SIZE)
+
+
+#define GRCAN_DEVNAME "/dev/grcan0"
+#define GRCAN_DEVNAME_NO(devstr,no) ((devstr)[10]='0'+(no))
+
+static int grcan_rasta_calc_memoffs(int maxcores, int corenum, unsigned int *mem_base, unsigned int *mem_end, unsigned int *bdtable_base);
+
+void grcan_rasta_interrupt_handler(int irq, void *pDev);
+
+unsigned int grcan_rasta_rambase;
+
+#include "grcan.c"
+
+
+int grcan_rasta_ram_register(amba_confarea_type *abus, int rambase)
+{
+ grcan_rasta_rambase = rambase;
+
+ return GRCAN_PREFIX(_register)(abus);
+}
+#if 0
+static void grcan_rasta_interrupt_handler(int v)
+{
+ /* We know there is always only one GRCAN core in a RASTA chip... */
+ grcan_interrupt(&grcans[0]);
+ /*
+ struct grcan_priv *pDev = arg;
+ grcan_interrupt(pDev);
+ */
+}
+#endif
+void GRCAN_PREFIX(_interrupt_handler)(int irq, void *pDev)
+{
+ grcan_interrupt(pDev);
+}
diff --git a/c/src/lib/libbsp/sparc/shared/can/occan.c b/c/src/lib/libbsp/sparc/shared/can/occan.c
new file mode 100644
index 0000000000..3227957d9d
--- /dev/null
+++ b/c/src/lib/libbsp/sparc/shared/can/occan.c
@@ -0,0 +1,1922 @@
+/* OC_CAN driver
+ *
+ * COPYRIGHT (c) 2007.
+ * Gaisler Research.
+ *
+ * The license and distribution terms for this file may be
+ * found in the file LICENSE in this distribution or at
+ * http://www.rtems.com/license/LICENSE.
+ *
+ * Author: Daniel Hellström, Gaisler Research AB, www.gaisler.com
+ */
+
+#include <rtems/libio.h>
+#include <stdlib.h>
+#include <stdio.h>
+#include <string.h>
+#include <bsp.h>
+#include <rtems/bspIo.h> /* printk */
+
+#include <leon.h>
+#include <ambapp.h>
+#include <occan.h>
+
+/* RTEMS -> ERRNO decoding table
+
+rtems_assoc_t errno_assoc[] = {
+ { "OK", RTEMS_SUCCESSFUL, 0 },
+ { "BUSY", RTEMS_RESOURCE_IN_USE, EBUSY },
+ { "INVALID NAME", RTEMS_INVALID_NAME, EINVAL },
+ { "NOT IMPLEMENTED", RTEMS_NOT_IMPLEMENTED, ENOSYS },
+ { "TIMEOUT", RTEMS_TIMEOUT, ETIMEDOUT },
+ { "NO MEMORY", RTEMS_NO_MEMORY, ENOMEM },
+ { "NO DEVICE", RTEMS_UNSATISFIED, ENODEV },
+ { "INVALID NUMBER", RTEMS_INVALID_NUMBER, EBADF},
+ { "NOT RESOURCE OWNER", RTEMS_NOT_OWNER_OF_RESOURCE, EPERM},
+ { "IO ERROR", RTEMS_IO_ERROR, EIO},
+ { 0, 0, 0 },
+};
+
+*/
+
+/*
+#undef DEBUG
+#undef DEBUG_EXTRA
+#undef DEBUG_PRINT_REGMAP
+*/
+
+/* default to byte regs */
+#ifndef OCCAN_WORD_REGS
+ #define OCCAN_BYTE_REGS
+#else
+ #undef OCCAN_BYTE_REGS
+#endif
+
+#ifndef OCCAN_PREFIX
+ #define OCCAN_PREFIX(name) occan##name
+#endif
+
+#if !defined(OCCAN_DEVNAME) || !defined(OCCAN_DEVNAME_NO)
+ #undef OCCAN_DEVNAME
+ #undef OCCAN_DEVNAME_NO
+ #define OCCAN_DEVNAME "/dev/occan0"
+ #define OCCAN_DEVNAME_NO(devstr,no) ((devstr)[10]='0'+(no))
+#endif
+
+#ifndef OCCAN_REG_INT
+ #define OCCAN_REG_INT(handler,irq,arg) set_vector(handler,irq+0x10,1)
+#endif
+
+/* Default to 40MHz system clock */
+/*#ifndef SYS_FREQ_HZ
+ #define SYS_FREQ_HZ 40000000
+#endif*/
+
+#define OCCAN_WORD_REG_OFS 0x80
+#define OCCAN_NCORE_OFS 0x100
+#define DEFAULT_CLKDIV 0x7
+#define DEFAULT_EXTENDED_MODE 1
+#define DEFAULT_RX_FIFO_LEN 64
+#define DEFAULT_TX_FIFO_LEN 64
+
+/* not implemented yet */
+#undef REDUNDANT_CHANNELS
+
+/* Define common debug macros */
+#ifdef DEBUG
+ #define DBG(fmt, vargs...) printk(fmt, ## vargs )
+#else
+ #define DBG(fmt, vargs...)
+#endif
+
+/* fifo interface */
+typedef struct {
+ int cnt;
+ int ovcnt; /* overwrite count */
+ int full; /* 1 = base contain cnt CANMsgs, tail==head */
+ CANMsg *tail, *head;
+ CANMsg *base;
+ char fifoarea[0];
+} occan_fifo;
+
+/* PELICAN */
+#ifdef OCCAN_BYTE_REGS
+typedef struct {
+ unsigned char
+ mode,
+ cmd,
+ status,
+ intflags,
+ inten,
+ resv0,
+ bustim0,
+ bustim1,
+ unused0[2],
+ resv1,
+ arbcode,
+ errcode,
+ errwarn,
+ rx_err_cnt,
+ tx_err_cnt,
+ rx_fi_xff; /* this is also acceptance code 0 in reset mode */
+ union{
+ struct {
+ unsigned char id[2];
+ unsigned char data[8];
+ unsigned char next_in_fifo[2];
+ } rx_sff;
+ struct {
+ unsigned char id[4];
+ unsigned char data[8];
+ } rx_eff;
+ struct {
+ unsigned char id[2];
+ unsigned char data[8];
+ unsigned char unused[2];
+ } tx_sff;
+ struct {
+ unsigned char id[4];
+ unsigned char data[8];
+ } tx_eff;
+ struct {
+ unsigned char code[3];
+ unsigned char mask[4];
+ } rst_accept;
+ } msg;
+ unsigned char rx_msg_cnt;
+ unsigned char unused1;
+ unsigned char clkdiv;
+} pelican_regs;
+#else
+typedef struct {
+ unsigned char
+ mode, unused0[3],
+ cmd, unused1[3],
+ status, unused2[3],
+ intflags, unused3[3],
+ inten, unused4[3],
+ resv0, unused5[3],
+ bustim0, unused6[3],
+ bustim1, unused7[3],
+ unused8[8],
+ resv1,unused9[3],
+ arbcode,unused10[3],
+ errcode,unused11[3],
+ errwarn,unused12[3],
+ rx_err_cnt,unused13[3],
+ tx_err_cnt,unused14[3],
+ rx_fi_xff, unused15[3]; /* this is also acceptance code 0 in reset mode */
+ /* make sure to use pointers when writing (byte access) to these registers */
+ union{
+ struct {
+ unsigned int id[2];
+ unsigned int data[8];
+ unsigned int next_in_fifo[2];
+ } rx_sff;
+ struct {
+ unsigned int id[4];
+ unsigned int data[8];
+ } rx_eff;
+ struct {
+ unsigned int id[2];
+ unsigned int data[8];
+ } tx_sff;
+ struct {
+ unsigned int id[4];
+ unsigned int data[8];
+ } tx_eff;
+ struct {
+ unsigned int code[3];
+ unsigned int mask[4];
+ } rst_accept;
+ } msg;
+ unsigned char rx_msg_cnt,unused16[3];
+ unsigned char unused17[4];
+ unsigned char clkdiv,unused18[3];
+} pelican_regs;
+#endif
+
+#define MAX_TSEG1 7
+#define MAX_TSEG2 15
+
+#if 0
+typedef struct {
+ unsigned char brp;
+ unsigned char sjw;
+ unsigned char tseg1;
+ unsigned char tseg2;
+ unsigned char sam;
+} occan_speed_regs;
+#endif
+typedef struct {
+ unsigned char btr0;
+ unsigned char btr1;
+} occan_speed_regs;
+
+typedef struct {
+ /* hardware shortcuts */
+ pelican_regs *regs;
+ int irq;
+ occan_speed_regs timing;
+ int channel; /* 0=default, 1=second bus */
+ int single_mode;
+
+ /* driver state */
+ rtems_id devsem;
+ rtems_id txsem;
+ rtems_id rxsem;
+ int open;
+ int started;
+ int rxblk;
+ int txblk;
+ unsigned int status;
+ occan_stats stats;
+
+ /* rx&tx fifos */
+ occan_fifo *rxfifo;
+ occan_fifo *txfifo;
+
+ /* Config */
+ unsigned int speed; /* speed in HZ */
+ unsigned char acode[4];
+ unsigned char amask[4];
+} occan_priv;
+
+/********** FIFO INTERFACE **********/
+static void occan_fifo_put(occan_fifo *fifo);
+static CANMsg *occan_fifo_put_claim(occan_fifo *fifo, int force);
+static occan_fifo *occan_fifo_create(int cnt);
+static void occan_fifo_free(occan_fifo *fifo);
+static int occan_fifo_full(occan_fifo *fifo);
+static int occan_fifo_empty(occan_fifo *fifo);
+static void occan_fifo_get(occan_fifo *fifo);
+static CANMsg *occan_fifo_claim_get(occan_fifo *fifo);
+
+/**** Hardware related Interface ****/
+static int occan_calc_speedregs(unsigned int clock_hz, unsigned int rate, occan_speed_regs *result);
+static int occan_set_speedregs(occan_priv *priv, occan_speed_regs *timing);
+static int pelican_speed_auto(occan_priv *priv);
+static void pelican_init(occan_priv *priv);
+static void pelican_open(occan_priv *priv);
+static void pelican_close(occan_priv *priv);
+static int pelican_start(occan_priv *priv);
+static void pelican_stop(occan_priv *priv);
+static void pelican_exit(occan_priv *priv);
+static int pelican_send(occan_priv *can, CANMsg *msg);
+static void pelican_set_accept(occan_priv *priv, unsigned char *acode, unsigned char *amask);
+static void occan_interrupt(occan_priv *can);
+static void pelican_regadr_print(pelican_regs *regs);
+
+/***** Driver related interface *****/
+static rtems_device_driver occan_ioctl(rtems_device_major_number major, rtems_device_minor_number minor, void *arg);
+static rtems_device_driver occan_write(rtems_device_major_number major, rtems_device_minor_number minor, void *arg);
+static rtems_device_driver occan_read(rtems_device_major_number major, rtems_device_minor_number minor, void *arg);
+static rtems_device_driver occan_close(rtems_device_major_number major, rtems_device_minor_number minor, void *arg);
+static rtems_device_driver occan_open(rtems_device_major_number major, rtems_device_minor_number minor, void *arg);
+static rtems_device_driver occan_initialize(rtems_device_major_number major, rtems_device_minor_number unused, void *arg);
+static void occan_interrupt_handler(rtems_vector_number v);
+
+static int can_cores;
+static occan_priv *cans;
+static amba_confarea_type *amba_bus;
+static unsigned int sys_freq_hz;
+
+
+/* Read byte bypassing */
+
+#ifdef OCCAN_DONT_BYPASS_CACHE
+ #define READ_REG(address) (*(unsigned char *)(address))
+#else
+ /* Bypass cache */
+ #define READ_REG(address) _OCCAN_REG_READ((unsigned int)(address))
+ static __inline__ unsigned char _OCCAN_REG_READ(unsigned int addr) {
+ unsigned char tmp;
+ asm(" lduba [%1]1, %0 "
+ : "=r"(tmp)
+ : "r"(addr)
+ );
+ return tmp;
+ }
+#endif
+
+#define WRITE_REG(address,data) (*(unsigned char *)(address) = (data))
+
+/* Mode register bit definitions */
+#define PELICAN_MOD_RESET 0x1
+#define PELICAN_MOD_LISTEN 0x2
+#define PELICAN_MOD_SELFTEST 0x4
+#define PELICAN_MOD_ACCEPT 0x8
+
+/* Command register bit definitions */
+#define PELICAN_CMD_TXREQ 0x1
+#define PELICAN_CMD_ABORT 0x2
+#define PELICAN_CMD_RELRXBUF 0x4
+#define PELICAN_CMD_CLRDOVR 0x8
+#define PELICAN_CMD_SELFRXRQ 0x10
+
+/* Status register bit definitions */
+#define PELICAN_STAT_RXBUF 0x1
+#define PELICAN_STAT_DOVR 0x2
+#define PELICAN_STAT_TXBUF 0x4
+#define PELICAN_STAT_TXOK 0x8
+#define PELICAN_STAT_RX 0x10
+#define PELICAN_STAT_TX 0x20
+#define PELICAN_STAT_ERR 0x40
+#define PELICAN_STAT_BUS 0x80
+
+/* Interrupt register bit definitions */
+#define PELICAN_IF_RX 0x1
+#define PELICAN_IF_TX 0x2
+#define PELICAN_IF_ERRW 0x4
+#define PELICAN_IF_DOVR 0x8
+#define PELICAN_IF_ERRP 0x20
+#define PELICAN_IF_ARB 0x40
+#define PELICAN_IF_BUS 0x80
+
+/* Interrupt Enable register bit definitions */
+#define PELICAN_IE_RX 0x1
+#define PELICAN_IE_TX 0x2
+#define PELICAN_IE_ERRW 0x4
+#define PELICAN_IE_DOVR 0x8
+#define PELICAN_IE_ERRP 0x20
+#define PELICAN_IE_ARB 0x40
+#define PELICAN_IE_BUS 0x80
+
+/* Arbitration lost capture register bit definitions */
+#define PELICAN_ARB_BITS 0x1f
+
+/* register bit definitions */
+#define PELICAN_ECC_CODE_BIT 0x00
+#define PELICAN_ECC_CODE_FORM 0x40
+#define PELICAN_ECC_CODE_STUFF 0x80
+#define PELICAN_ECC_CODE_OTHER 0xc0
+#define PELICAN_ECC_CODE 0xc0
+
+#define PELICAN_ECC_DIR 0x20
+#define PELICAN_ECC_SEG 0x1f
+
+/* Clock divider register bit definitions */
+#define PELICAN_CDR_DIV 0x7
+#define PELICAN_CDR_OFF 0x8
+#define PELICAN_CDR_MODE 0x80
+#define PELICAN_CDR_MODE_PELICAN 0x80
+#define PELICAN_CDR_MODE_BITS 7
+#define PELICAN_CDR_MODE_BASICAN 0x00
+
+
+/* register bit definitions */
+#define OCCAN_BUSTIM_SJW 0xc0
+#define OCCAN_BUSTIM_BRP 0x3f
+#define OCCAN_BUSTIM_SJW_BIT 6
+
+#define OCCAN_BUSTIM_SAM 0x80
+#define OCCAN_BUSTIM_TSEG2 0x70
+#define OCCAN_BUSTIM_TSEG2_BIT 4
+#define OCCAN_BUSTIM_TSEG1 0x0f
+
+/* register bit definitions */
+/*
+#define PELICAN_S_ 0x1
+#define PELICAN_S_ 0x2
+#define PELICAN_S_ 0x4
+#define PELICAN_S_ 0x8
+#define PELICAN_S_ 0x10
+#define PELICAN_S_ 0x20
+#define PELICAN_S_ 0x40
+#define PELICAN_S_ 0x80
+*/
+
+static void pelican_init(occan_priv *priv){
+ /* Reset core */
+ priv->regs->mode = PELICAN_MOD_RESET;
+
+ /* wait for core to reset complete */
+ /*usleep(1);*/
+}
+
+static void pelican_open(occan_priv *priv){
+ unsigned char tmp;
+ int ret;
+
+ /* Set defaults */
+ priv->speed = OCCAN_SPEED_250K;
+
+ /* set acceptance filters to accept all messages */
+ priv->acode[0] = 0;
+ priv->acode[1] = 0;
+ priv->acode[2] = 0;
+ priv->acode[3] = 0;
+ priv->amask[0] = 0xff;
+ priv->amask[1] = 0xff;
+ priv->amask[2] = 0xff;
+ priv->amask[3] = 0xff;
+
+ /* Set clock divider to extended mode, clkdiv not connected
+ */
+ priv->regs->clkdiv = (1<<PELICAN_CDR_MODE_BITS) | (DEFAULT_CLKDIV & PELICAN_CDR_DIV);
+
+ ret = occan_calc_speedregs(sys_freq_hz,priv->speed,&priv->timing);
+ if ( ret ){
+ /* failed to set speed for this system freq, try with 50K instead */
+ priv->speed = OCCAN_SPEED_50K;
+ occan_calc_speedregs(sys_freq_hz,priv->speed,&priv->timing);
+ }
+
+ /* disable all interrupts */
+ priv->regs->inten = 0;
+
+ /* clear pending interrupts by reading */
+ tmp = READ_REG(&priv->regs->intflags);
+}
+
+static void pelican_close(occan_priv *priv){
+
+ /* disable all interrupts */
+ priv->regs->inten = 0;
+
+ priv->regs->mode = PELICAN_MOD_RESET;
+}
+
+static int pelican_start(occan_priv *priv){
+ unsigned char tmp;
+ /* Start HW communication */
+
+ if ( !priv->rxfifo || !priv->txfifo )
+ return -1;
+
+ /* Clear status bits */
+ priv->status = 0;
+
+ /* clear pending interrupts */
+ tmp = READ_REG(&priv->regs->intflags);
+
+ /* clear error counters */
+ priv->regs->rx_err_cnt = 0;
+ priv->regs->tx_err_cnt = 0;
+
+#ifdef REDUNDANT_CHANNELS
+ if ( (priv->channel == 0) || (priv->channel >= REDUNDANT_CHANNELS) ){
+ /* Select the first (default) channel */
+ OCCAN_SET_CHANNEL(priv,0);
+ }else{
+ /* set gpio bit, or something */
+ OCCAN_SET_CHANNEL(priv,priv->channel);
+ }
+#endif
+ /* set the speed regs of the CAN core */
+ occan_set_speedregs(priv,&priv->timing);
+
+ DBG("OCCAN: start: set timing regs btr0: 0x%x, btr1: 0x%x\n\r",READ_REG(&priv->regs->bustim0),READ_REG(&priv->regs->bustim1));
+
+ /* Set default acceptance filter */
+ pelican_set_accept(priv,priv->acode,priv->amask);
+
+ /* turn on interrupts */
+ priv->regs->inten = PELICAN_IE_RX | PELICAN_IE_TX | PELICAN_IE_ERRW |
+ PELICAN_IE_ERRP | PELICAN_IE_BUS;
+
+#ifdef DEBUG
+ /* print setup before starting */
+ pelican_regs_print(priv->regs);
+ occan_stat_print(&priv->stats);
+#endif
+
+ /* core already in reset mode,
+ * ¤ Exit reset mode
+ * ¤ Enter Single/Dual mode filtering.
+ */
+ priv->regs->mode = (priv->single_mode << 3);
+
+ return 0;
+}
+
+static void pelican_stop(occan_priv *priv){
+ /* stop HW */
+
+#ifdef DEBUG
+ /* print setup before stopping */
+ pelican_regs_print(priv->regs);
+ occan_stat_print(&priv->stats);
+#endif
+
+ /* put core in reset mode */
+ priv->regs->mode = PELICAN_MOD_RESET;
+
+ /* turn off interrupts */
+ priv->regs->inten = 0;
+
+ priv->status |= OCCAN_STATUS_RESET;
+}
+
+
+static void pelican_exit(occan_priv *priv){
+ /* reset core */
+ priv->regs->mode = PELICAN_MOD_RESET;
+}
+
+/* Try to send message "msg", if hardware txfifo is
+ * full, then -1 is returned.
+ *
+ * Be sure to have disabled CAN interrupts when
+ * entering this function.
+ */
+static int pelican_send(occan_priv *can, CANMsg *msg){
+ unsigned char tmp,status;
+ pelican_regs *regs = can->regs;
+
+ /* is there room in send buffer? */
+ status = READ_REG(&regs->status);
+ if ( !(status & PELICAN_STAT_TXBUF) ){
+ /* tx fifo taken, we have to wait */
+ return -1;
+ }
+
+ tmp = msg->len & 0xf;
+ if ( msg->rtr )
+ tmp |= 0x40;
+
+ if ( msg->extended ){
+ /* Extended Frame */
+ regs->rx_fi_xff = 0x80 | tmp;
+ WRITE_REG(&regs->msg.tx_eff.id[0],(msg->id >> (5+8+8)) & 0xff);
+ WRITE_REG(&regs->msg.tx_eff.id[1],(msg->id >> (5+8)) & 0xff);
+ WRITE_REG(&regs->msg.tx_eff.id[2],(msg->id >> (5)) & 0xff);
+ WRITE_REG(&regs->msg.tx_eff.id[3],(msg->id << 3) & 0xf8);
+ tmp = msg->len;
+ while(tmp--){
+ WRITE_REG(&regs->msg.tx_eff.data[tmp],msg->data[tmp]);
+ }
+ }else{
+ /* Standard Frame */
+ regs->rx_fi_xff = tmp;
+ WRITE_REG(&regs->msg.tx_sff.id[0],(msg->id >> 3) & 0xff);
+ WRITE_REG(&regs->msg.tx_sff.id[1],(msg->id << 5) & 0xe0);
+ tmp = msg->len;
+ while(tmp--){
+ WRITE_REG(&regs->msg.tx_sff.data[tmp],msg->data[tmp]);
+ }
+ }
+
+ /* let HW know of new message */
+ if ( msg->sshot ){
+ regs->cmd = PELICAN_CMD_TXREQ | PELICAN_CMD_ABORT;
+ }else{
+ /* normal case -- try resend until sent */
+ regs->cmd = PELICAN_CMD_TXREQ;
+ }
+
+ return 0;
+}
+
+
+static void pelican_set_accept(occan_priv *priv, unsigned char *acode, unsigned char *amask){
+ unsigned char *acode0, *acode1, *acode2, *acode3;
+ unsigned char *amask0, *amask1, *amask2, *amask3;
+
+ acode0 = &priv->regs->rx_fi_xff;
+ acode1 = (unsigned char *)&priv->regs->msg.rst_accept.code[0];
+ acode2 = (unsigned char *)&priv->regs->msg.rst_accept.code[1];
+ acode3 = (unsigned char *)&priv->regs->msg.rst_accept.code[2];
+
+ amask0 = (unsigned char *)&priv->regs->msg.rst_accept.mask[0];
+ amask1 = (unsigned char *)&priv->regs->msg.rst_accept.mask[1];
+ amask2 = (unsigned char *)&priv->regs->msg.rst_accept.mask[2];
+ amask3 = (unsigned char *)&priv->regs->msg.rst_accept.mask[3];
+
+ /* Set new mask & code */
+ *acode0 = acode[0];
+ *acode1 = acode[1];
+ *acode2 = acode[2];
+ *acode3 = acode[3];
+
+ *amask0 = amask[0];
+ *amask1 = amask[1];
+ *amask2 = amask[2];
+ *amask3 = amask[3];
+}
+
+static void pelican_regs_print(pelican_regs *regs){
+ printk("--- PELICAN 0x%lx ---\n\r",(unsigned int)regs);
+ printk(" MODE: 0x%02x\n\r",READ_REG(&regs->mode));
+ printk(" CMD: 0x%02x\n\r",READ_REG(&regs->cmd));
+ printk(" STATUS: 0x%02x\n\r",READ_REG(&regs->status));
+ /*printk(" INTFLG: 0x%02x\n\r",READ_REG(&regs->intflags));*/
+ printk(" INTEN: 0x%02x\n\r",READ_REG(&regs->inten));
+ printk(" BTR0: 0x%02x\n\r",READ_REG(&regs->bustim0));
+ printk(" BTR1: 0x%02x\n\r",READ_REG(&regs->bustim1));
+ printk(" ARBCODE: 0x%02x\n\r",READ_REG(&regs->arbcode));
+ printk(" ERRCODE: 0x%02x\n\r",READ_REG(&regs->errcode));
+ printk(" ERRWARN: 0x%02x\n\r",READ_REG(&regs->errwarn));
+ printk(" RX_ERR_CNT: 0x%02x\n\r",READ_REG(&regs->rx_err_cnt));
+ printk(" TX_ERR_CNT: 0x%02x\n\r",READ_REG(&regs->tx_err_cnt));
+ if ( READ_REG(&regs->mode) & PELICAN_MOD_RESET ){
+ /* in reset mode it is possible to read acceptance filters */
+ printk(" ACR0: 0x%02x (0x%lx)\n\r",READ_REG(&regs->rx_fi_xff),&regs->rx_fi_xff);
+ printk(" ACR1: 0x%02x (0x%lx)\n\r",READ_REG(&regs->msg.rst_accept.code[0]),(unsigned int)&regs->msg.rst_accept.code[0]);
+ printk(" ACR1: 0x%02x (0x%lx)\n\r",READ_REG(&regs->msg.rst_accept.code[1]),(unsigned int)&regs->msg.rst_accept.code[1]);
+ printk(" ACR1: 0x%02x (0x%lx)\n\r",READ_REG(&regs->msg.rst_accept.code[2]),(unsigned int)&regs->msg.rst_accept.code[2]);
+ printk(" AMR0: 0x%02x (0x%lx)\n\r",READ_REG(&regs->msg.rst_accept.mask[0]),(unsigned int)&regs->msg.rst_accept.mask[0]);
+ printk(" AMR1: 0x%02x (0x%lx)\n\r",READ_REG(&regs->msg.rst_accept.mask[1]),(unsigned int)&regs->msg.rst_accept.mask[1]);
+ printk(" AMR2: 0x%02x (0x%lx)\n\r",READ_REG(&regs->msg.rst_accept.mask[2]),(unsigned int)&regs->msg.rst_accept.mask[2]);
+ printk(" AMR3: 0x%02x (0x%lx)\n\r",READ_REG(&regs->msg.rst_accept.mask[3]),(unsigned int)&regs->msg.rst_accept.mask[3]);
+
+ }else{
+ printk(" RXFI_XFF: 0x%02x\n\r",READ_REG(&regs->rx_fi_xff));
+ }
+ printk(" RX_MSG_CNT: 0x%02x\n\r",READ_REG(&regs->rx_msg_cnt));
+ printk(" CLKDIV: 0x%02x\n\r",READ_REG(&regs->clkdiv));
+ printk("-------------------\n\r");
+}
+
+static void pelican_regadr_print(pelican_regs *regs){
+ printk("--- PELICAN 0x%lx ---\n\r",(unsigned int)regs);
+ printk(" MODE: 0x%lx\n\r",(unsigned int)&regs->mode);
+ printk(" CMD: 0x%lx\n\r",(unsigned int)&regs->cmd);
+ printk(" STATUS: 0x%lx\n\r",(unsigned int)&regs->status);
+ /*printk(" INTFLG: 0x%lx\n\r",&regs->intflags);*/
+ printk(" INTEN: 0x%lx\n\r",(unsigned int)&regs->inten);
+ printk(" BTR0: 0x%lx\n\r",(unsigned int)&regs->bustim0);
+ printk(" BTR1: 0x%lx\n\r",(unsigned int)&regs->bustim1);
+ printk(" ARBCODE: 0x%lx\n\r",(unsigned int)&regs->arbcode);
+ printk(" ERRCODE: 0x%lx\n\r",(unsigned int)&regs->errcode);
+ printk(" ERRWARN: 0x%lx\n\r",(unsigned int)&regs->errwarn);
+ printk(" RX_ERR_CNT: 0x%lx\n\r",(unsigned int)&regs->rx_err_cnt);
+ printk(" TX_ERR_CNT: 0x%lx\n\r",(unsigned int)&regs->tx_err_cnt);
+
+ /* in reset mode it is possible to read acceptance filters */
+ printk(" RXFI_XFF: 0x%lx\n\r",(unsigned int)&regs->rx_fi_xff);
+
+ /* reset registers */
+ printk(" ACR0: 0x%lx\n\r",(unsigned int)&regs->rx_fi_xff);
+ printk(" ACR1: 0x%lx\n\r",(unsigned int)&regs->msg.rst_accept.code[0]);
+ printk(" ACR2: 0x%lx\n\r",(unsigned int)&regs->msg.rst_accept.code[1]);
+ printk(" ACR3: 0x%lx\n\r",(unsigned int)&regs->msg.rst_accept.code[2]);
+ printk(" AMR0: 0x%lx\n\r",(unsigned int)&regs->msg.rst_accept.mask[0]);
+ printk(" AMR1: 0x%lx\n\r",(unsigned int)&regs->msg.rst_accept.mask[1]);
+ printk(" AMR2: 0x%lx\n\r",(unsigned int)&regs->msg.rst_accept.mask[2]);
+ printk(" AMR3: 0x%lx\n\r",(unsigned int)&regs->msg.rst_accept.mask[3]);
+
+ /* TX Extended */
+ printk(" EFFTX_ID[0]: 0x%lx\n\r",(unsigned int)&regs->msg.tx_eff.id[0]);
+ printk(" EFFTX_ID[1]: 0x%lx\n\r",(unsigned int)&regs->msg.tx_eff.id[1]);
+ printk(" EFFTX_ID[2]: 0x%lx\n\r",(unsigned int)&regs->msg.tx_eff.id[2]);
+ printk(" EFFTX_ID[3]: 0x%lx\n\r",(unsigned int)&regs->msg.tx_eff.id[3]);
+
+ printk(" EFFTX_DATA[0]: 0x%lx\n\r",(unsigned int)&regs->msg.tx_eff.data[0]);
+ printk(" EFFTX_DATA[1]: 0x%lx\n\r",(unsigned int)&regs->msg.tx_eff.data[1]);
+ printk(" EFFTX_DATA[2]: 0x%lx\n\r",(unsigned int)&regs->msg.tx_eff.data[2]);
+ printk(" EFFTX_DATA[3]: 0x%lx\n\r",(unsigned int)&regs->msg.tx_eff.data[3]);
+ printk(" EFFTX_DATA[4]: 0x%lx\n\r",(unsigned int)&regs->msg.tx_eff.data[4]);
+ printk(" EFFTX_DATA[5]: 0x%lx\n\r",(unsigned int)&regs->msg.tx_eff.data[5]);
+ printk(" EFFTX_DATA[6]: 0x%lx\n\r",(unsigned int)&regs->msg.tx_eff.data[6]);
+ printk(" EFFTX_DATA[7]: 0x%lx\n\r",(unsigned int)&regs->msg.tx_eff.data[7]);
+
+ /* RX Extended */
+ printk(" EFFRX_ID[0]: 0x%lx\n\r",(unsigned int)&regs->msg.rx_eff.id[0]);
+ printk(" EFFRX_ID[1]: 0x%lx\n\r",(unsigned int)&regs->msg.rx_eff.id[1]);
+ printk(" EFFRX_ID[2]: 0x%lx\n\r",(unsigned int)&regs->msg.rx_eff.id[2]);
+ printk(" EFFRX_ID[3]: 0x%lx\n\r",(unsigned int)&regs->msg.rx_eff.id[3]);
+
+ printk(" EFFRX_DATA[0]: 0x%lx\n\r",(unsigned int)&regs->msg.rx_eff.data[0]);
+ printk(" EFFRX_DATA[1]: 0x%lx\n\r",(unsigned int)&regs->msg.rx_eff.data[1]);
+ printk(" EFFRX_DATA[2]: 0x%lx\n\r",(unsigned int)&regs->msg.rx_eff.data[2]);
+ printk(" EFFRX_DATA[3]: 0x%lx\n\r",(unsigned int)&regs->msg.rx_eff.data[3]);
+ printk(" EFFRX_DATA[4]: 0x%lx\n\r",(unsigned int)&regs->msg.rx_eff.data[4]);
+ printk(" EFFRX_DATA[5]: 0x%lx\n\r",(unsigned int)&regs->msg.rx_eff.data[5]);
+ printk(" EFFRX_DATA[6]: 0x%lx\n\r",(unsigned int)&regs->msg.rx_eff.data[6]);
+ printk(" EFFRX_DATA[7]: 0x%lx\n\r",(unsigned int)&regs->msg.rx_eff.data[7]);
+
+
+ /* RX Extended */
+ printk(" SFFRX_ID[0]: 0x%lx\n\r",(unsigned int)&regs->msg.rx_sff.id[0]);
+ printk(" SFFRX_ID[1]: 0x%lx\n\r",(unsigned int)&regs->msg.rx_sff.id[1]);
+
+ printk(" SFFRX_DATA[0]: 0x%lx\n\r",(unsigned int)&regs->msg.rx_sff.data[0]);
+ printk(" SFFRX_DATA[1]: 0x%lx\n\r",(unsigned int)&regs->msg.rx_sff.data[1]);
+ printk(" SFFRX_DATA[2]: 0x%lx\n\r",(unsigned int)&regs->msg.rx_sff.data[2]);
+ printk(" SFFRX_DATA[3]: 0x%lx\n\r",(unsigned int)&regs->msg.rx_sff.data[3]);
+ printk(" SFFRX_DATA[4]: 0x%lx\n\r",(unsigned int)&regs->msg.rx_sff.data[4]);
+ printk(" SFFRX_DATA[5]: 0x%lx\n\r",(unsigned int)&regs->msg.rx_sff.data[5]);
+ printk(" SFFRX_DATA[6]: 0x%lx\n\r",(unsigned int)&regs->msg.rx_sff.data[6]);
+ printk(" SFFRX_DATA[7]: 0x%lx\n\r",(unsigned int)&regs->msg.rx_sff.data[7]);
+
+ /* TX Extended */
+ printk(" SFFTX_ID[0]: 0x%lx\n\r",(unsigned int)&regs->msg.tx_sff.id[0]);
+ printk(" SFFTX_ID[1]: 0x%lx\n\r",(unsigned int)&regs->msg.tx_sff.id[1]);
+
+ printk(" SFFTX_DATA[0]: 0x%lx\n\r",(unsigned int)&regs->msg.tx_sff.data[0]);
+ printk(" SFFTX_DATA[1]: 0x%lx\n\r",(unsigned int)&regs->msg.tx_sff.data[1]);
+ printk(" SFFTX_DATA[2]: 0x%lx\n\r",(unsigned int)&regs->msg.tx_sff.data[2]);
+ printk(" SFFTX_DATA[3]: 0x%lx\n\r",(unsigned int)&regs->msg.tx_sff.data[3]);
+ printk(" SFFTX_DATA[4]: 0x%lx\n\r",(unsigned int)&regs->msg.tx_sff.data[4]);
+ printk(" SFFTX_DATA[5]: 0x%lx\n\r",(unsigned int)&regs->msg.tx_sff.data[5]);
+ printk(" SFFTX_DATA[6]: 0x%lx\n\r",(unsigned int)&regs->msg.tx_sff.data[6]);
+ printk(" SFFTX_DATA[7]: 0x%lx\n\r",(unsigned int)&regs->msg.tx_sff.data[7]);
+
+ printk(" RX_MSG_CNT: 0x%lx\n\r",(unsigned int)&regs->rx_msg_cnt);
+ printk(" CLKDIV: 0x%lx\n\r",(unsigned int)&regs->clkdiv);
+ printk("-------------------\n\r");
+}
+
+static void occan_stat_print(occan_stats *stats){
+ printk("----Stats----\n\r");
+ printk("rx_msgs: %d\n\r",stats->rx_msgs);
+ printk("tx_msgs: %d\n\r",stats->tx_msgs);
+ printk("err_warn: %d\n\r",stats->err_warn);
+ printk("err_dovr: %d\n\r",stats->err_dovr);
+ printk("err_errp: %d\n\r",stats->err_errp);
+ printk("err_arb: %d\n\r",stats->err_arb);
+ printk("err_bus: %d\n\r",stats->err_bus);
+ printk("Int cnt: %d\n\r",stats->ints);
+ printk("tx_buf_err: %d\n\r",stats->tx_buf_error);
+ printk("-------------\n\r");
+}
+
+/* This function calculates BTR0 BTR1 values for a given bitrate.
+ * Heavily based on mgt_mscan_bitrate() from peak driver, which
+ * in turn is based on work by Arnaud Westenberg.
+ *
+ * Set communication parameters.
+ * baud rate in Hz
+ * input clock frequency of can core in Hz (system frequency)
+ * sjw synchronization jump width (0-3) prescaled clock cycles
+ * sampl_pt sample point in % (0-100) sets (TSEG1+2)/(TSEG1+TSEG2+3)
+ * ratio
+ */
+static int occan_calc_speedregs(unsigned int clock_hz, unsigned int rate, occan_speed_regs *result){
+ int best_error = 1000000000;
+ int error;
+ int best_tseg=0, best_brp=0, best_rate=0, brp=0;
+ int tseg=0, tseg1=0, tseg2=0;
+ int sjw = 0;
+ int clock = clock_hz / 2;
+ int sampl_pt = 90;
+
+ if ( (rate<10000) || (rate>1000000) ){
+ /* invalid speed mode */
+ return -1;
+ }
+
+ /* find best match, return -2 if no good reg
+ * combination is available for this frequency */
+
+ /* some heuristic specials */
+ if (rate > ((1000000 + 500000) / 2))
+ sampl_pt = 75;
+
+ if (rate < ((12500 + 10000) / 2))
+ sampl_pt = 75;
+
+ if (rate < ((100000 + 125000) / 2))
+ sjw = 1;
+
+ /* tseg even = round down, odd = round up */
+ for (tseg = (0 + 0 + 2) * 2;
+ tseg <= (MAX_TSEG2 + MAX_TSEG1 + 2) * 2 + 1;
+ tseg++)
+ {
+ brp = clock / ((1 + tseg / 2) * rate) + tseg % 2;
+ if ((brp == 0) || (brp > 64))
+ continue;
+
+ error = rate - clock / (brp * (1 + tseg / 2));
+ if (error < 0)
+ {
+ error = -error;
+ }
+
+ if (error <= best_error)
+ {
+ best_error = error;
+ best_tseg = tseg/2;
+ best_brp = brp-1;
+ best_rate = clock/(brp*(1+tseg/2));
+ }
+ }
+
+ if (best_error && (rate / best_error < 10))
+ {
+ printk("OCCAN: bitrate %d is not possible with %d Hz clock\n\r",rate, clock);
+ return -2;
+ }else if ( !result )
+ return 0; /* nothing to store result in, but a valid bitrate can be calculated */
+
+ tseg2 = best_tseg - (sampl_pt * (best_tseg + 1)) / 100;
+
+ if (tseg2 < 0)
+ {
+ tseg2 = 0;
+ }
+
+ if (tseg2 > MAX_TSEG2)
+ {
+ tseg2 = MAX_TSEG2;
+ }
+
+ tseg1 = best_tseg - tseg2 - 2;
+
+ if (tseg1 > MAX_TSEG1)
+ {
+ tseg1 = MAX_TSEG1;
+ tseg2 = best_tseg - tseg1 - 2;
+ }
+/*
+ result->sjw = sjw;
+ result->brp = best_brp;
+ result->tseg1 = tseg1;
+ result->tseg2 = tseg2;
+*/
+ result->btr0 = (sjw<<OCCAN_BUSTIM_SJW_BIT) | (best_brp&OCCAN_BUSTIM_BRP);
+ result->btr1 = (0<<7) | (tseg2<<OCCAN_BUSTIM_TSEG2_BIT) | tseg1;
+
+ return 0;
+}
+
+static int occan_set_speedregs(occan_priv *priv, occan_speed_regs *timing){
+ if ( !timing || !priv || !priv->regs)
+ return -1;
+
+ priv->regs->bustim0 = timing->btr0;
+ priv->regs->bustim1 = timing->btr1;
+ /*
+ priv->regs->bustim0 = (timing->sjw<<OCCAN_BUSTIM_SJW_BIT) | (timing->brp&OCCAN_BUSTIM_BRP);
+ priv->regs->bustim1 = (timing->sam<<7) | (timing->tseg2<<OCCAN_BUSTIM_TSEG2_BIT) | timing->tseg1;
+ */
+ return 0;
+}
+
+#if 0
+static unsigned int pelican_speed_auto_steplist [] = {
+ OCCAN_SPEED_500K,
+ OCCAN_SPEED_250K,
+ OCCAN_SPEED_125K,
+ OCCAN_SPEED_75K,
+ OCCAN_SPEED_50K,
+ OCCAN_SPEED_25K,
+ OCCAN_SPEED_10K,
+ 0
+};
+#endif
+
+static int pelican_speed_auto(occan_priv *priv){
+ return -1;
+
+#if 0
+ int i=0;
+ occan_speed_regs timing;
+ unsigned int speed;
+ unsigned char tmp;
+
+ while ( (speed=pelican_speed_auto_steplist[i]) > 0){
+
+ /* Reset core */
+ priv->regs->mode = PELICAN_MOD_RESET;
+
+ /* tell int handler about the auto speed detection test */
+
+
+ /* wait for a moment (10ms) */
+ /*usleep(10000);*/
+
+ /* No acceptance filter */
+ pelican_set_accept(priv);
+
+ /* calc timing params for this */
+ if ( occan_calc_speedregs(sys_freq_hz,speed,&timing) ){
+ /* failed to get good timings for this frequency
+ * test with next
+ */
+ continue;
+ }
+
+ timing.sam = 0;
+
+ /* set timing params for this speed */
+ occan_set_speedregs(priv,&timing);
+
+ /* Empty previous messages in hardware RX fifo */
+ /*
+ while( READ_REG(&priv->regs->) ){
+
+ }
+ */
+
+ /* Clear pending interrupts */
+ tmp = READ_REG(&priv->regs->intflags);
+
+ /* enable RX & ERR interrupt */
+ priv->regs->inten =
+
+ /* Get out of reset state */
+ priv->regs->mode = PELICAN_MOD_LISTEN;
+
+ /* wait for frames or errors */
+ while(1){
+ /* sleep 10ms */
+
+ }
+
+ }
+#endif
+}
+
+
+static rtems_device_driver occan_initialize(rtems_device_major_number major, rtems_device_minor_number unused, void *arg){
+ int dev_cnt,minor,subcore_cnt,devi,subi,subcores;
+ amba_ahb_device ambadev;
+ occan_priv *can;
+ char fs_name[20];
+ rtems_status_code status;
+
+ strcpy(fs_name,OCCAN_DEVNAME);
+
+ /* find device on amba bus */
+ dev_cnt = amba_get_number_ahbslv_devices(amba_bus,VENDOR_GAISLER,GAISLER_OCCAN);
+ if ( dev_cnt < 1 ){
+ /* Failed to find any CAN cores! */
+ printk("OCCAN: Failed to find any CAN cores\n\r");
+ return -1;
+ }
+
+ /* Detect System Frequency from initialized timer */
+#ifndef SYS_FREQ_HZ
+#if defined(LEON3)
+ /* LEON3: find timer address via AMBA Plug&Play info */
+ {
+ amba_apb_device gptimer;
+ LEON3_Timer_Regs_Map *tregs;
+
+ if ( amba_find_apbslv(&amba_conf,VENDOR_GAISLER,GAISLER_GPTIMER,&gptimer) == 1 ){
+ tregs = (LEON3_Timer_Regs_Map *)gptimer.start;
+ sys_freq_hz = (tregs->scaler_reload+1)*1000*1000;
+ DBG("OCCAN: detected %dHZ system frequency\n\r",sys_freq_hz);
+ }else{
+ sys_freq_hz = 40000000; /* Default to 40MHz */
+ printk("OCCAN: Failed to detect system frequency\n\r");
+ }
+
+ }
+#elif defined(LEON2)
+ /* LEON2: use hardcoded address to get to timer */
+ {
+ LEON_Register_Map *regs = (LEON_Register_Map *)0x80000000;
+ sys_freq_hz = (regs->Scaler_Reload+1)*1000*1000;
+ }
+#else
+ #error CPU not supported for OC_CAN driver
+#endif
+#else
+ /* Use hardcoded frequency */
+ sys_freq_hz = SYS_FREQ_HZ;
+#endif
+
+ DBG("OCCAN: Detected %dHz system frequency\n\r",sys_freq_hz);
+
+ /* OCCAN speciality:
+ * Mulitple cores are supported through the same amba AHB interface.
+ * The number of "sub cores" can be detected by decoding the AMBA
+ * Plug&Play version information. verion = ncores. A maximum of 8
+ * sub cores are supported, each separeated with 0x100 inbetween.
+ *
+ * Now, lets detect sub cores.
+ */
+
+ for(subcore_cnt=devi=0; devi<dev_cnt; devi++){
+ amba_find_next_ahbslv(amba_bus,VENDOR_GAISLER,GAISLER_OCCAN,&ambadev,devi);
+ subcore_cnt += (ambadev.ver & 0x7)+1;
+ }
+
+ printk("OCCAN: Found %d devs, totally %d sub cores\n\r",dev_cnt,subcore_cnt);
+
+ /* allocate memory for cores */
+ can_cores = subcore_cnt;
+ cans = calloc(subcore_cnt*sizeof(occan_priv),1);
+
+ minor=0;
+ for(devi=0; devi<dev_cnt; devi++){
+
+ /* Get AHB device info */
+ amba_find_next_ahbslv(amba_bus,VENDOR_GAISLER,GAISLER_OCCAN,&ambadev,devi);
+ subcores = (ambadev.ver & 0x7)+1;
+ DBG("OCCAN: on dev %d found %d sub cores\n\r",devi,subcores);
+
+ /* loop all subcores, at least 1 */
+ for(subi=0; subi<subcores; subi++){
+ can = &cans[minor];
+
+#ifdef OCCAN_BYTE_REGS
+ /* regs is byte regs */
+ can->regs = (void *)ambadev.start[0] + OCCAN_NCORE_OFS*subi;
+#else
+ /* regs is word regs, accessed 0x100 from base address */
+ can->regs = (void *)(ambadev.start[0] + OCCAN_NCORE_OFS*subi+ OCCAN_WORD_REG_OFS);
+#endif
+
+ /* remember IRQ number */
+ can->irq = ambadev.irq+subi;
+
+ /* bind filesystem name to device */
+ OCCAN_DEVNAME_NO(fs_name,minor);
+ printk("OCCAN: Registering %s to [%d %d] @ 0x%lx irq %d\n\r",fs_name,major,minor,(unsigned int)can->regs,can->irq);
+ status = rtems_io_register_name(fs_name, major, minor);
+ if (RTEMS_SUCCESSFUL != status )
+ rtems_fatal_error_occurred(status);
+
+ /* initialize software */
+ can->open = 0;
+ can->rxfifo = NULL;
+ can->txfifo = NULL;
+ status = rtems_semaphore_create(
+ rtems_build_name('C', 'd', 'v', '0'+minor),
+ 1,
+ RTEMS_FIFO | RTEMS_SIMPLE_BINARY_SEMAPHORE | RTEMS_NO_INHERIT_PRIORITY | \
+ RTEMS_NO_PRIORITY_CEILING,
+ 0,
+ &can->devsem);
+ if ( status != RTEMS_SUCCESSFUL ){
+ printk("OCCAN: Failed to create dev semaphore for minor %d, (%d)\n\r",minor,status);
+ return RTEMS_UNSATISFIED;
+ }
+ status = rtems_semaphore_create(
+ rtems_build_name('C', 't', 'x', '0'+minor),
+ 0,
+ RTEMS_FIFO | RTEMS_SIMPLE_BINARY_SEMAPHORE | RTEMS_NO_INHERIT_PRIORITY | \
+ RTEMS_NO_PRIORITY_CEILING,
+ 0,
+ &can->txsem);
+ if ( status != RTEMS_SUCCESSFUL ){
+ printk("OCCAN: Failed to create tx semaphore for minor %d, (%d)\n\r",minor,status);
+ return RTEMS_UNSATISFIED;
+ }
+ status = rtems_semaphore_create(
+ rtems_build_name('C', 'r', 'x', '0'+minor),
+ 0,
+ RTEMS_FIFO | RTEMS_SIMPLE_BINARY_SEMAPHORE | RTEMS_NO_INHERIT_PRIORITY | \
+ RTEMS_NO_PRIORITY_CEILING,
+ 0,
+ &can->rxsem);
+ if ( status != RTEMS_SUCCESSFUL ){
+ printk("OCCAN: Failed to create rx semaphore for minor %d, (%d)\n\r",minor,status);
+ return RTEMS_UNSATISFIED;
+ }
+
+ /* hardware init/reset */
+ pelican_init(can);
+
+ /* Setup interrupt handler for each channel */
+ OCCAN_REG_INT(OCCAN_PREFIX(_interrupt_handler), can->irq, can);
+
+ minor++;
+#ifdef DEBUG_PRINT_REGMAP
+ pelican_regadr_print(can->regs);
+#endif
+ }
+ }
+
+ return RTEMS_SUCCESSFUL;
+}
+
+static rtems_device_driver occan_open(rtems_device_major_number major, rtems_device_minor_number minor, void *arg){
+ occan_priv *can;
+
+ DBG("OCCAN: Opening %d\n\r",minor);
+
+ if ( minor >= can_cores )
+ return RTEMS_UNSATISFIED; /* NODEV */
+
+ /* get can device */
+ can = &cans[minor];
+
+ /* already opened? */
+ rtems_semaphore_obtain(can->devsem,RTEMS_WAIT, RTEMS_NO_TIMEOUT);
+ if ( can->open ){
+ rtems_semaphore_release(can->devsem);
+ return RTEMS_RESOURCE_IN_USE; /* EBUSY */
+ }
+ can->open = 1;
+ rtems_semaphore_release(can->devsem);
+
+ /* allocate fifos */
+ can->rxfifo = occan_fifo_create(DEFAULT_RX_FIFO_LEN);
+ if ( !can->rxfifo ){
+ can->open = 0;
+ return RTEMS_NO_MEMORY; /* ENOMEM */
+ }
+
+ can->txfifo = occan_fifo_create(DEFAULT_TX_FIFO_LEN);
+ if ( !can->txfifo ){
+ occan_fifo_free(can->rxfifo);
+ can->rxfifo= NULL;
+ can->open = 0;
+ return RTEMS_NO_MEMORY; /* ENOMEM */
+ }
+
+ DBG("OCCAN: Opening %d success\n\r",minor);
+
+ can->started = 0;
+ can->channel = 0; /* Default to first can link */
+ can->txblk = 1; /* Default to Blocking mode */
+ can->rxblk = 1; /* Default to Blocking mode */
+ can->single_mode = 1; /* single mode acceptance filter */
+
+ /* reset stat counters */
+ memset(&can->stats,0,sizeof(occan_stats));
+
+ /* HW must be in reset mode here (close and initializes resets core...)
+ *
+ * 1. set default modes/speeds
+ */
+ pelican_open(can);
+
+ return RTEMS_SUCCESSFUL;
+}
+
+static rtems_device_driver occan_close(rtems_device_major_number major, rtems_device_minor_number minor, void *arg){
+ occan_priv *can = &cans[minor];
+
+ DBG("OCCAN: Closing %d\n\r",minor);
+
+ /* stop if running */
+ if ( can->started )
+ pelican_stop(can);
+
+ /* Enter Reset Mode */
+ can->regs->mode = PELICAN_MOD_RESET;
+
+ /* free fifo memory */
+ occan_fifo_free(can->rxfifo);
+ occan_fifo_free(can->txfifo);
+
+ can->rxfifo = NULL;
+ can->txfifo = NULL;
+
+ return RTEMS_SUCCESSFUL;
+}
+
+static rtems_device_driver occan_read(rtems_device_major_number major, rtems_device_minor_number minor, void *arg){
+ occan_priv *can = &cans[minor];
+ rtems_libio_rw_args_t *rw_args=(rtems_libio_rw_args_t *) arg;
+ CANMsg *dstmsg, *srcmsg;
+ rtems_interrupt_level oldLevel;
+ int left;
+
+ if ( !can->started ){
+ DBG("OCCAN: cannot read from minor %d when not started\n\r",minor);
+ return RTEMS_RESOURCE_IN_USE; /* -EBUSY*/
+ }
+
+ /* does at least one message fit */
+ left = rw_args->count;
+ if ( left < sizeof(CANMsg) ){
+ DBG("OCCAN: minor %d length of buffer must be at least %d, our is %d\n\r",minor,sizeof(CANMsg),left);
+ return RTEMS_INVALID_NAME; /* -EINVAL */
+ }
+
+ /* get pointer to start where to put CAN messages */
+ dstmsg = (CANMsg *)rw_args->buffer;
+ if ( !dstmsg ){
+ DBG("OCCAN: minor %d read: input buffer is NULL\n\r",minor);
+ return RTEMS_INVALID_NAME; /* -EINVAL */
+ }
+
+ while (left >= sizeof(CANMsg) ){
+
+ /* turn off interrupts */
+ rtems_interrupt_disable(oldLevel);
+
+ /* A bus off interrupt may have occured after checking can->started */
+ if ( can->status & OCCAN_STATUS_ERR_BUSOFF ){
+ rtems_interrupt_enable(oldLevel);
+ DBG("OCCAN: read is cancelled due to a BUS OFF error\n\r");
+ rw_args->bytes_moved = rw_args->count-left;
+ return RTEMS_IO_ERROR; /* EIO */
+ }
+
+ srcmsg = occan_fifo_claim_get(can->rxfifo);
+ if ( !srcmsg ){
+ /* no more messages in reception fifo.
+ * Wait for incoming packets only if in
+ * blocking mode AND no messages been
+ * read before.
+ */
+ if ( !can->rxblk || (left != rw_args->count) ){
+ /* turn on interrupts again */
+ rtems_interrupt_enable(oldLevel);
+ break;
+ }
+
+ /* turn on interrupts again */
+ rtems_interrupt_enable(oldLevel);
+
+ DBG("OCCAN: Waiting for RX int\n\r");
+
+ /* wait for incomming messages */
+ rtems_semaphore_obtain(can->rxsem,RTEMS_WAIT,RTEMS_NO_TIMEOUT);
+
+ /* did we get woken up by a BUS OFF error? */
+ if ( can->status & OCCAN_STATUS_ERR_BUSOFF ){
+ DBG("OCCAN: Blocking read got woken up by BUS OFF error\n\r");
+ /* At this point it should not matter how many messages we handled */
+ rw_args->bytes_moved = rw_args->count-left;
+ return RTEMS_IO_ERROR; /* EIO */
+ }
+
+ /* no errors detected, it must be a message */
+ continue;
+ }
+
+ /* got message, copy it to userspace buffer */
+ *dstmsg = *srcmsg;
+
+ /* Return borrowed message, RX interrupt can use it again */
+ occan_fifo_get(can->rxfifo);
+
+ /* turn on interrupts again */
+ rtems_interrupt_enable(oldLevel);
+
+ /* increase pointers */
+ left -= sizeof(CANMsg);
+ dstmsg++;
+ }
+
+ /* save number of read bytes. */
+ rw_args->bytes_moved = rw_args->count-left;
+ if ( rw_args->bytes_moved == 0 ){
+ DBG("OCCAN: minor %d read would block, returning\n\r",minor);
+ return RTEMS_TIMEOUT; /* ETIMEDOUT should be EAGAIN/EWOULDBLOCK */
+ }
+ return RTEMS_SUCCESSFUL;
+}
+
+static rtems_device_driver occan_write(rtems_device_major_number major, rtems_device_minor_number minor, void *arg){
+ occan_priv *can = &cans[minor];
+ rtems_libio_rw_args_t *rw_args=(rtems_libio_rw_args_t *) arg;
+ CANMsg *msg,*fifo_msg;
+ rtems_interrupt_level oldLevel;
+ int left;
+
+ DBG("OCCAN: Writing %d bytes from 0x%lx (%d)\n\r",rw_args->count,rw_args->buffer,sizeof(CANMsg));
+
+ if ( !can->started )
+ return RTEMS_RESOURCE_IN_USE; /* EBUSY */
+
+ left = rw_args->count;
+ if ( (left < sizeof(CANMsg)) || (!rw_args->buffer) ){
+ return RTEMS_INVALID_NAME; /* EINVAL */
+ }
+
+ msg = (CANMsg *)rw_args->buffer;
+
+ /* limit CAN message length to 8 */
+ msg->len = (msg->len > 8) ? 8 : msg->len;
+
+#ifdef DEBUG_VERBOSE
+ pelican_regs_print(can->regs);
+ occan_stat_print(&can->stats);
+#endif
+
+ /* turn off interrupts */
+ rtems_interrupt_disable(oldLevel);
+
+ /* A bus off interrupt may have occured after checking can->started */
+ if ( can->status & OCCAN_STATUS_ERR_BUSOFF ){
+ rtems_interrupt_enable(oldLevel);
+ rw_args->bytes_moved = 0;
+ return RTEMS_IO_ERROR; /* EIO */
+ }
+
+ /* If no messages in software tx fifo, we will
+ * try to send first message by putting it directly
+ * into the HW TX fifo.
+ */
+ if ( occan_fifo_empty(can->txfifo) ){
+ /*pelican_regs_print(cans[minor+1].regs);*/
+ if ( !pelican_send(can,msg) ) {
+ /* First message put directly into HW TX fifo
+ * This will turn TX interrupt on.
+ */
+ left -= sizeof(CANMsg);
+ msg++;
+
+ /* bump stat counters */
+ can->stats.tx_msgs++;
+
+ DBG("OCCAN: Sending direct via HW\n\r");
+ }
+ }
+
+ /* Put messages into software fifo */
+ while ( left >= sizeof(CANMsg) ){
+
+ /* limit CAN message length to 8 */
+ msg->len = (msg->len > 8) ? 8 : msg->len;
+
+ fifo_msg = occan_fifo_put_claim(can->txfifo,0);
+ if ( !fifo_msg ){
+
+ DBG("OCCAN: FIFO is full\n\r");
+ /* Block only if no messages previously sent
+ * and no in blocking mode
+ */
+ if ( !can->txblk || (left != rw_args->count) )
+ break;
+
+ /* turn on interupts again and wait
+ INT_ON
+ WAIT FOR FREE BUF;
+ INT_OFF;
+ CHECK_IF_FIFO_EMPTY ==> SEND DIRECT VIA HW;
+ */
+ rtems_interrupt_enable(oldLevel);
+
+ DBG("OCCAN: Waiting for tx int\n\r");
+
+ rtems_semaphore_obtain(can->txsem, RTEMS_WAIT, RTEMS_NO_TIMEOUT);
+
+ /* did we get woken up by a BUS OFF error? */
+ if ( can->status & OCCAN_STATUS_ERR_BUSOFF ){
+ DBG("OCCAN: Blocking write got woken up by BUS OFF error\n\r");
+ /* At this point it should not matter how many messages we handled */
+ rw_args->bytes_moved = rw_args->count-left;
+ return RTEMS_IO_ERROR; /* EIO */
+ }
+
+ rtems_interrupt_disable(oldLevel);
+
+ if ( occan_fifo_empty(can->txfifo) ){
+ if ( !pelican_send(can,msg) ) {
+ /* First message put directly into HW TX fifo
+ * This will turn TX interrupt on.
+ */
+ left -= sizeof(CANMsg);
+ msg++;
+
+ /* bump stat counters */
+ can->stats.tx_msgs++;
+
+ DBG("OCCAN: Sending direct2 via HW\n\r");
+ }
+ }
+ continue;
+ }
+
+ /* copy message into fifo area */
+ *fifo_msg = *msg;
+
+ /* tell interrupt handler about the message */
+ occan_fifo_put(can->txfifo);
+
+ DBG("OCCAN: Put info fifo SW\n\r");
+
+ /* Prepare insert of next message */
+ msg++;
+ left-=sizeof(CANMsg);
+ }
+
+ rtems_interrupt_enable(oldLevel);
+
+ rw_args->bytes_moved = rw_args->count-left;
+ DBG("OCCAN: Sent %d\n\r",rw_args->bytes_moved);
+
+ if ( left == rw_args->count )
+ return RTEMS_TIMEOUT; /* ETIMEDOUT should be EAGAIN/EWOULDBLOCK */
+ return RTEMS_SUCCESSFUL;
+}
+
+static rtems_device_driver occan_ioctl(rtems_device_major_number major, rtems_device_minor_number minor, void *arg){
+ int ret;
+ occan_speed_regs timing;
+ occan_priv *can = &cans[minor];
+ unsigned int speed;
+ rtems_libio_ioctl_args_t *ioarg = (rtems_libio_ioctl_args_t *) arg;
+ struct occan_afilter *afilter;
+ occan_stats *dststats;
+ unsigned char btr0, btr1;
+ unsigned int rxcnt,txcnt;
+
+ DBG("OCCAN: IOCTL %d\n\r",ioarg->command);
+
+ ioarg->ioctl_return = 0;
+ switch(ioarg->command){
+ case OCCAN_IOC_SET_SPEED:
+
+ /* cannot change speed during run mode */
+ if ( can->started )
+ return RTEMS_RESOURCE_IN_USE; /* EBUSY */
+
+ /* get speed rate from argument */
+ speed = (unsigned int)ioarg->buffer;
+ ret = occan_calc_speedregs(sys_freq_hz,speed,&timing);
+ if ( ret )
+ return RTEMS_INVALID_NAME; /* EINVAL */
+
+ /* set the speed regs of the CAN core */
+ /* occan_set_speedregs(can,timing); */
+
+ /* save timing/speed */
+ can->speed = speed;
+ can->timing = timing;
+ break;
+
+ case OCCAN_IOC_SET_BTRS:
+ /* Set BTR registers manually
+ * Read OCCAN Manual.
+ */
+ if ( can->started )
+ return RTEMS_RESOURCE_IN_USE; /* EBUSY */
+
+ can->speed = 0; /* custom */
+ can->timing.btr1 = (unsigned int)ioarg->buffer & 0xff;
+ can->timing.btr0 = ((unsigned int)ioarg->buffer>>8) & 0xff;
+/*
+ can->timing.sjw = (btr0 >> OCCAN_BUSTIM_SJW_BIT) & 0x3;
+ can->timing.brp = btr0 & OCCAN_BUSTIM_BRP;
+ can->timing.tseg1 = btr1 & 0xf;
+ can->timing.tseg2 = (btr1 >> OCCAN_BUSTIM_TSEG2_BIT) & 0x7;
+ can->timing.sam = (btr1 >> 7) & 0x1;
+ */
+ break;
+
+ case OCCAN_IOC_SPEED_AUTO:
+ return RTEMS_NOT_IMPLEMENTED;
+ if ( can->started )
+ return RTEMS_RESOURCE_IN_USE; /* EBUSY */
+
+ if ( (speed=pelican_speed_auto(can)) < 0 ){
+ /* failed */
+ return RTEMS_IO_ERROR;
+ }
+
+ /* set new speed */
+ can->speed = speed;
+
+ if ( (int *)ioarg->buffer ){
+ *(int *)ioarg->buffer = speed;
+ }
+ return RTEMS_SUCCESSFUL;
+ break;
+
+ case OCCAN_IOC_SET_BUFLEN:
+ /* set rx & tx fifo buffer length */
+ if ( can->started )
+ return RTEMS_RESOURCE_IN_USE; /* EBUSY */
+
+ rxcnt = (unsigned int)ioarg->buffer & 0x0000ffff;
+ txcnt = (unsigned int)ioarg->buffer >> 16;
+
+ occan_fifo_free(can->rxfifo);
+ occan_fifo_free(can->txfifo);
+
+ /* allocate new buffers */
+ can->rxfifo = occan_fifo_create(rxcnt);
+ can->txfifo = occan_fifo_create(txcnt);
+
+ if ( !can->rxfifo || !can->txfifo )
+ return RTEMS_NO_MEMORY; /* ENOMEM */
+ break;
+
+ case OCCAN_IOC_GET_CONF:
+ return RTEMS_NOT_IMPLEMENTED;
+ break;
+
+ case OCCAN_IOC_GET_STATS:
+ dststats = (occan_stats *)ioarg->buffer;
+ if ( !dststats )
+ return RTEMS_INVALID_NAME; /* EINVAL */
+
+ /* copy data stats into userspace buffer */
+ if ( can->rxfifo )
+ can->stats.rx_sw_dovr = can->rxfifo->ovcnt;
+ *dststats = can->stats;
+ break;
+
+ case OCCAN_IOC_GET_STATUS:
+ /* return the status of the */
+ if ( !ioarg->buffer )
+ return RTEMS_INVALID_NAME;
+
+ *(unsigned int *)ioarg->buffer = can->status;
+ break;
+
+ /* Set physical link */
+ case OCCAN_IOC_SET_LINK:
+#ifdef REDUNDANT_CHANNELS
+ if ( can->started )
+ return RTEMS_RESOURCE_IN_USE; /* EBUSY */
+
+ /* switch HW channel */
+ can->channel = (unsigned int)ioargs->buffer;
+#else
+ return RTEMS_NOT_IMPLEMENTED;
+#endif
+ break;
+
+ case OCCAN_IOC_SET_FILTER:
+ if ( can->started )
+ return RTEMS_RESOURCE_IN_USE; /* EBUSY */
+
+ afilter = (struct occan_afilter *)ioarg->buffer;
+
+ if ( !afilter )
+ return RTEMS_INVALID_NAME; /* EINVAL */
+
+ /* copy acceptance filter */
+ can->acode[0] = afilter->code[0];
+ can->acode[1] = afilter->code[1];
+ can->acode[2] = afilter->code[2];
+ can->acode[3] = afilter->code[3];
+
+ can->amask[0] = afilter->mask[0];
+ can->amask[1] = afilter->mask[1];
+ can->amask[2] = afilter->mask[2];
+ can->amask[3] = afilter->mask[3];
+
+ can->single_mode = ( afilter->single_mode ) ? 1 : 0;
+
+ /* Acceptance filter is written to hardware
+ * when starting.
+ */
+ /* pelican_set_accept(can,can->acode,can->amask);*/
+ break;
+
+ case OCCAN_IOC_SET_BLK_MODE:
+ can->rxblk = (unsigned int)ioarg->buffer & OCCAN_BLK_MODE_RX;
+ can->txblk = ((unsigned int)ioarg->buffer & OCCAN_BLK_MODE_TX) >> 1;
+ break;
+
+ case OCCAN_IOC_START:
+ if ( can->started )
+ return RTEMS_RESOURCE_IN_USE; /* EBUSY */
+ if ( pelican_start(can) )
+ return RTEMS_NO_MEMORY; /* failed because of no memory, can happen if SET_BUFLEN failed */
+ can->started = 1;
+ break;
+
+ case OCCAN_IOC_STOP:
+ if ( !can->started )
+ return RTEMS_RESOURCE_IN_USE; /* EBUSY */
+ pelican_stop(can);
+ can->started = 0;
+ break;
+
+ default:
+ return RTEMS_NOT_DEFINED;
+ }
+ return RTEMS_SUCCESSFUL;
+}
+
+static void occan_interrupt(occan_priv *can){
+ unsigned char iflags;
+ pelican_regs *regs = can->regs;
+ CANMsg *msg;
+ int signal_rx=0, signal_tx=0;
+ unsigned char tmp, errcode, arbcode;
+ int tx_error_cnt,rx_error_cnt;
+
+ can->stats.ints++;
+
+ while ( (iflags = READ_REG(&can->regs->intflags)) != 0 ){
+ /* still interrupts to handle */
+
+ if ( iflags & PELICAN_IF_RX ){
+ /* the rx fifo is not empty
+ * put 1 message into rxfifo for later use
+ */
+
+ /* get empty (or make room) message */
+ msg = occan_fifo_put_claim(can->rxfifo,1);
+ tmp = READ_REG(&regs->rx_fi_xff);
+ msg->extended = tmp >> 7;
+ msg->rtr = (tmp >> 6) & 1;
+ msg->len = tmp = tmp & 0x0f;
+
+ if ( msg->extended ){
+ /* extended message */
+ msg->id = READ_REG(&regs->msg.rx_eff.id[0])<<(5+8+8) |
+ READ_REG(&regs->msg.rx_eff.id[1])<<(5+8) |
+ READ_REG(&regs->msg.rx_eff.id[2])<<5 |
+ READ_REG(&regs->msg.rx_eff.id[3])>>3;
+ while(tmp--){
+ msg->data[tmp] = READ_REG(&regs->msg.rx_eff.data[tmp]);
+ }
+ /*
+ msg->data[0] = READ_REG(&regs->msg.rx_eff.data[0]);
+ msg->data[1] = READ_REG(&regs->msg.rx_eff.data[1]);
+ msg->data[2] = READ_REG(&regs->msg.rx_eff.data[2]);
+ msg->data[3] = READ_REG(&regs->msg.rx_eff.data[3]);
+ msg->data[4] = READ_REG(&regs->msg.rx_eff.data[4]);
+ msg->data[5] = READ_REG(&regs->msg.rx_eff.data[5]);
+ msg->data[6] = READ_REG(&regs->msg.rx_eff.data[6]);
+ msg->data[7] = READ_REG(&regs->msg.rx_eff.data[7]);
+ */
+ }else{
+ /* standard message */
+ msg->id = READ_REG(&regs->msg.rx_sff.id[0])<<3 |
+ READ_REG(&regs->msg.rx_sff.id[1])>>5;
+
+ while(tmp--){
+ msg->data[tmp] = READ_REG(&regs->msg.rx_sff.data[tmp]);
+ }
+ /*
+ msg->data[0] = READ_REG(&regs->msg.rx_sff.data[0]);
+ msg->data[1] = READ_REG(&regs->msg.rx_sff.data[1]);
+ msg->data[2] = READ_REG(&regs->msg.rx_sff.data[2]);
+ msg->data[3] = READ_REG(&regs->msg.rx_sff.data[3]);
+ msg->data[4] = READ_REG(&regs->msg.rx_sff.data[4]);
+ msg->data[5] = READ_REG(&regs->msg.rx_sff.data[5]);
+ msg->data[6] = READ_REG(&regs->msg.rx_sff.data[6]);
+ msg->data[7] = READ_REG(&regs->msg.rx_sff.data[7]);
+ */
+ }
+
+ /* Re-Enable RX buffer for a new message */
+ regs->cmd = READ_REG(&regs->cmd) | PELICAN_CMD_RELRXBUF;
+
+ /* make message available to the user */
+ occan_fifo_put(can->rxfifo);
+
+ /* bump stat counters */
+ can->stats.rx_msgs++;
+
+ /* signal the semaphore only once */
+ signal_rx = 1;
+ }
+
+ if ( iflags & PELICAN_IF_TX ){
+ /* there is room in tx fifo of HW */
+
+ if ( !occan_fifo_empty(can->txfifo) ){
+ /* send 1 more messages */
+ msg = occan_fifo_claim_get(can->txfifo);
+
+ if ( pelican_send(can,msg) ){
+ /* ERROR! We got an TX interrupt telling us
+ * tx fifo is empty, yet it is not.
+ *
+ * Complain about this max 10 times
+ */
+ if ( can->stats.tx_buf_error < 10 ){
+ printk("OCCAN: got TX interrupt but TX fifo in not empty (%d)\n\r",can->stats.tx_buf_error);
+ }
+ can->status |= OCCAN_STATUS_QUEUE_ERROR;
+ can->stats.tx_buf_error++;
+ }
+
+ /* free software-fifo space taken by sent message */
+ occan_fifo_get(can->txfifo);
+
+ /* bump stat counters */
+ can->stats.tx_msgs++;
+
+ /* wake any sleeping thread waiting for "fifo not full" */
+ signal_tx = 1;
+ }
+ }
+
+ if ( iflags & PELICAN_IF_ERRW ){
+ tx_error_cnt = READ_REG(&regs->tx_err_cnt);
+ rx_error_cnt = READ_REG(&regs->rx_err_cnt);
+
+ /* 1. if bus off tx error counter = 127 */
+ if ( (tx_error_cnt > 96) || (rx_error_cnt > 96) ){
+ /* in Error Active Warning area or BUS OFF */
+ can->status |= OCCAN_STATUS_WARN;
+
+ /* check reset bit for reset mode */
+ if ( READ_REG(&regs->mode) & PELICAN_MOD_RESET ){
+ /* in reset mode ==> bus off */
+ can->status |= OCCAN_STATUS_ERR_BUSOFF | OCCAN_STATUS_RESET;
+
+ /***** pelican_stop(can) ******
+ * turn off interrupts
+ * enter reset mode (HW already done that for us)
+ */
+ regs->inten = 0;
+
+ /* Indicate that we are not started any more.
+ * This will make write/read return with EBUSY
+ * on read/write attempts.
+ *
+ * User must issue a ioctl(START) to get going again.
+ */
+ can->started = 0;
+
+ /* signal any waiting read/write threads, so that they
+ * can handle the bus error.
+ */
+ signal_rx = 1;
+ signal_tx = 1;
+
+ /* ingnore any old pending interrupt */
+ break;
+ }
+
+ }else{
+ /* not in Upper Error Active area any more */
+ can->status &= ~(OCCAN_STATUS_WARN);
+ }
+ can->stats.err_warn++;
+ }
+
+ if ( iflags & PELICAN_IF_DOVR){
+ can->status |= OCCAN_STATUS_OVERRUN;
+ can->stats.err_dovr++;
+ DBG("OCCAN_INT: DOVR\n\r");
+ }
+
+ if ( iflags & PELICAN_IF_ERRP){
+ /* Let the error counters decide what kind of
+ * interrupt it was. In/Out of EPassive area.
+ */
+ tx_error_cnt = READ_REG(&regs->tx_err_cnt);
+ rx_error_cnt = READ_REG(&regs->rx_err_cnt);
+
+ if ( (tx_error_cnt > 127) || (tx_error_cnt > 127) ){
+ can->status |= OCCAN_STATUS_ERR_PASSIVE;
+ }else{
+ can->status &= ~(OCCAN_STATUS_ERR_PASSIVE);
+ }
+
+ /* increase Error Passive In/out interrupt counter */
+ can->stats.err_errp++;
+ }
+
+ if ( iflags & PELICAN_IF_ARB){
+ arbcode = READ_REG(&regs->arbcode);
+ can->stats.err_arb_bitnum[arbcode & PELICAN_ARB_BITS]++;
+ can->stats.err_arb++;
+ DBG("OCCAN_INT: ARB (0x%x)\n\r",arbcode & PELICAN_ARB_BITS);
+ }
+
+ if ( iflags & PELICAN_IF_BUS){
+ /* Some kind of BUS error, only used for
+ * statistics. Error Register is decoded
+ * and put into can->stats.
+ */
+ errcode = READ_REG(&regs->errcode);
+ switch( errcode & PELICAN_ECC_CODE ){
+ case PELICAN_ECC_CODE_BIT:
+ can->stats.err_bus_bit++;
+ break;
+ case PELICAN_ECC_CODE_FORM:
+ can->stats.err_bus_form++;
+ break;
+ case PELICAN_ECC_CODE_STUFF:
+ can->stats.err_bus_stuff++;
+ break;
+ case PELICAN_ECC_CODE_OTHER:
+ can->stats.err_bus_other++;
+ break;
+ }
+
+ /* Get Direction (TX/RX) */
+ if ( errcode & PELICAN_ECC_DIR ){
+ can->stats.err_bus_rx++;
+ }else{
+ can->stats.err_bus_tx++;
+ }
+
+ /* Get Segment in frame that went wrong */
+ can->stats.err_bus_segs[errcode & PELICAN_ECC_SEG]++;
+
+ /* total number of bus errors */
+ can->stats.err_bus++;
+ }
+ }
+
+ /* signal Binary semaphore, messages available! */
+ if ( signal_rx ){
+ rtems_semaphore_release(can->rxsem);
+ }
+
+ if ( signal_tx ){
+ rtems_semaphore_release(can->txsem);
+ }
+}
+
+static void occan_interrupt_handler(rtems_vector_number v){
+ int minor;
+
+ /* convert to */
+ for(minor = 0; minor < can_cores; minor++) {
+ if ( v == (cans[minor].irq+0x10) ) {
+ occan_interrupt(&cans[minor]);
+ return;
+ }
+ }
+}
+
+#define OCCAN_DRIVER_TABLE_ENTRY { occan_initialize, occan_open, occan_close, occan_read, occan_write, occan_ioctl }
+
+static rtems_driver_address_table occan_driver = OCCAN_DRIVER_TABLE_ENTRY;
+
+int OCCAN_PREFIX(_register)(amba_confarea_type *bus){
+ rtems_status_code r;
+ rtems_device_major_number m;
+
+ amba_bus = bus;
+ if ( !bus )
+ return 1;
+
+ if ((r = rtems_io_register_driver(0, &occan_driver, &m)) == RTEMS_SUCCESSFUL) {
+ DBG("OCCAN driver successfully registered, major: %d\n\r", m);
+ }else{
+ switch(r) {
+ case RTEMS_TOO_MANY:
+ printk("OCCAN rtems_io_register_driver failed: RTEMS_TOO_MANY\n\r"); break;
+ case RTEMS_INVALID_NUMBER:
+ printk("OCCAN rtems_io_register_driver failed: RTEMS_INVALID_NUMBER\n\r"); break;
+ case RTEMS_RESOURCE_IN_USE:
+ printk("OCCAN rtems_io_register_driver failed: RTEMS_RESOURCE_IN_USE\n\r"); break;
+ default:
+ printk("OCCAN rtems_io_register_driver failed\n\r");
+ }
+ return 1;
+ }
+ return 0;
+}
+
+
+/*******************************************************************************
+ * FIFO IMPLEMENTATION
+ */
+
+static occan_fifo *occan_fifo_create(int cnt){
+ occan_fifo *fifo;
+ fifo = malloc(sizeof(occan_fifo)+cnt*sizeof(CANMsg));
+ if ( fifo ){
+ fifo->cnt = cnt;
+ fifo->full = 0;
+ fifo->ovcnt = 0;
+ fifo->base = (CANMsg *)&fifo->fifoarea[0];
+ fifo->tail = fifo->head = fifo->base;
+ /* clear CAN Messages */
+ memset(fifo->base,0,cnt * sizeof(CANMsg));
+ }
+ return fifo;
+}
+
+static void occan_fifo_free(occan_fifo *fifo){
+ if ( fifo )
+ free(fifo);
+}
+
+static int occan_fifo_full(occan_fifo *fifo){
+ return fifo->full;
+}
+
+static int occan_fifo_empty(occan_fifo *fifo){
+ return (!fifo->full) && (fifo->head == fifo->tail);
+}
+
+/* Stage 1 - get buffer to fill (never fails if force!=0) */
+static CANMsg *occan_fifo_put_claim(occan_fifo *fifo, int force){
+ if ( !fifo )
+ return NULL;
+
+ if ( occan_fifo_full(fifo) ){
+
+ if ( !force )
+ return NULL;
+
+ /* all buffers already used ==> overwrite the oldest */
+ fifo->ovcnt++;
+ occan_fifo_get(fifo);
+ }
+
+ return fifo->head;
+}
+
+/* Stage 2 - increment indexes */
+static void occan_fifo_put(occan_fifo *fifo){
+ if ( occan_fifo_full(fifo) )
+ return;
+
+ /* wrap around */
+ fifo->head = (fifo->head >= &fifo->base[fifo->cnt-1])? fifo->base : fifo->head+1;
+
+ if ( fifo->head == fifo->tail )
+ fifo->full = 1;
+}
+
+static CANMsg *occan_fifo_claim_get(occan_fifo *fifo){
+ if ( occan_fifo_empty(fifo) )
+ return NULL;
+
+ /* return oldest message */
+ return fifo->tail;
+}
+
+
+static void occan_fifo_get(occan_fifo *fifo){
+ if ( !fifo )
+ return;
+
+ if ( occan_fifo_empty(fifo) )
+ return;
+
+ /* increment indexes */
+ fifo->tail = (fifo->tail >= &fifo->base[fifo->cnt-1])? fifo->base : fifo->tail+1;
+ fifo->full = 0;
+}
+/*******************************************************************************/
diff --git a/c/src/lib/libbsp/sparc/shared/can/occan_pci.c b/c/src/lib/libbsp/sparc/shared/can/occan_pci.c
new file mode 100644
index 0000000000..f68d04e9ca
--- /dev/null
+++ b/c/src/lib/libbsp/sparc/shared/can/occan_pci.c
@@ -0,0 +1,64 @@
+
+/* PCI cannot do byte accesses to addresses aligned byte wise
+ * Use alternative reg map.
+ */
+#define OCCAN_WORD_REGS
+
+/* Set registered device name */
+#define OCCAN_DEVNAME "/dev/occanpci0"
+#define OCCAN_DEVNAME_NO(devstr,no) ((devstr)[13]='0'+(no))
+
+/* Any non-static function will begin with */
+#define OCCAN_PREFIX(name) occanpci##name
+
+/* do nothing, assume that the interrupt handler is called
+ * setup externally calling b1553_interrupt_handler.
+ */
+#define OCCAN_REG_INT(handler,irq,arg) \
+ if ( occan_pci_int_reg ) \
+ occan_pci_int_reg(handler,irq,arg);
+
+void (*occan_pci_int_reg)(void *handler, int irq, void *arg) = 0;
+
+void occanpci_interrupt_handler(int irq, void *arg);
+
+/* AMBA Bus is clocked using the PCI clock (33.3MHz) */
+#define SYS_FREQ_HZ 33333333
+
+/* Enable two redundant channels */
+#define REDUNDANT_CHANNELS 2
+
+#define OCCAN_SET_CHANNEL(priv,channel) occanpci_set_channel(priv,channel)
+
+#include "occan.c"
+
+/* Define method that sets redundant channel
+ * The channel select register:
+ * 0x00 = byte regs
+ * 0x40 = channel select
+ * 0x80 = word regs
+ */
+static void inline occanpci_set_channel(occan_priv *priv, int channel){
+ unsigned int *chan_sel = (unsigned int *)(((unsigned int)priv->regs & ~0xff)+0x40);
+ if ( channel == 0 )
+ *chan_sel = 0;
+ else
+ *chan_sel = 0xffffffff;
+}
+
+int occan_pci_register(amba_confarea_type *bus)
+{
+ /* Setup configuration */
+
+ /* Register the driver */
+ return OCCAN_PREFIX(_register)(bus);
+}
+
+
+/* Call this from PCI interrupt handler
+ * irq = the irq number of the HW device local to that IRQMP controller
+ *
+ */
+void occanpci_interrupt_handler(int irq, void *arg){
+ occan_interrupt(arg);
+}