Merged in masayuki2009/nuttx.nuttx/fe310_with_pll (pull request #1094)

fe310 with pll

* arch: fe310: Introduce CONFIG_ARCH_CHIP_FE310_QEMU

* boards: hifive1-revb: Introduce CONFIG_ARCH_CHIP_FE310_QEMU

* arch: fe310: Add support for PLL

* boards: hifive1-revb: Increase uart0 tx buff size and add getprime app

Approved-by: Gregory Nutt <gnutt@nuttx.org>
This commit is contained in:
Masayuki Ishikawa 2019-12-11 12:01:53 +00:00 committed by Gregory Nutt
parent 813902cf87
commit 0eb9bfa49d
16 changed files with 486 additions and 44 deletions

View File

@ -17,12 +17,14 @@ config ARCH_CHIP_FE310_G002
---help---
FE310, RV32IMAC 16KB SRAM
endchoice
config FE310_G002
bool
default y
config ARCH_CHIP_FE310_QEMU
bool "FE310_QEMU"
select FE310_HAVE_UART0
select FE310_HAVE_GPIO
---help---
FE310, RV32IMAC 16KB SRAM
endchoice
menu "FE310 Peripheral Support"

View File

@ -55,7 +55,7 @@ CMN_CSRCS += up_vfork.c
endif
# Specify our C code within this directory to be included
CHIP_CSRCS = fe310_allocateheap.c fe310_idle.c
CHIP_CSRCS = fe310_allocateheap.c fe310_clockconfig.c fe310_idle.c
CHIP_CSRCS += 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,152 @@
/****************************************************************************
* arch/arm/src/fe310/fe310_clockconfig.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_clockconfig.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define EXT_OSC 16000000
#define PLL_64M (1 + (31 << 4) + (3 << 10)) /* R:2 F:64 Q:8 8M/512M/64M */
#define PLL_128M (1 + (31 << 4) + (2 << 10)) /* R:2 F:64 Q:8 8M/512M/128M */
#define PLL_256M (1 + (31 << 4) + (1 << 10)) /* R:2 F:64 Q:8 8M/512M/256M */
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: fe310_get_hfclk
****************************************************************************/
uint32_t fe310_get_hfclk(void)
{
uint32_t val;
uint32_t freq = 0;
/* Check pllbypass */
if (0 != (getreg32(FE310_PLLCFG) & PLLCFG_PLLBYPASS))
{
freq = EXT_OSC;
goto out;
}
/* Check pllsel */
if (0 != ((val = getreg32(FE310_PLLCFG)) & PLLCFG_PLLSEL))
{
freq = EXT_OSC;
freq /= ((val & 0x3) + 1); /* R: 2bit */
freq *= ((((val >> 4) & 0x3f) + 1) * 2); /* F: 6bit */
freq /= (1 << ((val >> 10) & 0x3)); /* Q: 2bit */
goto out;
}
/* TODO: HFROSC */
ASSERT(false);
out:
return freq;
}
/****************************************************************************
* Name: fe310_clockconfig
****************************************************************************/
void fe310_clockconfig(void)
{
uint32_t val;
uint32_t pllsel;
/* NOTE: These are workarounds to avoid a bug with debugger */
pllsel = 0x1;
pllsel <<= 16;
/* Disable PLL by setting pllbypass and clear pllsel */
modifyreg32(FE310_PLLCFG, pllsel, PLLCFG_PLLBYPASS);
/* Enable HFXOSC (external Xtal OSC 16MHz) and wait */
putreg32(HFXOSCCFG_HFXOSCEN, FE310_HFXOSCCFG);
while ((getreg32(FE310_HFXOSCCFG) & HFXOSCCFG_HFXOSCRDY)
!= HFXOSCCFG_HFXOSCRDY)
{
}
val = PLL_256M;
val |= (PLLCFG_PLLREFSEL); /* Set PLLREFSEL (XOSCOUT) */
val |= PLLCFG_PLLBYPASS; /* But Still disable PLL */
putreg32(val, FE310_PLLCFG); /* Set PLL config */
/* Set plloutdiv to pass-through */
putreg32(0x1 << 8, FE310_PLLOUTDIV);
/* Enable PLL by clearing pllbypass and wait */
modifyreg32(FE310_PLLCFG, PLLCFG_PLLBYPASS, 0);
while ((getreg32(FE310_PLLCFG) & PLLCFG_PLLLOCK) == 0x0)
{
}
/* TODO: Set QSPI divider if needed */
/* Select PLL as hfclk */
modifyreg32(FE310_PLLCFG, 0, pllsel);
}

View File

@ -0,0 +1,80 @@
/****************************************************************************
* arch/arm/src/fe310/fe310_clockconfig.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_CLOCKCONFIG_H
#define __ARCH_RISCV_SRC_FE310_FE310_CLOCKCONFIG_H
/****************************************************************************
* Included Files
****************************************************************************/
#include "fe310_memorymap.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/****************************************************************************
* Public Types
****************************************************************************/
#ifndef __ASSEMBLY__
/****************************************************************************
* Public Data
****************************************************************************/
#ifdef __cplusplus
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
/****************************************************************************
* Public Functions
****************************************************************************/
EXTERN uint32_t fe310_get_hfclk(void);
EXTERN void fe310_clockconfig(void);
#if defined(__cplusplus)
}
#endif
#undef EXTERN
#endif /* __ASSEMBLY__ */
#endif /* __ARCH_RISCV_SRC_FE310_FE310_CLOCKCONFIG_H */

