Merged in masayuki2009/nuttx.nuttx/fe310_gpio (pull request #1097)

fe310 gpio

* arch: risc-v: Add arch/risc-v/src/common/up_mdelay.c

* arch: risc-v: Add arch/risc-v/src/common/up_udelay.c

* arch: fe310: Add #include <stdint.h> to fe310_start.c

* arch: risc-v: Add up_ack_irq() definition to commpn/up_internal.h

* arch: fe310: Add FE310 GPIO driver

* boards: hifive-revb: Add compiler optimization

* boards: hifive1-revb: Add auto leds related files.

* arch: fe310: Add CPU activity led to fe310_idle.c

* boards: hifive-revb: Add a button

    NOTE: still having a trouble in signal handling.

Approved-by: Gregory Nutt <gnutt@nuttx.org>
This commit is contained in:
Masayuki Ishikawa 2019-12-19 04:59:30 +00:00 committed by Gregory Nutt
parent 13038d03c2
commit 466ab56c10
23 changed files with 1101 additions and 26 deletions

View File

@ -82,9 +82,42 @@
#define FE310_IRQ_UART0 (FE310_IRQ_MEXT + 3)
#define FE310_IRQ_UART1 (FE310_IRQ_MEXT + 4)
#define FE310_IRQ_GPIO0 (FE310_IRQ_MEXT + 8)
#define FE310_IRQ_GPIO1 (FE310_IRQ_MEXT + 9)
#define FE310_IRQ_GPIO2 (FE310_IRQ_MEXT + 10)
#define FE310_IRQ_GPIO3 (FE310_IRQ_MEXT + 11)
#define FE310_IRQ_GPIO4 (FE310_IRQ_MEXT + 12)
#define FE310_IRQ_GPIO5 (FE310_IRQ_MEXT + 13)
#define FE310_IRQ_GPIO6 (FE310_IRQ_MEXT + 14)
#define FE310_IRQ_GPIO7 (FE310_IRQ_MEXT + 15)
#define FE310_IRQ_GPIO8 (FE310_IRQ_MEXT + 16)
#define FE310_IRQ_GPIO9 (FE310_IRQ_MEXT + 17)
#define FE310_IRQ_GPIO10 (FE310_IRQ_MEXT + 18)
#define FE310_IRQ_GPIO11 (FE310_IRQ_MEXT + 19)
#define FE310_IRQ_GPIO12 (FE310_IRQ_MEXT + 20)
#define FE310_IRQ_GPIO13 (FE310_IRQ_MEXT + 21)
#define FE310_IRQ_GPIO14 (FE310_IRQ_MEXT + 22)
#define FE310_IRQ_GPIO15 (FE310_IRQ_MEXT + 23)
#define FE310_IRQ_GPIO16 (FE310_IRQ_MEXT + 24)
#define FE310_IRQ_GPIO17 (FE310_IRQ_MEXT + 25)
#define FE310_IRQ_GPIO18 (FE310_IRQ_MEXT + 26)
#define FE310_IRQ_GPIO19 (FE310_IRQ_MEXT + 27)
#define FE310_IRQ_GPIO20 (FE310_IRQ_MEXT + 28)
#define FE310_IRQ_GPIO21 (FE310_IRQ_MEXT + 29)
#define FE310_IRQ_GPIO22 (FE310_IRQ_MEXT + 30)
#define FE310_IRQ_GPIO23 (FE310_IRQ_MEXT + 31)
#define FE310_IRQ_GPIO24 (FE310_IRQ_MEXT + 32)
#define FE310_IRQ_GPIO25 (FE310_IRQ_MEXT + 33)
#define FE310_IRQ_GPIO26 (FE310_IRQ_MEXT + 34)
#define FE310_IRQ_GPIO27 (FE310_IRQ_MEXT + 35)
#define FE310_IRQ_GPIO28 (FE310_IRQ_MEXT + 36)
#define FE310_IRQ_GPIO29 (FE310_IRQ_MEXT + 37)
#define FE310_IRQ_GPIO30 (FE310_IRQ_MEXT + 38)
#define FE310_IRQ_GPIO31 (FE310_IRQ_MEXT + 39)
/* Total number of IRQs */
#define NR_IRQS (FE310_IRQ_UART1 + 1)
#define NR_IRQS (FE310_IRQ_GPIO31 + 1)
/****************************************************************************
* Public Types

View File

@ -161,6 +161,8 @@ void up_allocate_heap(FAR void **heap_start, size_t *heap_size);
/* IRQ initialization *******************************************************/
void up_irqinitialize(void);
void up_ack_irq(int irq);
void up_copystate(uint32_t *dest, uint32_t *src);
void up_sigdeliver(void);
int up_swint(int irq, FAR void *context, FAR void *arg);

View File

@ -0,0 +1,70 @@
/****************************************************************************
* arch/risc-v/src/common/up_mdelay.c
*
* Copyright (C) 2007, 2008, 2014 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 unsigned int i;
volatile unsigned int j;
for (i = 0; i < milliseconds; i++)
{
for (j = 0; j < CONFIG_BOARD_LOOPSPERMSEC; j++)
{
}
}
}

View File

@ -0,0 +1,117 @@
/****************************************************************************
* arch/risc-v/src/common/up_udelay.c
*
* Copyright (C) 2007, 2008 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 <nuttx/arch.h>
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define CONFIG_BOARD_LOOPSPER100USEC ((CONFIG_BOARD_LOOPSPERMSEC+5)/10)
#define CONFIG_BOARD_LOOPSPER10USEC ((CONFIG_BOARD_LOOPSPERMSEC+50)/100)
#define CONFIG_BOARD_LOOPSPERUSEC ((CONFIG_BOARD_LOOPSPERMSEC+500)/1000)
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: up_udelay
*
* Description:
* Delay inline for the requested number of microseconds. NOTE: Because
* of all of the setup, several microseconds will be lost before the actual
* timing loop begins. Thus, the delay will always be a few microseconds
* longer than requested.
*
* *** NOT multi-tasking friendly ***
*
* ASSUMPTIONS:
* The setting CONFIG_BOARD_LOOPSPERMSEC has been calibrated
*
****************************************************************************/
void up_udelay(useconds_t microseconds)
{
volatile int i;
/* We'll do this a little at a time because we expect that the
* CONFIG_BOARD_LOOPSPERUSEC is very inaccurate during to truncation in
* the divisions of its calculation. We'll use the largest values that
* we can in order to prevent significant error buildup in the loops.
*/
while (microseconds > 1000)
{
for (i = 0; i < CONFIG_BOARD_LOOPSPERMSEC; i++)
{
}
microseconds -= 1000;
}
while (microseconds > 100)
{
for (i = 0; i < CONFIG_BOARD_LOOPSPER100USEC; i++)
{
}
microseconds -= 100;
}
while (microseconds > 10)
{
for (i = 0; i < CONFIG_BOARD_LOOPSPER10USEC; i++)
{
}
microseconds -= 10;
}
while (microseconds > 0)
{
for (i = 0; i < CONFIG_BOARD_LOOPSPERUSEC; i++)
{
}
microseconds--;
}
}

View File

@ -41,10 +41,10 @@ CHIP_ASRCS = fe310_head.S up_syscall.S
CMN_CSRCS += up_initialize.c up_swint.c
CMN_CSRCS += up_allocateheap.c up_createstack.c up_exit.c
CMN_CSRCS += up_assert.c up_blocktask.c up_copystate.c up_initialstate.c
CMN_CSRCS += up_interruptcontext.c up_modifyreg32.c up_puts.c
CMN_CSRCS += up_interruptcontext.c up_modifyreg32.c up_puts.c up_mdelay.c
CMN_CSRCS += up_releasepending.c up_reprioritizertr.c
CMN_CSRCS += up_releasestack.c up_stackframe.c up_schedulesigaction.c
CMN_CSRCS += up_sigdeliver.c up_unblocktask.c up_usestack.c
CMN_CSRCS += up_sigdeliver.c up_udelay.c up_unblocktask.c up_usestack.c
ifeq ($(CONFIG_STACK_COLORATION),y)
CMN_CSRCS += up_checkstack.c
@ -55,8 +55,8 @@ CMN_CSRCS += up_vfork.c
endif
# Specify our C code within this directory to be included
CHIP_CSRCS = fe310_allocateheap.c fe310_clockconfig.c fe310_idle.c
CHIP_CSRCS += fe310_irq.c fe310_irq_dispatch.c
CHIP_CSRCS = fe310_allocateheap.c fe310_clockconfig.c fe310_gpio.c
CHIP_CSRCS += fe310_idle.c fe310_irq.c fe310_irq_dispatch.c
CHIP_CSRCS += fe310_lowputc.c fe310_serial.c
CHIP_CSRCS += fe310_start.c fe310_timerisr.c

View File

@ -0,0 +1,244 @@
/****************************************************************************
* arch/arm/src/fe310/fe310_gpio.c
*
* Copyright (C) 2019 Masayuki Ishikawa. All rights reserved.
* Author: Masayuki Ishikawa <masayuki.ishikawa@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 <stdint.h>
#include <assert.h>
#include <debug.h>
#include <nuttx/arch.h>
#include <arch/board/board.h>
#include "up_arch.h"
#include "fe310_gpio.h"
#include "fe310_memorymap.h"
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: fe310_gpio_getpin()
****************************************************************************/
static uint32_t fe310_gpio_getpin(uint16_t gpiocfg)
{
return ((gpiocfg & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT);
}
/****************************************************************************
* Name: fe310_gpio_configinput()
****************************************************************************/
static int fe310_gpio_configinput(uint16_t gpiocfg)
{
uint32_t pin = fe310_gpio_getpin(gpiocfg);
/* Enable input & disable output */
modifyreg32(FE310_GPIO_INPUT_EN, 0, 0x1 << pin);
modifyreg32(FE310_GPIO_OUTPUT_EN, 0x1 << pin, 0);
return 0;
}
/****************************************************************************
* Name: fe310_gpio_configirq()
****************************************************************************/
static int fe310_gpio_configirq(uint16_t gpiocfg)
{
uint32_t pin = fe310_gpio_getpin(gpiocfg);
/* Enable input & disable output */
modifyreg32(FE310_GPIO_INPUT_EN, 0, 0x1 << pin);
modifyreg32(FE310_GPIO_OUTPUT_EN, 0x1 << pin, 0);
/* Disable all gpio interrupts for the pin */
modifyreg32(FE310_GPIO_RISE_IE, 0x1 << pin, 0x0);
modifyreg32(FE310_GPIO_FALL_IE, 0x1 << pin, 0x0);
modifyreg32(FE310_GPIO_HIGH_IE, 0x1 << pin, 0x0);
modifyreg32(FE310_GPIO_LOW_IE, 0x1 << pin, 0x0);
/* Then enable interrupt */
switch (gpiocfg & GPIO_INT_MASK)
{
case GPIO_INT_RISE:
modifyreg32(FE310_GPIO_RISE_IE, 0, 0x1 << pin);
break;
case GPIO_INT_FALL:
modifyreg32(FE310_GPIO_FALL_IE, 0, 0x1 << pin);
break;
case GPIO_INT_BOTH:
modifyreg32(FE310_GPIO_RISE_IE, 0, 0x1 << pin);
modifyreg32(FE310_GPIO_FALL_IE, 0, 0x1 << pin);
break;
case GPIO_INT_HIGH:
modifyreg32(FE310_GPIO_HIGH_IE, 0, 0x1 << pin);
break;
case GPIO_INT_LOW:
modifyreg32(FE310_GPIO_LOW_IE, 0, 0x1 << pin);
break;
}
return 0;
}
/****************************************************************************
* Name: fe310_gpio_configoutput()
****************************************************************************/
static int fe310_gpio_configoutput(uint16_t gpiocfg)
{
uint32_t pin = fe310_gpio_getpin(gpiocfg);
/* TOD: set initial value */
/* Disable input & enable output */
modifyreg32(FE310_GPIO_INPUT_EN, 0x1 << pin, 0);
modifyreg32(FE310_GPIO_OUTPUT_EN, 0, 0x1 << pin);
return 0;
}
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: fe310_gpio_config
****************************************************************************/
int fe310_gpio_config(uint16_t gpiocfg)
{
int ret = 0;
irqstate_t flags;
uint32_t pin = fe310_gpio_getpin(gpiocfg);
flags = spin_lock_irqsave();
/* Disable IOF for the pin to be used as GPIO */
modifyreg32(FE310_GPIO_IOF_EN, 0x1 << pin, 0);
/* Pullup */
if (gpiocfg & GPIO_PULLUP)
{
modifyreg32(FE310_GPIO_PU_EN, 0, 0x1 << pin);
}
else
{
modifyreg32(FE310_GPIO_PU_EN, 0x1 << pin, 0);
}
switch (gpiocfg & GPIO_MODE_MASK)
{
case GPIO_MODE_INPUT:
ret = fe310_gpio_configinput(gpiocfg);
break;
case GPIO_MODE_OUTPUT:
ret = fe310_gpio_configoutput(gpiocfg);
break;
case GPIO_MODE_INIRQ:
ret = fe310_gpio_configirq(gpiocfg);
break;
}
spin_unlock_irqrestore(flags);
return ret;
}
/****************************************************************************
* Name: fe310_gpio_write
****************************************************************************/
void fe310_gpio_write(uint16_t gpiocfg, bool value)
{
uint32_t pin = fe310_gpio_getpin(gpiocfg);
if (value)
{
modifyreg32(FE310_GPIO_OUTPUT_VAL, 0, 0x1 << pin);
}
else
{
modifyreg32(FE310_GPIO_OUTPUT_VAL, 0x1 << pin, 0);
}
}
/****************************************************************************
* Name: fe310_gpio_read
****************************************************************************/
bool fe310_gpio_read(uint16_t gpiocfg)
{
uint32_t pin = fe310_gpio_getpin(gpiocfg);
return (getreg32(FE310_GPIO_INPUT_VAL) & (0x1 << pin)) != 0;
}
/****************************************************************************
* Name: fe310_gpio_clearpending
****************************************************************************/
void fe310_gpio_clearpending(uint32_t pin)
{
ASSERT(0 <= pin && pin <= 31);
/* Clear all gpio interrupts for the pin */
modifyreg32(FE310_GPIO_RISE_IP, 0x0, 0x1 << pin);
modifyreg32(FE310_GPIO_FALL_IP, 0x0, 0x1 << pin);
modifyreg32(FE310_GPIO_HIGH_IP, 0x0, 0x1 << pin);
modifyreg32(FE310_GPIO_LOW_IP, 0x0, 0x1 << pin);
}

View File

@ -0,0 +1,205 @@
/****************************************************************************
* arch/risc-v/src/fe310/fe310_gpio.h
*
* Copyright (C) 2019 Masayuki Ishikawa. All rights reserved.
* Author: Masayuki Ishikawa <masayuki.ishikawa@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_RISCV_SRC_FE310_FE310_GPIO_H
#define __ARCH_RISCV_SRC_FE310_FE310_GPIO_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <stdint.h>
#include "up_internal.h"
#include "chip.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* Input/Output mode
*
* 1111 1100 0000 0000
* 5432 1098 7654 3210
* ---- ---- ---- ----
* MM.. .... .... ....
*/
#define GPIO_MODE_SHIFT (14) /* Bits 14-15: Mode of the GPIO pin */
#define GPIO_MODE_MASK (3 << GPIO_MODE_SHIFT)
#define GPIO_MODE_INPUT (0 << GPIO_MODE_SHIFT) /* input */
#define GPIO_MODE_OUTPUT (1 << GPIO_MODE_SHIFT) /* output */
#define GPIO_MODE_INIRQ (2 << GPIO_MODE_SHIFT) /* input interrupt */
#define GPIO_MODE_OUTPUT_INV (3 << GPIO_MODE_SHIFT) /* output inverted */
/* Initial value (for GPIO outputs only)
*
* 1111 1100 0000 0000
* 5432 1098 7654 3210
* ---- ---- ---- ----
* ..V. .... .... ....
*/
#define GPIO_VALUE_SHIFT (13) /* Bits 13: Value of the GPIO pin */
#define GPIO_VALUE_MASK (1 << GPIO_VALUE_SHIFT)
#define GPIO_VALUE_ZERO (0 << GPIO_VALUE_SHIFT)
#define GPIO_VALUE_ONE (1 << GPIO_VALUE_SHIFT)
/* GPIO IOF selection
*
* 1111 1100 0000 0000
* 5432 1098 7654 3210
* ---- ---- ---- ----
* .... XX.. .... ....
*/
#define GPIO_IOF_SHIFT (10) /* Bits 10-11: IOF_SEL */
#define GPIO_IOF_MASK (3 << GPIO_IOF_SHIFT)
#define GPIO_IOF_GPIO (0 << GPIO_IOF_SHIFT) /* GPIO */
#define GPIO_IOF_0 (1 << GPIO_IOF_SHIFT) /* IOF0 */
#define GPIO_IOF_1 (2 << GPIO_IOF_SHIFT) /* IOF1 */
/* GPIO pull-up (NOTE: FE310 only supports pull-up)
*
* 1111 1100 0000 0000
* 5432 1098 7654 3210
* ---- ---- ---- ----
* .... ...U .... ....
*/
#define GPIO_PULL_SHIFT (8) /* Bits 8: Pull-up */
#define GPIO_PULL_MASK (1 << GPIO_PULL_SHIFT)
#define GPIO_DEFAULT (0 << GPIO_PULL_SHIFT)
#define GPIO_PULLUP (1 << GPIO_PULL_SHIFT)
/* GPIO interrupt
*
* 1111 1100 0000 0000
* 5432 1098 7654 3210
* ---- ---- ---- ----
* .... .... III. ....
*/
#define GPIO_INT_SHIFT (5) /* Bits 5-7: Interrupt */
#define GPIO_INT_MASK (7 << GPIO_INT_SHIFT)
#define GPIO_INT_RISE (0 << GPIO_INT_SHIFT)
#define GPIO_INT_FALL (1 << GPIO_INT_SHIFT)
#define GPIO_INT_BOTH (2 << GPIO_INT_SHIFT) /* Both edges */
#define GPIO_INT_HIGH (3 << GPIO_INT_SHIFT)
#define GPIO_INT_LOW (4 << GPIO_INT_SHIFT)
/* GPIO Pin Number:
*
* 1111 1100 0000 0000
* 5432 1098 7654 3210
* ---- ---- ---- ----
* .... .... ...P PPPP
*/
#define GPIO_PIN_SHIFT (0) /* Bits 0-4: Pin number */
#define GPIO_PIN_MASK (31 << GPIO_PIN_SHIFT)
#define GPIO_PIN0 (0 << GPIO_PIN_SHIFT)
#define GPIO_PIN1 (1 << GPIO_PIN_SHIFT)
#define GPIO_PIN2 (2 << GPIO_PIN_SHIFT)
#define GPIO_PIN3 (3 << GPIO_PIN_SHIFT)
#define GPIO_PIN4 (4 << GPIO_PIN_SHIFT)
#define GPIO_PIN5 (5 << GPIO_PIN_SHIFT)
#define GPIO_PIN6 (6 << GPIO_PIN_SHIFT)
#define GPIO_PIN7 (7 << GPIO_PIN_SHIFT)
#define GPIO_PIN8 (8 << GPIO_PIN_SHIFT)
#define GPIO_PIN9 (9 << GPIO_PIN_SHIFT)
#define GPIO_PIN10 (10 << GPIO_PIN_SHIFT)
#define GPIO_PIN11 (11 << GPIO_PIN_SHIFT)
#define GPIO_PIN12 (12 << GPIO_PIN_SHIFT)
#define GPIO_PIN13 (13 << GPIO_PIN_SHIFT)
#define GPIO_PIN14 (14 << GPIO_PIN_SHIFT)
#define GPIO_PIN15 (15 << GPIO_PIN_SHIFT)
#define GPIO_PIN16 (16 << GPIO_PIN_SHIFT)
#define GPIO_PIN17 (17 << GPIO_PIN_SHIFT)
#define GPIO_PIN18 (18 << GPIO_PIN_SHIFT)
#define GPIO_PIN19 (19 << GPIO_PIN_SHIFT)
#define GPIO_PIN20 (20 << GPIO_PIN_SHIFT)
#define GPIO_PIN21 (21 << GPIO_PIN_SHIFT)
#define GPIO_PIN22 (22 << GPIO_PIN_SHIFT)
#define GPIO_PIN23 (23 << GPIO_PIN_SHIFT)
/****************************************************************************
* Public Functions
****************************************************************************/
#ifndef __ASSEMBLY__
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
/****************************************************************************
* Name: fe310_gpio_config
****************************************************************************/
EXTERN int fe310_gpio_config(uint16_t gpiocfg);
/****************************************************************************
* Name: fe310_gpio_write
****************************************************************************/
EXTERN void fe310_gpio_write(uint16_t gpiocfg, bool value);
/****************************************************************************
* Name: fe310_gpio_read
****************************************************************************/
EXTERN bool fe310_gpio_read(uint16_t gpiocfg);
/****************************************************************************
* Name: fe310_gpio_clearpending
****************************************************************************/
EXTERN void fe310_gpio_clearpending(uint32_t pin);
#undef EXTERN
#if defined(__cplusplus)
}
#endif
#endif /* __ASSEMBLY__ */
#endif /* __ARCH_RISCV_SRC_FE310_FE310_GPIO_H */

View File

@ -42,6 +42,8 @@
#include <nuttx/config.h>
#include <nuttx/irq.h>
#include <nuttx/arch.h>
#include <nuttx/board.h>
#include <arch/board/board.h>
#include "up_internal.h"
@ -72,6 +74,8 @@ void up_idle(void)
nxsched_process_timer();
#else
board_autoled_off(LED_CPU);
/* This would be an appropriate place to put some MCU-specific logic to
* sleep in a reduced power mode until an interrupt occurs to save power
*/

View File

@ -44,7 +44,9 @@
#include <debug.h>
#include <nuttx/arch.h>
#include <nuttx/board.h>
#include <arch/irq.h>
#include <arch/board/board.h>
#include "up_internal.h"
#include "up_arch.h"
@ -130,11 +132,18 @@ void up_disable_irq(int irq)
else if (irq > FE310_IRQ_MEXT)
{
extirq = irq - FE310_IRQ_MEXT;
ASSERT(31 >= extirq); /* TODO */
/* Clear enable bit for the irq */
modifyreg32(FE310_PLIC_ENABLE1, 1 << extirq, 0);
if (0 <= extirq && extirq <= 63)
{
modifyreg32(FE310_PLIC_ENABLE1 + (4 * (extirq / 32)),
1 << (extirq % 32), 0);
}
else
{
ASSERT(false);
}
}
}
@ -160,11 +169,18 @@ void up_enable_irq(int irq)
else if (irq > FE310_IRQ_MEXT)
{
extirq = irq - FE310_IRQ_MEXT;
ASSERT(31 >= extirq); /* TODO */
/* Set enable bit for the irq */
modifyreg32(FE310_PLIC_ENABLE1, 0, 1 << extirq);
if (0 <= extirq && extirq <= 63)
{
modifyreg32(FE310_PLIC_ENABLE1 + (4 * (extirq / 32)),
0, 1 << (extirq % 32));
}
else
{
ASSERT(false);
}
}
}
@ -191,6 +207,7 @@ uint32_t up_get_newintctx(void)
void up_ack_irq(int irq)
{
board_autoled_on(LED_CPU);
}
/****************************************************************************

View File

@ -47,7 +47,8 @@
#include "up_arch.h"
#include "up_internal.h"
#include "group/group.h"
#include "fe310_gpio.h"
#include "fe310.h"
/****************************************************************************
* Public Data
@ -68,12 +69,13 @@ void *fe310_dispatch_irq(uint32_t vector, uint32_t *regs)
uint32_t irq = (vector >> 27) | (vector & 0xf);
uint32_t *mepc = regs;
/* Firstly, check if the irq is machine external interrupt */
if (FE310_IRQ_MEXT == irq)
{
/* Read & write FE310_PLIC_CLAIM to clear pending */
uint32_t val = getreg32(FE310_PLIC_CLAIM);
putreg32(val, FE310_PLIC_CLAIM);
/* Add the value to nuttx irq which is offset to the mext */
irq += val;
}
@ -85,6 +87,10 @@ void *fe310_dispatch_irq(uint32_t vector, uint32_t *regs)
*mepc += 4;
}
/* Acknowledge the interrupt */
up_ack_irq(irq);
#ifdef CONFIG_SUPPRESS_INTERRUPTS
PANIC();
#else
@ -100,6 +106,20 @@ void *fe310_dispatch_irq(uint32_t vector, uint32_t *regs)
/* Deliver the IRQ */
irq_dispatch(irq, regs);
if (FE310_IRQ_MEXT <= irq)
{
/* If the irq is from GPIO, clear pending bit in the GPIO */
if (FE310_IRQ_GPIO0 <= irq && irq <= FE310_IRQ_GPIO31)
{
fe310_gpio_clearpending(irq - FE310_IRQ_GPIO0);
}
/* Then write PLIC_CLAIM to clear pending in PLIC */
putreg32(irq - FE310_IRQ_MEXT, FE310_PLIC_CLAIM);
}
#endif
/* If a context switch occurred while processing the interrupt then

View File

@ -40,6 +40,7 @@
#include "hardware/fe310_memorymap.h"
#include "hardware/fe310_uart.h"
#include "hardware/fe310_clint.h"
#include "hardware/fe310_gpio.h"
#include "hardware/fe310_plic.h"
#include "hardware/fe310_prci.h"

View File

@ -34,6 +34,8 @@
* Included Files
****************************************************************************/
#include <stdint.h>
#include <nuttx/config.h>
#include <arch/board/board.h>

