KL25Z: Fix serial driver; freedom-kl25z/nsh configuration now works
This commit is contained in:
parent
50d1a961bc
commit
2b411b516a
@ -4619,3 +4619,7 @@
|
||||
register definitions (2014-4-25).
|
||||
* arch/arm/src/kl/Kconfig, kl_lowputc.c, kl_serial.c, and kl_config.h:
|
||||
No UART3-5 (2014-4-25).
|
||||
* arch/arm/src/kl/kl_serial.c: Various fixes to various fils in the
|
||||
KL architecture directory as need to get the interrupt-driven
|
||||
serial driver to work. The Freedom KL25Z NSH configuration now
|
||||
works (2014-4-25).
|
||||
|
@ -414,10 +414,3 @@ config KL_SDHC_DMAPRIO
|
||||
SDHC DMA priority
|
||||
|
||||
endif
|
||||
|
||||
comment "Kinetis UART Configuration"
|
||||
|
||||
config KL_UARTFIFOS
|
||||
bool "Enable UART0 FIFO"
|
||||
default n
|
||||
depends on KL_UART0
|
||||
|
@ -68,8 +68,8 @@ CMN_CSRCS += up_dumpnvic.c
|
||||
endif
|
||||
|
||||
CHIP_ASRCS =
|
||||
CHIP_CSRCS = kl_clockconfig.c kl_gpio.c kl_idle.c kl_irq.c kl_lowputc.c
|
||||
CHIP_CSRCS += kl_serial.c kl_start.c kl_timerisr.c kl_cfmconfig.c kl_led.c
|
||||
CHIP_CSRCS = kl_clockconfig.c kl_gpio.c kl_idle.c kl_irq.c kl_irqprio.c
|
||||
CHIP_CSRCS += kl_lowputc.c kl_serial.c kl_start.c kl_timerisr.c kl_cfmconfig.c
|
||||
|
||||
ifeq ($(CONFIG_NUTTX_KERNEL),y)
|
||||
CHIP_CSRCS += kl_userspace.c
|
||||
|
@ -154,6 +154,7 @@
|
||||
#define UART_S1_RDRF (1 << 5) /* Bit 5: Receive Data Register Full Flag */
|
||||
#define UART_S1_TC (1 << 6) /* Bit 6: Transmit Complete Flag */
|
||||
#define UART_S1_TDRE (1 << 7) /* Bit 7: Transmit Data Register Empty Flag */
|
||||
#define UART_S1_ERRORS (0x0f)
|
||||
|
||||
/* UART Status Register 2 */
|
||||
|
||||
|
@ -97,32 +97,6 @@
|
||||
# undef CONFIG_UART1_FLOWCONTROL
|
||||
# undef CONFIG_UART2_FLOWCONTROL
|
||||
|
||||
/* UART FIFO support is not fully implemented.
|
||||
*
|
||||
* NOTE: UART0 has an 8-byte deep FIFO; the other UARTs have no FIFOs
|
||||
* (1-deep). There appears to be no way to know when the FIFO is not
|
||||
* full (other than reading the FIFO length and comparing the FIFO count).
|
||||
* Hence, the FIFOs are not used in this implementation and, as a result
|
||||
* TDRE indeed mean that the single output buffer is available.
|
||||
*
|
||||
* Performance on UART0 could be improved by enabling the FIFO and by
|
||||
* redesigning all of the FIFO status logic.
|
||||
*/
|
||||
|
||||
#undef CONFIG_KL_UARTFIFOS
|
||||
|
||||
/* UART Default Interrupt Priorities */
|
||||
|
||||
#ifndef CONFIG_KL_UART0PRIO
|
||||
# define CONFIG_KL_UART0PRIO NVIC_SYSH_PRIORITY_DEFAULT
|
||||
#endif
|
||||
#ifndef CONFIG_KL_UART1PRIO
|
||||
# define CONFIG_KL_UART1PRIO NVIC_SYSH_PRIORITY_DEFAULT
|
||||
#endif
|
||||
#ifndef CONFIG_KL_UART2PRIO
|
||||
# define CONFIG_KL_UART2PRIO NVIC_SYSH_PRIORITY_DEFAULT
|
||||
#endif
|
||||
|
||||
/* Ethernet controller configuration */
|
||||
|
||||
#ifndef CONFIG_ENET_NRXBUFFERS
|
||||
|
@ -336,72 +336,3 @@ void up_maskack_irq(int irq)
|
||||
up_disable_irq(irq);
|
||||
kl_clrpend(irq);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_prioritize_irq
|
||||
*
|
||||
* Description:
|
||||
* Set the priority of an IRQ.
|
||||
*
|
||||
* Since this API is not supported on all architectures, it should be
|
||||
* avoided in common implementations where possible.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef CONFIG_ARCH_IRQPRIO
|
||||
int up_prioritize_irq(int irq, int priority)
|
||||
{
|
||||
uint32_t regaddr;
|
||||
uint32_t regval;
|
||||
int shift;
|
||||
|
||||
DEBUGASSERT(irq == KL_IRQ_SVCALL ||
|
||||
irq == KL_IRQ_PENDSV ||
|
||||
irq == KL_IRQ_SYSTICK ||
|
||||
(irq >= KL_IRQ_EXTINT && irq < NR_IRQS));
|
||||
DEBUGASSERT(priority >= NVIC_SYSH_PRIORITY_MAX &&
|
||||
priority <= NVIC_SYSH_PRIORITY_MIN);
|
||||
|
||||
/* Check for external interrupt */
|
||||
|
||||
if (irq >= KL_IRQ_EXTINT && irq < (KL_IRQ_EXTINT + 32))
|
||||
{
|
||||
/* ARMV6M_NVIC_IPR() maps register IPR0-IPR7 with four settings per
|
||||
* register.
|
||||
*/
|
||||
|
||||
regaddr = ARMV6M_NVIC_IPR(irq >> 2);
|
||||
shift = (irq & 3) << 3;
|
||||
}
|
||||
|
||||
/* Handle processor exceptions. Only SVCall, PendSV, and SysTick can be
|
||||
* reprioritized. And we will not permit modification of SVCall through
|
||||
* this function.
|
||||
*/
|
||||
|
||||
else if (irq == KL_IRQ_PENDSV)
|
||||
{
|
||||
regaddr = ARMV6M_SYSCON_SHPR2;
|
||||
shift = SYSCON_SHPR3_PRI_14_SHIFT;
|
||||
}
|
||||
else if (irq == KL_IRQ_SYSTICK)
|
||||
{
|
||||
regaddr = ARMV6M_SYSCON_SHPR2;
|
||||
shift = SYSCON_SHPR3_PRI_15_SHIFT;
|
||||
}
|
||||
else
|
||||
{
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
/* Set the priority */
|
||||
|
||||
regval = getreg32(regaddr);
|
||||
regval &= ~((uint32_t)0xff << shift);
|
||||
regval |= ((uint32_t)priority << shift);
|
||||
putreg32(regval, regaddr);
|
||||
|
||||
kl_dumpnvic("prioritize", irq);
|
||||
return OK;
|
||||
}
|
||||
#endif
|
||||
|
127
arch/arm/src/kl/kl_irqprio.c
Normal file
127
arch/arm/src/kl/kl_irqprio.c
Normal file
@ -0,0 +1,127 @@
|
||||
/****************************************************************************
|
||||
* arch/arm/src/stm32/kl_irqprio.c
|
||||
* arch/arm/src/chip/kl_irqprio.c
|
||||
*
|
||||
* Copyright (C) 2013 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 <sys/types.h>
|
||||
#include <assert.h>
|
||||
#include <arch/irq.h>
|
||||
|
||||
#include "nvic.h"
|
||||
#include "up_arch.h"
|
||||
|
||||
#include "kl_irq.h"
|
||||
|
||||
#ifdef CONFIG_ARCH_IRQPRIO
|
||||
|
||||
/****************************************************************************
|
||||
* Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Data
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
int up_prioritize_irq(int irq, int priority)
|
||||
{
|
||||
uint32_t regaddr;
|
||||
uint32_t regval;
|
||||
int shift;
|
||||
|
||||
DEBUGASSERT(irq == KL_IRQ_SVCALL ||
|
||||
irq == KL_IRQ_PENDSV ||
|
||||
irq == KL_IRQ_SYSTICK ||
|
||||
(irq >= KL_IRQ_EXTINT && irq < NR_IRQS));
|
||||
DEBUGASSERT(priority >= NVIC_SYSH_PRIORITY_MAX &&
|
||||
priority <= NVIC_SYSH_PRIORITY_MIN);
|
||||
|
||||
/* Check for external interrupt */
|
||||
|
||||
if (irq >= KL_IRQ_EXTINT && irq < (KL_IRQ_EXTINT + 32))
|
||||
{
|
||||
/* ARMV6M_NVIC_IPR() maps register IPR0-IPR7 with four settings per
|
||||
* register.
|
||||
*/
|
||||
|
||||
regaddr = ARMV6M_NVIC_IPR(irq >> 2);
|
||||
shift = (irq & 3) << 3;
|
||||
}
|
||||
|
||||
/* Handle processor exceptions. Only SVCall, PendSV, and SysTick can be
|
||||
* reprioritized. And we will not permit modification of SVCall through
|
||||
* this function.
|
||||
*/
|
||||
|
||||
else if (irq == KL_IRQ_PENDSV)
|
||||
{
|
||||
regaddr = ARMV6M_SYSCON_SHPR2;
|
||||
shift = SYSCON_SHPR3_PRI_14_SHIFT;
|
||||
}
|
||||
else if (irq == KL_IRQ_SYSTICK)
|
||||
{
|
||||
regaddr = ARMV6M_SYSCON_SHPR2;
|
||||
shift = SYSCON_SHPR3_PRI_15_SHIFT;
|
||||
}
|
||||
else
|
||||
{
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
/* Set the priority */
|
||||
|
||||
regval = getreg32(regaddr);
|
||||
regval &= ~((uint32_t)0xff << shift);
|
||||
regval |= ((uint32_t)priority << shift);
|
||||
putreg32(regval, regaddr);
|
||||
return OK;
|
||||
}
|
||||
#endif
|
@ -1,28 +0,0 @@
|
||||
void blueled(int on)
|
||||
{
|
||||
volatile unsigned int *SIM_COPC = ((volatile unsigned int *)0x40048100);
|
||||
volatile unsigned int *SIM_SCGC5 = ((volatile unsigned int *)0x40048038);
|
||||
volatile unsigned int *PORTD_PCR1 = ((volatile unsigned int *)0x4004C004);
|
||||
volatile unsigned int *GPIOD_PSOR = ((volatile unsigned int *)0x400FF0C4);
|
||||
volatile unsigned int *GPIOD_PCOR = ((volatile unsigned int *)0x400FF0C8);
|
||||
volatile unsigned int *GPIOD_PDDR = ((volatile unsigned int *)0x400FF0D4);
|
||||
|
||||
/*acassis: disable SIM_COP*/
|
||||
*SIM_COPC = 0;
|
||||
|
||||
/* enable clocks for PORTD */
|
||||
*SIM_SCGC5 = 0x1000;
|
||||
|
||||
/* set D1 to GPIO */
|
||||
*PORTD_PCR1 = 0x100;
|
||||
|
||||
/* set D1 DDR to output */
|
||||
*GPIOD_PDDR |= 2;
|
||||
|
||||
if(on)
|
||||
*GPIOD_PCOR = 2;
|
||||
else
|
||||
*GPIOD_PSOR = 2;
|
||||
|
||||
}
|
||||
|
@ -99,14 +99,6 @@
|
||||
* Private Variables
|
||||
**************************************************************************/
|
||||
|
||||
/* This array maps an encoded FIFO depth (index) to the actual size of the
|
||||
* FIFO (indexed value). NOTE: That there is no 8th value.
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_KL_UARTFIFOS
|
||||
static uint8_t g_sizemap[8] = {1, 4, 8, 16, 32, 64, 128, 0};
|
||||
#endif
|
||||
|
||||
/**************************************************************************
|
||||
* Private Functions
|
||||
**************************************************************************/
|
||||
@ -126,15 +118,6 @@ static uint8_t g_sizemap[8] = {1, 4, 8, 16, 32, 64, 128, 0};
|
||||
void kl_lowputc(uint32_t ch)
|
||||
{
|
||||
#if defined HAVE_UART_DEVICE && defined HAVE_SERIAL_CONSOLE
|
||||
#ifdef CONFIG_KL_UARTFIFOS
|
||||
/* Wait until there is space in the TX FIFO: Read the number of bytes
|
||||
* currently in the FIFO and compare that to the size of the FIFO. If
|
||||
* there are fewer bytes in the FIFO than the size of the FIFO, then we
|
||||
* are able to transmit.
|
||||
*/
|
||||
|
||||
# error "Missing logic"
|
||||
#else
|
||||
/* Wait until the transmit data register is "empty" (TDRE). This state
|
||||
* depends on the TX watermark setting and may not mean that the transmit
|
||||
* buffer is truly empty. It just means that we can now add another
|
||||
@ -152,8 +135,6 @@ void kl_lowputc(uint32_t ch)
|
||||
|
||||
while ((getreg8(CONSOLE_BASE+KL_UART_S1_OFFSET) & UART_S1_TDRE) == 0);
|
||||
|
||||
#endif
|
||||
|
||||
/* Then write the character to the UART data register */
|
||||
|
||||
putreg8((uint8_t)ch, CONSOLE_BASE+KL_UART_D_OFFSET);
|
||||
@ -272,9 +253,6 @@ void kl_uartconfigure(uintptr_t uart_base, uint32_t baud, uint32_t clock,
|
||||
uint32_t sbr;
|
||||
uint32_t tmp;
|
||||
uint8_t regval;
|
||||
#ifdef CONFIG_KL_UARTFIFOS
|
||||
unsigned int depth;
|
||||
#endif
|
||||
|
||||
/* Disable the transmitter and receiver throughout the reconfiguration */
|
||||
|
||||
|
@ -158,11 +158,7 @@ struct up_dev_s
|
||||
uintptr_t uartbase; /* Base address of UART registers */
|
||||
uint32_t baud; /* Configured baud */
|
||||
uint32_t clock; /* Clocking frequency of the UART module */
|
||||
#ifdef CONFIG_DEBUG
|
||||
uint8_t irqe; /* Error IRQ associated with this UART (for enable) */
|
||||
#endif
|
||||
uint8_t irqs; /* Status IRQ associated with this UART (for enable) */
|
||||
uint8_t irqprio; /* Interrupt priority */
|
||||
uint8_t irq; /* IRQ associated with this UART (for enable) */
|
||||
uint8_t ie; /* Interrupts enabled */
|
||||
uint8_t parity; /* 0=none, 1=odd, 2=even */
|
||||
uint8_t bits; /* Number of bits (8 or 9) */
|
||||
@ -176,9 +172,6 @@ static int up_setup(struct uart_dev_s *dev);
|
||||
static void up_shutdown(struct uart_dev_s *dev);
|
||||
static int up_attach(struct uart_dev_s *dev);
|
||||
static void up_detach(struct uart_dev_s *dev);
|
||||
#ifdef CONFIG_DEBUG
|
||||
static int up_interrupte(int irq, void *context);
|
||||
#endif
|
||||
static int up_interrupts(int irq, void *context);
|
||||
static int up_ioctl(struct file *filep, int cmd, unsigned long arg);
|
||||
static int up_receive(struct uart_dev_s *dev, uint32_t *status);
|
||||
@ -187,9 +180,6 @@ static bool up_rxavailable(struct uart_dev_s *dev);
|
||||
static void up_send(struct uart_dev_s *dev, int ch);
|
||||
static void up_txint(struct uart_dev_s *dev, bool enable);
|
||||
static bool up_txready(struct uart_dev_s *dev);
|
||||
#ifdef CONFIG_KL_UARTFIFOS
|
||||
static bool up_txempty(struct uart_dev_s *dev);
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Private Variables
|
||||
@ -208,11 +198,7 @@ static const struct uart_ops_s g_uart_ops =
|
||||
.send = up_send,
|
||||
.txint = up_txint,
|
||||
.txready = up_txready,
|
||||
#ifdef CONFIG_KL_UARTFIFOS
|
||||
.txempty = up_txempty,
|
||||
#else
|
||||
.txempty = up_txready,
|
||||
#endif
|
||||
};
|
||||
|
||||
/* I/O buffers */
|
||||
@ -238,7 +224,7 @@ static struct up_dev_s g_uart0priv =
|
||||
.uartbase = KL_UART0_BASE,
|
||||
.clock = BOARD_CORECLK_FREQ,
|
||||
.baud = CONFIG_UART0_BAUD,
|
||||
.irqprio = CONFIG_KL_UART0PRIO,
|
||||
.irq = KL_IRQ_UART0,
|
||||
.parity = CONFIG_UART0_PARITY,
|
||||
.bits = CONFIG_UART0_BITS,
|
||||
};
|
||||
@ -268,11 +254,7 @@ static struct up_dev_s g_uart1priv =
|
||||
.uartbase = KL_UART1_BASE,
|
||||
.clock = BOARD_BUSCLK_FREQ,
|
||||
.baud = CONFIG_UART1_BAUD,
|
||||
#ifdef CONFIG_DEBUG
|
||||
.irqe = KL_IRQ_UART1E,
|
||||
#endif
|
||||
.irqs = KL_IRQ_UART1S,
|
||||
.irqprio = CONFIG_KL_UART1PRIO,
|
||||
.irq = KL_IRQ_UART1,
|
||||
.parity = CONFIG_UART1_PARITY,
|
||||
.bits = CONFIG_UART1_BITS,
|
||||
};
|
||||
@ -302,11 +284,7 @@ static struct up_dev_s g_uart2priv =
|
||||
.uartbase = KL_UART2_BASE,
|
||||
.clock = BOARD_BUSCLK_FREQ,
|
||||
.baud = CONFIG_UART2_BAUD,
|
||||
#ifdef CONFIG_DEBUG
|
||||
.irqe = KL_IRQ_UART2E,
|
||||
#endif
|
||||
.irqs = KL_IRQ_UART2S,
|
||||
.irqprio = CONFIG_KL_UART2PRIO,
|
||||
.irq = KL_IRQ_UART2,
|
||||
.parity = CONFIG_UART2_PARITY,
|
||||
.bits = CONFIG_UART2_BITS,
|
||||
};
|
||||
@ -426,13 +404,6 @@ static int up_setup(struct uart_dev_s *dev)
|
||||
/* Make sure that all interrupts are disabled */
|
||||
|
||||
up_restoreuartint(priv, 0);
|
||||
|
||||
/* Set up the interrupt priority */
|
||||
|
||||
up_prioritize_irq(priv->irqs, priv->irqprio);
|
||||
#ifdef CONFIG_DEBUG
|
||||
up_prioritize_irq(priv->irqe, priv->irqprio);
|
||||
#endif
|
||||
return OK;
|
||||
}
|
||||
|
||||
@ -482,20 +453,10 @@ static int up_attach(struct uart_dev_s *dev)
|
||||
* disabled in the C2 register.
|
||||
*/
|
||||
|
||||
ret = irq_attach(priv->irqs, up_interrupts);
|
||||
#ifdef CONFIG_DEBUG
|
||||
ret = irq_attach(priv->irq, up_interrupts);
|
||||
if (ret == OK)
|
||||
{
|
||||
ret = irq_attach(priv->irqe, up_interrupte);
|
||||
}
|
||||
#endif
|
||||
|
||||
if (ret == OK)
|
||||
{
|
||||
#ifdef CONFIG_DEBUG
|
||||
up_enable_irq(priv->irqe);
|
||||
#endif
|
||||
up_enable_irq(priv->irqs);
|
||||
up_enable_irq(priv->irq);
|
||||
}
|
||||
|
||||
return ret;
|
||||
@ -518,79 +479,13 @@ static void up_detach(struct uart_dev_s *dev)
|
||||
/* Disable interrupts */
|
||||
|
||||
up_restoreuartint(priv, 0);
|
||||
#ifdef CONFIG_DEBUG
|
||||
up_disable_irq(priv->irqe);
|
||||
#endif
|
||||
up_disable_irq(priv->irqs);
|
||||
up_disable_irq(priv->irq);
|
||||
|
||||
/* Detach from the interrupt(s) */
|
||||
|
||||
irq_detach(priv->irqs);
|
||||
#ifdef CONFIG_DEBUG
|
||||
irq_detach(priv->irqe);
|
||||
#endif
|
||||
irq_detach(priv->irq);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_interrupte
|
||||
*
|
||||
* Description:
|
||||
* This is the UART error interrupt handler. It will be invoked when an
|
||||
* interrupt received on the 'irq'
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef CONFIG_DEBUG
|
||||
static int up_interrupte(int irq, void *context)
|
||||
{
|
||||
struct uart_dev_s *dev = NULL;
|
||||
struct up_dev_s *priv;
|
||||
uint8_t regval;
|
||||
|
||||
#ifdef CONFIG_KL_UART0
|
||||
if (g_uart0priv.irqe == irq)
|
||||
{
|
||||
dev = &g_uart0port;
|
||||
}
|
||||
else
|
||||
#endif
|
||||
#ifdef CONFIG_KL_UART1
|
||||
if (g_uart1priv.irqe == irq)
|
||||
{
|
||||
dev = &g_uart1port;
|
||||
}
|
||||
else
|
||||
#endif
|
||||
#ifdef CONFIG_KL_UART2
|
||||
if (g_uart2priv.irqe == irq)
|
||||
{
|
||||
dev = &g_uart2port;
|
||||
}
|
||||
else
|
||||
#endif
|
||||
{
|
||||
PANIC(OSERR_INTERNAL);
|
||||
}
|
||||
priv = (struct up_dev_s*)dev->priv;
|
||||
DEBUGASSERT(priv);
|
||||
|
||||
/* Handle error interrupts. This interrupt may be caused by:
|
||||
*
|
||||
* FE: Framing error. To clear FE, read S1 with FE set and then read the
|
||||
* UART data register (D).
|
||||
* NF: Noise flag. To clear NF, read S1 and then read the UART data
|
||||
* register (D).
|
||||
* PF: Parity error flag. To clear PF, read S1 and then read the UART data
|
||||
* register (D).
|
||||
*/
|
||||
|
||||
regval = up_serialin(priv, KL_UART_S1_OFFSET);
|
||||
lldbg("S1: %02x\n", regval);
|
||||
regval = up_serialin(priv, KL_UART_D_OFFSET);
|
||||
return OK;
|
||||
}
|
||||
#endif /* CONFIG_DEBUG */
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_interrupts
|
||||
*
|
||||
@ -608,29 +503,25 @@ static int up_interrupts(int irq, void *context)
|
||||
struct uart_dev_s *dev = NULL;
|
||||
struct up_dev_s *priv;
|
||||
int passes;
|
||||
#ifdef CONFIG_KL_UARTFIFOS
|
||||
unsigned int count;
|
||||
#else
|
||||
uint8_t s1;
|
||||
#endif
|
||||
bool handled;
|
||||
|
||||
#ifdef CONFIG_KL_UART0
|
||||
if (g_uart0priv.irqs == irq)
|
||||
if (g_uart0priv.irq == irq)
|
||||
{
|
||||
dev = &g_uart0port;
|
||||
}
|
||||
else
|
||||
#endif
|
||||
#ifdef CONFIG_KL_UART1
|
||||
if (g_uart1priv.irqs == irq)
|
||||
if (g_uart1priv.irq == irq)
|
||||
{
|
||||
dev = &g_uart1port;
|
||||
}
|
||||
else
|
||||
#endif
|
||||
#ifdef CONFIG_KL_UART2
|
||||
if (g_uart2priv.irqs == irq)
|
||||
if (g_uart2priv.irq == irq)
|
||||
{
|
||||
dev = &g_uart2port;
|
||||
}
|
||||
@ -653,18 +544,8 @@ static int up_interrupts(int irq, void *context)
|
||||
|
||||
/* Read status register 1 */
|
||||
|
||||
#ifndef CONFIG_KL_UARTFIFOS
|
||||
s1 = up_serialin(priv, KL_UART_S1_OFFSET);
|
||||
#endif
|
||||
|
||||
/* Handle incoming, receive bytes */
|
||||
|
||||
#ifdef CONFIG_KL_UARTFIFOS
|
||||
/* Check the count of bytes in the RX FIFO */
|
||||
|
||||
count = up_serialin(priv, KL_UART_RCFIFO_OFFSET);
|
||||
if (count > 0)
|
||||
#else
|
||||
/* Check if the receive data register is full (RDRF). NOTE: If
|
||||
* FIFOS are enabled, this does not mean that the the FIFO is full,
|
||||
* rather, it means that the the number of bytes in the RX FIFO has
|
||||
@ -676,7 +557,6 @@ static int up_interrupts(int irq, void *context)
|
||||
*/
|
||||
|
||||
if ((s1 & UART_S1_RDRF) != 0)
|
||||
#endif
|
||||
{
|
||||
/* Process incoming bytes */
|
||||
|
||||
@ -686,14 +566,6 @@ static int up_interrupts(int irq, void *context)
|
||||
|
||||
/* Handle outgoing, transmit bytes */
|
||||
|
||||
#ifdef CONFIG_KL_UARTFIFOS
|
||||
/* Read the number of bytes currently in the FIFO and compare that to
|
||||
* the size of the FIFO. If there are fewer bytes in the FIFO than
|
||||
* the size of the FIFO, then we are able to transmit.
|
||||
*/
|
||||
|
||||
# error "Missing logic"
|
||||
#else
|
||||
/* Check if the transmit data register is "empty." NOTE: If FIFOS
|
||||
* are enabled, this does not mean that the the FIFO is empty, rather,
|
||||
* it means that the the number of bytes in the TX FIFO is below the
|
||||
@ -705,13 +577,25 @@ static int up_interrupts(int irq, void *context)
|
||||
*/
|
||||
|
||||
if ((s1 & UART_S1_TDRE) != 0)
|
||||
#endif
|
||||
{
|
||||
/* Process outgoing bytes */
|
||||
|
||||
uart_xmitchars(dev);
|
||||
handled = true;
|
||||
}
|
||||
|
||||
/* Handle error interrupts. This interrupt may be caused by:
|
||||
*
|
||||
* FE: Framing error. To clear FE, write a logic one to the FE flag.
|
||||
* NF: Noise flag. To clear NF, write logic one to the NF.
|
||||
* PF: Parity error flag. To clear PF, write a logic one to the PF.
|
||||
* OR: Receiver Overrun Flag. To clear OR, write a logic 1 to the OR flag.
|
||||
*/
|
||||
|
||||
if ((s1 & UART_S1_ERRORS) != 0)
|
||||
{
|
||||
up_serialout(priv, KL_UART_S1_OFFSET, (s1 & UART_S1_ERRORS));
|
||||
}
|
||||
}
|
||||
|
||||
return OK;
|
||||
@ -824,12 +708,7 @@ static void up_rxint(struct uart_dev_s *dev, bool enable)
|
||||
}
|
||||
else
|
||||
{
|
||||
#ifdef CONFIG_DEBUG
|
||||
# warning "Revisit: How are errors enabled?"
|
||||
priv->ie |= UART_C2_RIE;
|
||||
#else
|
||||
priv->ie |= UART_C2_RIE;
|
||||
#endif
|
||||
up_setuartint(priv);
|
||||
}
|
||||
|
||||
@ -847,14 +726,7 @@ static void up_rxint(struct uart_dev_s *dev, bool enable)
|
||||
static bool up_rxavailable(struct uart_dev_s *dev)
|
||||
{
|
||||
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
|
||||
#ifdef CONFIG_KL_UARTFIFOS
|
||||
unsigned int count;
|
||||
|
||||
/* Return true if there are any bytes in the RX FIFO */
|
||||
|
||||
count = up_serialin(priv, KL_UART_RCFIFO_OFFSET);
|
||||
return count > 0;
|
||||
#else
|
||||
/* Return true if the receive data register is full (RDRF). NOTE: If
|
||||
* FIFOS are enabled, this does not mean that the the FIFO is full,
|
||||
* rather, it means that the the number of bytes in the RX FIFO has
|
||||
@ -863,7 +735,6 @@ static bool up_rxavailable(struct uart_dev_s *dev)
|
||||
*/
|
||||
|
||||
return (up_serialin(priv, KL_UART_S1_OFFSET) & UART_S1_RDRF) != 0;
|
||||
#endif
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
@ -932,14 +803,6 @@ static bool up_txready(struct uart_dev_s *dev)
|
||||
{
|
||||
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
|
||||
|
||||
#ifdef CONFIG_KL_UARTFIFOS
|
||||
/* Read the number of bytes currently in the FIFO and compare that to the
|
||||
* size of the FIFO. If there are fewer bytes in the FIFO than the size
|
||||
* of the FIFO, then we are able to transmit.
|
||||
*/
|
||||
|
||||
# error "Missing logic"
|
||||
#else
|
||||
/* Return true if the transmit data register is "empty." NOTE: If
|
||||
* FIFOS are enabled, this does not mean that the the FIFO is empty,
|
||||
* rather, it means that the the number of bytes in the TX FIFO is
|
||||
@ -948,28 +811,8 @@ static bool up_txready(struct uart_dev_s *dev)
|
||||
*/
|
||||
|
||||
return (up_serialin(priv, KL_UART_S1_OFFSET) & UART_S1_TDRE) != 0;
|
||||
#endif
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_txempty
|
||||
*
|
||||
* Description:
|
||||
* Return true if the tranmsit data register is empty
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef CONFIG_KL_UARTFIFOS
|
||||
static bool up_txempty(struct uart_dev_s *dev)
|
||||
{
|
||||
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
|
||||
|
||||
/* Return true if the transmit buffer/fifo is "empty." */
|
||||
|
||||
return (up_serialin(priv, KL_UART_SFIFO_OFFSET) & UART_SFIFO_TXEMPT) != 0;
|
||||
}
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
@ -50,6 +50,8 @@
|
||||
#include "up_arch.h"
|
||||
#include "up_internal.h"
|
||||
|
||||
#include "chip/kl_sim.h"
|
||||
|
||||
#include "kl_config.h"
|
||||
#include "kl_lowputc.h"
|
||||
#include "kl_userspace.h"
|
||||
@ -102,14 +104,6 @@ const uint32_t g_idle_topstack = IDLE_STACK;
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
void iprintf(const char *string)
|
||||
{
|
||||
while(*string != '\0')
|
||||
{
|
||||
kl_lowputc((char) *string++);
|
||||
}
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: _start
|
||||
*
|
||||
@ -122,23 +116,17 @@ void __start(void)
|
||||
{
|
||||
const uint32_t *src;
|
||||
uint32_t *dest;
|
||||
volatile unsigned int *SIM_COPC = ((volatile unsigned int *)0x40048100);
|
||||
//int i = 0;
|
||||
|
||||
/*acassis: disable SIM_COP*/
|
||||
*SIM_COPC = 0;
|
||||
/* Disable the watchdog */
|
||||
|
||||
putreg32(0, KL_SIM_COPC);
|
||||
|
||||
/* Configure the uart so that we can get debug output as soon as possible */
|
||||
|
||||
kl_clockconfig();
|
||||
kl_lowsetup();
|
||||
//uart_init();
|
||||
showprogress('A');
|
||||
|
||||
/* Blink blue LED to indicate we are here */
|
||||
//for (; ; i++)
|
||||
// blueled(i & 0x10000);
|
||||
|
||||
/* Clear .bss. We'll do this inline (vs. calling memset) just to be
|
||||
* certain that there are no issues with the state of global variables.
|
||||
*/
|
||||
@ -186,12 +174,8 @@ void __start(void)
|
||||
|
||||
/* Then start NuttX */
|
||||
|
||||
//iprintf("\r\nWelcome to NuttX!\r\n");
|
||||
|
||||
//showprogress('\r');
|
||||
//showprogress('\n');
|
||||
|
||||
iprintf("\r\n\r\n");
|
||||
showprogress('\r');
|
||||
showprogress('\n');
|
||||
|
||||
os_start();
|
||||
|
||||
|
@ -38,27 +38,9 @@ CONFIG_RAW_BINARY=y
|
||||
#
|
||||
# Debug Options
|
||||
#
|
||||
CONFIG_DEBUG=y
|
||||
# CONFIG_DEBUG is not set
|
||||
# CONFIG_DEBUG_VERBOSE is not set
|
||||
|
||||
#
|
||||
# Subsystem Debug Options
|
||||
#
|
||||
# CONFIG_DEBUG_MM is not set
|
||||
CONFIG_DEBUG_SCHED=y
|
||||
# CONFIG_DEBUG_FS is not set
|
||||
# CONFIG_DEBUG_LIB is not set
|
||||
# CONFIG_DEBUG_BINFMT is not set
|
||||
# CONFIG_DEBUG_GRAPHICS is not set
|
||||
|
||||
#
|
||||
# Driver Debug Options
|
||||
#
|
||||
# CONFIG_DEBUG_LEDS is not set
|
||||
# CONFIG_DEBUG_ANALOG is not set
|
||||
# CONFIG_DEBUG_GPIO is not set
|
||||
# CONFIG_DEBUG_SYMBOLS is not set
|
||||
|
||||
#
|
||||
# System Type
|
||||
#
|
||||
@ -235,7 +217,6 @@ CONFIG_TASK_NAME_SIZE=0
|
||||
CONFIG_SCHED_HAVE_PARENT=y
|
||||
CONFIG_SCHED_CHILD_STATUS=y
|
||||
CONFIG_PREALLOC_CHILDSTATUS=0
|
||||
# CONFIG_DEBUG_CHILDSTATUS is not set
|
||||
# CONFIG_JULIAN_TIME is not set
|
||||
CONFIG_START_YEAR=2013
|
||||
CONFIG_START_MONTH=2
|
||||
|
Loading…
x
Reference in New Issue
Block a user