View File

@ -49,6 +49,7 @@
#include "fe310_config.h"
#include "hardware/fe310_memorymap.h"
#include "hardware/fe310_uart.h"
#include "fe310_clockconfig.h"
#include "fe310.h"
/****************************************************************************
@ -79,8 +80,6 @@
# endif
#endif /* HAVE_CONSOLE */
#define HFCLK 16000000 /* TODO */
/****************************************************************************
* Public Functions
****************************************************************************/
@ -128,7 +127,13 @@ void fe310_lowsetup(void)
/* Configure the UART Baud Rate */
uint32_t div = HFCLK / 115200 - 1;
uint32_t hfclk = fe310_get_hfclk();
uint32_t div;
div = hfclk / 1152; /* NOTE: To avoid a bug with debugger */
div /= 100;
div -= 1;
putreg32(div, FE310_CONSOLE_BASE + UART_DIV_OFFSET);
/* Enable TX */

View File

@ -41,6 +41,7 @@
#include "hardware/fe310_uart.h"
#include "hardware/fe310_clint.h"
#include "hardware/fe310_plic.h"
#include "hardware/fe310_prci.h"
/****************************************************************************
* Pre-processor Definitions

View File

@ -230,8 +230,12 @@ static void up_serialout(struct up_dev_s *priv, int offset, uint32_t value)
static void up_restoreuartint(struct up_dev_s *priv, uint8_t im)
{
irqstate_t flags = enter_critical_section();
priv->im = im;
up_serialout(priv, UART_IE_OFFSET, im);
leave_critical_section(flags);
}
/****************************************************************************
@ -240,6 +244,8 @@ static void up_restoreuartint(struct up_dev_s *priv, uint8_t im)
static void up_disableuartint(struct up_dev_s *priv, uint8_t *im)
{
irqstate_t flags = enter_critical_section();
/* Return the current interrupt mask value */
if (im)
@ -251,6 +257,7 @@ static void up_disableuartint(struct up_dev_s *priv, uint8_t *im)
priv->im = 0;
up_serialout(priv, UART_IE_OFFSET, 0);
leave_critical_section(flags);
}
/****************************************************************************
@ -273,9 +280,9 @@ static int up_setup(struct uart_dev_s *dev)
up_serialout(priv, UART_RXCTL_OFFSET, 1);
/* Enable TX */
/* Set TX watermark levl to 1 Enable TX */
up_serialout(priv, UART_TXCTL_OFFSET, 1);
up_serialout(priv, UART_TXCTL_OFFSET, 1 << 16 | 1);
return OK;
}
@ -309,7 +316,7 @@ static void up_shutdown(struct uart_dev_s *dev)
*
* 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.
* interrupts are not enabled until the txint() and rxint() are called.
*
****************************************************************************/
@ -376,23 +383,28 @@ static int up_interrupt(int irq, void *context, FAR void *arg)
struct uart_dev_s *dev = (struct uart_dev_s *)arg;
struct up_dev_s *priv;
uint32_t status;
int passes;
DEBUGASSERT(dev != NULL && dev->priv != NULL);
priv = (struct up_dev_s *)dev->priv;
/* Retrieve interrupt pending status */
/* Loop until there are no characters to be transferred or,
* until we have been looping for a long time.
*/
status = up_serialin(priv, UART_IP_OFFSET);
if (status & UART_IP_RXWM)
for (passes = 0; passes < 256; passes++)
{
/* Process incoming bytes */
/* Retrieve interrupt pending status */
uart_recvchars(dev);
}
status = up_serialin(priv, UART_IP_OFFSET);
if (status & UART_IP_RXWM)
{
/* Process incoming bytes */
uart_recvchars(dev);
}
if (status & UART_IP_TXWM)
{
/* Process outgoing bytes */
uart_xmitchars(dev);
@ -449,6 +461,7 @@ static int up_receive(struct uart_dev_s *dev, uint32_t *status)
static void up_rxint(struct uart_dev_s *dev, bool enable)
{
struct up_dev_s *priv = (struct up_dev_s *)dev->priv;
irqstate_t flags = enter_critical_section();
if (enable)
{
@ -462,6 +475,7 @@ static void up_rxint(struct uart_dev_s *dev, bool enable)
}
up_serialout(priv, UART_IE_OFFSET, priv->im);
leave_critical_section(flags);
}
/****************************************************************************
@ -545,7 +559,7 @@ static void up_txint(struct uart_dev_s *dev, bool enable)
* Name: up_txready
*
* Description:
* Return true if the tranmsit data register is empty
* Return true if the tranmsit data register is not full
*
****************************************************************************/
@ -553,7 +567,7 @@ static bool up_txready(struct uart_dev_s *dev)
{
struct up_dev_s *priv = (struct up_dev_s *)dev->priv;
/* Return TRUE if the Transmit buffer register is not full */
/* Return TRUE if the TX FIFO is not full */
return (up_serialin(priv, UART_TXDATA_OFFSET) & UART_TX_FULL) == 0;
}
@ -570,9 +584,9 @@ 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 shift register is empty */
/* Return TRUE if the TX wartermak is pending */
return (up_serialin(priv, UART_TXDATA_OFFSET) & UART_TX_FULL) != 0;
return (up_serialin(priv, UART_IP_OFFSET) & UART_IP_TXWM) == 1;
}
/****************************************************************************

View File

@ -38,6 +38,7 @@
#include <arch/board/board.h>
#include "fe310_clockconfig.h"
#include "fe310.h"
#include "chip.h"
@ -100,7 +101,9 @@ void __fe310_start(void)
*dest++ = *src++;
}
/* TODO: Setup PLL */
/* Setup PLL */
fe310_clockconfig();
/* Configure the UART so we can get debug output */