View File

@ -0,0 +1,58 @@
/****************************************************************************
* arch/risc-v/src/fe310/hardware/fe310_gpio.h
*
* Copyright (C) 2019 Masayuki Ishikawa. All rights reserved.
* Author: Masayuki Ishikawa <masayuki.ishikawa@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.
*
* 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_RISCV_SRC_FE310_HARDWARE_FE310_GPIO_H
#define __ARCH_RISCV_SRC_FE310_HARDWARE_FE310_GPIO_H
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define FE310_GPIO_INPUT_VAL (FE310_GPIO_BASE + 0x00)
#define FE310_GPIO_INPUT_EN (FE310_GPIO_BASE + 0x04)
#define FE310_GPIO_OUTPUT_EN (FE310_GPIO_BASE + 0x08)
#define FE310_GPIO_OUTPUT_VAL (FE310_GPIO_BASE + 0x0c)
#define FE310_GPIO_PU_EN (FE310_GPIO_BASE + 0x10)
#define FE310_GPIO_DS (FE310_GPIO_BASE + 0x14)
#define FE310_GPIO_RISE_IE (FE310_GPIO_BASE + 0x18)
#define FE310_GPIO_RISE_IP (FE310_GPIO_BASE + 0x1c)
#define FE310_GPIO_FALL_IE (FE310_GPIO_BASE + 0x20)
#define FE310_GPIO_FALL_IP (FE310_GPIO_BASE + 0x24)
#define FE310_GPIO_HIGH_IE (FE310_GPIO_BASE + 0x28)
#define FE310_GPIO_HIGH_IP (FE310_GPIO_BASE + 0x2c)
#define FE310_GPIO_LOW_IE (FE310_GPIO_BASE + 0x30)
#define FE310_GPIO_LOW_IP (FE310_GPIO_BASE + 0x34)
#define FE310_GPIO_IOF_EN (FE310_GPIO_BASE + 0x38)
#define FE310_GPIO_IOF_SEL (FE310_GPIO_BASE + 0x3c)
#define FE310_GPIO_OUTPUT_XOR (FE310_GPIO_BASE + 0x40)
#endif /* __ARCH_RISCV_SRC_FE310_HARDWARE_FE310_GPIO_H */

