This is the mail archive of the ecos-discuss@sources.redhat.com mailing list for the eCos project.


Index Nav: [Date Index] [Subject Index] [Author Index] [Thread Index]
Message Nav: [Date Prev] [Date Next] [Thread Prev] [Thread Next]

MPC860 SCC2 UART diagnostic driver


hi all,

due to having time after porting RedBoot/HAL to
my custom MPC860 based board i send you this:

i am having a working SCC2 UART diagnostic driver.
The driver is based on the eCos SMC1 diagnostic driver and
here is my contribution.

As i started with it i didnt really knew where to put it.
So i put it in my local ecos repository where the SMC1
diagnostic driver is, i.e. $ECOS_REPOSITORY/hal/powerpc/quicc/

Then I adjusted "compile quicc_smc1" to "compile quicc_scc2" in
the belonging .cdl file.

thanks a lot for such a great service

best regards, christoph
-- 
//==========================================================================
//
//      quicc_scc2.c
//
//      PowerPC QUICC basic Serial IO using port SCC2
//
//==========================================================================
//####COPYRIGHTBEGIN####
//                                                                          
// -------------------------------------------                              
// The contents of this file are subject to the Red Hat eCos Public License 
// Version 1.1 (the "License"); you may not use this file except in         
// compliance with the License.  You may obtain a copy of the License at    
// http://www.redhat.com/                                                   
//                                                                          
// Software distributed under the License is distributed on an "AS IS"      
// basis, WITHOUT WARRANTY OF ANY KIND, either express or implied.  See the 
// License for the specific language governing rights and limitations under 
// the License.                                                             
//                                                                          
// The Original Code is eCos - Embedded Configurable Operating System,      
// released September 30, 1998.                                             
//                                                                          
// The Initial Developer of the Original Code is Red Hat.                   
// Portions created by Red Hat are                                          
// Copyright (C) 1998, 1999, 2000, 2001 Red Hat, Inc.                             
// All Rights Reserved.                                                     
// -------------------------------------------                              
//                                                                          
//####COPYRIGHTEND####
//==========================================================================
//#####DESCRIPTIONBEGIN####
//
// Author(s):    Red Hat
// Contributors: hmt, gthomas
// Date:         1999-06-08
// Purpose:      Provide basic Serial IO for MPC860 based board
// Description:  Serial IO for MPC860 based boards which connect their debug
//               channel to SCC2; or any QUICC user who wants to use SCC2.
// Usage:
// Notes:        The driver hooks itself up on procs channel 0. This should
//               probably be made configurable, allowing the platform
//               to specify location.
//
//####DESCRIPTIONEND####
//
//==========================================================================

#include <pkgconf/hal.h>
#include <pkgconf/hal_powerpc_quicc.h>
#include <cyg/infra/cyg_type.h>
#include <cyg/hal/hal_cache.h>

#include <cyg/hal/hal_arch.h>

#ifdef CYGPKG_HAL_POWERPC_MPC860

// eCos headers decribing PowerQUICC:
#include <cyg/hal/quicc/ppc8xx.h>

#include <cyg/hal/quicc/quicc_scc2.h>

#include <cyg/hal/hal_stub.h>           // target_register_t
#include <cyg/hal/hal_intr.h>           // HAL_INTERRUPT_UNMASK(...)
#include <cyg/hal/hal_if.h>             // Calling interface definitions
#include <cyg/hal/hal_misc.h>           // Helper functions
#include <cyg/hal/drv_api.h>            // CYG_ISR_HANDLED

#define UART_BIT_RATE(n) (((int)((CYGHWR_HAL_POWERPC_BOARD_SPEED)*1000000)/16)/n)
#define UART_BAUD_RATE CYGNUM_HAL_QUICC_DIAG_BAUD

#define SCC2    1

#define DPRAM   0x2000
#define MAX_RECEIVE_BUFFER_LEN 1

#define Txbd     0x2800       /* Tx Buffer Descriptor Offset */
#define Rxbd     0x2810       /* Rx Buffer Descriptor Offset */
#define NUM_Rxbd 128
//#define Txbuf    0x2f000 //( ( volatile char * )eppc + 0x2000 )
#define Txbuf    ((volatile char *)eppc + 0x2808)
//#define Rxbuf    0x2f010 //( ( volatile char * )eppc + 0x2010 )
#define Rxbuf    ((volatile char *)eppc + Rxbd + (NUM_Rxbd*sizeof(struct cp_bufdesc)))