View File

@ -44,6 +44,7 @@
#include <debug.h>
#include <nuttx/arch.h>
#include <nuttx/clock.h>
#include <arch/board/board.h>
#include "up_arch.h"
@ -57,6 +58,12 @@
#define getreg64(a) (*(volatile uint64_t *)(a))
#define putreg64(v,a) (*(volatile uint64_t *)(a) = (v))
#ifdef CONFIG_ARCH_CHIP_FE310_QEMU
#define TICK_COUNT (10000000 / TICK_PER_SEC)
#else
#define TICK_COUNT (32768 / TICK_PER_SEC)
#endif
/****************************************************************************
* Private Data
****************************************************************************/
@ -88,9 +95,7 @@ static void fe310_reload_mtimecmp(void)
current = getreg64(FE310_CLINT_MTIMECMP);
}
uint64_t tick = 100000; /* TODO */
next = current + tick;
next = current + TICK_COUNT;
putreg64(next, FE310_CLINT_MTIMECMP);
spin_unlock_irqrestore(flags);

View File

@ -42,8 +42,11 @@
#define FE310_CLINT_BASE 0x02000000
#define FE310_PLIC_BASE 0x0c000000
#define FE310_PRCI_BASE 0x10008000 /* 0x10008000 - 0x10008fff: PRCI */
#define FE310_GPIO_BASE 0x10012000 /* 0x10012000 - 0x10012fff: GPIO */
#define FE310_UART0_BASE 0x10013000 /* 0x10013000 - 0x10013fff: UART0 */
#define FE310_QSPI0_BASE 0x10014000 /* 0x10014000 - 0x10014fff: QSPI0 */
#define FE310_UART1_BASE 0x10023000 /* 0x10023000 - 0x10023fff: UART1 */
#endif /* __ARCH_RISCV_SRC_FE310_HARDWARE_FE310_MEMORYMAP_H */

