summaryrefslogtreecommitdiff
path: root/nuttx/configs/pjrc-8051
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-03-23 02:24:38 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-03-23 02:24:38 +0000
commit4343c3bdcd0b366f31cf0f17eef01c1f3d1f9c62 (patch)
treefebec22088721155db384fd5d24306221e069ec3 /nuttx/configs/pjrc-8051
parent91451bb1709c1d79fd000e927ee13aace1ca5104 (diff)
downloadpx4-nuttx-4343c3bdcd0b366f31cf0f17eef01c1f3d1f9c62.tar.gz
px4-nuttx-4343c3bdcd0b366f31cf0f17eef01c1f3d1f9c62.tar.bz2
px4-nuttx-4343c3bdcd0b366f31cf0f17eef01c1f3d1f9c62.zip
Initial Release
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@125 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/configs/pjrc-8051')
-rw-r--r--nuttx/configs/pjrc-8051/Make.defs65
-rw-r--r--nuttx/configs/pjrc-8051/README.txt37
-rw-r--r--nuttx/configs/pjrc-8051/defconfig244
-rw-r--r--nuttx/configs/pjrc-8051/sdcc-2.6.0.patch28
-rwxr-xr-xnuttx/configs/pjrc-8051/setenv.sh45
5 files changed, 419 insertions, 0 deletions
diff --git a/nuttx/configs/pjrc-8051/Make.defs b/nuttx/configs/pjrc-8051/Make.defs
new file mode 100644
index 000000000..5c4349fc2
--- /dev/null
+++ b/nuttx/configs/pjrc-8051/Make.defs
@@ -0,0 +1,65 @@
+############################################################
+# Make.defs
+#
+# Copyright (C) 2007 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+#
+# 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 Gregory Nutt 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.
+#
+############################################################
+
+include ${TOPDIR}/.config
+
+ifeq ("${CONFIG_DEBUG}","y")
+ ARCHOPTIMIZATION = --debug
+else
+ ARCHOPTIMIZATION =
+endif
+
+ARCHCPUFLAGS = -mmcs51 --stack-auto --model-large --int-long-reent --float-reent
+ARCHPICFLAGS =
+ARCHWARNINGS =
+ARCHDEFINES =
+ARCHINCLUDES = -I. -I$(TOPDIR)/include
+
+CROSSDEV =
+CC = sdcc
+CPP = sdcpp
+LD = aslink
+AS = asx8051
+AR = sdcclib -a
+
+CFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) \
+ $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES)
+
+ASMEXT = .asm
+OBJEXT = .rel
+LIBEXT = .lib
+EXEEXT = .hex
+
+
diff --git a/nuttx/configs/pjrc-8051/README.txt b/nuttx/configs/pjrc-8051/README.txt
new file mode 100644
index 000000000..dae92b59b
--- /dev/null
+++ b/nuttx/configs/pjrc-8051/README.txt
@@ -0,0 +1,37 @@
+pjrc-8051 README
+^^^^^^^^^^^^^^^^
+
+This port uses the PJRC 87C52 development system and the SDCC toolchain.
+
+The PJRC 87C52 development system can be obtained from http://www.pjrc.com/.
+
+The SDCC toolchain is available from http://sdcc.sourceforge.net/. All
+testing has been performed using verison 2.6.0 of the SDDC toolchain.
+
+Building the SDCC toolchain
+^^^^^^^^^^^^^^^^^^^^^^^^^^^
+
+The SDCC toolchain is built with the standard configure/make/make install
+sequence. However, some special actions are required to generate libraries
+compatible with this build. First start with the usual steps
+
+ download
+ unpack
+ cd sdcc
+ ./configure
+ make
+
+But before installing, we need to apply a patch to the SDCC 2.6.0 source.
+WARNING: This patch is specific to the particular combination of CFLAGS
+that are used in the compilation. If you change Make.defs, then you will
+likely have to change the patch as well.
+
+ Apply sdcc-2.6.0.patch
+ cd sdcc/device/lib
+ make model-mcs51-stack-auto
+
+Then
+
+ cd sdcc
+ make install
+
diff --git a/nuttx/configs/pjrc-8051/defconfig b/nuttx/configs/pjrc-8051/defconfig
new file mode 100644
index 000000000..cdb73acda
--- /dev/null
+++ b/nuttx/configs/pjrc-8051/defconfig
@@ -0,0 +1,244 @@
+############################################################
+# defconfig
+#
+# Copyright (C) 2007 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+#
+# 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 Gregory Nutt 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.
+#
+############################################################
+#
+# Architecture selection
+#
+# CONFIG_ARCH - identifies the arch subdirectory
+# CONFIG_ARCH_8051 - Set if processor is 8051 family
+# CONFIG_ARCH_8052 = Set if processor is 8052 family
+#
+CONFIG_ARCH=pjrc-8051
+CONFIG_ARCH_8051=n
+CONFIG_ARCH_8052=y
+
+#
+# Architecture-specific settings. These may mean nothing to
+# other architectures.
+#
+# CONFIG-ARCH_PJRC - Set if using the PJRC 87C52 board
+# CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to 8051.
+# CONFIG_8052_TIMER2 - Use timer2 for the 100Hz system timer.
+# (default is timer0 at 112.5Hz).
+#
+# These features are only supported when CONFIG_ARCH_BRINGUP
+# is set:
+#
+# CONFIG_ARCH_BRINGUP - Enables some bringup features
+# CONFIG_FRAME_DUMP - Enable stack/frame dumping logic
+# CONFIG_FRAME_DUMP_SHORT - Terse frame dump output
+# CONFIG_SUPPRESS_INTERRUPTS - Do not enable interrupts
+# CONFIG_SWITCH_FRAME_DUMP - Dump frames from normal switches
+# CONFIG_INTERRUPT_FRAME_DUMP - Dump frames from interrupt switches
+# CONFIG_LED_DEBUG - Enable debug output from LED logic
+#
+CONFIG_ARCH_PJRC=y
+CONFIG_ARCH_LEDS=y
+CONFIG_8052_TIMER2=y
+
+CONFIG_ARCH_BRINGUP=y
+CONFIG_FRAME_DUMP=n
+CONFIG_FRAME_DUMP_SHORT=n
+CONFIG_SUPPRESS_INTERRUPTS=y
+CONFIG_SWITCH_FRAME_DUMP=n
+CONFIG_INTERRUPT_FRAME_DUMP=n
+CONFIG_LED_DEBUG=n
+
+#
+# General OS setup
+#
+# CONFIG_EXAMPLE - identifies the subdirectory in examples
+# that will be used in the build
+# CONFIG_DEBUG - enables built-in debug options
+# CONFIG_DEBUG_VERBOSE - enables verbose debug output
+# CONFIG_MM_REGIONS - If the architecture includes multiple
+# regions of memory to allocate from, this specifies the
+# number of memory regions that the memory manager must
+# handle and enables the API mm_addregion(start, end);
+# CONFIG_HAVE_LOWPUTC - architecture supports low-level, boot
+# time console output
+# CONFIG_RR_INTERVAL - The round robin timeslice will be set
+# this number of milliseconds; Round robin scheduling can
+# be disabled by setting this value to zero.
+# CONFIG_SCHED_INSTRUMENTATION - enables instrumentation in
+# scheduler to monitor system performance
+# CONFIG_TASK_NAME_SIZE - Spcifies that maximum size of a
+# task name to save in the TCB. Useful if scheduler
+# instrumentation is selected. Set to zero to disable.
+# CONFIG_JULIAN_TIME - Enables Julian time conversions
+# CONFIG_START_YEAR, CONFIG_START_MONTH, CONFIG_START_DAY -
+# Used to initialize the internal time logic.
+# CONFIG_DEV_CONSOLE - Set if architecture-specific logic
+# provides /dev/console. Enables stdout, stderr, stdin.
+#
+CONFIG_EXAMPLE=ostest
+CONFIG_DEBUG=n
+CONFIG_DEBUG_VERBOSE=n
+CONFIG_MM_REGIONS=2
+CONFIG_ARCH_LOWPUTC=y
+CONFIG_RR_INTERVAL=0
+CONFIG_SCHED_INSTRUMENTATION=n
+CONFIG_TASK_NAME_SIZE=0
+CONFIG_START_YEAR=2007
+CONFIG_START_MONTH=2
+CONFIG_START_DAY=21
+CONFIG_JULIAN_TIME=n
+CONFIG_DEV_CONSOLE=n
+
+#
+# The following can be used to disable categories of
+# APIs supported by the OS. If the compiler supports
+# weak functions, then it should not be necessary to
+# disable functions unless you want to restrict usage
+# of those APIs.
+#
+# There are certain dependency relationships in these
+# features.
+#
+# o mq_notify logic depends on signals to awaken tasks
+# waiting for queues to become full or empty.
+# o pthread_condtimedwait() depends on signals to wake
+# up waiting tasks.
+#
+CONFIG_DISABLE_CLOCK=y
+CONFIG_DISABLE_POSIX_TIMERS=y
+CONFIG_DISABLE_PTHREAD=y
+CONFIG_DISABLE_SIGNALS=y
+CONFIG_DISABLE_MQUEUE=y
+
+#
+# Misc libc settings
+#
+# CONFIG_NOPRINTF_FIELDWIDTH - sprintf-related logic is a
+# little smaller if we do not support fieldwidthes
+#
+CONFIG_NOPRINTF_FIELDWIDTH=y
+
+#
+# Allow for architecture optimized implementations
+#
+# The architecture can provide optimized versions of the
+# following to improve sysem performance
+#
+CONFIG_ARCH_MEMCPY=n
+CONFIG_ARCH_MEMCMP=n
+CONFIG_ARCH_MEMMOVE=n
+CONFIG_ARCH_MEMSET=n
+CONFIG_ARCH_STRCMP=n
+CONFIG_ARCH_STRCPY=n
+CONFIG_ARCH_STRNCPY=n
+CONFIG_ARCH_STRLEN=n
+CONFIG_ARCH_BZERO=n
+CONFIG_ARCH_KMALLOC=n
+CONFIG_ARCH_KZMALLOC=n
+CONFIG_ARCH_KFREE=n
+
+#
+# General build options
+#
+# CONFIG_RRLOAD_BINARY - make the rrload binary format used with
+# BSPs from www.ridgerun.com
+#
+CONFIG_RRLOAD_BINARY=n
+
+#
+# Sizes of configurable things (0 disables)
+#
+# CONFIG_MAX_TASKS - The maximum number of simultaneously
+# actived tasks. This value must be a power of two.
+# CONFIG_MAX_TASK_ARGS - This controls the maximum number of
+# of parameters that a task may receive (i.e., maxmum value
+# of 'argc')
+# CONFIG_NPTHREAD_KEYS - The number of items of thread-
+# specific data that can be retained
+# CONFIG_NFILE_DESCRIPTORS - The maximum number of file
+# descriptors (one for each open)
+# CONFIG_NFILE_STREAMS - The maximum number of streams that
+# can be fopen'ed
+# CONFIG_NAME_MAX - The maximum size of a file name.
+# CONFIG_STDIO_BUFFER_SIZE - Size of the buffer to allocate
+# on fopen. (Only if CONFIG_NFILE_STREAMS > 0)
+# CONFIG_NUNGET_CHARS - Number of characters that can be
+# buffered by ungetc() (Only if CONFIG_NFILE_STREAMS > 0)
+# CONFIG_PREALLOC_MQ_MSGS - The number of pre-allocated message
+# structures. The system manages a pool of preallocated
+# message structures to minimize dynamic allocations
+# CONFIG_MQ_MAXMSGSIZE - Message structures are allocated with
+# a fixed payload size given by this settin (does not include
+# other message structure overhead.
+# CONFIG_MAX_WDOGPARMS - Maximum number of parameters that
+# can be passed to a watchdog handler
+# CONFIG_PREALLOC_WDOGS - The number of pre-allocated watchdog
+# structures. The system manages a pool of preallocated
+# watchdog structures to minimize dynamic allocations
+# CONFIG_PREALLOC_TIMERS - The number of pre-allocated POSIX
+# timer structures. The system manages a pool of preallocated
+# timer structures to minimize dynamic allocations. Set to
+# zero for all dynamic allocations.
+#
+CONFIG_MAX_TASKS=8
+CONFIG_MAX_TASK_ARGS=4
+CONFIG_NPTHREAD_KEYS=0
+CONFIG_NFILE_DESCRIPTORS=0
+CONFIG_NFILE_STREAMS=0
+CONFIG_NAME_MAX=32
+CONFIG_STDIO_BUFFER_SIZE=0
+CONFIG_NUNGET_CHARS=0
+CONFIG_PREALLOC_MQ_MSGS=0
+CONFIG_MQ_MAXMSGSIZE=0
+CONFIG_MAX_WDOGPARMS=2
+CONFIG_PREALLOC_WDOGS=4
+CONFIG_PREALLOC_TIMERS=0
+
+#
+# Stack and heap information
+#
+# CONFIG_BOOT_FROM_FLASH - Some configurations support XIP
+# operation from FLASH.
+# CONFIG_CUSTOM_STACK - The up_ implementation will handle
+# all stack operations outside of the nuttx model.
+# CONFIG_STACK_POINTER - The initial stack pointer
+# CONFIG_PROC_STACK_SIZE - The size of the initial stack
+# CONFIG_PTHREAD_STACK_MIN - Minimum pthread stack size
+# CONFIG_PTHREAD_STACK_DEFAULT - Default pthread stack size
+# CONFIG_HEAP_BASE - The beginning of the heap
+# CONFIG_HEAP_SIZE - The size of the heap
+#
+CONFIG_BOOT_FROM_FLASH=n
+CONFIG_CUSTOM_STACK=y
+CONFIG_PROC_STACK_SIZE=
+CONFIG_PTHREAD_STACK_MIN=
+CONFIG_PTHREAD_STACK_DEFAULT=
+CONFIG_HEAP_BASE=
+CONFIG_HEAP_SIZE=
diff --git a/nuttx/configs/pjrc-8051/sdcc-2.6.0.patch b/nuttx/configs/pjrc-8051/sdcc-2.6.0.patch
new file mode 100644
index 000000000..beb8bf2ea
--- /dev/null
+++ b/nuttx/configs/pjrc-8051/sdcc-2.6.0.patch
@@ -0,0 +1,28 @@
+diff -u sdcc/device/lib/Makefile.orig sdcc/device/lib/Makefile
+--- sdcc/device/lib/Makefile.orig 2007-03-06 09:55:01.000000000 -0600
++++ sdcc/device/lib/Makefile 2007-03-06 09:58:32.000000000 -0600
+@@ -242,7 +242,7 @@
+ model-mcs51-stack-auto:
+ if [ "`grep mcs51 $(top_builddir)ports.build`" = mcs51 ]; then \
+ for model in $(MODELS); do \
+- $(MAKE) MODELFLAGS="--model-$$model --stack-auto" PORT=$$model PORTDIR=$(BUILDDIR)/$$model-stack-auto PORTINCDIR=$(INCDIR)/mcs51 objects; \
++ $(MAKE) MODELFLAGS="--model-$$model --stack-auto --int-long-reent --float-reent" PORT=$$model PORTDIR=$(BUILDDIR)/$$model-stack-auto PORTINCDIR=$(INCDIR)/mcs51 objects; \
+ done \
+ fi
+
+diff -u sdcc/device/include/stdarg.h.orig sdcc/device/include/stdarg.h
+--- sdcc/device/include/stdarg.h.orig 2007-03-11 13:21:15.000000000 -0600
++++ sdcc/device/include/stdarg.h 2007-03-11 13:26:59.000000000 -0600
+@@ -25,9 +25,9 @@
+
+ #else
+
+-typedef unsigned char __data * va_list ;
+-#define va_arg(marker,type) *((type __data * )(marker -= sizeof(type)))
+-#define va_start(marker,first) { marker = (va_list) ((char __data * )&first); }
++typedef unsigned char * va_list ;
++#define va_arg(marker,type) *((type * )(marker -= sizeof(type)))
++#define va_start(marker,first) { marker = (va_list) ((char * )&first); }
+
+ #endif
+
diff --git a/nuttx/configs/pjrc-8051/setenv.sh b/nuttx/configs/pjrc-8051/setenv.sh
new file mode 100755
index 000000000..69614aefe
--- /dev/null
+++ b/nuttx/configs/pjrc-8051/setenv.sh
@@ -0,0 +1,45 @@
+#!/bin/sh
+# setenv.sh
+#
+# Copyright (C) 2007 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+#
+# 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 Gregory Nutt 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.
+#
+
+if [ "$(basename $0)" = "setenv" ] ; then
+ echo "You must source this script, not run it!" 1>&2
+ exit 1
+fi
+
+if [ -z ${PATH_ORIG} ]; then export PATH_ORIG=${PATH}; fi
+
+export SDCC_BIN=/usr/local/bin
+export PATH=${SDCC_BIN}:/sbin:/usr/sbin:${PATH_ORIG}
+
+echo "PATH : ${PATH}"