LM32: Progress on interrupt and serial driver.
This commit is contained in:
parent
8fe916e133
commit
45caca804a
@ -11,7 +11,7 @@ choice
|
||||
|
||||
config ARCH_CHIP_LM32
|
||||
bool "LM32"
|
||||
select MISOC_HAVE_UART0
|
||||
select MISOC_HAVE_UART1
|
||||
---help---
|
||||
LM32 Chip Selected
|
||||
|
||||
@ -32,15 +32,15 @@ menu "MISOC Peripheral Support"
|
||||
# These "hidden" settings determine is a peripheral option is available for the
|
||||
# selection MCU
|
||||
|
||||
config MISOC_HAVE_UART0
|
||||
config MISOC_HAVE_UART1
|
||||
bool
|
||||
default n
|
||||
select UART0_SERIALDRIVER
|
||||
select UART1_SERIALDRIVER
|
||||
|
||||
config MISOC_UART0
|
||||
bool "UART0"
|
||||
config MISOC_UART1
|
||||
bool "UART1"
|
||||
default n
|
||||
select ARCH_HAVE_UART0
|
||||
select ARCH_HAVE_UART1
|
||||
select MISOC_UART
|
||||
|
||||
endmenu # MISOC Peripheral Support
|
||||
|
64
arch/misoc/src/common/misoc.h
Normal file
64
arch/misoc/src/common/misoc.h
Normal file
@ -0,0 +1,64 @@
|
||||
/****************************************************************************
|
||||
* arch/misoc/src/common/serial.h
|
||||
*
|
||||
* Copyright (C) 2016 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
* Ramtin Amin <keytwo@gmail.com>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name NuttX nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifndef __ARCH_MISOC_SRC_COMMON_MISOC_H
|
||||
#define __ARCH_MISOC_SRC_COMMON_MISOC_H
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
#ifndef __ASSEMBLY__
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_serialinit
|
||||
*
|
||||
* Description:
|
||||
* Register serial console and serial ports. This assumes that
|
||||
* misoc_earlyserialinit was called previously.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void misoc_serial_initialize(void);
|
||||
|
||||
#endif /* __ASSEMBLY__ */
|
||||
#endif /* __ARCH_MISOC_SRC_COMMON_MISOC_H */
|
70
arch/misoc/src/common/misoc_mdelay.c
Normal file
70
arch/misoc/src/common/misoc_mdelay.c
Normal file
@ -0,0 +1,70 @@
|
||||
/****************************************************************************
|
||||
* arch/misoc/src/common/misoc_mdelay.c
|
||||
*
|
||||
* Copyright (C) 2016 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name NuttX nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <nuttx/arch.h>
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_mdelay
|
||||
*
|
||||
* Description:
|
||||
* Delay inline for the requested number of milliseconds.
|
||||
* *** NOT multi-tasking friendly ***
|
||||
*
|
||||
* ASSUMPTIONS:
|
||||
* The setting CONFIG_BOARD_LOOPSPERMSEC has been calibrated
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void up_mdelay(unsigned int milliseconds)
|
||||
{
|
||||
volatile int i;
|
||||
volatile int j;
|
||||
|
||||
for (i = 0; i < milliseconds; i++)
|
||||
{
|
||||
for (j = 0; j < CONFIG_BOARD_LOOPSPERMSEC; j++)
|
||||
{
|
||||
}
|
||||
}
|
||||
}
|
685
arch/misoc/src/common/misoc_serial.c
Normal file
685
arch/misoc/src/common/misoc_serial.c
Normal file
@ -0,0 +1,685 @@
|
||||
/****************************************************************************
|
||||
* arch/misoc/src/lm32/lm32_blocktask.c
|
||||
*
|
||||
* Copyright (C) 2016 Gregory Nutt. All rights reserved.
|
||||
* Author: Ramtin Amin <keytwo@gmail.com>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name NuttX nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <unistd.h>
|
||||
#include <semaphore.h>
|
||||
#include <string.h>
|
||||
#include <errno.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/irq.h>
|
||||
#include <nuttx/arch.h>
|
||||
#include <nuttx/serial/serial.h>
|
||||
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include <arch/board/generated/csr.h>
|
||||
|
||||
#include "chip.h"
|
||||
#include "hw/flags.h
|
||||
#include "misoc.h"
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
#undef HAVE_UART_DEVICE
|
||||
#if defined(CONFIG_MISOC_UART1) || defined(CONFIG_MISOC_UART2)
|
||||
# define HAVE_UART_DEVICE 1
|
||||
#endif
|
||||
|
||||
/* Is there a serial console? There should be no more than one defined. It
|
||||
* could be on any UARTn, n=1,.. CHIP_NUARTS
|
||||
*/
|
||||
|
||||
#if defined(CONFIG_UART1_SERIAL_CONSOLE) && defined(CONFIG_MISOC_UART1)
|
||||
# undef CONFIG_UART2_SERIAL_CONSOLE
|
||||
# define HAVE_SERIAL_CONSOLE 1
|
||||
#elif defined(CONFIG_UART2_SERIAL_CONSOLE) && defined(CONFIG_MISOC_UART2)
|
||||
# undef CONFIG_UART1_SERIAL_CONSOLE
|
||||
# define HAVE_SERIAL_CONSOLE 1
|
||||
#else
|
||||
# undef CONFIG_UART1_SERIAL_CONSOLE
|
||||
# undef CONFIG_UART2_SERIAL_CONSOLE
|
||||
# undef HAVE_SERIAL_CONSOLE
|
||||
#endif
|
||||
|
||||
/* If we are not using the serial driver for the console, then we still must
|
||||
* provide some minimal implementation of misoc_putc.
|
||||
*/
|
||||
|
||||
#ifdef USE_SERIALDRIVER
|
||||
|
||||
/* Which UART with be tty0/console and which tty1? The console will always
|
||||
* be ttyS0. If there is no console then will use the lowest numbered UART.
|
||||
*/
|
||||
|
||||
#ifdef HAVE_SERIAL_CONSOLE
|
||||
# if defined(CONFIG_UART1_SERIAL_CONSOLE)
|
||||
# define CONSOLE_DEV g_uart1port /* UART1 is console */
|
||||
# define TTYS0_DEV g_uart1port /* UART1 is ttyS0 */
|
||||
# undef TTYS1_DEV /* No ttyS1 */
|
||||
# define SERIAL_CONSOLE 1
|
||||
# else
|
||||
# error "I'm confused... Do we have a serial console or not?"
|
||||
# endif
|
||||
#else
|
||||
# undef CONSOLE_DEV /* No console */
|
||||
# undef CONFIG_UART1_SERIAL_CONSOLE
|
||||
# if defined(CONFIG_NR5_UART1)
|
||||
# define TTYS0_DEV g_uart1port /* UART1 is ttyS0 */
|
||||
# undef TTYS1_DEV /* No ttyS1 */
|
||||
# define SERIAL_CONSOLE 1
|
||||
# else
|
||||
# undef TTYS0_DEV
|
||||
# undef TTYS1_DEV
|
||||
# endif
|
||||
#endif
|
||||
|
||||
/* Common initialization logic will not not know that the all of the UARTs
|
||||
* have been disabled. So, as a result, we may still have to provide
|
||||
* stub implementations of misoc_earlyserialinit(), misoc_serial_initialize(), and
|
||||
* misoc_putc().
|
||||
*/
|
||||
|
||||
#ifdef HAVE_UART_DEVICE
|
||||
|
||||
/****************************************************************************
|
||||
* Private Types
|
||||
****************************************************************************/
|
||||
|
||||
struct misoc_dev_s
|
||||
{
|
||||
uintptr_t uartbase;
|
||||
uintptr_t rxtx_addr;
|
||||
uintptr_t txfull_addr;
|
||||
uintptr_t rxempty_addr;
|
||||
uintptr_t ev_status_addr;
|
||||
uintptr_t ev_pending_addr;
|
||||
uintptr_t ev_enable_addr;
|
||||
uint8_t irq;
|
||||
};
|
||||
|
||||
/****************************************************************************
|
||||
* Private Function Prototypes
|
||||
****************************************************************************/
|
||||
|
||||
/* Low-level helpers */
|
||||
|
||||
static inline uint32_t misoc_serialin(struct misoc_dev_s *priv, int offset);
|
||||
static inline void misoc_serialout(struct misoc_dev_s *priv, int offset,
|
||||
uint32_t value);
|
||||
static void misoc_restoreuartint(struct uart_dev_s *dev, uint8_t im);
|
||||
static void misoc_disableuartint(struct uart_dev_s *dev, uint8_t *im);
|
||||
|
||||
/* Serial driver methods */
|
||||
|
||||
static int misoc_setup(struct uart_dev_s *dev);
|
||||
static void misoc_shutdown(struct uart_dev_s *dev);
|
||||
static int misoc_attach(struct uart_dev_s *dev);
|
||||
static void misoc_detach(struct uart_dev_s *dev);
|
||||
static int misoc_uart_interrupt(int irq, void *context);
|
||||
static int misoc_ioctl(struct file *filep, int cmd, unsigned long arg);
|
||||
static int misoc_receive(struct uart_dev_s *dev, uint32_t *status);
|
||||
static void misoc_rxint(struct uart_dev_s *dev, bool enable);
|
||||
static bool misoc_rxavailable(struct uart_dev_s *dev);
|
||||
static void misoc_send(struct uart_dev_s *dev, int ch);
|
||||
static void misoc_txint(struct uart_dev_s *dev, bool enable);
|
||||
static bool misoc_txready(struct uart_dev_s *dev);
|
||||
static bool misoc_txempty(struct uart_dev_s *dev);
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
|
||||
static const struct uart_ops_s g_uart_ops =
|
||||
{
|
||||
.setup = misoc_setup,
|
||||
.shutdown = misoc_shutdown,
|
||||
.attach = misoc_attach,
|
||||
.detach = misoc_detach,
|
||||
.ioctl = misoc_ioctl,
|
||||
.receive = misoc_receive,
|
||||
.rxint = misoc_rxint,
|
||||
.rxavailable = misoc_rxavailable,
|
||||
#ifdef CONFIG_SERIAL_IFLOWCONTROL
|
||||
.rxflowcontrol = NULL,
|
||||
#endif
|
||||
.send = misoc_send,
|
||||
.txint = misoc_txint,
|
||||
.txready = misoc_txready,
|
||||
.txempty = misoc_txempty,
|
||||
};
|
||||
|
||||
/* I/O buffers */
|
||||
|
||||
#ifdef CONFIG_MISOC_UART1
|
||||
static char g_uart1rxbuffer[CONFIG_UART1_RXBUFSIZE];
|
||||
static char g_uart1txbuffer[CONFIG_UART1_TXBUFSIZE];
|
||||
#endif
|
||||
|
||||
/* This describes the state of the NR5 UART1 port. */
|
||||
|
||||
#ifdef CONFIG_MISOC_UART1
|
||||
#ifndef CONFIG_MISOC_UART1PRIO
|
||||
# define CONFIG_MISOC_UART1PRIO 4
|
||||
#endif
|
||||
|
||||
static struct misoc_dev_s g_uart1priv =
|
||||
{
|
||||
.uartbase = CSR_UART_BASE,
|
||||
.irq = UART_INTERRUPT,
|
||||
.rxtx_addr = CSR_UART_RXTX_ADDR,
|
||||
.rxempty_addr = CSR_UART_RXEMPTY_ADDR,
|
||||
.txfull_addr = CSR_UART_TXFULL_ADDR,
|
||||
.ev_status_addr = CSR_UART_EV_STATUS_ADDR,
|
||||
.ev_pending_addr = CSR_UART_EV_PENDING_ADDR,
|
||||
.ev_enable_addr = CSR_UART_EV_ENABLE_ADDR,
|
||||
};
|
||||
|
||||
static uart_dev_t g_uart1port =
|
||||
{
|
||||
#if SERIAL_CONSOLE == 1
|
||||
.isconsole = 1,
|
||||
#endif
|
||||
.recv =
|
||||
{
|
||||
.size = CONFIG_UART1_RXBUFSIZE,
|
||||
.buffer = g_uart1rxbuffer,
|
||||
},
|
||||
.xmit =
|
||||
{
|
||||
.size = CONFIG_UART1_TXBUFSIZE,
|
||||
.buffer = g_uart1txbuffer,
|
||||
},
|
||||
.ops = &g_uart_ops,
|
||||
.priv = &g_uart1priv,
|
||||
};
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: misoc_restoreuartint
|
||||
****************************************************************************/
|
||||
|
||||
static void misoc_restoreuartint(struct uart_dev_s *dev, uint8_t im)
|
||||
{
|
||||
/* Re-enable/re-disable interrupts corresponding to the state of bits in
|
||||
* im.
|
||||
*/
|
||||
|
||||
uart_ev_enable_write(im);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: misoc_disableuartint
|
||||
****************************************************************************/
|
||||
|
||||
static void misoc_disableuartint(struct uart_dev_s *dev, uint8_t *im)
|
||||
{
|
||||
struct misoc_dev_s *priv = (struct misoc_dev_s *)dev->priv;
|
||||
|
||||
if (im)
|
||||
{
|
||||
*im = uart_ev_enable_read();
|
||||
}
|
||||
|
||||
misoc_restoreuartint(dev, 0);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: misoc_setup
|
||||
*
|
||||
* Description:
|
||||
* Configure the UART baud, bits, parity, etc. This method is called the
|
||||
* first time that the serial port is opened.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static int misoc_setup(struct uart_dev_s *dev)
|
||||
{
|
||||
uart_ev_pending_write(uart_ev_pending_read());
|
||||
return OK;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: misoc_shutdown
|
||||
*
|
||||
* Description:
|
||||
* Disable the UART. This method is called when the serial
|
||||
* port is closed
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static void misoc_shutdown(struct uart_dev_s *dev)
|
||||
{
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: misoc_attach
|
||||
*
|
||||
* Description:
|
||||
* Configure the UART to operation in interrupt driven mode. This method is
|
||||
* called when the serial port is opened. Normally, this is just after the
|
||||
* the setup() method is called, however, the serial console may operate in
|
||||
* a non-interrupt driven mode during the boot phase.
|
||||
*
|
||||
* RX and TX interrupts are not enabled by the attach method (unless the
|
||||
* hardware supports multiple levels of interrupt enabling). The RX and TX
|
||||
* interrupts are not enabled until the txint() and rxint() methods are called.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static int misoc_attach(struct uart_dev_s *dev)
|
||||
{
|
||||
struct misoc_dev_s *priv = (struct misoc_dev_s *)dev->priv;
|
||||
uint32_t im;
|
||||
|
||||
irq_attach(priv->irq, misoc_uart_interrupt);
|
||||
|
||||
/* enable interrupt */
|
||||
/* TODO: move that somewhere proper ! */
|
||||
|
||||
im = irq_getmask();
|
||||
im |= (1 << UART_INTERRUPT);
|
||||
irq_setmask(im);
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: misoc_detach
|
||||
*
|
||||
* Description:
|
||||
* Detach UART interrupts. This method is called when the serial port is
|
||||
* closed normally just before the shutdown method is called. The exception
|
||||
* is the serial console which is never shutdown.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static void misoc_detach(struct uart_dev_s *dev)
|
||||
{
|
||||
struct misoc_dev_s *priv = (struct misoc_dev_s *)dev->priv;
|
||||
uint32_t im;
|
||||
|
||||
/* TODO: move that somewhere proper */
|
||||
|
||||
im = irq_getmask();
|
||||
im &= ~(1 << UART_INTERRUPT);
|
||||
irq_setmask(im);
|
||||
|
||||
irq_detach(priv->irq);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: misoc_interrupt
|
||||
*
|
||||
* Description:
|
||||
* This is the UART interrupt handler. It will be invoked when an
|
||||
* interrupt received on the 'irq' It should call uart_transmitchars or
|
||||
* uart_receivechar to perform the appropriate data transfers. The
|
||||
* interrupt handling logic must be able to map the 'irq' number into the
|
||||
* approprite uart_dev_s structure in order to call these functions.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static int misoc_uart_interrupt(int irq, void *context)
|
||||
{
|
||||
uint32_t stat;
|
||||
struct uart_dev_s *dev = NULL;
|
||||
int i;
|
||||
|
||||
dev = &g_uart1port;
|
||||
|
||||
/* Read as much as we can */
|
||||
|
||||
stat = uart_ev_pending_read();
|
||||
if (stat & UART_EV_RX)
|
||||
{
|
||||
while (!uart_rxempty_read())
|
||||
{
|
||||
uart_recvchars(dev);
|
||||
}
|
||||
}
|
||||
|
||||
/* Try to send all the buffer that were not sent. Does uart_xmitchars
|
||||
* send only if there is something to send ???
|
||||
*/
|
||||
|
||||
if ((stat & UART_EV_TX) != 0)
|
||||
{
|
||||
uart_ev_pending_write(UART_EV_TX);
|
||||
uart_xmitchars(dev);
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: misoc_ioctl
|
||||
*
|
||||
* Description:
|
||||
* All ioctl calls will be routed through this method
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static int misoc_ioctl(struct file *filep, int cmd, unsigned long arg)
|
||||
{
|
||||
#ifdef CONFIG_SERIAL_TERMIOS
|
||||
return -ENOSYS;
|
||||
#else
|
||||
return -ENOTTY;
|
||||
#endif
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: misoc_receive
|
||||
*
|
||||
* Description:
|
||||
* Called (usually) from the interrupt level to receive one
|
||||
* character from the UART. Error bits associated with the
|
||||
* receipt are provided in the return 'status'.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static int misoc_receive(struct uart_dev_s *dev, uint32_t *status)
|
||||
{
|
||||
int ret;
|
||||
|
||||
if (status != NULL)
|
||||
{
|
||||
*status = 0;
|
||||
}
|
||||
|
||||
ret = uart_rxtx_read();
|
||||
|
||||
uart_ev_pending_write(UART_EV_RX);
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: misoc_rxint
|
||||
*
|
||||
* Description:
|
||||
* Call to enable or disable RX interrupts
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static void misoc_rxint(struct uart_dev_s *dev, bool enable)
|
||||
{
|
||||
uint8_t im;
|
||||
|
||||
im = uart_ev_enable_read();
|
||||
if (enable)
|
||||
{
|
||||
im |= UART_EV_RX;
|
||||
}
|
||||
else
|
||||
{
|
||||
im &= ~UART_EV_RX;
|
||||
}
|
||||
|
||||
uart_ev_enable_write(im);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: misoc_rxavailable
|
||||
*
|
||||
* Description:
|
||||
* Return true if the receive register is not empty
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static bool misoc_rxavailable(struct uart_dev_s *dev)
|
||||
{
|
||||
return !uart_rxempty_read();
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: misoc_send
|
||||
*
|
||||
* Description:
|
||||
* This method will send one byte on the UART.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static void misoc_send(struct uart_dev_s *dev, int ch)
|
||||
{
|
||||
uart_rxtx_write(ch);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: misoc_txint
|
||||
*
|
||||
* Description:
|
||||
* Call to enable or disable TX interrupts
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static void misoc_txint(struct uart_dev_s *dev, bool enable)
|
||||
{
|
||||
uint8_t im;
|
||||
int i;
|
||||
|
||||
im = uart_ev_enable_read();
|
||||
if (enable)
|
||||
{
|
||||
im |= UART_EV_TX;
|
||||
uart_ev_enable_write(im);
|
||||
|
||||
/* Fake an uart INT */
|
||||
|
||||
uart_xmitchars(dev);
|
||||
}
|
||||
else
|
||||
{
|
||||
im &= ~UART_EV_TX;
|
||||
uart_ev_enable_write(im);
|
||||
}
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: misoc_txready
|
||||
*
|
||||
* Description:
|
||||
* Return true if the tranmsit data register is empty
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static bool misoc_txready(struct uart_dev_s *dev)
|
||||
{
|
||||
return !uart_txfull_read();
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: misoc_txempty
|
||||
*
|
||||
* Description:
|
||||
* Return true if the tranmsit data register is empty
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static bool misoc_txempty(struct uart_dev_s *dev)
|
||||
{
|
||||
return !uart_txfull_read();
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: misoc_earlyserialinit
|
||||
*
|
||||
* Description:
|
||||
* Performs the low level UART initialization early in debug so that the
|
||||
* serial console will be available during bootup. This must be called
|
||||
* before misoc_serial_initialize.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void misoc_earlyserialinit(void)
|
||||
{
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: misoc_putc
|
||||
*
|
||||
* Description:
|
||||
* Provide priority, low-level access to support OS debug writes
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
int up_putc(int ch)
|
||||
{
|
||||
#ifdef HAVE_SERIAL_CONSOLE
|
||||
struct uart_dev_s *dev = (struct uart_dev_s *)&CONSOLE_DEV;
|
||||
uint8_t imr;
|
||||
|
||||
misoc_disableuartint(dev, &imr);
|
||||
|
||||
/* Check for LF */
|
||||
|
||||
if (ch == '\n')
|
||||
{
|
||||
/* Add CR */
|
||||
|
||||
misoc_lowputc('\r');
|
||||
}
|
||||
|
||||
misoc_lowputc(ch);
|
||||
misoc_restoreuartint(dev, imr);
|
||||
#endif
|
||||
return ch;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: misoc_earlyserialinit, misoc_serial_initialize, and misoc_putc
|
||||
*
|
||||
* Description:
|
||||
* stubs that may be needed. These stubs would be used if all UARTs are
|
||||
* disabled. In that case, the logic in common/misoc_initialize() is not
|
||||
* smart enough to know that there are not UARTs and will still expect
|
||||
* these interfaces to be provided.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#else /* HAVE_UART_DEVICE */
|
||||
void misoc_earlyserialinit(void)
|
||||
{
|
||||
}
|
||||
|
||||
void misoc_serial_initialize(void)
|
||||
{
|
||||
}
|
||||
|
||||
int up_putc(int ch)
|
||||
{
|
||||
return ch;
|
||||
}
|
||||
|
||||
#endif /* HAVE_UART_DEVICE */
|
||||
#else /* USE_SERIALDRIVER */
|
||||
|
||||
/****************************************************************************
|
||||
* Name: misoc_putc
|
||||
*
|
||||
* Description:
|
||||
* Provide priority, low-level access to support OS debug writes
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
int up_putc(int ch)
|
||||
{
|
||||
#ifdef HAVE_SERIAL_CONSOLE
|
||||
/* Check for LF */
|
||||
|
||||
if (ch == '\n')
|
||||
{
|
||||
/* Add CR */
|
||||
|
||||
misoc_lowputc('\r');
|
||||
}
|
||||
|
||||
misoc_lowputc(ch);
|
||||
#endif
|
||||
|
||||
return ch;
|
||||
}
|
||||
|
||||
#endif /* USE_SERIALDRIVER */
|
||||
|
||||
void misoc_lowputc(char ch)
|
||||
{
|
||||
while (uart_txfull_read());
|
||||
uart_rxtx_write(ch);
|
||||
uart_ev_pending_write(UART_EV_TX);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: misoc_serial_initialize
|
||||
*
|
||||
* Description:
|
||||
* Register serial console and serial ports. This assumes
|
||||
* that misoc_earlyserialinit was called previously.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void misoc_serial_initialize(void)
|
||||
{
|
||||
#ifdef USE_SERIALDRIVER
|
||||
/* Register the console */
|
||||
|
||||
#ifdef HAVE_SERIAL_CONSOLE
|
||||
(void)uart_register("/dev/console", &CONSOLE_DEV);
|
||||
#endif
|
||||
|
||||
/* Register all UARTs */
|
||||
(void)uart_register("/dev/ttyS0", &TTYS0_DEV);
|
||||
#endif
|
||||
}
|
@ -37,7 +37,7 @@
|
||||
HEAD_ASRC = lm32_vectors.S
|
||||
|
||||
CMN_ASRCS =
|
||||
CMN_CSRCS = misoc_uart.c
|
||||
CMN_CSRCS = misoc_serial.c misoc_mdelay.c
|
||||
|
||||
CHIP_ASRCS = lm32_syscall.S
|
||||
|
||||
|
@ -87,8 +87,8 @@ endif
|
||||
# Generic GNU toolchain on OS X, Linux or any typical Posix system
|
||||
|
||||
ifeq ($(CONFIG_LM32_TOOLCHAIN),GNUL)
|
||||
CROSSDEV ?= lm32-elf--
|
||||
ARCROSSDEV ?= lm32-elf--
|
||||
CROSSDEV ?= lm32-elf-
|
||||
ARCROSSDEV ?= lm32-elf-
|
||||
MAXOPTIMIZATION ?= -Os
|
||||
endif
|
||||
|
||||
|
@ -34,8 +34,8 @@
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifndef __ARCH_MISOC_SRC_COMMON_LM32_H
|
||||
#define __ARCH_MISOC_SRC_COMMON_LM32_H
|
||||
#ifndef __ARCH_MISOC_SRC_LM32_LM32_H
|
||||
#define __ARCH_MISOC_SRC_LM32_LM32_H
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
@ -141,13 +141,17 @@ void lm32_copystate(uint32_t *dest, uint32_t *src);
|
||||
|
||||
void lm32_irq_initialize(void);
|
||||
|
||||
/* System timer *************************************************************/
|
||||
/* Interrupt decode *********************************************************/
|
||||
|
||||
void lm32_timer_initialize(void);
|
||||
uint32_t *lm32_decodeirq(uint32_t intstat, uint32_t *regs);
|
||||
|
||||
/* Software interrupts ******************************************************/
|
||||
|
||||
uint32_t *lm32_swint(int irq, FAR void *context);
|
||||
int lm32_swint(int irq, FAR void *context);
|
||||
|
||||
/* System timer *************************************************************/
|
||||
|
||||
void lm32_timer_initialize(void);
|
||||
|
||||
/* Signal handling **********************************************************/
|
||||
|
||||
@ -163,10 +167,5 @@ void modifyreg32(unsigned int addr, uint32_t clearbits, uint32_t setbits);
|
||||
|
||||
void lm32_dumpstate(void);
|
||||
|
||||
#undef EXTERN
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
#endif /* __ASSEMBLY__ */
|
||||
|
||||
#endif /* __ARCH_MISOC_SRC_COMMON_LM32_H */
|
||||
#endif /* __ARCH_MISOC_SRC_LM32_LM32_H */
|
||||
|
97
arch/misoc/src/lm32/lm32_config.h
Normal file
97
arch/misoc/src/lm32/lm32_config.h
Normal file
@ -0,0 +1,97 @@
|
||||
/************************************************************************************
|
||||
* arch/misoc/src/lm32/lm32_config.h
|
||||
*
|
||||
* Copyright (C) 2015 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Modified for LM32:
|
||||
*
|
||||
* Copyright (C) 2016 Ramin Amin. All rights reserved.
|
||||
* Author: Ramtin Amin <keytwo@gmail.com>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name NuttX nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifndef __ARCH_MISOC_SRC_LM32_LM32_CONFIG_H
|
||||
#define __ARCH_MISOC_SRC_LM32_LM32_CONFIG_H
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <arch/chip/chip.h>
|
||||
#include <arch/board/board.h>
|
||||
|
||||
/************************************************************************************
|
||||
* Pre-processor Definitions
|
||||
************************************************************************************/
|
||||
/* UARTs ****************************************************************************/
|
||||
|
||||
/* Are any UARTs enabled? */
|
||||
|
||||
#undef HAVE_UART_DEVICE
|
||||
#if defined(CONFIG_MISOC_UART1) || defined(CONFIG_MISOC_UART2)
|
||||
# define HAVE_UART_DEVICE 1
|
||||
#endif
|
||||
|
||||
/* Is there a serial console? There should be no more than one defined. It
|
||||
* could be on any UARTn, n=1,.. CHIP_NUARTS
|
||||
*/
|
||||
|
||||
#if defined(CONFIG_UART1_SERIAL_CONSOLE) && defined(CONFIG_MISOC_UART1)
|
||||
# undef CONFIG_UART2_SERIAL_CONSOLE
|
||||
# define HAVE_SERIAL_CONSOLE 1
|
||||
#elif defined(CONFIG_UART2_SERIAL_CONSOLE) && defined(CONFIG_MISOC_UART2)
|
||||
# undef CONFIG_UART1_SERIAL_CONSOLE
|
||||
# define HAVE_SERIAL_CONSOLE 1
|
||||
#else
|
||||
# undef CONFIG_UART1_SERIAL_CONSOLE
|
||||
# undef CONFIG_UART2_SERIAL_CONSOLE
|
||||
# undef HAVE_SERIAL_CONSOLE
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Public Types
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Public Data
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Inline Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Public Functions
|
||||
************************************************************************************/
|
||||
|
||||
#endif /* __ARCH_MISOC_SRC_LM32_LM32_CONFIG_H */
|
@ -61,18 +61,10 @@
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
uint32_t *lm32_decodeirq(uint32_t *regs)
|
||||
uint32_t *lm32_decodeirq(uint32_t intstat, uint32_t *regs)
|
||||
{
|
||||
uint32_t intstat;
|
||||
int irq;
|
||||
|
||||
/* Read the pending interrupts */
|
||||
/* REVISIT: How do I get the interupt status */
|
||||
#warning Missing logic
|
||||
intstat = 0;
|
||||
|
||||
/* REVIST: Do I need to mask the interrupt status with the IM? */
|
||||
|
||||
irqinfo("intstat=%08lx\n", (unsigned long)intstat);
|
||||
|
||||
/* Decode and dispatch interrupts */
|
||||
|
@ -42,10 +42,13 @@
|
||||
|
||||
#include <stdint.h>
|
||||
#include <assert.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/irq.h>
|
||||
#include <nuttx/arch.h>
|
||||
#include <nuttx/board.h>
|
||||
|
||||
#include <arch/irq.h>
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include "group/group.h"
|
||||
|
@ -57,6 +57,7 @@
|
||||
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include "misoc.h"
|
||||
#include "lm32.h"
|
||||
|
||||
/****************************************************************************
|
||||
@ -71,7 +72,7 @@ void up_initialize(void)
|
||||
|
||||
/* Initialize the serial driver */
|
||||
|
||||
#warning REVISIT: Here you should all lm32_serial_initialize(). That initializes the entire serial driver, a part of the operation is the uart initialization.
|
||||
#warning REVISIT: Here you should all misoc_serial_initialize(). That initializes the entire serial driver, a part of the operation is the uart initialization.
|
||||
|
||||
uart_init();
|
||||
misoc_serial_initialize();
|
||||
}
|
||||
|
@ -130,7 +130,7 @@ static void dispatch_syscall(void)
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
uint32_t *lm32_swint(int irq, FAR void *context)
|
||||
int lm32_swint(int irq, FAR void *context)
|
||||
{
|
||||
uint32_t *regs = (uint32_t *)context;
|
||||
|
||||
@ -313,19 +313,5 @@ uint32_t *lm32_swint(int irq, FAR void *context)
|
||||
}
|
||||
#endif
|
||||
|
||||
/* If a context switch occurred while processing the interrupt then
|
||||
* g_current_regs may have change value. If we return any value different
|
||||
* from the input regs, then the lower level will know that a context
|
||||
* switch occurred during interrupt processing.
|
||||
*/
|
||||
|
||||
regs = (uint32_t *)g_current_regs;
|
||||
|
||||
/* Set g_current_regs to NULL to indicate that we are no longer in an
|
||||
* interrupt handler.
|
||||
*/
|
||||
|
||||
g_current_regs = NULL;
|
||||
|
||||
return regs;
|
||||
return OK;
|
||||
}
|
||||
|
@ -143,101 +143,103 @@ _do_reset:
|
||||
|
||||
.clearBSS:
|
||||
be r1, r3, .callMain
|
||||
sw (r1+0), r0
|
||||
addi r1, r1, 4
|
||||
sw (r1+0), r0
|
||||
addi r1, r1, 4
|
||||
bi .clearBSS
|
||||
|
||||
.callMain:
|
||||
bi os_start
|
||||
|
||||
.save_all:
|
||||
addi sp, sp, -136
|
||||
sw (sp+REG_X0), r0
|
||||
sw (sp+REG_X1), r1
|
||||
sw (sp+REG_X2), r2
|
||||
sw (sp+REG_X3), r3
|
||||
sw (sp+REG_X4), r4
|
||||
sw (sp+REG_X5), r5
|
||||
sw (sp+REG_X6), r6
|
||||
sw (sp+REG_X7), r7
|
||||
sw (sp+REG_X8), r8
|
||||
sw (sp+REG_X9), r9
|
||||
sw (sp+REG_X10), r10
|
||||
sw (sp+REG_X11), r11
|
||||
sw (sp+REG_X12), r12
|
||||
sw (sp+REG_X13), r13
|
||||
sw (sp+REG_X14), r14
|
||||
sw (sp+REG_X15), r15
|
||||
sw (sp+REG_X16), r16
|
||||
sw (sp+REG_X17), r17
|
||||
sw (sp+REG_X18), r18
|
||||
sw (sp+REG_X19), r19
|
||||
sw (sp+REG_X20), r20
|
||||
sw (sp+REG_X21), r21
|
||||
sw (sp+REG_X22), r22
|
||||
sw (sp+REG_X23), r23
|
||||
sw (sp+REG_X24), r24
|
||||
sw (sp+REG_X25), r25
|
||||
addi sp, sp, -136
|
||||
sw (sp+REG_X0), r0
|
||||
sw (sp+REG_X1), r1
|
||||
sw (sp+REG_X2), r2
|
||||
sw (sp+REG_X3), r3
|
||||
sw (sp+REG_X4), r4
|
||||
sw (sp+REG_X5), r5
|
||||
sw (sp+REG_X6), r6
|
||||
sw (sp+REG_X7), r7
|
||||
sw (sp+REG_X8), r8
|
||||
sw (sp+REG_X9), r9
|
||||
sw (sp+REG_X10), r10
|
||||
sw (sp+REG_X11), r11
|
||||
sw (sp+REG_X12), r12
|
||||
sw (sp+REG_X13), r13
|
||||
sw (sp+REG_X14), r14
|
||||
sw (sp+REG_X15), r15
|
||||
sw (sp+REG_X16), r16
|
||||
sw (sp+REG_X17), r17
|
||||
sw (sp+REG_X18), r18
|
||||
sw (sp+REG_X19), r19
|
||||
sw (sp+REG_X20), r20
|
||||
sw (sp+REG_X21), r21
|
||||
sw (sp+REG_X22), r22
|
||||
sw (sp+REG_X23), r23
|
||||
sw (sp+REG_X24), r24
|
||||
sw (sp+REG_X25), r25
|
||||
|
||||
sw (sp+REG_GP), r26
|
||||
sw (sp+REG_FP), r27
|
||||
sw (sp+REG_SP), r28
|
||||
sw (sp+REG_GP), r26
|
||||
sw (sp+REG_FP), r27
|
||||
sw (sp+REG_SP), r28
|
||||
|
||||
/* reg RA done later */
|
||||
|
||||
sw (sp+REG_EA), r30
|
||||
sw (sp+REG_BA), r31
|
||||
sw (sp+REG_EA), r30
|
||||
sw (sp+REG_BA), r31
|
||||
|
||||
/* ra needs to be moved from initial stack location */
|
||||
|
||||
lw r1, (sp+ 136)
|
||||
sw (sp+REG_RA), r1
|
||||
w r1, (sp+ 136)
|
||||
sw (sp+REG_RA), r1
|
||||
|
||||
/* Get IE/REG_INT_CTX */
|
||||
|
||||
/* get IE/REG_INT_CTX */
|
||||
rcsr r1, IE
|
||||
sw (sp+REG_INT_CTX), r1
|
||||
sw (sp+REG_INT_CTX), r1
|
||||
|
||||
/* the 2nd argument is the regs pointer */
|
||||
addi r2, sp, 0
|
||||
/* The 2nd argument is the regs pointer */
|
||||
|
||||
addi r2, sp, 0
|
||||
ret
|
||||
|
||||
.restore_all_and_eret:
|
||||
/* r1 should have the place where we restore ! */
|
||||
|
||||
lw r2, (r1+REG_X2)
|
||||
lw r3, (r1+REG_X3)
|
||||
lw r4, (r1+REG_X4)
|
||||
lw r5, (r1+REG_X5)
|
||||
lw r6, (r1+REG_X6)
|
||||
lw r7, (r1+REG_X7)
|
||||
lw r8, (r1+REG_X8)
|
||||
lw r9, (r1+REG_X9)
|
||||
lw r10, (r1+REG_X10)
|
||||
lw r11, (r1+REG_X11)
|
||||
lw r12, (r1+REG_X12)
|
||||
lw r13, (r1+REG_X13)
|
||||
lw r14, (r1+REG_X14)
|
||||
lw r15, (r1+REG_X15)
|
||||
lw r16, (r1+REG_X16)
|
||||
lw r17, (r1+REG_X17)
|
||||
lw r18, (r1+REG_X18)
|
||||
lw r19, (r1+REG_X19)
|
||||
lw r20, (r1+REG_X20)
|
||||
lw r21, (r1+REG_X21)
|
||||
lw r22, (r1+REG_X22)
|
||||
lw r23, (r1+REG_X23)
|
||||
lw r24, (r1+REG_X24)
|
||||
lw r25, (r1+REG_X25)
|
||||
lw r26, (r1+REG_GP)
|
||||
lw r27, (r1+REG_FP)
|
||||
lw r28, (r1+REG_SP)
|
||||
lw r29, (r1+REG_RA)
|
||||
lw r30, (r1+REG_EA)
|
||||
lw r31, (r1+REG_BA)
|
||||
lw r1, (r1+REG_INT_CTX)
|
||||
w r2, (r1+REG_X2)
|
||||
w r3, (r1+REG_X3)
|
||||
w r4, (r1+REG_X4)
|
||||
w r5, (r1+REG_X5)
|
||||
w r6, (r1+REG_X6)
|
||||
w r7, (r1+REG_X7)
|
||||
w r8, (r1+REG_X8)
|
||||
w r9, (r1+REG_X9)
|
||||
w r10, (r1+REG_X10)
|
||||
w r11, (r1+REG_X11)
|
||||
w r12, (r1+REG_X12)
|
||||
w r13, (r1+REG_X13)
|
||||
w r14, (r1+REG_X14)
|
||||
w r15, (r1+REG_X15)
|
||||
w r16, (r1+REG_X16)
|
||||
w r17, (r1+REG_X17)
|
||||
w r18, (r1+REG_X18)
|
||||
w r19, (r1+REG_X19)
|
||||
w r20, (r1+REG_X20)
|
||||
w r21, (r1+REG_X21)
|
||||
w r22, (r1+REG_X22)
|
||||
w r23, (r1+REG_X23)
|
||||
w r24, (r1+REG_X24)
|
||||
w r25, (r1+REG_X25)
|
||||
w r26, (r1+REG_GP)
|
||||
w r27, (r1+REG_FP)
|
||||
w r28, (r1+REG_SP)
|
||||
w r29, (r1+REG_RA)
|
||||
w r30, (r1+REG_EA)
|
||||
w r31, (r1+REG_BA)
|
||||
lw r1, (r1+REG_INT_CTX)
|
||||
wcsr IE, r1
|
||||
lw r1, (r1+REG_X1)
|
||||
addi sp, sp, 136
|
||||
w r1, (r1+REG_X1)
|
||||
addi sp, sp, 136
|
||||
eret
|
||||
|
||||
/* This global variable is unsigned long g_idle_topstack and is
|
||||
|
@ -1,397 +1,250 @@
|
||||
/****************************************************************************
|
||||
* configs/misoc/include/generated/csr.h
|
||||
*
|
||||
* Copyright (C) 2016 Gregory Nutt. All rights reserved.
|
||||
* Author: Ramtin Amin <keytwo@gmail.com>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name NuttX nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifndef __CONFIGS_MISOC_INCLUDE_GENERATED_CSR_H
|
||||
#define __CONFIGS_MISOC_INCLUDE_GENERATED_CSR_H
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include "hw/common.h"
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/* SDRAM */
|
||||
#ifndef __GENERATED_CSR_H
|
||||
#define __GENERATED_CSR_H
|
||||
#include <hw/common.h>
|
||||
|
||||
/* sdram */
|
||||
#define CSR_SDRAM_BASE 0xe0004000
|
||||
#define CSR_SDRAM_DFII_CONTROL_ADDR 0xe0004000
|
||||
#define CSR_SDRAM_DFII_CONTROL_SIZE 1
|
||||
|
||||
static inline unsigned char sdram_dfii_control_read(void) {
|
||||
unsigned char r = MMPTR(0xe0004000);
|
||||
return r;
|
||||
}
|
||||
static inline void sdram_dfii_control_write(unsigned char value) {
|
||||
MMPTR(0xe0004000) = value;
|
||||
}
|
||||
#define CSR_SDRAM_DFII_PI0_COMMAND_ADDR 0xe0004004
|
||||
#define CSR_SDRAM_DFII_PI0_COMMAND_SIZE 1
|
||||
|
||||
static inline unsigned char sdram_dfii_pi0_command_read(void) {
|
||||
unsigned char r = MMPTR(0xe0004004);
|
||||
return r;
|
||||
}
|
||||
static inline void sdram_dfii_pi0_command_write(unsigned char value) {
|
||||
MMPTR(0xe0004004) = value;
|
||||
}
|
||||
#define CSR_SDRAM_DFII_PI0_COMMAND_ISSUE_ADDR 0xe0004008
|
||||
#define CSR_SDRAM_DFII_PI0_COMMAND_ISSUE_SIZE 1
|
||||
|
||||
static inline unsigned char sdram_dfii_pi0_command_issue_read(void) {
|
||||
unsigned char r = MMPTR(0xe0004008);
|
||||
return r;
|
||||
}
|
||||
static inline void sdram_dfii_pi0_command_issue_write(unsigned char value) {
|
||||
MMPTR(0xe0004008) = value;
|
||||
}
|
||||
#define CSR_SDRAM_DFII_PI0_ADDRESS_ADDR 0xe000400c
|
||||
#define CSR_SDRAM_DFII_PI0_ADDRESS_SIZE 2
|
||||
|
||||
static inline unsigned short int sdram_dfii_pi0_address_read(void) {
|
||||
unsigned short int r = MMPTR(0xe000400c);
|
||||
r <<= 8;
|
||||
r |= MMPTR(0xe0004010);
|
||||
return r;
|
||||
}
|
||||
static inline void sdram_dfii_pi0_address_write(unsigned short int value) {
|
||||
MMPTR(0xe000400c) = value >> 8;
|
||||
MMPTR(0xe0004010) = value;
|
||||
}
|
||||
#define CSR_SDRAM_DFII_PI0_BADDRESS_ADDR 0xe0004014
|
||||
#define CSR_SDRAM_DFII_PI0_BADDRESS_SIZE 1
|
||||
|
||||
static inline unsigned char sdram_dfii_pi0_baddress_read(void) {
|
||||
unsigned char r = MMPTR(0xe0004014);
|
||||
return r;
|
||||
}
|
||||
static inline void sdram_dfii_pi0_baddress_write(unsigned char value) {
|
||||
MMPTR(0xe0004014) = value;
|
||||
}
|
||||
#define CSR_SDRAM_DFII_PI0_WRDATA_ADDR 0xe0004018
|
||||
#define CSR_SDRAM_DFII_PI0_WRDATA_SIZE 2
|
||||
|
||||
static inline unsigned short int sdram_dfii_pi0_wrdata_read(void) {
|
||||
unsigned short int r = MMPTR(0xe0004018);
|
||||
r <<= 8;
|
||||
r |= MMPTR(0xe000401c);
|
||||
return r;
|
||||
}
|
||||
static inline void sdram_dfii_pi0_wrdata_write(unsigned short int value) {
|
||||
MMPTR(0xe0004018) = value >> 8;
|
||||
MMPTR(0xe000401c) = value;
|
||||
}
|
||||
#define CSR_SDRAM_DFII_PI0_RDDATA_ADDR 0xe0004020
|
||||
#define CSR_SDRAM_DFII_PI0_RDDATA_SIZE 2
|
||||
static inline unsigned short int sdram_dfii_pi0_rddata_read(void) {
|
||||
unsigned short int r = MMPTR(0xe0004020);
|
||||
r <<= 8;
|
||||
r |= MMPTR(0xe0004024);
|
||||
return r;
|
||||
}
|
||||
|
||||
/* timer0 */
|
||||
#define CSR_TIMER0_BASE 0xe0002000
|
||||
#define CSR_TIMER0_LOAD_ADDR 0xe0002000
|
||||
#define CSR_TIMER0_LOAD_SIZE 4
|
||||
|
||||
static inline unsigned int timer0_load_read(void) {
|
||||
unsigned int r = MMPTR(0xe0002000);
|
||||
r <<= 8;
|
||||
r |= MMPTR(0xe0002004);
|
||||
r <<= 8;
|
||||
r |= MMPTR(0xe0002008);
|
||||
r <<= 8;
|
||||
r |= MMPTR(0xe000200c);
|
||||
return r;
|
||||
}
|
||||
static inline void timer0_load_write(unsigned int value) {
|
||||
MMPTR(0xe0002000) = value >> 24;
|
||||
MMPTR(0xe0002004) = value >> 16;
|
||||
MMPTR(0xe0002008) = value >> 8;
|
||||
MMPTR(0xe000200c) = value;
|
||||
}
|
||||
#define CSR_TIMER0_RELOAD_ADDR 0xe0002010
|
||||
#define CSR_TIMER0_RELOAD_SIZE 4
|
||||
|
||||
static inline unsigned int timer0_reload_read(void) {
|
||||
unsigned int r = MMPTR(0xe0002010);
|
||||
r <<= 8;
|
||||
r |= MMPTR(0xe0002014);
|
||||
r <<= 8;
|
||||
r |= MMPTR(0xe0002018);
|
||||
r <<= 8;
|
||||
r |= MMPTR(0xe000201c);
|
||||
return r;
|
||||
}
|
||||
static inline void timer0_reload_write(unsigned int value) {
|
||||
MMPTR(0xe0002010) = value >> 24;
|
||||
MMPTR(0xe0002014) = value >> 16;
|
||||
MMPTR(0xe0002018) = value >> 8;
|
||||
MMPTR(0xe000201c) = value;
|
||||
}
|
||||
#define CSR_TIMER0_EN_ADDR 0xe0002020
|
||||
#define CSR_TIMER0_EN_SIZE 1
|
||||
|
||||
static inline unsigned char timer0_en_read(void) {
|
||||
unsigned char r = MMPTR(0xe0002020);
|
||||
return r;
|
||||
}
|
||||
static inline void timer0_en_write(unsigned char value) {
|
||||
MMPTR(0xe0002020) = value;
|
||||
}
|
||||
#define CSR_TIMER0_UPDATE_VALUE_ADDR 0xe0002024
|
||||
#define CSR_TIMER0_UPDATE_VALUE_SIZE 1
|
||||
|
||||
static inline unsigned char timer0_update_value_read(void) {
|
||||
unsigned char r = MMPTR(0xe0002024);
|
||||
return r;
|
||||
}
|
||||
static inline void timer0_update_value_write(unsigned char value) {
|
||||
MMPTR(0xe0002024) = value;
|
||||
}
|
||||
#define CSR_TIMER0_VALUE_ADDR 0xe0002028
|
||||
#define CSR_TIMER0_VALUE_SIZE 4
|
||||
|
||||
static inline unsigned int timer0_value_read(void) {
|
||||
unsigned int r = MMPTR(0xe0002028);
|
||||
r <<= 8;
|
||||
r |= MMPTR(0xe000202c);
|
||||
r <<= 8;
|
||||
r |= MMPTR(0xe0002030);
|
||||
r <<= 8;
|
||||
r |= MMPTR(0xe0002034);
|
||||
return r;
|
||||
}
|
||||
#define CSR_TIMER0_EV_STATUS_ADDR 0xe0002038
|
||||
#define CSR_TIMER0_EV_STATUS_SIZE 1
|
||||
|
||||
static inline unsigned char timer0_ev_status_read(void) {
|
||||
unsigned char r = MMPTR(0xe0002038);
|
||||
return r;
|
||||
}
|
||||
static inline void timer0_ev_status_write(unsigned char value) {
|
||||
MMPTR(0xe0002038) = value;
|
||||
}
|
||||
#define CSR_TIMER0_EV_PENDING_ADDR 0xe000203c
|
||||
#define CSR_TIMER0_EV_PENDING_SIZE 1
|
||||
|
||||
static inline unsigned char timer0_ev_pending_read(void) {
|
||||
unsigned char r = MMPTR(0xe000203c);
|
||||
return r;
|
||||
}
|
||||
static inline void timer0_ev_pending_write(unsigned char value) {
|
||||
MMPTR(0xe000203c) = value;
|
||||
}
|
||||
#define CSR_TIMER0_EV_ENABLE_ADDR 0xe0002040
|
||||
#define CSR_TIMER0_EV_ENABLE_SIZE 1
|
||||
static inline unsigned char timer0_ev_enable_read(void) {
|
||||
unsigned char r = MMPTR(0xe0002040);
|
||||
return r;
|
||||
}
|
||||
static inline void timer0_ev_enable_write(unsigned char value) {
|
||||
MMPTR(0xe0002040) = value;
|
||||
}
|
||||
|
||||
/* uart */
|
||||
#define CSR_UART_BASE 0xe0001000
|
||||
#define CSR_UART_RXTX_ADDR 0xe0001000
|
||||
#define CSR_UART_RXTX_SIZE 1
|
||||
static inline unsigned char uart_rxtx_read(void) {
|
||||
unsigned char r = MMPTR(0xe0001000);
|
||||
return r;
|
||||
}
|
||||
static inline void uart_rxtx_write(unsigned char value) {
|
||||
MMPTR(0xe0001000) = value;
|
||||
}
|
||||
#define CSR_UART_TXFULL_ADDR 0xe0001004
|
||||
#define CSR_UART_TXFULL_SIZE 1
|
||||
|
||||
static inline unsigned char uart_txfull_read(void) {
|
||||
unsigned char r = MMPTR(0xe0001004);
|
||||
return r;
|
||||
}
|
||||
#define CSR_UART_RXEMPTY_ADDR 0xe0001008
|
||||
#define CSR_UART_RXEMPTY_SIZE 1
|
||||
|
||||
static inline unsigned char uart_rxempty_read(void) {
|
||||
unsigned char r = MMPTR(0xe0001008);
|
||||
return r;
|
||||
}
|
||||
#define CSR_UART_EV_STATUS_ADDR 0xe000100c
|
||||
#define CSR_UART_EV_STATUS_SIZE 1
|
||||
|
||||
static inline unsigned char uart_ev_status_read(void) {
|
||||
unsigned char r = MMPTR(0xe000100c);
|
||||
return r;
|
||||
}
|
||||
static inline void uart_ev_status_write(unsigned char value) {
|
||||
MMPTR(0xe000100c) = value;
|
||||
}
|
||||
#define CSR_UART_EV_PENDING_ADDR 0xe0001010
|
||||
#define CSR_UART_EV_PENDING_SIZE 1
|
||||
|
||||
static inline unsigned char uart_ev_pending_read(void) {
|
||||
unsigned char r = MMPTR(0xe0001010);
|
||||
return r;
|
||||
}
|
||||
static inline void uart_ev_pending_write(unsigned char value) {
|
||||
MMPTR(0xe0001010) = value;
|
||||
}
|
||||
#define CSR_UART_EV_ENABLE_ADDR 0xe0001014
|
||||
#define CSR_UART_EV_ENABLE_SIZE 1
|
||||
static inline unsigned char uart_ev_enable_read(void) {
|
||||
unsigned char r = MMPTR(0xe0001014);
|
||||
return r;
|
||||
}
|
||||
static inline void uart_ev_enable_write(unsigned char value) {
|
||||
MMPTR(0xe0001014) = value;
|
||||
}
|
||||
|
||||
/* uart_phy */
|
||||
#define CSR_UART_PHY_BASE 0xe0000800
|
||||
#define CSR_UART_PHY_TUNING_WORD_ADDR 0xe0000800
|
||||
#define CSR_UART_PHY_TUNING_WORD_SIZE 4
|
||||
static inline unsigned int uart_phy_tuning_word_read(void) {
|
||||
unsigned int r = MMPTR(0xe0000800);
|
||||
r <<= 8;
|
||||
r |= MMPTR(0xe0000804);
|
||||
r <<= 8;
|
||||
r |= MMPTR(0xe0000808);
|
||||
r <<= 8;
|
||||
r |= MMPTR(0xe000080c);
|
||||
return r;
|
||||
}
|
||||
static inline void uart_phy_tuning_word_write(unsigned int value) {
|
||||
MMPTR(0xe0000800) = value >> 24;
|
||||
MMPTR(0xe0000804) = value >> 16;
|
||||
MMPTR(0xe0000808) = value >> 8;
|
||||
MMPTR(0xe000080c) = value;
|
||||
}
|
||||
|
||||
/* Constants */
|
||||
|
||||
/* constants */
|
||||
#define UART_INTERRUPT 0
|
||||
#define TIMER0_INTERRUPT 1
|
||||
#define SYSTEM_CLOCK_FREQUENCY 80000000
|
||||
#define L2_SIZE 8192
|
||||
|
||||
/****************************************************************************
|
||||
* Inline Functions
|
||||
****************************************************************************/
|
||||
|
||||
static inline unsigned char sdram_dfii_control_read(void)
|
||||
{
|
||||
unsigned char r = MMPTR(0xe0004000);
|
||||
return r;
|
||||
}
|
||||
|
||||
static inline void sdram_dfii_control_write(unsigned char value)
|
||||
{
|
||||
MMPTR(0xe0004000) = value;
|
||||
}
|
||||
|
||||
static inline unsigned char sdram_dfii_pi0_command_read(void)
|
||||
{
|
||||
unsigned char r = MMPTR(0xe0004004);
|
||||
return r;
|
||||
}
|
||||
|
||||
static inline void sdram_dfii_pi0_command_write(unsigned char value)
|
||||
{
|
||||
MMPTR(0xe0004004) = value;
|
||||
}
|
||||
|
||||
static inline unsigned char sdram_dfii_pi0_command_issue_read(void)
|
||||
{
|
||||
unsigned char r = MMPTR(0xe0004008);
|
||||
return r;
|
||||
}
|
||||
|
||||
static inline void sdram_dfii_pi0_command_issue_write(unsigned char value)
|
||||
{
|
||||
MMPTR(0xe0004008) = value;
|
||||
}
|
||||
|
||||
static inline unsigned short int sdram_dfii_pi0_address_read(void)
|
||||
{
|
||||
unsigned short int r = MMPTR(0xe000400c);
|
||||
r <<= 8;
|
||||
r |= MMPTR(0xe0004010);
|
||||
return r;
|
||||
}
|
||||
|
||||
static inline void sdram_dfii_pi0_address_write(unsigned short int value)
|
||||
{
|
||||
MMPTR(0xe000400c) = value >> 8;
|
||||
MMPTR(0xe0004010) = value;
|
||||
}
|
||||
|
||||
static inline unsigned char sdram_dfii_pi0_baddress_read(void)
|
||||
{
|
||||
unsigned char r = MMPTR(0xe0004014);
|
||||
return r;
|
||||
}
|
||||
|
||||
static inline void sdram_dfii_pi0_baddress_write(unsigned char value)
|
||||
{
|
||||
MMPTR(0xe0004014) = value;
|
||||
}
|
||||
|
||||
static inline unsigned short int sdram_dfii_pi0_wrdata_read(void)
|
||||
{
|
||||
unsigned short int r = MMPTR(0xe0004018);
|
||||
r <<= 8;
|
||||
r |= MMPTR(0xe000401c);
|
||||
return r;
|
||||
}
|
||||
|
||||
static inline void sdram_dfii_pi0_wrdata_write(unsigned short int value)
|
||||
{
|
||||
MMPTR(0xe0004018) = value >> 8;
|
||||
MMPTR(0xe000401c) = value;
|
||||
}
|
||||
|
||||
static inline unsigned short int sdram_dfii_pi0_rddata_read(void)
|
||||
{
|
||||
unsigned short int r = MMPTR(0xe0004020);
|
||||
r <<= 8;
|
||||
r |= MMPTR(0xe0004024);
|
||||
return r;
|
||||
}
|
||||
|
||||
/* Timer0 */
|
||||
|
||||
static inline unsigned int timer0_load_read(void)
|
||||
{
|
||||
unsigned int r = MMPTR(0xe0002000);
|
||||
r <<= 8;
|
||||
r |= MMPTR(0xe0002004);
|
||||
r <<= 8;
|
||||
r |= MMPTR(0xe0002008);
|
||||
r <<= 8;
|
||||
r |= MMPTR(0xe000200c);
|
||||
return r;
|
||||
}
|
||||
|
||||
static inline void timer0_load_write(unsigned int value)
|
||||
{
|
||||
MMPTR(0xe0002000) = value >> 24;
|
||||
MMPTR(0xe0002004) = value >> 16;
|
||||
MMPTR(0xe0002008) = value >> 8;
|
||||
MMPTR(0xe000200c) = value;
|
||||
}
|
||||
|
||||
static inline unsigned int timer0_reload_read(void)
|
||||
{
|
||||
unsigned int r = MMPTR(0xe0002010);
|
||||
r <<= 8;
|
||||
r |= MMPTR(0xe0002014);
|
||||
r <<= 8;
|
||||
r |= MMPTR(0xe0002018);
|
||||
r <<= 8;
|
||||
r |= MMPTR(0xe000201c);
|
||||
return r;
|
||||
}
|
||||
|
||||
static inline void timer0_reload_write(unsigned int value)
|
||||
{
|
||||
MMPTR(0xe0002010) = value >> 24;
|
||||
MMPTR(0xe0002014) = value >> 16;
|
||||
MMPTR(0xe0002018) = value >> 8;
|
||||
MMPTR(0xe000201c) = value;
|
||||
}
|
||||
|
||||
static inline unsigned char timer0_en_read(void)
|
||||
{
|
||||
unsigned char r = MMPTR(0xe0002020);
|
||||
return r;
|
||||
}
|
||||
|
||||
static inline void timer0_en_write(unsigned char value)
|
||||
{
|
||||
MMPTR(0xe0002020) = value;
|
||||
}
|
||||
|
||||
static inline unsigned char timer0_update_value_read(void)
|
||||
{
|
||||
unsigned char r = MMPTR(0xe0002024);
|
||||
return r;
|
||||
}
|
||||
|
||||
static inline void timer0_update_value_write(unsigned char value)
|
||||
{
|
||||
MMPTR(0xe0002024) = value;
|
||||
}
|
||||
|
||||
static inline unsigned int timer0_value_read(void)
|
||||
{
|
||||
unsigned int r = MMPTR(0xe0002028);
|
||||
r <<= 8;
|
||||
r |= MMPTR(0xe000202c);
|
||||
r <<= 8;
|
||||
r |= MMPTR(0xe0002030);
|
||||
r <<= 8;
|
||||
r |= MMPTR(0xe0002034);
|
||||
return r;
|
||||
}
|
||||
|
||||
static inline unsigned char timer0_ev_status_read(void)
|
||||
{
|
||||
unsigned char r = MMPTR(0xe0002038);
|
||||
return r;
|
||||
}
|
||||
|
||||
static inline void timer0_ev_status_write(unsigned char value)
|
||||
{
|
||||
MMPTR(0xe0002038) = value;
|
||||
}
|
||||
|
||||
static inline unsigned char timer0_ev_pending_read(void)
|
||||
{
|
||||
unsigned char r = MMPTR(0xe000203c);
|
||||
return r;
|
||||
}
|
||||
|
||||
static inline void timer0_ev_pending_write(unsigned char value)
|
||||
{
|
||||
MMPTR(0xe000203c) = value;
|
||||
}
|
||||
|
||||
static inline unsigned char timer0_ev_enable_read(void)
|
||||
{
|
||||
unsigned char r = MMPTR(0xe0002040);
|
||||
return r;
|
||||
}
|
||||
|
||||
static inline void timer0_ev_enable_write(unsigned char value)
|
||||
{
|
||||
MMPTR(0xe0002040) = value;
|
||||
}
|
||||
|
||||
/* UART */
|
||||
|
||||
static inline unsigned char uart_rxtx_read(void)
|
||||
{
|
||||
unsigned char r = MMPTR(0xe0001000);
|
||||
return r;
|
||||
}
|
||||
|
||||
static inline void uart_rxtx_write(unsigned char value)
|
||||
{
|
||||
MMPTR(0xe0001000) = value;
|
||||
}
|
||||
|
||||
static inline unsigned char uart_txfull_read(void)
|
||||
{
|
||||
unsigned char r = MMPTR(0xe0001004);
|
||||
return r;
|
||||
}
|
||||
|
||||
static inline unsigned char uart_rxempty_read(void)
|
||||
{
|
||||
unsigned char r = MMPTR(0xe0001008);
|
||||
return r;
|
||||
}
|
||||
|
||||
static inline unsigned char uart_ev_status_read(void)
|
||||
{
|
||||
unsigned char r = MMPTR(0xe000100c);
|
||||
return r;
|
||||
}
|
||||
|
||||
static inline void uart_ev_status_write(unsigned char value)
|
||||
{
|
||||
MMPTR(0xe000100c) = value;
|
||||
}
|
||||
|
||||
static inline unsigned char uart_ev_pending_read(void)
|
||||
{
|
||||
unsigned char r = MMPTR(0xe0001010);
|
||||
return r;
|
||||
}
|
||||
|
||||
static inline void uart_ev_pending_write(unsigned char value)
|
||||
{
|
||||
MMPTR(0xe0001010) = value;
|
||||
}
|
||||
|
||||
static inline unsigned char uart_ev_enable_read(void)
|
||||
{
|
||||
unsigned char r = MMPTR(0xe0001014);
|
||||
return r;
|
||||
}
|
||||
|
||||
static inline void uart_ev_enable_write(unsigned char value)
|
||||
{
|
||||
MMPTR(0xe0001014) = value;
|
||||
}
|
||||
|
||||
/* uart_phy */
|
||||
|
||||
static inline unsigned int uart_phy_tuning_word_read(void)
|
||||
{
|
||||
unsigned int r = MMPTR(0xe0000800);
|
||||
r <<= 8;
|
||||
r |= MMPTR(0xe0000804);
|
||||
r <<= 8;
|
||||
r |= MMPTR(0xe0000808);
|
||||
r <<= 8;
|
||||
r |= MMPTR(0xe000080c);
|
||||
return r;
|
||||
}
|
||||
|
||||
static inline void uart_phy_tuning_word_write(unsigned int value)
|
||||
{
|
||||
MMPTR(0xe0000800) = value >> 24;
|
||||
MMPTR(0xe0000804) = value >> 16;
|
||||
MMPTR(0xe0000808) = value >> 8;
|
||||
MMPTR(0xe000080c) = value;
|
||||
}
|
||||
|
||||
#endif /* __CONFIGS_MISOC_INCLUDE_GENERATED_CSR_H */
|
||||
#endif
|
||||
|
@ -1,44 +1,5 @@
|
||||
/****************************************************************************
|
||||
* configs/misoc/include/generated/mem.h
|
||||
*
|
||||
* Copyright (C) 2016 Gregory Nutt. All rights reserved.
|
||||
* Author: Ramtin Amin <keytwo@gmail.com>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name NuttX nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifndef __CONFIGS_MISOC_INCLUDE_GENERATED_MEM_H
|
||||
#define __CONFIGS_MISOC_INCLUDE_GENERATED_MEM_H
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
#ifndef __GENERATED_MEM_H
|
||||
#define __GENERATED_MEM_H
|
||||
|
||||
#define ROM_BASE 0x00000000
|
||||
#define ROM_SIZE 0x00008000
|
||||
@ -49,4 +10,4 @@
|
||||
#define MAIN_RAM_BASE 0x40000000
|
||||
#define MAIN_RAM_SIZE 0x00800000
|
||||
|
||||
#endif /* __CONFIGS_MISOC_INCLUDE_GENERATED_MEM_H /
|
||||
#endif
|
||||
|
@ -1,5 +1,4 @@
|
||||
MEMORY
|
||||
{
|
||||
MEMORY {
|
||||
rom : ORIGIN = 0x00000000, LENGTH = 0x00008000
|
||||
sram : ORIGIN = 0x10000000, LENGTH = 0x00001000
|
||||
main_ram : ORIGIN = 0x40000000, LENGTH = 0x00800000
|
||||
|
@ -1,56 +1,20 @@
|
||||
/****************************************************************************
|
||||
* configs/misoc/include/generated/common.h
|
||||
*
|
||||
* Copyright (C) 2016 Gregory Nutt. All rights reserved.
|
||||
* Author: Ramtin Amin <keytwo@gmail.com>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name NuttX nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifndef __CONFIGS_MISOC_INCLUDE_GENERATED_SDRAM_PHY_H
|
||||
#define __CONFIGS_MISOC_INCLUDE_GENERATED_SDRAM_PHY_H
|
||||
|
||||
/****************************************************************************
|
||||
* Included Filese
|
||||
****************************************************************************/
|
||||
|
||||
#include "hw/common.h"
|
||||
#include "hw/flags.h"
|
||||
|
||||
#include <arch/board/generated/csr.h>
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
#ifndef __GENERATED_SDRAM_PHY_H
|
||||
#define __GENERATED_SDRAM_PHY_H
|
||||
#include <hw/common.h>
|
||||
#include <generated/csr.h>
|
||||
#include <hw/flags.h>
|
||||
|
||||
#define DFII_NPHASES 1
|
||||
|
||||
static void cdelay(int i);
|
||||
|
||||
static void command_p0(int cmd)
|
||||
{
|
||||
sdram_dfii_pi0_command_write(cmd);
|
||||
sdram_dfii_pi0_command_issue_write(1);
|
||||
}
|
||||
|
||||
|
||||
#define sdram_dfii_pird_address_write(X) sdram_dfii_pi0_address_write(X)
|
||||
#define sdram_dfii_piwr_address_write(X) sdram_dfii_pi0_address_write(X)
|
||||
|
||||
@ -62,83 +26,55 @@
|
||||
|
||||
#define DFII_PIX_DATA_SIZE CSR_SDRAM_DFII_PI0_WRDATA_SIZE
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
|
||||
const unsigned int sdram_dfii_pix_wrdata_addr[1] =
|
||||
{
|
||||
CSR_SDRAM_DFII_PI0_WRDATA_ADDR
|
||||
const unsigned int sdram_dfii_pix_wrdata_addr[1] = {
|
||||
CSR_SDRAM_DFII_PI0_WRDATA_ADDR
|
||||
};
|
||||
|
||||
const unsigned int sdram_dfii_pix_rddata_addr[1] =
|
||||
{
|
||||
CSR_SDRAM_DFII_PI0_RDDATA_ADDR
|
||||
const unsigned int sdram_dfii_pix_rddata_addr[1] = {
|
||||
CSR_SDRAM_DFII_PI0_RDDATA_ADDR
|
||||
};
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
static void cdelay(int i);
|
||||
|
||||
static void command_p0(int cmd)
|
||||
{
|
||||
sdram_dfii_pi0_command_write(cmd);
|
||||
sdram_dfii_pi0_command_issue_write(1);
|
||||
}
|
||||
|
||||
static void init_sequence(void)
|
||||
{
|
||||
/* Bring CKE high */
|
||||
/* Bring CKE high */
|
||||
sdram_dfii_pi0_address_write(0x0);
|
||||
sdram_dfii_pi0_baddress_write(0);
|
||||
sdram_dfii_control_write(DFII_CONTROL_CKE|DFII_CONTROL_ODT|DFII_CONTROL_RESET_N);
|
||||
cdelay(20000);
|
||||
|
||||
sdram_dfii_pi0_address_write(0x0);
|
||||
sdram_dfii_pi0_baddress_write(0);
|
||||
sdram_dfii_control_write(DFII_CONTROL_CKE | DFII_CONTROL_ODT |
|
||||
DFII_CONTROL_RESET_N);
|
||||
cdelay(20000);
|
||||
/* Precharge All */
|
||||
sdram_dfii_pi0_address_write(0x400);
|
||||
sdram_dfii_pi0_baddress_write(0);
|
||||
command_p0(DFII_COMMAND_RAS|DFII_COMMAND_WE|DFII_COMMAND_CS);
|
||||
|
||||
/* Precharge All */
|
||||
/* Load Mode Register / Reset DLL, CL=2, BL=1 */
|
||||
sdram_dfii_pi0_address_write(0x120);
|
||||
sdram_dfii_pi0_baddress_write(0);
|
||||
command_p0(DFII_COMMAND_RAS|DFII_COMMAND_CAS|DFII_COMMAND_WE|DFII_COMMAND_CS);
|
||||
cdelay(200);
|
||||
|
||||
sdram_dfii_pi0_address_write(0x400);
|
||||
sdram_dfii_pi0_baddress_write(0);
|
||||
command_p0(DFII_COMMAND_RAS | DFII_COMMAND_WE | DFII_COMMAND_CS);
|
||||
/* Precharge All */
|
||||
sdram_dfii_pi0_address_write(0x400);
|
||||
sdram_dfii_pi0_baddress_write(0);
|
||||
command_p0(DFII_COMMAND_RAS|DFII_COMMAND_WE|DFII_COMMAND_CS);
|
||||
|
||||
/* Load Mode Register / Reset DLL, CL=2, BL=1 */
|
||||
/* Auto Refresh */
|
||||
sdram_dfii_pi0_address_write(0x0);
|
||||
sdram_dfii_pi0_baddress_write(0);
|
||||
command_p0(DFII_COMMAND_RAS|DFII_COMMAND_CAS|DFII_COMMAND_CS);
|
||||
cdelay(4);
|
||||
|
||||
sdram_dfii_pi0_address_write(0x120);
|
||||
sdram_dfii_pi0_baddress_write(0);
|
||||
command_p0(DFII_COMMAND_RAS | DFII_COMMAND_CAS | DFII_COMMAND_WE |
|
||||
DFII_COMMAND_CS);
|
||||
cdelay(200);
|
||||
/* Auto Refresh */
|
||||
sdram_dfii_pi0_address_write(0x0);
|
||||
sdram_dfii_pi0_baddress_write(0);
|
||||
command_p0(DFII_COMMAND_RAS|DFII_COMMAND_CAS|DFII_COMMAND_CS);
|
||||
cdelay(4);
|
||||
|
||||
/* Precharge All */
|
||||
/* Load Mode Register / CL=2, BL=1 */
|
||||
sdram_dfii_pi0_address_write(0x20);
|
||||
sdram_dfii_pi0_baddress_write(0);
|
||||
command_p0(DFII_COMMAND_RAS|DFII_COMMAND_CAS|DFII_COMMAND_WE|DFII_COMMAND_CS);
|
||||
cdelay(200);
|
||||
|
||||
sdram_dfii_pi0_address_write(0x400);
|
||||
sdram_dfii_pi0_baddress_write(0);
|
||||
command_p0(DFII_COMMAND_RAS | DFII_COMMAND_WE | DFII_COMMAND_CS);
|
||||
|
||||
/* Auto Refresh */
|
||||
|
||||
sdram_dfii_pi0_address_write(0x0);
|
||||
sdram_dfii_pi0_baddress_write(0);
|
||||
command_p0(DFII_COMMAND_RAS | DFII_COMMAND_CAS | DFII_COMMAND_CS);
|
||||
cdelay(4);
|
||||
|
||||
/* Auto Refresh */
|
||||
|
||||
sdram_dfii_pi0_address_write(0x0);
|
||||
sdram_dfii_pi0_baddress_write(0);
|
||||
command_p0(DFII_COMMAND_RAS | DFII_COMMAND_CAS | DFII_COMMAND_CS);
|
||||
cdelay(4);
|
||||
|
||||
/* Load Mode Register / CL=2, BL=1 */
|
||||
|
||||
sdram_dfii_pi0_address_write(0x20);
|
||||
sdram_dfii_pi0_baddress_write(0);
|
||||
command_p0(DFII_COMMAND_RAS | DFII_COMMAND_CAS | DFII_COMMAND_WE |
|
||||
DFII_COMMAND_CS);
|
||||
cdelay(200);
|
||||
}
|
||||
|
||||
#endif /* __CONFIGS_MISOC_INCLUDE_GENERATED_SDRAM_PHY_H
|
||||
#endif
|
||||
|
Loading…
x
Reference in New Issue
Block a user