View File

@ -300,6 +300,9 @@ config ARCH_BOARD_GAPUINO
config ARCH_BOARD_HIFIVE1_REVB
bool "HiFive1 Rev B board"
depends on ARCH_CHIP_FE310
select ARCH_HAVE_LEDS
select ARCH_HAVE_BUTTONS
select ARCH_HAVE_IRQBUTTONS
---help---
This is the board configuration for the port of NuttX to the SiFive HiFive1
Rev B board. This board features the RISC-V FE310-G002

View File

@ -12,24 +12,34 @@
CONFIG_ARCH="risc-v"
CONFIG_ARCH_BOARD="hifive1-revb"
CONFIG_ARCH_BOARD_HIFIVE1_REVB=y
CONFIG_ARCH_BUTTONS=y
CONFIG_ARCH_CHIP="fe310"
CONFIG_ARCH_CHIP_FE310=y
CONFIG_ARCH_CHIP_FE310_G002=y
CONFIG_ARCH_INTERRUPTSTACK=1536
CONFIG_ARCH_IRQBUTTONS=y
CONFIG_ARCH_RISCV=y
CONFIG_ARCH_STACKDUMP=y
CONFIG_BINFMT_DISABLE=y
CONFIG_BOARD_LOOPSPERMSEC=15000
CONFIG_BUILTIN=y
CONFIG_BUTTONS=y
CONFIG_BUTTONS_LOWER=y
CONFIG_BUTTONS_NPOLLWAITERS=1
CONFIG_DEBUG_FULLOPT=y
CONFIG_DEBUG_SYMBOLS=y
CONFIG_DEFAULT_SMALL=y
CONFIG_DEV_ZERO=y
CONFIG_DISABLE_MQUEUE=y
CONFIG_EXAMPLES_BUTTONS=y
CONFIG_EXAMPLES_BUTTONS_NAMES=y
CONFIG_EXAMPLES_BUTTONS_QTD=1
CONFIG_EXAMPLES_BUTTONS_STACKSIZE=1572
CONFIG_EXAMPLES_HELLO=y
CONFIG_FS_PROCFS=y
CONFIG_FS_WRITABLE=y
CONFIG_IDLETHREAD_STACKSIZE=1536
CONFIG_INPUT=y
CONFIG_INTELHEX_BINARY=y
CONFIG_LIBC_PERROR_STDOUT=y
CONFIG_LIBC_STRERROR=y

