summaryrefslogtreecommitdiff
path: root/nuttx/configs/skp16c26
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/configs/skp16c26')
-rw-r--r--nuttx/configs/skp16c26/include/board.h5
-rw-r--r--nuttx/configs/skp16c26/ostest/Make.defs2
-rw-r--r--nuttx/configs/skp16c26/ostest/defconfig33
3 files changed, 17 insertions, 23 deletions
diff --git a/nuttx/configs/skp16c26/include/board.h b/nuttx/configs/skp16c26/include/board.h
index 5f694f5de..b087ec072 100644
--- a/nuttx/configs/skp16c26/include/board.h
+++ b/nuttx/configs/skp16c26/include/board.h
@@ -44,8 +44,6 @@
#ifndef __ASSEMBLY__
# include <sys/types.h>
#endif
-#include "sfr262.h" /* M16C/26 special function register definitions */
-#include "skp_lcd.h" /* SKP LCD function definitions */
/************************************************************************************
* Definitions
@@ -80,9 +78,6 @@
#define LED_ON 0
#define LED_OFF 1
-#define ENABLE_IRQ {_asm(" FSET I");}
-#define DISABLE_IRQ {_asm(" FCLR I");}
-
/* Use these macros for switch inputs */
#define ENABLE_SWITCHES {S1_DDR = 0; S2_DDR = 0; S3_DDR = 0;}
diff --git a/nuttx/configs/skp16c26/ostest/Make.defs b/nuttx/configs/skp16c26/ostest/Make.defs
index a1267dbf0..7225216e1 100644
--- a/nuttx/configs/skp16c26/ostest/Make.defs
+++ b/nuttx/configs/skp16c26/ostest/Make.defs
@@ -53,7 +53,7 @@ else
ARCHOPTIMIZATION = -Os -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer
endif
-ARCHCPUFLAGS = --m16c -msoft-float -fno-builtin
+ARCHCPUFLAGS = -mcpu=m16c -fno-builtin
ARCHPICFLAGS = -fpic
ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow
ARCHDEFINES =
diff --git a/nuttx/configs/skp16c26/ostest/defconfig b/nuttx/configs/skp16c26/ostest/defconfig
index 1f515adba..c194f02f6 100644
--- a/nuttx/configs/skp16c26/ostest/defconfig
+++ b/nuttx/configs/skp16c26/ostest/defconfig
@@ -47,9 +47,9 @@
# CONFIG_ARCH_BOARD_name - for use in C code
# CONFIG_ENDIAN_BIG - define if big endian (default is little endian)
# CONFIG_BOARD_LOOPSPERMSEC - for delay loops
-# CONFIG_DRAM_SIZE - Describes the installed DRAM.
-# CONFIG_DRAM_START - The start address of DRAM (physical)
-# CONFIG_DRAM_VSTART - The startaddress of DRAM (virtual)
+# CONFIG_DRAM_SIZE - Describes the internal SRAM.
+# CONFIG_DRAM_START - The start address of internal SRAM
+# CONFIG_DRAM_END - The end+1 address of internal SRAM
# CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt
# stack. If defined, this symbol is the size of the interrupt
# stack in bytes. If not defined, the user task stacks will be
@@ -63,12 +63,11 @@ CONFIG_ARCH_CHIP_M30262F8=y
CONFIG_ARCH_BOARD=skp16c26
CONFIG_ARCH_BOARD_SKP16C26=y
CONFIG_ENDIAN_BIG=y
+CONFIG_DRAM_SIZE=0x00800
+CONFIG_DRAM_START=0x00400
+CONFIG_DRAM_END=(CONFIG_DRAM_START+CONFIG_DRAM_SIZE)
CONFIG_BOARD_LOOPSPERMSEC=16945
-CONFIG_DRAM_SIZE=0x01000000
-CONFIG_DRAM_START=0x01000000
-CONFIG_DRAM_VSTART=0x00000000
-CONFIG_DRAM_NUTTXENTRY=0x01008000
-CONFIG_ARCH_INTERRUPTSTACK=0
+CONFIG_ARCH_INTERRUPTSTACK=128
CONFIG_ARCH_STACKDUMP=y
#
@@ -87,12 +86,12 @@ CONFIG_ARCH_STACKDUMP=y
#
CONFIG_UART0_SERIAL_CONSOLE=y
CONFIG_UART1_SERIAL_CONSOLE=n
-CONFIG_UART0_TXBUFSIZE=256
-CONFIG_UART1_TXBUFSIZE=256
-CONFIG_UART0_RXBUFSIZE=256
-CONFIG_UART1_RXBUFSIZE=256
-CONFIG_UART0_BAUD=115200
-CONFIG_UART1_BAUD=115200
+CONFIG_UART0_TXBUFSIZE=64
+CONFIG_UART1_TXBUFSIZE=64
+CONFIG_UART0_RXBUFSIZE=64
+CONFIG_UART1_RXBUFSIZE=64
+CONFIG_UART0_BAUD=9600
+CONFIG_UART1_BAUD=9600
CONFIG_UART0_BITS=8
CONFIG_UART1_BITS=8
CONFIG_UART0_PARITY=0
@@ -160,9 +159,9 @@ CONFIG_ARCH_LOWPUTC=y
CONFIG_RR_INTERVAL=200
CONFIG_SCHED_INSTRUMENTATION=n
CONFIG_TASK_NAME_SIZE=0
-CONFIG_START_YEAR=2008
-CONFIG_START_MONTH=8
-CONFIG_START_DAY=29
+CONFIG_START_YEAR=2009
+CONFIG_START_MONTH=2
+CONFIG_START_DAY=8
CONFIG_JULIAN_TIME=n
CONFIG_DEV_CONSOLE=y
CONFIG_DEV_LOWCONSOLE=n