// SCC Events (interrupts)
#define QUICC_SCCE_TX  0x02  // Tx interrupt
#define QUICC_SCCE_RX  0x01  // Rx interrupt

// General SCC Mode Register (section 22.1.1 )
#define QUICC_GSMR_L_TEN        0x10    // enable transmitter
#define QUICC_GSMR_L_REN        0x20    // enable receiver

// CPM Interrupt-in-Servive Register (section 35.5.4)
#define CPM_CISR_SCC2   0x20000000      // clear SCC2 interrupts

static struct cp_bufdesc *next_rxbd;

// ------------------------------------------------------
//  Initialize SCC2 as a uart.
// ------------------------------------------------------
// 
// Comments below reference Motorola's "MPC860 PowerQUICC User's Manual".

void
cyg_hal_plf_serial_init_channel(void)
{
    EPPC *eppc;
    int i;
    volatile struct uart_pram *uart_pram;
    struct cp_bufdesc *txbd, *rxbd;

    static int init_done = 0;
    if (init_done) return;
    init_done++;

    eppc = eppc_base();

    // --------------------------------------------------
    //  Reset communications processor and stop transmitter
    // --------------------------------------------------

    eppc->cp_cr = QUICC_CPM_CR_RESET | QUICC_CPM_CR_BUSY;

    while ( eppc -> cp_cr & QUICC_CPM_CR_BUSY );        // wait for CP ready

    // --------------------------------------------------
    // set up the port A pins for UART operation
    // --------------------------------------------------

    // Set PAR and DIR to allow SCC_TXD1 and SCC_RXD1
    // (Table 34-1)

    eppc -> pio_paodr = 0x0c00;
    eppc -> pio_padir |= 0x0c00;
    eppc -> pio_papar |= 0x000c;

#ifdef CYGPKG_HAL_POWERPC_PB04
    // enable 4 wire RS485 - target specific thing
    eppc -> pio_padat = 0x0400;
#endif

    // --------------------------------------------------
    // initialize the SDMA configuration register
    // --------------------------------------------------

    // normal operation (Table 20-2)
    eppc -> dma_sdcr |= 0x0001;
    
    // --------------------------------------------------
    // Configure baud rate generator (section 21.4)
    // --------------------------------------------------

    eppc -> brgc1 = 0x10000 | ( (UART_BIT_RATE(UART_BAUD_RATE)) << 1 );

    // map BRG1 to SCC2 (section 21.2.4.3)
    eppc -> si_sicr = 0;

    // --------------------------------------------------
    // set SCC2 UART parameter ram (Table 22-4)
    // --------------------------------------------------
    
    uart_pram = &eppc->pram[ SCC2 ].scc.pscc.u;

    // set pointers to buffer descriptors (section 22.3)
    uart_pram->rbase = Rxbd;
    uart_pram->tbase = Txbd;

    // set Rx and Tx function code (section 22.3.1)
    uart_pram->rfcr = 0x10;
    uart_pram->tfcr = 0x10;

    // initialize RX, TX parameters for SCC2 (section 19.5.2)
    eppc -> cp_cr = 0x0041;

    while ( eppc -> cp_cr & QUICC_CPM_CR_BUSY );        // wait for CP ready

    // --------------------------------------------------
    // initialize UART parameter RAM (section 23.4)
    // --------------------------------------------------

    // max receive buffer length
    uart_pram->mrblr = MAX_RECEIVE_BUFFER_LEN;

    // disable max_idle feature
    uart_pram->max_idl = 0;             // taken from SCCX.S

    // 1 break char sent on top XMIT
    uart_pram->brkcr = 0;

    // clear error counters, not used
    uart_pram -> parec = 0;
    uart_pram -> frmer = 0;
    uart_pram -> nosec = 0;
    uart_pram -> brkec = 0;

    // no last brk char received
    uart_pram->brkln = 0;

    // set address character, not used
    uart_pram -> uaddr1 = 0;
    uart_pram -> uaddr2 = 0;

    // set Transmit-out-of-Sequence character, not used
    uart_pram -> toseq = 0;

    // set RX control characters, not used
    for ( i = 0; i < 8; i++ )
    {
       uart_pram -> cc[ i ] = 0x8000;
    }

    // set receive control character mask
    uart_pram -> rccm = 0xc0ff;

    // setup RX buffer descriptors
    rxbd = (struct cp_bufdesc *)((char *)eppc + Rxbd);
    next_rxbd = rxbd;
    for (i = 0;  i < NUM_Rxbd;  i++) {

        rxbd->length = 0;
        rxbd->buffer = (volatile char*)(Rxbuf + i * MAX_RECEIVE_BUFFER_LEN);
        rxbd->ctrl   = QUICC_BD_CTL_Ready | QUICC_BD_CTL_Int;
        if (i == (NUM_Rxbd-1)) {
            rxbd->ctrl   |= QUICC_BD_CTL_Wrap;
        }
        rxbd++;
    }
    // Compiler bug: for whatever reason, the Wrap code above fails!
    rxbd = (struct cp_bufdesc *)((char *)eppc + Rxbd);
    rxbd[NUM_Rxbd-1].ctrl   |= QUICC_BD_CTL_Wrap;

    // setup TX buffer descriptor
    txbd = (struct cp_bufdesc *)((char *)eppc + Txbd);
    txbd->length = 1;
    txbd->buffer = (volatile char*)Txbuf;
    txbd->ctrl   = QUICC_BD_CTL_Wrap;

    // Clear any previous events. Mask interrupts.
    // (section 23.19)

    eppc->scc_regs[ SCC2 ].scc_scce = 0xffff;
//    eppc->scc_regs[ SCC2 ].scc_sccm = 0;        // no interrupts
    eppc->scc_regs[ SCC2 ].scc_sccm |= QUICC_SCCE_RX; // enable interrupts for rx

    // --------------------------------------------------
    // configure CPM (Communications Processor Module)
    // --------------------------------------------------

    // CPM interrupt configuration register (section 35.5.1)
    // level 4, HP=15, enable interrupts, grouped
    eppc -> cpmi_cicr = 0x00049f80;

    // CPM interrupt pending register (section 35.5.2)
    eppc -> cpmi_cimr = 0x20000000;

    // enable level 4 interrupts
    eppc -> siu_simask |= 0x00400000; 

    // --------------------------------------------------
    // setting GSMR (General SCC Mode Register) (section 22.1.1)
    // --------------------------------------------------
    
    // setting TDCR, RDCR for UART, NRZ UART mode
    eppc -> scc_regs[ SCC2 ] . scc_gsmr_l = 0x00028004;    // normal mode
//    eppc -> scc_regs[ SCC2 ] . scc_gsmr_l = 0x00028044;    // local loopback mode
//    eppc -> scc_regs[ SCC2 ] . scc_gsmr_l = 0x00028084;    // automatic echo mode
//    eppc -> scc_regs[ SCC2 ] . scc_gsmr_l = 0x000280c4;    // echo & loopback mode

    // setting TFL, RFW for UART
    eppc -> scc_regs[ SCC2 ] . scc_gsmr_h = 0x00000060;

    // --------------------------------------------------
    // setting PSMR (Protocol Specific Mode Register) (section 23.16)
    // --------------------------------------------------

    // set 8,n,1, flow control
//    eppc -> scc_regs[ SCC2 ] . scc_psmr = 0xB000;       // 1 stop bit
    eppc -> scc_regs[ SCC2 ] . scc_psmr = 0xF000;       // 2 stop bit

    // enable receiver and transmitter
    eppc -> scc_regs[ SCC2 ] . scc_gsmr_l |= 0x00000030;

#ifndef CYGSEM_HAL_VIRTUAL_VECTOR_SUPPORT // remove below
#ifdef CYGDBG_HAL_DEBUG_GDB_BREAK_SUPPORT
    HAL_INTERRUPT_UNMASK( CYGNUM_HAL_INTERRUPT_CPM_SCC2 );
#endif
#endif
}


