aboutsummaryrefslogtreecommitdiff
path: root/nuttx/arch
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-01-24 19:19:38 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-01-24 19:19:38 +0000
commit25e9b8d0846b68a18014c63146234193bfe539e8 (patch)
treee48f905cc912d6a082af49fb9e631a5a5b66d251 /nuttx/arch
parent91504abf89988b25322cd04f416c44bfbfbc86c2 (diff)
downloadpx4-firmware-25e9b8d0846b68a18014c63146234193bfe539e8.tar.gz
px4-firmware-25e9b8d0846b68a18014c63146234193bfe539e8.tar.bz2
px4-firmware-25e9b8d0846b68a18014c63146234193bfe539e8.zip
Fix poll/select issue reported by Qiang
git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5559 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch')
-rw-r--r--nuttx/arch/8051/src/up_reprioritizertr.c13
-rw-r--r--nuttx/arch/arm/src/armv7-m/up_reprioritizertr.c13
-rw-r--r--nuttx/arch/arm/src/lm/chip/lm4f_memorymap.h85
-rw-r--r--nuttx/arch/avr/src/avr/up_reprioritizertr.c13
-rw-r--r--nuttx/arch/avr/src/avr32/up_reprioritizertr.c13
-rw-r--r--nuttx/arch/hc/src/common/up_reprioritizertr.c2
-rw-r--r--nuttx/arch/mips/src/mips32/up_reprioritizertr.c13
-rw-r--r--nuttx/arch/sh/src/common/up_reprioritizertr.c13
-rw-r--r--nuttx/arch/sim/src/up_reprioritizertr.c6
-rw-r--r--nuttx/arch/x86/src/common/up_reprioritizertr.c2
-rw-r--r--nuttx/arch/z16/src/common/up_reprioritizertr.c13
-rw-r--r--nuttx/arch/z80/src/common/up_reprioritizertr.c13
12 files changed, 162 insertions, 37 deletions
diff --git a/nuttx/arch/8051/src/up_reprioritizertr.c b/nuttx/arch/8051/src/up_reprioritizertr.c
index 6d4a72487..0d1941f66 100644
--- a/nuttx/arch/8051/src/up_reprioritizertr.c
+++ b/nuttx/arch/8051/src/up_reprioritizertr.c
@@ -1,7 +1,7 @@
/****************************************************************************
* up_reprioritizertr.c
*
- * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -90,9 +90,14 @@ void up_reprioritize_rtr(FAR _TCB *tcb, uint8_t priority)
/* Verify that the caller is sane */
if (tcb->task_state < FIRST_READY_TO_RUN_STATE ||
- tcb->task_state > LAST_READY_TO_RUN_STATE ||
- priority < SCHED_PRIORITY_MIN ||
- priority > SCHED_PRIORITY_MAX)
+ tcb->task_state > LAST_READY_TO_RUN_STATE
+#if SCHED_PRIORITY_MIN > 0
+ || priority < SCHED_PRIORITY_MIN
+#endif
+#if SCHED_PRIORITY_MAX < UINT8_MAX
+ || priority > SCHED_PRIORITY_MAX
+#endif
+ )
{
PANIC(OSERR_BADREPRIORITIZESTATE);
}
diff --git a/nuttx/arch/arm/src/armv7-m/up_reprioritizertr.c b/nuttx/arch/arm/src/armv7-m/up_reprioritizertr.c
index f1c961b15..9a971f064 100644
--- a/nuttx/arch/arm/src/armv7-m/up_reprioritizertr.c
+++ b/nuttx/arch/arm/src/armv7-m/up_reprioritizertr.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/armv7-m/up_reprioritizertr.c
*
- * Copyright (C) 2007-2009, 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009, 2012-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -89,9 +89,14 @@ void up_reprioritize_rtr(_TCB *tcb, uint8_t priority)
/* Verify that the caller is sane */
if (tcb->task_state < FIRST_READY_TO_RUN_STATE ||
- tcb->task_state > LAST_READY_TO_RUN_STATE ||
- priority < SCHED_PRIORITY_MIN ||
- priority > SCHED_PRIORITY_MAX)
+ tcb->task_state > LAST_READY_TO_RUN_STATE
+#if SCHED_PRIORITY_MIN > 0
+ || priority < SCHED_PRIORITY_MIN
+#endif
+#if SCHED_PRIORITY_MAX < UINT8_MAX
+ || priority > SCHED_PRIORITY_MAX
+#endif
+ )
{
PANIC(OSERR_BADREPRIORITIZESTATE);
}
diff --git a/nuttx/arch/arm/src/lm/chip/lm4f_memorymap.h b/nuttx/arch/arm/src/lm/chip/lm4f_memorymap.h
new file mode 100644
index 000000000..6963545fe
--- /dev/null
+++ b/nuttx/arch/arm/src/lm/chip/lm4f_memorymap.h
@@ -0,0 +1,85 @@
+/************************************************************************************
+ * arch/arm/src/lm/chip/lm3s_memorymap.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Authors: Gregory Nutt <gnutt@nuttx.org>
+ * Jose Pablo Carballo <jcarballo@nx-engineering.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_ARM_SRC_LM_CHIP_LM4F_MEMORYMAP_H
+#define __ARCH_ARM_SRC_LM_CHIP_LM4F_MEMORYMAP_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Memory map ***********************************************************************/
+
+#if defined(CONFIG_ARCH_CHIP_LM4F120)
+# define LM_FLASH_BASE 0x00000000 /* -0x0003ffff: On-chip FLASH */
+ /* -0x00ffffff: Reserved */
+# define LM_ROM_BASE 0x01000000 /* -0x1fffffff: Reserved for ROM */
+# define LM_SRAM_BASE 0x20000000 /* -0x20007fff: Bit-banded on-chip SRAM */
+ /* -0x21ffffff: Reserved */
+/* @TODO */
+#endif
+
+#else
+# error "Memory map not specified for this LM4F chip"
+#endif
+
+/* Peripheral base addresses ********************************************************/
+
+#if defined(CONFIG_ARCH_CHIP_LM4F120)
+/* @TODO */
+#else
+# error "Peripheral base addresses not specified for this Stellaris chip"
+#endif
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Function Prototypes
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_LM_CHIP_LM4F_MEMORYMAP_H */
diff --git a/nuttx/arch/avr/src/avr/up_reprioritizertr.c b/nuttx/arch/avr/src/avr/up_reprioritizertr.c
index 14033a3bd..af329c13f 100644
--- a/nuttx/arch/avr/src/avr/up_reprioritizertr.c
+++ b/nuttx/arch/avr/src/avr/up_reprioritizertr.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/avr/src/avr/up_reprioritizertr.c
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -89,9 +89,14 @@ void up_reprioritize_rtr(_TCB *tcb, uint8_t priority)
/* Verify that the caller is sane */
if (tcb->task_state < FIRST_READY_TO_RUN_STATE ||
- tcb->task_state > LAST_READY_TO_RUN_STATE ||
- priority < SCHED_PRIORITY_MIN ||
- priority > SCHED_PRIORITY_MAX)
+ tcb->task_state > LAST_READY_TO_RUN_STATE
+#if SCHED_PRIORITY_MIN > 0
+ || priority < SCHED_PRIORITY_MIN
+#endif
+#if SCHED_PRIORITY_MAX < UINT8_MAX
+ || priority > SCHED_PRIORITY_MAX
+#endif
+ )
{
PANIC(OSERR_BADREPRIORITIZESTATE);
}
diff --git a/nuttx/arch/avr/src/avr32/up_reprioritizertr.c b/nuttx/arch/avr/src/avr32/up_reprioritizertr.c
index e1712fed0..0aad214e8 100644
--- a/nuttx/arch/avr/src/avr32/up_reprioritizertr.c
+++ b/nuttx/arch/avr/src/avr32/up_reprioritizertr.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/avr/src/avr32/up_reprioritizertr.c
*
- * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2010, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -89,9 +89,14 @@ void up_reprioritize_rtr(_TCB *tcb, uint8_t priority)
/* Verify that the caller is sane */
if (tcb->task_state < FIRST_READY_TO_RUN_STATE ||
- tcb->task_state > LAST_READY_TO_RUN_STATE ||
- priority < SCHED_PRIORITY_MIN ||
- priority > SCHED_PRIORITY_MAX)
+ tcb->task_state > LAST_READY_TO_RUN_STATE
+#if SCHED_PRIORITY_MIN > 0
+ || priority < SCHED_PRIORITY_MIN
+#endif
+#if SCHED_PRIORITY_MAX < UINT8_MAX
+ || priority > SCHED_PRIORITY_MAX
+#endif
+ )
{
PANIC(OSERR_BADREPRIORITIZESTATE);
}
diff --git a/nuttx/arch/hc/src/common/up_reprioritizertr.c b/nuttx/arch/hc/src/common/up_reprioritizertr.c
index ffd90bf1f..31c76a9f5 100644
--- a/nuttx/arch/hc/src/common/up_reprioritizertr.c
+++ b/nuttx/arch/hc/src/common/up_reprioritizertr.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/hc/src/common/up_reprioritizertr.c
*
- * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2010, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
diff --git a/nuttx/arch/mips/src/mips32/up_reprioritizertr.c b/nuttx/arch/mips/src/mips32/up_reprioritizertr.c
index 66ce687e0..2e5f41d68 100644
--- a/nuttx/arch/mips/src/mips32/up_reprioritizertr.c
+++ b/nuttx/arch/mips/src/mips32/up_reprioritizertr.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/mips/src/mips32/up_reprioritizertr.c
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -91,9 +91,14 @@ void up_reprioritize_rtr(_TCB *tcb, uint8_t priority)
/* Verify that the caller is sane */
if (tcb->task_state < FIRST_READY_TO_RUN_STATE ||
- tcb->task_state > LAST_READY_TO_RUN_STATE ||
- priority < SCHED_PRIORITY_MIN ||
- priority > SCHED_PRIORITY_MAX)
+ tcb->task_state > LAST_READY_TO_RUN_STATE
+#if SCHED_PRIORITY_MIN > 0
+ || priority < SCHED_PRIORITY_MIN
+#endif
+#if SCHED_PRIORITY_MAX < UINT8_MAX
+ || priority > SCHED_PRIORITY_MAX
+#endif
+ )
{
PANIC(OSERR_BADREPRIORITIZESTATE);
}
diff --git a/nuttx/arch/sh/src/common/up_reprioritizertr.c b/nuttx/arch/sh/src/common/up_reprioritizertr.c
index 728cafdf3..99d350b29 100644
--- a/nuttx/arch/sh/src/common/up_reprioritizertr.c
+++ b/nuttx/arch/sh/src/common/up_reprioritizertr.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/sh/src/common/up_reprioritizertr.c
*
- * Copyright (C) 2008-2009, 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2008-2009, 2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -89,9 +89,14 @@ void up_reprioritize_rtr(_TCB *tcb, uint8_t priority)
/* Verify that the caller is sane */
if (tcb->task_state < FIRST_READY_TO_RUN_STATE ||
- tcb->task_state > LAST_READY_TO_RUN_STATE ||
- priority < SCHED_PRIORITY_MIN ||
- priority > SCHED_PRIORITY_MAX)
+ tcb->task_state > LAST_READY_TO_RUN_STATE
+#if SCHED_PRIORITY_MIN > 0
+ || priority < SCHED_PRIORITY_MIN
+#endif
+#if SCHED_PRIORITY_MAX < UINT8_MAX
+ || priority > SCHED_PRIORITY_MAX
+#endif
+ )
{
PANIC(OSERR_BADREPRIORITIZESTATE);
}
diff --git a/nuttx/arch/sim/src/up_reprioritizertr.c b/nuttx/arch/sim/src/up_reprioritizertr.c
index 913d8d5f5..15c1b26d5 100644
--- a/nuttx/arch/sim/src/up_reprioritizertr.c
+++ b/nuttx/arch/sim/src/up_reprioritizertr.c
@@ -1,7 +1,7 @@
/****************************************************************************
* up_reprioritizertr.c
*
- * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -91,13 +91,13 @@ void up_reprioritize_rtr(_TCB *tcb, uint8_t priority)
if (tcb->task_state < FIRST_READY_TO_RUN_STATE ||
tcb->task_state > LAST_READY_TO_RUN_STATE
-#if SCHED_PRIORITY_MIN > UINT8_MIN
+#if SCHED_PRIORITY_MIN > 0
|| priority < SCHED_PRIORITY_MIN
#endif
#if SCHED_PRIORITY_MAX < UINT8_MAX
|| priority > SCHED_PRIORITY_MAX
#endif
- )
+ )
{
PANIC(OSERR_BADREPRIORITIZESTATE);
}
diff --git a/nuttx/arch/x86/src/common/up_reprioritizertr.c b/nuttx/arch/x86/src/common/up_reprioritizertr.c
index ad8a748a8..53a0e4315 100644
--- a/nuttx/arch/x86/src/common/up_reprioritizertr.c
+++ b/nuttx/arch/x86/src/common/up_reprioritizertr.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/arm/up_reprioritizertr.c
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
diff --git a/nuttx/arch/z16/src/common/up_reprioritizertr.c b/nuttx/arch/z16/src/common/up_reprioritizertr.c
index 0363184cd..6e76d6ce1 100644
--- a/nuttx/arch/z16/src/common/up_reprioritizertr.c
+++ b/nuttx/arch/z16/src/common/up_reprioritizertr.c
@@ -1,7 +1,7 @@
/****************************************************************************
* common/up_reprioritizertr.c
*
- * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2008-2009, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -91,9 +91,14 @@ void up_reprioritize_rtr(FAR _TCB *tcb, uint8_t priority)
/* Verify that the caller is sane */
if (tcb->task_state < FIRST_READY_TO_RUN_STATE ||
- tcb->task_state > LAST_READY_TO_RUN_STATE ||
- priority < SCHED_PRIORITY_MIN ||
- priority > SCHED_PRIORITY_MAX)
+ tcb->task_state > LAST_READY_TO_RUN_STATE
+#if SCHED_PRIORITY_MIN > 0
+ || priority < SCHED_PRIORITY_MIN
+#endif
+#if SCHED_PRIORITY_MAX < UINT8_MAX
+ || priority > SCHED_PRIORITY_MAX
+#endif
+ )
{
PANIC(OSERR_BADREPRIORITIZESTATE);
}
diff --git a/nuttx/arch/z80/src/common/up_reprioritizertr.c b/nuttx/arch/z80/src/common/up_reprioritizertr.c
index 84cd3e1e1..b8102c99f 100644
--- a/nuttx/arch/z80/src/common/up_reprioritizertr.c
+++ b/nuttx/arch/z80/src/common/up_reprioritizertr.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/z80/src/common/up_reprioritizertr.c
*
- * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -92,9 +92,14 @@ void up_reprioritize_rtr(FAR _TCB *tcb, uint8_t priority)
/* Verify that the caller is sane */
if (tcb->task_state < FIRST_READY_TO_RUN_STATE ||
- tcb->task_state > LAST_READY_TO_RUN_STATE ||
- priority < SCHED_PRIORITY_MIN ||
- priority > SCHED_PRIORITY_MAX)
+ tcb->task_state > LAST_READY_TO_RUN_STATE
+#if SCHED_PRIORITY_MIN > 0
+ || priority < SCHED_PRIORITY_MIN
+#endif
+#if SCHED_PRIORITY_MAX < UINT8_MAX
+ || priority > SCHED_PRIORITY_MAX
+#endif
+ )
{
PANIC(OSERR_BADREPRIORITIZESTATE);
}