summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rwxr-xr-xnuttx/arch/avr/include/at91uc3/irq.h2
-rw-r--r--nuttx/arch/avr/include/avr32/irq.h8
-rwxr-xr-xnuttx/arch/avr/src/at91uc3/at91uc3_internal.h62
-rwxr-xr-xnuttx/arch/avr/src/at91uc3/chip.h4
-rw-r--r--nuttx/arch/avr/src/avr32/up_schedulesigaction.c1
-rw-r--r--nuttx/arch/avr/src/avr32/up_sigdeliver.c9
-rwxr-xr-xnuttx/configs/avr32dev1/include/board.h9
-rwxr-xr-xnuttx/configs/avr32dev1/ostest/Make.defs4
-rwxr-xr-xnuttx/configs/avr32dev1/ostest/defconfig3
-rwxr-xr-xnuttx/configs/avr32dev1/ostest/setenv.sh7
-rwxr-xr-xnuttx/configs/avr32dev1/ostest/test-result.txt432
-rwxr-xr-xnuttx/configs/avr32dev1/src/up_boot.c2
-rwxr-xr-xnuttx/configs/avr32dev1/src/up_leds.c2
-rw-r--r--nuttx/sched/irq_initialize.c2
14 files changed, 97 insertions, 450 deletions
diff --git a/nuttx/arch/avr/include/at91uc3/irq.h b/nuttx/arch/avr/include/at91uc3/irq.h
index 395c88188..adb1cc18b 100755
--- a/nuttx/arch/avr/include/at91uc3/irq.h
+++ b/nuttx/arch/avr/include/at91uc3/irq.h
@@ -56,7 +56,7 @@
/* Total number of IRQ numbers */
-#define NR_IRQS
+#define NR_IRQS 1
/****************************************************************************
* Public Types
diff --git a/nuttx/arch/avr/include/avr32/irq.h b/nuttx/arch/avr/include/avr32/irq.h
index cc8222e86..2425b9f30 100644
--- a/nuttx/arch/avr/include/avr32/irq.h
+++ b/nuttx/arch/avr/include/avr32/irq.h
@@ -50,9 +50,11 @@
* Definitions
****************************************************************************/
-/* Indices the register state save array */
+/* Register state save array indices */
-#defin XCPTCONTEXT_REGS 1
+/* Size of the register state save array */
+
+#define XCPTCONTEXT_REGS 1
/****************************************************************************
* Public Types
@@ -87,6 +89,7 @@ struct xcptcontext
static inline irqstate_t irqsave(void)
{
+# warning "Not implemented"
return 0;
}
@@ -94,6 +97,7 @@ static inline irqstate_t irqsave(void)
static inline void irqrestore(irqstate_t flags)
{
+# warning "Not implemented"
}
#endif /* __ASSEMBLY__ */
diff --git a/nuttx/arch/avr/src/at91uc3/at91uc3_internal.h b/nuttx/arch/avr/src/at91uc3/at91uc3_internal.h
new file mode 100755
index 000000000..a2bf10d6c
--- /dev/null
+++ b/nuttx/arch/avr/src/at91uc3/at91uc3_internal.h
@@ -0,0 +1,62 @@
+/************************************************************************************
+ * arch/avr/src/at91uc3b/at91uc3_internal.h
+ *
+ * Copyright (C) 2010 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 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_AVR_SRC_AVR32_AT91UC3_INTERNAL_H
+#define __ARCH_AVR_SRC_AVR32_AT91UC3_INTERNAL_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_AVR_SRC_AVR32_AT91UC3_INTERNAL_H */
+
diff --git a/nuttx/arch/avr/src/at91uc3/chip.h b/nuttx/arch/avr/src/at91uc3/chip.h
index c5133d6c1..9e8ac83f7 100755
--- a/nuttx/arch/avr/src/at91uc3/chip.h
+++ b/nuttx/arch/avr/src/at91uc3/chip.h
@@ -48,7 +48,7 @@
/* Get customizations for each supported chip */
-#if 0
+#if CONFIG_ARCH_CHIP_AT91UC3B0256
#else
# error "Unsupported AVR32 chip"
#endif
@@ -57,7 +57,7 @@
* file for the proper setup
*/
-#include "atuc3_memorymap.h"
+#include "at91uc3_memorymap.h"
/************************************************************************************
* Public Types
diff --git a/nuttx/arch/avr/src/avr32/up_schedulesigaction.c b/nuttx/arch/avr/src/avr32/up_schedulesigaction.c
index 7f7dff6a3..c5e6a7af5 100644
--- a/nuttx/arch/avr/src/avr32/up_schedulesigaction.c
+++ b/nuttx/arch/avr/src/avr32/up_schedulesigaction.c
@@ -45,7 +45,6 @@
#include <nuttx/arch.h>
-#include "psr.h"
#include "os_internal.h"
#include "up_internal.h"
#include "up_arch.h"
diff --git a/nuttx/arch/avr/src/avr32/up_sigdeliver.c b/nuttx/arch/avr/src/avr32/up_sigdeliver.c
index 2159ce0c0..1a8c2a7bc 100644
--- a/nuttx/arch/avr/src/avr32/up_sigdeliver.c
+++ b/nuttx/arch/avr/src/avr32/up_sigdeliver.c
@@ -112,16 +112,15 @@ void up_sigdeliver(void)
/* Then restore the task interrupt state */
- irqrestore((uint16_t)regs[REG_PRIMASK]);
+#warning "Not Implemented"
/* Deliver the signals */
sigdeliver(rtcb);
- /* Output any debug messaged BEFORE restoreing errno
- * (becuase they may alter errno), then restore the
- * original errno that is needed by the user logic
- * (it is probably EINTR).
+ /* Output any debug messaged BEFORE restoring errno (becuase they may
+ * alter errno), then restore the original errno that is needed by
+ * the user logic (it is probably EINTR).
*/
sdbg("Resuming\n");
diff --git a/nuttx/configs/avr32dev1/include/board.h b/nuttx/configs/avr32dev1/include/board.h
index 6f93d68a9..636107198 100755
--- a/nuttx/configs/avr32dev1/include/board.h
+++ b/nuttx/configs/avr32dev1/include/board.h
@@ -51,6 +51,15 @@
/* LED definitions ******************************************************************/
+#define LED_STARTED 0
+#define LED_HEAPALLOCATE 1
+#define LED_IRQSENABLED 2
+#define LED_STACKCREATED 3
+#define LED_INIRQ 4
+#define LED_SIGNAL 5
+#define LED_ASSERTION 6
+#define LED_PANIC 7
+
/************************************************************************************
* Public Types
************************************************************************************/
diff --git a/nuttx/configs/avr32dev1/ostest/Make.defs b/nuttx/configs/avr32dev1/ostest/Make.defs
index e9f384ead..f576986b4 100755
--- a/nuttx/configs/avr32dev1/ostest/Make.defs
+++ b/nuttx/configs/avr32dev1/ostest/Make.defs
@@ -41,12 +41,12 @@ ifeq ($(CONFIG_AVR32_AVRTOOLSW),y)
# AVR Tools under Windows
CROSSDEV = avr32-
WINTOOL = y
- ARCHCPUFLAGS = -march=uc -mpart=uc3b0256
+ ARCHCPUFLAGS = -mpart=uc3b0256
endif
ifeq ($(CONFIG_AVR32_AVRTOOLSL),y)
# AVR Tools under Linux
CROSSDEV = avr32-
- ARCHCPUFLAGS = -march=uc -mpart=uc3b0256
+ ARCHCPUFLAGS = -mpart=uc3b0256
endif
ifeq ($(WINTOOL),y)
diff --git a/nuttx/configs/avr32dev1/ostest/defconfig b/nuttx/configs/avr32dev1/ostest/defconfig
index bf6fa61ff..9f2b9ec5b 100755
--- a/nuttx/configs/avr32dev1/ostest/defconfig
+++ b/nuttx/configs/avr32dev1/ostest/defconfig
@@ -371,6 +371,8 @@ CONFIG_ARCH_KFREE=n
# 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
@@ -389,6 +391,7 @@ CONFIG_STDIO_BUFFER_SIZE=256
CONFIG_NUNGET_CHARS=2
CONFIG_PREALLOC_MQ_MSGS=4
CONFIG_MQ_MAXMSGSIZE=32
+CONFIG_MAX_WDOGPARMS=2
CONFIG_PREALLOC_WDOGS=4
CONFIG_PREALLOC_TIMERS=4
diff --git a/nuttx/configs/avr32dev1/ostest/setenv.sh b/nuttx/configs/avr32dev1/ostest/setenv.sh
index 079fe51cb..b2d102c48 100755
--- a/nuttx/configs/avr32dev1/ostest/setenv.sh
+++ b/nuttx/configs/avr32dev1/ostest/setenv.sh
@@ -39,7 +39,10 @@ fi
#
# This PATH setup assumes that you are using versin 2.1.4 of the Atmel
-# AVR GNU tools installed at the default location on Windows.
+# AVR GNU tools installed at the default location on Windows. NOTE
+# that the path is in appended to the end of the PATH variable; this is
+# because there are also many GNUWin32 binaries there that conflict with
+# Cygwin versions.
#
if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
@@ -47,6 +50,6 @@ if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
WD=`pwd`
export AVRTOOLS_BIN="/cygdrive/c/Program Files/Atmel/AVR Tools/AVR32 Toolchain/bin/"
-export PATH="${AVRTOOLS_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
+export PATH="/sbin:/usr/sbin:${PATH_ORIG}:${AVRTOOLS_BIN}"
echo "PATH : ${PATH}"
diff --git a/nuttx/configs/avr32dev1/ostest/test-result.txt b/nuttx/configs/avr32dev1/ostest/test-result.txt
deleted file mode 100755
index bfae9ef4c..000000000
--- a/nuttx/configs/avr32dev1/ostest/test-result.txt
+++ /dev/null
@@ -1,432 +0,0 @@
-Output from examples/ostest for the Nucleus-2G board. June 21, 2010.
---------------------------------------------------------------------
-stdio_test: write fd=1
-stdio_test: write fd=2
-stdio_test: Standard I/O Check: printf
-user_start: Started user_main at PID=2
-user_start: Exitting
-stdio_test: Standard I/O Check: fprintf to stderr
-stdio_test: write fd=1
-stdio_test: write fd=2
-stdio_test: Standard I/O Check: printf
-user_start: Started user_main at PID=2
-user_start: Exitting
-stdio_test: Standard I/O Check: fprintf to stderr
-
-user_main: Begin argument test
-user_main: Started with argc=5
-user_main: argv[0]="<noname>"
-user_main: argv[1]="Arg1"
-user_main: argv[2]="Arg2"
-user_main: argv[3]="Arg3"
-user_main: argv[4]="Arg4"
-
-End of test memory usage:
-VARIABLE BEFORE AFTER
-======== ======== ========
-arena b1c0 b1c0
-ordblks 3 3
-mxordblk 7ff0 7ff0
-uordblks 1d20 1d20
-fordblks 94a0 94a0
-
-user_main: /dev/null test
-dev_null: Read 0 bytes from /dev/null
-dev_null: Wrote 1024 bytes to /dev/null
-
-End of test memory usage:
-VARIABLE BEFORE AFTER
-======== ======== ========
-arena b1c0 b1c0
-ordblks 3 3
-mxordblk 7ff0 7ff0
-uordblks 1d20 1d20
-fordblks 94a0 94a0
-
-user_main: mutex test
-Initializing mutex
-Starting thread 1
-Starting thread 2
- Thread1 Thread2
- Loops 32 32
- Errors 0 0
-
-End of test memory usage:
-VARIABLE BEFORE AFTER
-======== ======== ========
-arena b1c0 b1c0
-ordblks 3 3
-mxordblk 7ff0 7ff0
-uordblks 1d20 1d20
-fordblks 94a0 94a0
-
-user_main: cancel test
-cancel_test: Test 1: Normal Cancelation
-cancel_test: Starting thread
-start_thread: Initializing mutex
-start_thread: Initializing cond
-start_thread: Starting thread
-thread_waiter: Taking mutex
-thread_waiter: Starting wait for condition
-start_thread: Yielding
-cancel_test: Canceling thread
-cancel_test: Joining
-cancel_test: waiter exited with result=ffffffff
-cancel_test: PASS thread terminated with PTHREAD_CANCELED
-cancel_test: Test 2: Cancelation of detached thread
-cancel_test: Re-starting thread
-restart_thread: Destroying cond
-restart_thread: Destroying mutex
-restart_thread: Re-starting thread
-start_thread: Initializing mutex
-start_thread: Initializing cond
-start_thread: Starting thread
-thread_waiter: Taking mutex
-thread_waiter: Starting wait for condition
-start_thread: Yielding
-cancel_test: Canceling thread
-cancel_test: Joining
-cancel_test: PASS pthread_join failed with status=ESRCH
-cancel_test: Test 3: Non-cancelable threads
-cancel_test: Re-starting thread (non-cancelable)
-restart_thread: Destroying cond
-restart_thread: Destroying mutex
-restart_thread: Re-starting thread
-start_thread: Initializing mutex
-start_thread: Initializing cond
-start_thread: Starting thread
-thread_waiter: Taking mutex
-thread_waiter: Starting wait for condition
-thread_waiter: Setting non-cancelable
-start_thread: Yielding
-cancel_test: Canceling thread
-cancel_test: Joining
-thread_waiter: Releasing mutex
-thread_waiter: Setting cancelable
-cancel_test: waiter exited with result=ffffffff
-cancel_test: PASS thread terminated with PTHREAD_CANCELED
-
-End of test memory usage:
-VARIABLE BEFORE AFTER
-======== ======== ========
-arena b1c0 b1c0
-ordblks 3 3
-mxordblk 7ff0 7ff0
-uordblks 1d20 1d20
-fordblks 94a0 94a0
-
-user_main: semaphore test
-sem_test: Initializing semaphore to 0
-sem_test: Starting waiter thread 1
-sem_test: Set thread 1 priority to 191
-waiter_func: Thread 1 Started
-waiter_func: Thread 1 initial semaphore value = 0
-waiter_func: Thread 1 waiting on semaphore
-sem_test: Starting waiter thread 2
-sem_test: Set thread 2 priority to 128
-waiter_func: Thread 2 Started
-waiter_func: Thread 2 initial semaphore value = -1
-waiter_func: Thread 2 waiting on semaphore
-sem_test: Starting poster thread 3
-sem_test: Set thread 3 priority to 64
-poster_func: Thread 3 started
-poster_func: Thread 3 semaphore value = -2
-poster_func: Thread 3 posting semaphore
-waiter_func: Thread 1 awakened
-waiter_func: Thread 1 new semaphore value = -1
-waiter_func: Thread 1 done
-poster_func: Thread 3 new semaphore value = -1
-poster_func: Thread 3 semaphore value = -1
-poster_func: Thread 3 posting semaphore
-waiter_func: Thread 2 awakened
-waiter_func: Thread 2 new semaphore value = 0
-waiter_func: Thread 2 done
-poster_func: Thread 3 new semaphore value = 0
-poster_func: Thread 3 done
-
-End of test memory usage:
-VARIABLE BEFORE AFTER
-======== ======== ========
-arena b1c0 b1c0
-ordblks 3 3
-mxordblk 7ff0 7ff0
-uordblks 1d20 1d20
-fordblks 94a0 94a0
-
-user_main: condition variable test
-cond_test: Initializing mutex
-cond_test: Initializing cond
-cond_test: Starting waiter
-cond_test: Set thread 1 priority to 128
-waiter_thread: Started
-cond_test: Starting signaler
-cond_test: Set thread 2 priority to 64
-thread_signaler: Started
-thread_signaler: Terminating
-cond_test: signaler terminated, now cancel the waiter
-cond_test: Waiter Signaler
-cond_test: Loops 32 32
-cond_test: Errors 0 0
-cond_test:
-cond_test: 0 times, waiter did not have to wait for data
-cond_test: 0 times, data was already available when the signaler run
-cond_test: 0 times, the waiter was in an unexpected state when the signaler ran
-
-End of test memory usage:
-VARIABLE BEFORE AFTER
-======== ======== ========
-arena b1c0 b1c0
-ordblks 3 3
-mxordblk 7ff0 7ff0
-uordblks 1d20 1d20
-fordblks 94a0 94a0
-
-user_main: timed wait test
-thread_waiter: Initializing mutex
-timedwait_test: Initializing cond
-timedwait_test: Starting waiter
-timedwait_test: Set thread 2 priority to 177
-thread_waiter: Taking mutex
-thread_waiter: Starting 5 second wait for condition
-timedwait_test: Joining
-thread_waiter: pthread_cond_timedwait timed out
-thread_waiter: Releasing mutex
-thread_waiter: Exit with status 0x12345678
-timedwait_test: waiter exited with result=12345678
-
-End of test memory usage:
-VARIABLE BEFORE AFTER
-======== ======== ========
-arena b1c0 b1c0
-ordblks 3 3
-mxordblk 7ff0 7ff0
-uordblks 1d20 1d20
-fordblks 94a0 94a0
-
-user_main: message queue test
-mqueue_test: Starting receiver
-mqueue_test: Set receiver priority to 128
-receiver_thread: Starting
-mqueue_test: Starting sender
-mqueue_test: Set sender thread priority to 64
-mqueue_test: Waiting for sender to complete
-sender_thread: Starting
-receiver_thread: mq_receive succeeded on msg 0
-sender_thread: mq_send succeeded on msg 0
-receiver_thread: mq_receive succeeded on msg 1
-sender_thread: mq_send succeeded on msg 1
-receiver_thread: mq_receive succeeded on msg 2
-sender_thread: mq_send succeeded on msg 2
-receiver_thread: mq_receive succeeded on msg 3
-sender_thread: mq_send succeeded on msg 3
-receiver_thread: mq_receive succeeded on msg 4
-sender_thread: mq_send succeeded on msg 4
-receiver_thread: mq_receive succeeded on msg 5
-sender_thread: mq_send succeeded on msg 5
-receiver_thread: mq_receive succeeded on msg 6
-sender_thread: mq_send succeeded on msg 6
-receiver_thread: mq_receive succeeded on msg 7
-sender_thread: mq_send succeeded on msg 7
-receiver_thread: mq_receive succeeded on msg 8
-sender_thread: mq_send succeeded on msg 8
-receiver_thread: mq_receive succeeded on msg 9
-sender_thread: mq_send succeeded on msg 9
-sender_thread: returning nerrors=0
-mqueue_test: Killing receiver
-receiver_thread: mq_receive interrupted!
-receiver_thread: returning nerrors=0
-mqueue_test: Canceling receiver
-mqueue_test: receiver has already terminated
-
-End of test memory usage:
-VARIABLE BEFORE AFTER
-======== ======== ========
-arena b1c0 b1c0
-ordblks 3 3
-mxordblk 7ff0 7ff0
-uordblks 1d20 1d20
-fordblks 94a0 94a0
-
-user_main: timed message queue test
-timedmqueue_test: Starting sender
-sender_thread: Starting
-sender_thread: mq_timedsend succeeded on msg 0
-sender_thread: mq_timedsend succeeded on msg 1
-sender_thread: mq_timedsend succeeded on msg 2
-sender_thread: mq_timedsend succeeded on msg 3
-sender_thread: mq_timedsend succeeded on msg 4
-sender_thread: mq_timedsend succeeded on msg 5
-sender_thread: mq_timedsend succeeded on msg 6
-sender_thread: mq_timedsend succeeded on msg 7
-sender_thread: mq_timedsend succeeded on msg 8
-timedmqueue_test: Waiting for sender to complete
-sender_thread: mq_timedsend 9 timed out as expected
-sender_thread: returning nerrors=0
-timedmqueue_test: Starting receiver
-receiver_thread: Starting
-receiver_thread: mq_timedreceive succeeded on msg 0
-receiver_thread: mq_timedreceive succeeded on msg 1
-receiver_thread: mq_timedreceive succeeded on msg 2
-receiver_thread: mq_timedreceive succeeded on msg 3
-receiver_thread: mq_timedreceive succeeded on msg 4
-receiver_thread: mq_timedreceive succeeded on msg 5
-receiver_thread: mq_timedreceive succeeded on msg 6
-receiver_thread: mq_timedreceive succeeded on msg 7
-receiver_thread: mq_timedreceive succeeded on msg 8
-timedmqueue_test: Waiting for receiver to complete
-receiver_thread: Receive 9 timed out as expected
-receiver_thread: returning nerrors=0
-timedmqueue_test: Test complete
-
-End of test memory usage:
-VARIABLE BEFORE AFTER
-======== ======== ========
-arena b1c0 b1c0
-ordblks 3 3
-mxordblk 7ff0 7ff0
-uordblks 1d20 1d20
-fordblks 94a0 94a0
-
-user_main: signal handler test
-sighand_test: Initializing semaphore to 0
-sighand_test: Starting waiter task
-sighand_test: Started waiter_main pid=20
-waiter_main: Waiter started
-waiter_main: Unmasking signal 17
-waiter_main: Registering signal handler
-waiter_main: oact.sigaction=0 oact.sa_flags=0 oact.sa_mask=0
-waiter_main: Waiting on semaphore
-sighand_test: Signaling pid=20 with signo=17 sigvalue=42
-wakeup_action: Received signal 17
-wakeup_action: sival_int=42
-wakeup_action: si_code=1
-wakeup_action: ucontext=0
-waiter_main: sem_wait() successfully interrupted by signal
-waiter_main: done
-sighand_test: done
-
-End of test memory usage:
-VARIABLE BEFORE AFTER
-======== ======== ========
-arena b1c0 b1c0
-ordblks 3 3
-mxordblk 7ff0 7ff0
-uordblks 1d20 1d20
-fordblks 94a0 94a0
-
-user_main: POSIX timer test
-timer_test: Initializing semaphore to 0
-timer_test: Unmasking signal 17
-timer_test: Registering signal handler
-timer_test: oact.sigaction=0 oact.sa_flags=0 oact.sa_mask=0
-timer_test: Creating timer
-timer_test: Starting timer
-timer_test: Waiting on semaphore
-timer_expiration: Received signal 17
-timer_expiration: sival_int=42
-timer_expiration: si_code=2 (SI_TIMER)
-timer_expiration: ucontext=0
-timer_test: sem_wait() successfully interrupted by signal
-timer_test: g_nsigreceived=1
-timer_test: Waiting on semaphore
-timer_expiration: Received signal 17
-timer_expiration: sival_int=42
-timer_expiration: si_code=2 (SI_TIMER)
-timer_expiration: ucontext=0
-timer_test: sem_wait() successfully interrupted by signal
-timer_test: g_nsigreceived=2
-timer_test: Waiting on semaphore
-timer_expiration: Received signal 17
-timer_expiration: sival_int=42
-timer_expiration: si_code=2 (SI_TIMER)
-timer_expiration: ucontext=0
-timer_test: sem_wait() successfully interrupted by signal
-timer_test: g_nsigreceived=3
-timer_test: Waiting on semaphore
-timer_expiration: Received signal 17
-timer_expiration: sival_int=42
-timer_expiration: si_code=2 (SI_TIMER)
-timer_expiration: ucontext=0
-timer_test: sem_wait() successfully interrupted by signal
-timer_test: g_nsigreceived=4
-timer_test: Waiting on semaphore
-timer_expiration: Received signal 17
-timer_expiration: sival_int=42
-timer_expiration: si_code=2 (SI_TIMER)
-timer_expiration: ucontext=0
-timer_test: sem_wait() successfully interrupted by signal
-timer_test: g_nsigreceived=5
-timer_test: Deleting timer
-timer_test: done
-
-End of test memory usage:
-VARIABLE BEFORE AFTER
-======== ======== ========
-arena b1c0 b1c0
-ordblks 3 3
-mxordblk 7ff0 7ff0
-uordblks 1d20 1d20
-fordblks 94a0 94a0
-
-user_main: round-robin scheduler test
-rr_test: Starting sieve1 thread
-rr_test: Set thread priority to 1
-rr_test: Set thread policty to SCHED_RR
-rr_test: Starting sieve1 thread
-sieve1 started
-rr_test: Waiting for sieves to complete -- this should take awhile
-rr_test: If RR scheduling is working, they should start and complete at
-rr_test: about the same time
-sieve2 started
-sieve1 finished
-sieve2 finished
-rr_test: Done
-
-End of test memory usage:
-VARIABLE BEFORE AFTER
-======== ======== ========
-arena b1c0 b1c0
-ordblks 3 3
-mxordblk 7ff0 7ff0
-uordblks 1d20 1d20
-fordblks 94a0 94a0
-
-user_main: barrier test
-barrier_test: Initializing barrier
-barrier_func: Thread 0 started
-barrier_test: Thread 0 created
-barrier_func: Thread 1 started
-barrier_test: Thread 1 created
-barrier_func: Thread 2 started
-barrier_test: Thread 2 created
-barrier_func: Thread 0 calling pthread_barrier_wait()
-barrier_func: Thread 1 calling pthread_barrier_wait()
-barrier_func: Thread 2 calling pthread_barrier_wait()
-barrier_func: Thread 2, back with status=PTHREAD_BARRIER_SERIAL_THREAD (I AM SPECIAL)
-barrier_func: Thread 0, back with status=0 (I am not special)
-barrier_func: Thread 1, back with status=0 (I am not special)
-barrier_func: Thread 2 done
-barrier_func: Thread 0 done
-barrier_func: Thread 1 done
-barrier_test: Thread 0 completed with result=0
-barrier_test: Thread 1 completed with result=0
-barrier_test: Thread 2 completed with result=0
-
-End of test memory usage:
-VARIABLE BEFORE AFTER
-======== ======== ========
-arena b1c0 b1c0
-ordblks 3 3
-mxordblk 7ff0 7ff0
-uordblks 1d20 1d20
-fordblks 94a0 94a0
-
-Final memory usage:
-VARIABLE BEFORE AFTER
-======== ======== ========
-arena b1c0 b1c0
-ordblks 3 3
-mxordblk 7ff0 7ff0
-uordblks 1d20 1d20
-fordblks 94a0 94a0
-user_main: Exitting
diff --git a/nuttx/configs/avr32dev1/src/up_boot.c b/nuttx/configs/avr32dev1/src/up_boot.c
index d831389e6..0fc8971d1 100755
--- a/nuttx/configs/avr32dev1/src/up_boot.c
+++ b/nuttx/configs/avr32dev1/src/up_boot.c
@@ -47,7 +47,7 @@
#include "up_arch.h"
#include "up_internal.h"
-#include "avr32_internal.h"
+#include "at91uc3_internal.h"
#include "avr32dev1_internal.h"
/************************************************************************************
diff --git a/nuttx/configs/avr32dev1/src/up_leds.c b/nuttx/configs/avr32dev1/src/up_leds.c
index 0ea291207..62ccd5a88 100755
--- a/nuttx/configs/avr32dev1/src/up_leds.c
+++ b/nuttx/configs/avr32dev1/src/up_leds.c
@@ -50,7 +50,7 @@
#include "up_arch.h"
#include "up_internal.h"
-#include "avr32_internal.h"
+#include "at91uc3_internal.h"
#include "avr32dev1_internal.h"
#ifdef CONFIG_ARCH_LEDS
diff --git a/nuttx/sched/irq_initialize.c b/nuttx/sched/irq_initialize.c
index 91e812644..48afa4431 100644
--- a/nuttx/sched/irq_initialize.c
+++ b/nuttx/sched/irq_initialize.c
@@ -1,7 +1,7 @@
/****************************************************************************
* sched/irq_initialize.c
*
- * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2008, 2010 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without