View File

@ -0,0 +1,53 @@
/****************************************************************************
* arch/risc-v/src/fe310/hardware/fe310_prci.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_PRCI_H
#define __ARCH_RISCV_SRC_FE310_HARDWARE_FE310_PRCI_H
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define FE310_HFROSCCFG (FE310_PRCI_BASE + 0x00)
#define FE310_HFXOSCCFG (FE310_PRCI_BASE + 0x04)
#define FE310_PLLCFG (FE310_PRCI_BASE + 0x08)
#define FE310_PLLOUTDIV (FE310_PRCI_BASE + 0x0c)
#define HFXOSCCFG_HFXOSCEN (0x1 << 30)
#define HFXOSCCFG_HFXOSCRDY (0x1 << 31)
#define PLLCFG_PLLSEL (0x1 << 16)
#define PLLCFG_PLLREFSEL (0x1 << 17)
#define PLLCFG_PLLBYPASS (0x1 << 18)
#define PLLCFG_PLLLOCK (0x1 << 31)
#endif /* __ARCH_RISCV_SRC_FE310_HARDWARE_FE310_PRCI_H */

View File

@ -10,19 +10,20 @@
$ make
$ sudo make install
3. Modify flash origin address
3. Modify defconfig
index 559c1813b8..a67c37b576 100644
--- a/boards/risc-v/fe310/hifive1-revb/scripts/ld.script
+++ b/boards/risc-v/fe310/hifive1-revb/scripts/ld.script
@@ -35,7 +35,7 @@
MEMORY
{
- flash (rx) : ORIGIN = 0x20010000, LENGTH = 4096K
+ flash (rx) : ORIGIN = 0x20400000, LENGTH = 4096K
sram (rwx) : ORIGIN = 0x80000000, LENGTH = 16K
}
index c449421741..5a76600785 100644
--- a/boards/risc-v/fe310/hifive1-revb/configs/nsh/defconfig
+++ b/boards/risc-v/fe310/hifive1-revb/configs/nsh/defconfig
@@ -14,7 +14,7 @@ CONFIG_ARCH_BOARD="hifive1-revb"
CONFIG_ARCH_BOARD_HIFIVE1_REVB=y
CONFIG_ARCH_CHIP="fe310"
CONFIG_ARCH_CHIP_FE310=y
-CONFIG_ARCH_CHIP_FE310_G002=y
+CONFIG_ARCH_CHIP_FE310_QEMU=y
CONFIG_ARCH_INTERRUPTSTACK=1536
CONFIG_ARCH_RISCV=y
CONFIG_ARCH_STACKDUMP=y
4. Configure and build NuttX

View File

@ -31,6 +31,5 @@
5. TODO
Configure PLL
Support GPIO/SPI/I2C/RTC/WDT/PWM
Support RISC-V User mode

View File