#ifdef CYGDBG_DIAG_BUF
extern int enable_diag_uart;
#endif // CYGDBG_DIAG_BUF

void 
cyg_hal_plf_serial_putc(void* __ch_data, cyg_uint8 ch)
{
    volatile struct cp_bufdesc *bd, *first;
    EPPC *eppc = (EPPC*) __ch_data;
    volatile struct uart_pram *uart_pram = &eppc->pram[ SCC2 ].scc.pscc.u;
    int timeout;
    CYGARC_HAL_SAVE_GP();

    /* tx buffer descriptor */
    bd = (struct cp_bufdesc *)((char *)eppc + uart_pram->tbptr);

    // Scan for a free buffer
    first = bd;
    while (bd->ctrl & QUICC_BD_CTL_Ready) {
        if (bd->ctrl & QUICC_BD_CTL_Wrap) {
            bd = (struct cp_bufdesc *)((char *)eppc + uart_pram->tbase);
        } else {
            bd++;
        }
        if (bd == first) break;
    }

    while (bd->ctrl & QUICC_BD_CTL_Ready) ;  // Wait for buffer free
    
    if (bd->ctrl & QUICC_BD_CTL_Int) {
        // This buffer has just completed interrupt output.  Reset bits
        bd->ctrl &= ~QUICC_BD_CTL_Int;
        bd->length = 0;
    }

    bd->buffer[bd->length++] = ch;
    bd->ctrl      |= QUICC_BD_CTL_Ready;

#ifdef CYGDBG_DIAG_BUF
        enable_diag_uart = 0;
#endif // CYGDBG_DIAG_BUF

    timeout = 0;

    while (bd->ctrl & QUICC_BD_CTL_Ready) {

// Wait until buffer free
        if (++timeout == 0x7FFFF) {
            // A really long time!

#ifdef CYGDBG_DIAG_BUF
            diag_printf("bd fail? bd: %x, ctrl: %x, tx state: %x\n", bd, bd->ctrl, uart_pram->tstate);
#endif // CYGDBG_DIAG_BUF

            eppc -> scc_regs[ SCC2 ].scc_gsmr_l &= ~QUICC_GSMR_L_TEN;  // Disable transmitter
            bd -> ctrl &= ~QUICC_BD_CTL_Ready;
            eppc -> scc_regs[ SCC2 ].scc_gsmr_l |= QUICC_GSMR_L_TEN;   // Enable transmitter
            bd -> ctrl |= QUICC_BD_CTL_Ready;
            timeout = 0;

#ifdef CYGDBG_DIAG_BUF
            diag_printf("bd retry? bd: %x, ctrl: %x, tx state: %x\n", bd, bd->ctrl, uart_pram->tstate);
            first = (struct cp_bufdesc *)((char *)eppc + uart_pram->tbase);
            while (true) {
                diag_printf("bd: %x, ctrl: %x, length: %x\n", first, first->ctrl, first->length);
                if (first->ctrl & QUICC_BD_CTL_Wrap) break;
                first++;
            }
#endif // CYGDBG_DIAG_BUF

        }
    }

    while (bd->ctrl & QUICC_BD_CTL_Ready) ;  // Wait until buffer free

    bd -> length = 0;

#ifdef CYGDBG_DIAG_BUF
    enable_diag_uart = 1;
#endif // CYGDBG_DIAG_BUF

    CYGARC_HAL_RESTORE_GP();
}


