Skip to content

Commit

Permalink
Fix issues on fe310 including interrupt handling (#46)
Browse files Browse the repository at this point in the history
* arch: fe310: Fix comments

* arch: fe310: Improve irq handling in fe310_serial.c

* arch: fe310: Fix initial interrupt status (mstatus)

Also, removed unnecessary up_enable_irq(FE310_IRQ_ECALLM)
  • Loading branch information
masayuki2009 authored and acassis committed Jan 7, 2020
1 parent 926a41f commit 4ea49c5
Show file tree
Hide file tree
Showing 6 changed files with 17 additions and 9 deletions.
1 change: 1 addition & 0 deletions arch/risc-v/include/fe310/irq.h
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,7 @@
/* In mstatus register */

#define MSTATUS_MIE (0x1 << 3) /* Machine Interrupt Enable */
#define MSTATUS_MPIE (0x1 << 7) /* Machine Previous Interrupt Enable */

/* In mie (machine interrupt enable) register */

Expand Down
2 changes: 1 addition & 1 deletion arch/risc-v/src/fe310/fe310_clockconfig.c
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
/****************************************************************************
* arch/arm/src/fe310/fe310_clockconfig.c
* arch/risc-v/src/fe310/fe310_clockconfig.c
*
* Copyright (C) 2019 Masayuki Ishikawa. All rights reserved.
* Author: Masayuki Ishikawa <masayuki.ishikawa@gmail.com>
Expand Down
2 changes: 1 addition & 1 deletion arch/risc-v/src/fe310/fe310_clockconfig.h
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
/****************************************************************************
* arch/arm/src/fe310/fe310_clockconfig.h
* arch/risc-v/src/fe310/fe310_clockconfig.h
*
* Copyright (C) 2019 Masayuki Ishikawa. All rights reserved.
* Author: Masayuki Ishikawa <masayuki.ishikawa@gmail.com>
Expand Down
2 changes: 1 addition & 1 deletion arch/risc-v/src/fe310/fe310_gpio.c
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
/****************************************************************************
* arch/arm/src/fe310/fe310_gpio.c
* arch/risc-v/src/fe310/fe310_gpio.c
*
* Copyright (C) 2019 Masayuki Ishikawa. All rights reserved.
* Author: Masayuki Ishikawa <masayuki.ishikawa@gmail.com>
Expand Down
7 changes: 3 additions & 4 deletions arch/risc-v/src/fe310/fe310_irq.c
Original file line number Diff line number Diff line change
Expand Up @@ -100,7 +100,6 @@ void up_irqinitialize(void)
/* Attach the ecall interrupt handler */

irq_attach(FE310_IRQ_ECALLM, up_swint, NULL);
up_enable_irq(FE310_IRQ_ECALLM);

#ifndef CONFIG_SUPPRESS_INTERRUPTS

Expand Down Expand Up @@ -188,13 +187,13 @@ void up_enable_irq(int irq)
* Name: up_get_newintctx
*
* Description:
* Return a value for EPIC. But FE310 doesn't use EPIC for event control.
* Return initial mstatus when a task is created.
*
****************************************************************************/

uint32_t up_get_newintctx(void)
{
return 0;
return (MSTATUS_MPIE | MSTATUS_MIE);
}

/****************************************************************************
Expand Down Expand Up @@ -238,7 +237,7 @@ irqstate_t up_irq_save(void)

void up_irq_restore(irqstate_t flags)
{
/* Machine mode - mstatus */
/* Write flags to mstatus */

asm volatile("csrw mstatus, %0" : /* no output */ : "r" (flags));
}
Expand Down
12 changes: 10 additions & 2 deletions arch/risc-v/src/fe310/fe310_serial.c
Original file line number Diff line number Diff line change
Expand Up @@ -398,16 +398,24 @@ static int up_interrupt(int irq, void *context, FAR void *arg)

status = up_serialin(priv, UART_IP_OFFSET);

if (status == 0)
{
break;
}

if (status & UART_IP_RXWM)
{
/* Process incoming bytes */

uart_recvchars(dev);
}

/* Process outgoing bytes */
if (status & UART_IP_TXWM)
{
/* Process outgoing bytes */

uart_xmitchars(dev);
uart_xmitchars(dev);
}
}

return OK;
Expand Down

0 comments on commit 4ea49c5

Please sign in to comment.