View File

@ -42,11 +42,21 @@
#include <nuttx/config.h>
#ifndef __ASSEMBLY__
# include <stdint.h>
#endif
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#include "fe310.h"
#define NUM_BUTTONS 1
#define LED_STARTED 0 /* N/A */
#define LED_HEAPALLOCATE 1 /* N/A */
#define LED_IRQSENABLED 2 /* N/A */
#define LED_STACKCREATED 3 /* N/A */
#define LED_INIRQ 4 /* N/A */
#define LED_SIGNAL 5 /* N/A */
#define LED_ASSERTION 6 /* N/A */
#define LED_PANIC 7 /* N/A */
#define LED_CPU 8 /* LED */
/****************************************************************************
* Public Types

View File

@ -77,12 +77,14 @@ ifeq ($(CONFIG_DEBUG_SYMBOLS),y)
ASARCHCPUFLAGS += -Wa,-g
endif
MAXOPTIMIZATION = -Os
ifneq ($(CONFIG_DEBUG_NOOPT),y)
ARCHOPTIMIZATION += $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer
endif
ARCHCPUFLAGS = -march=rv32imac -mabi=ilp32
ARCHCFLAGS = -fno-builtin
ARCHCFLAGS = -fno-builtin -ffunction-sections -fdata-sections
ARCHCXXFLAGS = -fno-builtin -fno-exceptions -fcheck-new -fno-rtti
ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow -Wundef
ARCHWARNINGSXX = -Wall -Wshadow -Wundef
@ -105,13 +107,7 @@ OBJEXT = .o
LIBEXT = .a
EXEEXT =
ifneq ($(CROSSDEV),arm-nuttx-elf-)
LDFLAGS += -nostartfiles -nodefaultlibs -melf32lriscv
endif
ifeq ($(CONFIG_DEBUG_SYMBOLS),y)
LDFLAGS += -g -melf32lriscv
endif
LDFLAGS += --gc-sections -melf32lriscv
HOSTCC = gcc
HOSTINCLUDES = -I.

View File

@ -82,7 +82,7 @@ SECTIONS
.data : ALIGN(4) {
_sdata = ABSOLUTE(.);
*(.data .data.*)
*(.sdata .sdata.*)
*(.sdata .sdata.* .sdata2.*)
*(.gnu.linkonce.d.*)
*(.gnu.linkonce.s.*)
CONSTRUCTORS

View File

@ -41,4 +41,12 @@ ifeq ($(CONFIG_LIB_BOARDCTL),y)
CSRCS += fe310_appinit.c
endif
ifeq ($(CONFIG_ARCH_LEDS),y)
CSRCS += fe310_autoleds.c
endif
ifeq ($(CONFIG_ARCH_BUTTONS),y)
CSRCS += fe310_buttons.c
endif
include $(TOPDIR)/boards/Board.mk

View File

@ -0,0 +1,89 @@
/****************************************************************************
* boards/risc-v/fe310/hifive1-revb/src/fe310_autoleds.c
*
* Copyright (C) 2019 Masayuki Ishikawa. All rights reserved.
* Author: Masayuki Ishikawa <masayuki.ishikawa@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 <debug.h>
#include <arch/board/board.h>
#include "fe310_gpio.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define GPIO_LED (GPIO_MODE_OUTPUT | GPIO_VALUE_ONE | GPIO_PIN5)
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: board_autoled_initialize
****************************************************************************/
void board_autoled_initialize(void)
{
fe310_gpio_config(GPIO_LED);
}
/****************************************************************************
* Name: board_autoled_on
****************************************************************************/
void board_autoled_on(int led)
{
if (LED_CPU == led)
{
fe310_gpio_write(GPIO_LED, true);
}
}
/****************************************************************************
* Name: board_autoled_off
****************************************************************************/
void board_autoled_off(int led)
{
if (LED_CPU == led)
{
fe310_gpio_write(GPIO_LED, false);
}
}