static cyg_bool
cyg_hal_plf_serial_getc_nonblock(void* __ch_data, cyg_uint8* ch)
{
    volatile struct cp_bufdesc *bd;
    EPPC *eppc = (EPPC*) __ch_data;
    volatile struct uart_pram *uart_pram = &eppc->pram[ SCC2 ].scc.pscc.u;
    int cache_state;

    /* rx buffer descriptor */
    bd = next_rxbd;

    if (bd->ctrl & QUICC_BD_CTL_Ready)
    {
        return false;
    }

    *ch = bd -> buffer[0];

    bd->length = MAX_RECEIVE_BUFFER_LEN;
    bd->buffer[0] = '\0';
    bd->ctrl |= QUICC_BD_CTL_Ready;
    if (bd->ctrl & QUICC_BD_CTL_Wrap) {
        bd = (struct cp_bufdesc *)((char *)eppc + Rxbd);
    } else {
        bd++;
    }
    next_rxbd = (struct cp_bufdesc *)bd;

    // Note: the MBX860 does not seem to snoop/invalidate the data cache properly!
    HAL_DCACHE_IS_ENABLED(cache_state);
    if (cache_state) {
        HAL_DCACHE_INVALIDATE(bd->buffer, uart_pram->mrblr);  // Make sure no stale data
    }

    return true;
}

cyg_uint8
cyg_hal_plf_serial_getc(void* __ch_data)
{
    cyg_uint8 ch;
    CYGARC_HAL_SAVE_GP();

    while(!cyg_hal_plf_serial_getc_nonblock(__ch_data, &ch))
    {
#ifdef CYGPKG_HAL_POWERPC_PB04
       // toggle hardware watchdog
       TOGGLE_WATCHDOG;
#endif
    }

    CYGARC_HAL_RESTORE_GP();
    return ch;
}