@ -65,8 +65,10 @@ CONFIG_STDIO_DISABLE_BUFFERING=y
CONFIG_SYSTEM_NSH=y
CONFIG_TASK_NAME_SIZE=12
CONFIG_TASK_SPAWN_DEFAULT_STACKSIZE=1536
CONFIG_TESTING_GETPRIME=y
CONFIG_TESTING_GETPRIME_STACKSIZE=2048
CONFIG_UART0_RXBUFSIZE=8
CONFIG_UART0_SERIAL_CONSOLE=y
CONFIG_UART0_TXBUFSIZE=4
CONFIG_UART0_TXBUFSIZE=32
CONFIG_USER_ENTRYPOINT="nsh_main"
CONFIG_WDOG_INTRESERVE=0

View File

@ -37,7 +37,11 @@ include ${TOPDIR}/.config
include ${TOPDIR}/tools/Config.mk
include ${TOPDIR}/arch/risc-v/src/rv32im/Toolchain.defs
LDSCRIPT = ld.script
ifeq ($(CONFIG_ARCH_CHIP_FE310_QEMU),y)
LDSCRIPT = ld-qemu.script
else
LDSCRIPT = ld.script
endif
ifeq ($(WINTOOL),y)
# Windows-native toolchains

View File

@ -0,0 +1,118 @@
/****************************************************************************
* boards/risc-v/fe310/hifive1-revb/scripts/ld-qemu.script
*
* 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.
*
****************************************************************************/
MEMORY
{
flash (rx) : ORIGIN = 0x20400000, LENGTH = 4096K
sram (rwx) : ORIGIN = 0x80000000, LENGTH = 16K
}
OUTPUT_ARCH("riscv")
ENTRY(_stext)
EXTERN(_vectors)
SECTIONS
{
.text : {
_stext = ABSOLUTE(.);
*(.vectors)
*(.text .text.*)
*(.fixup)
*(.gnu.warning)
*(.rodata .rodata.*)
*(.gnu.linkonce.t.*)
*(.glue_7)
*(.glue_7t)
*(.got)
*(.gcc_except_table)
*(.gnu.linkonce.r.*)
_etext = ABSOLUTE(.);
} > flash
.init_section : ALIGN(4) {
_sinit = ABSOLUTE(.);
KEEP(*(.init_array .init_array.*))
_einit = ABSOLUTE(.);
} > flash
.ARM.extab : ALIGN(4) {
*(.ARM.extab*)
} > flash
.ARM.exidx : ALIGN(4) {
__exidx_start = ABSOLUTE(.);
*(.ARM.exidx*)
__exidx_end = ABSOLUTE(.);
} > flash
_eronly = ABSOLUTE(.);
.data : ALIGN(4) {
_sdata = ABSOLUTE(.);
*(.data .data.*)
*(.sdata .sdata.*)
*(.gnu.linkonce.d.*)
*(.gnu.linkonce.s.*)
CONSTRUCTORS
. = ALIGN(4);
_edata = ABSOLUTE(.);
} > sram AT > flash
.bss : ALIGN(4) {
_sbss = ABSOLUTE(.);
*(.bss .bss.*)
*(.sbss .sbss.*)
*(.gnu.linkonce.b.*)
*(.gnu.linkonce.sb.*)
*(COMMON)
. = ALIGN(4);
_ebss = ABSOLUTE(.);
} > sram
/* Stabs debugging sections. */
.stab 0 : { *(.stab) }
.stabstr 0 : { *(.stabstr) }
.stab.excl 0 : { *(.stab.excl) }
.stab.exclstr 0 : { *(.stab.exclstr) }
.stab.index 0 : { *(.stab.index) }
.stab.indexstr 0 : { *(.stab.indexstr) }
.comment 0 : { *(.comment) }
.debug_abbrev 0 : { *(.debug_abbrev) }
.debug_info 0 : { *(.debug_info) }
.debug_line 0 : { *(.debug_line) }
.debug_pubnames 0 : { *(.debug_pubnames) }
.debug_aranges 0 : { *(.debug_aranges) }
}