View File

@ -41,6 +41,7 @@
#include <debug.h>
#include <nuttx/board.h>
#include <arch/board/board.h>
/****************************************************************************
@ -68,4 +69,9 @@
void fe310_boardinitialize(void)
{
#ifdef CONFIG_ARCH_LEDS
/* Configure on-board LEDs if LED support has been selected. */
board_autoled_initialize();
#endif
}

View File

@ -46,6 +46,7 @@
#include <errno.h>
#include <nuttx/board.h>
#include <nuttx/input/buttons.h>
#include "fe310.h"
@ -71,5 +72,15 @@ int fe310_bringup(void)
}
#endif
#ifdef CONFIG_BUTTONS
/* Register the BUTTON driver */
ret = btn_lower_initialize("/dev/buttons");
if (ret < 0)
{
serr("ERROR: btn_lower_initialize() failed: %d\n", ret);
}
#endif
return ret;
}

View File

@ -0,0 +1,169 @@
/****************************************************************************
* boards/risc-v/fe310/hifive1-revb/src/fe310_buttons.c
*
* Copyright (C) 2019 Masayuki Ishikawa. All rights reserved.
* Author: Masayuki Ishikawa <masayuki.ishikawa@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 <nuttx/board.h>
#include <nuttx/arch.h>
#include <stdbool.h>
#include <stdio.h>
#include <syslog.h>
#include <errno.h>
#include "fe310_gpio.h"
#include "fe310.h"
#include "hifive1-revb.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define GPIO_BTN (GPIO_MODE_INIRQ | GPIO_INT_BOTH | GPIO_PULLUP | GPIO_PIN23)
#define BTN_IRQ FE310_IRQ_GPIO23
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: board_button_initialize
*
* Description:
* board_button_initialize() must be called to initialize button resources.
* After that, board_buttons() may be called to collect the current state of
* all buttons or board_button_irq() may be called to register button
* interrupt handlers.
*
****************************************************************************/
void board_button_initialize(void)
{
fe310_gpio_config(GPIO_BTN);
}
/****************************************************************************
* Name: board_buttons
*
* Description:
* After board_button_initialize() has been called, board_buttons() may be
* called to collect the state of all buttons. board_buttons() returns an
* 8-bit bit set with each bit associated with a button. See the
* BUTTON_*_BIT definitions in board.h for the meaning of each bit.
*
****************************************************************************/
uint32_t board_buttons(void)
{
uint8_t ret = 0;
int i = 0;
int n = 0;
bool b0 = fe310_gpio_read(GPIO_BTN);
for (i = 0; i < 10; i++)
{
up_mdelay(1); /* TODO */
bool b1 = fe310_gpio_read(GPIO_BTN);
if (b0 == b1)
{
n++;
}
else
{
n = 0;
}
if (3 == n)
{
break;
}
b0 = b1;
}
iinfo("b=%d n=%d \n", b0, n);
/* Low value means that the button is pressed */
if (!b0)
{
ret = 0x1;
}
return ret;
}
/****************************************************************************
* Name: board_button_irq
*
* Description:
* board_button_irq() may be called to register an interrupt handler that
* will be called when a button is depressed or released. The ID value is
* a button enumeration value that uniquely identifies a button resource.
* See the BUTTON_* definitions in board.h for the meaning of enumeration
* value.
*
****************************************************************************/
#ifdef CONFIG_ARCH_IRQBUTTONS
int board_button_irq(int id, xcpt_t irqhandler, FAR void *arg)
{
int ret = -EINVAL;
ASSERT(id == 0);
if (NULL != irqhandler)
{
/* Attach the new button handler. */
ret = irq_attach(BTN_IRQ, irqhandler, arg);
/* Then make sure that interrupts are enabled on the pin */
up_enable_irq(BTN_IRQ);
}
else
{
up_disable_irq(BTN_IRQ);
}
return ret;
}
#endif