static void
cyg_hal_plf_serial_write(void* __ch_data, const cyg_uint8* __buf, 
                         cyg_uint32 __len)
{
    CYGARC_HAL_SAVE_GP();

    while(__len-- > 0)
        cyg_hal_plf_serial_putc(__ch_data, *__buf++);

    CYGARC_HAL_RESTORE_GP();
}

static void
cyg_hal_plf_serial_read(void* __ch_data, cyg_uint8* __buf, cyg_uint32 __len)
{
    CYGARC_HAL_SAVE_GP();

    while(__len-- > 0)
        *__buf++ = cyg_hal_plf_serial_getc(__ch_data);

    CYGARC_HAL_RESTORE_GP();
}

cyg_int32 msec_timeout = 1000;

cyg_bool
cyg_hal_plf_serial_getc_timeout(void* __ch_data, cyg_uint8* ch)
{
    int delay_count = msec_timeout * 10; // delay in .1 ms steps
    cyg_bool res;
    CYGARC_HAL_SAVE_GP();

    for(;;) {

#ifdef CYGPKG_HAL_POWERPC_PB04
        // toggle hardware watchdog
        TOGGLE_WATCHDOG;
#endif

        res = cyg_hal_plf_serial_getc_nonblock(__ch_data, ch);
        if (res || 0 == delay_count--)
            break;
        
        CYGACC_CALL_IF_DELAY_US(100);
    }

    CYGARC_HAL_RESTORE_GP();
    return res;
}

static int
cyg_hal_plf_serial_control(void *__ch_data, __comm_control_cmd_t __func, ...)
{
    static int irq_state = 0;
    int ret = 0;
    CYGARC_HAL_SAVE_GP();

    switch (__func) {
    case __COMMCTL_IRQ_ENABLE:
        HAL_INTERRUPT_UNMASK(CYGNUM_HAL_INTERRUPT_CPM_SCC2);
        irq_state = 1;
        break;
    case __COMMCTL_IRQ_DISABLE:
        ret = irq_state;
        irq_state = 0;
        HAL_INTERRUPT_MASK(CYGNUM_HAL_INTERRUPT_CPM_SCC2);
        break;
    case __COMMCTL_DBG_ISR_VECTOR:
        ret = CYGNUM_HAL_INTERRUPT_CPM_SCC2;
        break;
    case __COMMCTL_SET_TIMEOUT:
    {
        va_list ap;

        va_start(ap, __func);

        ret = msec_timeout;
        msec_timeout = va_arg(ap, cyg_uint32);

        va_end(ap);
    }        
    default:
        break;
    }
    CYGARC_HAL_RESTORE_GP();
    return ret;
}

static int
cyg_hal_plf_serial_isr(void *__ch_data, int* __ctrlc, 
                       CYG_ADDRWORD __vector, CYG_ADDRWORD __data)
{
    EPPC *eppc = (EPPC*) __ch_data;
    struct cp_bufdesc *bd;
    char ch;
    int res = 0;
    CYGARC_HAL_SAVE_GP();

    if ( __vector != 0x1d ) 
    {
       return 0;        // FIXME: needs further investigation
    }

    *__ctrlc = 0;
    if (eppc->scc_regs[ SCC2 ].scc_scce & QUICC_SCCE_RX) {

        eppc->scc_regs[ SCC2 ].scc_scce = QUICC_SCCE_RX;

        /* rx buffer descriptors */
        bd = next_rxbd;

        if ((bd->ctrl & QUICC_BD_CTL_Ready) == 0) {
            
            // then there be a character waiting
            ch = bd->buffer[0];

            bd->length = MAX_RECEIVE_BUFFER_LEN;
            bd->ctrl   |= QUICC_BD_CTL_Int;

            if( cyg_hal_is_break( &ch , 1 ) )
            {
                *__ctrlc = 1;
                bd->ctrl   |= QUICC_BD_CTL_Ready;

               if ( bd -> ctrl & QUICC_BD_CTL_Wrap ) {
                   bd = (struct cp_bufdesc *)((char *)eppc + Rxbd);
               } else {
                   bd++;
               }
               next_rxbd = bd;
            }

        }

        // Interrupt handled. Acknowledge it.
        eppc->cpmi_cisr |= CPM_CISR_SCC2;

        res = CYG_ISR_HANDLED;
    }

    CYGARC_HAL_RESTORE_GP();
    return res;
}

/*
 * Early initialization of comm channels. Must not rely
 * on interrupts, yet. Interrupt operation can be enabled
 * in _bsp_board_init().
 */
void
cyg_hal_plf_serial_init(void)
{
    hal_virtual_comm_table_t* comm;
    int cur = CYGACC_CALL_IF_SET_CONSOLE_COMM(CYGNUM_CALL_IF_SET_COMM_ID_QUERY_CURRENT);

    static int init = 0;  // It's wrong to do this more than once
    if (init) return;
    init++;

    cyg_hal_plf_serial_init_channel();

    // Setup procs in the vector table

    // Set channel 0
    CYGACC_CALL_IF_SET_CONSOLE_COMM(0);// Should be configurable!
    comm = CYGACC_CALL_IF_CONSOLE_PROCS();
    CYGACC_COMM_IF_CH_DATA_SET(*comm, eppc_base());
    CYGACC_COMM_IF_WRITE_SET(*comm, cyg_hal_plf_serial_write);
    CYGACC_COMM_IF_READ_SET(*comm, cyg_hal_plf_serial_read);
    CYGACC_COMM_IF_PUTC_SET(*comm, cyg_hal_plf_serial_putc);
    CYGACC_COMM_IF_GETC_SET(*comm, cyg_hal_plf_serial_getc);
    CYGACC_COMM_IF_CONTROL_SET(*comm, cyg_hal_plf_serial_control);
    CYGACC_COMM_IF_DBG_ISR_SET(*comm, cyg_hal_plf_serial_isr);
    CYGACC_COMM_IF_GETC_TIMEOUT_SET(*comm, cyg_hal_plf_serial_getc_timeout);

    // Restore original console
    CYGACC_CALL_IF_SET_CONSOLE_COMM(cur);
}

#endif // CYGPKG_HAL_POWERPC_MPC860
// EOF quicc_scc2.c
#ifndef CYGONCE_HAL_PPC_QUICC_SCC2_H
#define CYGONCE_HAL_PPC_QUICC_SCC2_H
//=============================================================================
//
//      quicc_scc2.h
//
//      PowerPC QUICC basic Serial IO using port SCC2
//
//=============================================================================
//####COPYRIGHTBEGIN####
//                                                                          
// -------------------------------------------                              
// The contents of this file are subject to the Red Hat eCos Public License 
// Version 1.1 (the "License"); you may not use this file except in         
// compliance with the License.  You may obtain a copy of the License at    
// http://www.redhat.com/                                                   
//                                                                          
// Software distributed under the License is distributed on an "AS IS"      
// basis, WITHOUT WARRANTY OF ANY KIND, either express or implied.  See the 
// License for the specific language governing rights and limitations under 
// the License.                                                             
//                                                                          
// The Original Code is eCos - Embedded Configurable Operating System,      
// released September 30, 1998.                                             
//                                                                          
// The Initial Developer of the Original Code is Red Hat.                   
// Portions created by Red Hat are                                          
// Copyright (C) 1998, 1999, 2000 Red Hat, Inc.                             
// All Rights Reserved.                                                     
// -------------------------------------------                              
//                                                                          
//####COPYRIGHTEND####
//=============================================================================
//#####DESCRIPTIONBEGIN####
//
// Author(s):    Red Hat
// Contributors: hmt
// Date:         1999-06-08
// Purpose:      Provide basic Serial IO for MBX board
// Description:  Serial IO for MBX boards which connect their debug channel
//               to SCC2; or any QUICC user who wants to use SCC2.
// Usage:
//
//####DESCRIPTIONEND####
//
//=============================================================================

#include <cyg/infra/cyg_type.h>
#include <cyg/hal/quicc/ppc8xx.h>             // FIXME: bad, but need eppc_base


#if !defined(CYGSEM_HAL_VIRTUAL_VECTOR_DIAG)
// This one should only be used by old-stub compatibility code!
externC void cyg_hal_plf_serial_init_channel(void);
#endif

externC void cyg_hal_plf_serial_init(void);
externC void cyg_hal_plf_serial_putc(void* __ch_data, cyg_uint8 __ch);
externC cyg_uint8 cyg_hal_plf_serial_getc(void* __ch_data);

#endif /* CYGONCE_HAL_PPC_QUICC_SCC2_H */

Index Nav: [Date Index] [Subject Index] [Author Index] [Thread Index]
Message Nav: [Date Prev] [Date Next] [Thread Prev] [Thread Next]