aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rwxr-xr-xapps/ChangeLog.txt7
-rw-r--r--apps/examples/ostest/prioinherit.c12
-rw-r--r--apps/nshlib/nsh_parse.c2
-rw-r--r--nuttx/ChangeLog18
-rw-r--r--nuttx/Makefile1
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_otgfshost.c168
-rw-r--r--nuttx/configs/README.txt8
-rwxr-xr-xnuttx/fs/nxffs/README.txt11
-rw-r--r--nuttx/fs/romfs/fs_romfsutil.c2
-rw-r--r--nuttx/sched/sched_setuptaskfiles.c4
-rw-r--r--nuttx/sched/sem_holder.c296
-rw-r--r--nuttx/sched/sem_post.c16
-rw-r--r--nuttx/syscall/syscall.csv4
-rw-r--r--nuttx/tools/Config.mk38
14 files changed, 434 insertions, 153 deletions
diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt
index 6c151ae50..361fb97dc 100755
--- a/apps/ChangeLog.txt
+++ b/apps/ChangeLog.txt
@@ -283,4 +283,11 @@
* apps/netutils/thttpd/thttpd_cgi.c: Missing NULL in argv[]
list (contributed by Kate).
+ * apps/nshlib/nsh_parse.c: CONFIG_NSH_DISABLE_WGET not CONFIG_NSH_DISABLE_GET
+ in one location (found by Kate).
+ * apps/examples/ostest/prioinherit.c: Limit the number of test
+ threds to no more than 3 of each priority. Bad things happen
+ when the existing logic tried to created several hundred test
+ treads!
+
diff --git a/apps/examples/ostest/prioinherit.c b/apps/examples/ostest/prioinherit.c
index 87849abcf..eea5a818f 100644
--- a/apps/examples/ostest/prioinherit.c
+++ b/apps/examples/ostest/prioinherit.c
@@ -59,20 +59,28 @@
# define CONFIG_SEM_PREALLOCHOLDERS 0
#endif
+/* If resources were configured for lots of holders, then run 3 low priority
+ * threads. Otherwise, just one.
+ */
+
#if CONFIG_SEM_PREALLOCHOLDERS > 3
# define NLOWPRI_THREADS 3
#else
-# define NLOWPRI_THREADS (CONFIG_SEM_PREALLOCHOLDERS+1)
+# define NLOWPRI_THREADS 1
#endif
#ifndef CONFIG_SEM_NNESTPRIO
# define CONFIG_SEM_NNESTPRIO 0
#endif
+/* Where resources configured for lots of waiters? If so then run 3 high
+ * priority threads. Otherwise, just one.
+ */
+
#if CONFIG_SEM_NNESTPRIO > 3
# define NHIGHPRI_THREADS 3
#else
-# define NHIGHPRI_THREADS (CONFIG_SEM_NNESTPRIO+1)
+# define NHIGHPRI_THREADS 1
#endif
/****************************************************************************
diff --git a/apps/nshlib/nsh_parse.c b/apps/nshlib/nsh_parse.c
index 165f842fc..ba597a062 100644
--- a/apps/nshlib/nsh_parse.c
+++ b/apps/nshlib/nsh_parse.c
@@ -370,7 +370,7 @@ static const struct cmdmap_s g_cmdmap[] =
#endif
#if defined(CONFIG_NET_TCP) && CONFIG_NFILE_DESCRIPTORS > 0
-# ifndef CONFIG_NSH_DISABLE_GET
+# ifndef CONFIG_NSH_DISABLE_WGET
{ "wget", cmd_wget, 2, 4, "[-o <local-path>] <url>" },
# endif
#endif
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index cb7f4079d..eff224f79 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -3185,3 +3185,21 @@
This list handling was probably causing errors reported by Mike Smith
* sched/sched_waitpid.c: Fix a possible issue with logic logic that
should be brought into a critical section (suggested by Mike Smith)
+ * sched/sched_setuptaskfiles.c: Should be 'struct socket' not
+ 'struct sockets'. How did this compile before? (found by Kate)
+ * syscall/syscall.csv: Fix prototype for usleep() and prctl() (also
+ from Kate).
+ * arch/arm/src/lpc17xx/lpc17_ethernet.c: Conditionally elide setting PHY
+ speed/duplex. This does not work for certain PHYs. Still some unresolved
+ issues (also from Kate).
+ * tools/Config.mk, Makefile, configs/*/Make.defs: Add a new Makefile
+ fragement to de-quoate certain strings from the Kconfig logic that
+ need to be used at path segments (Richard Cochran).
+ * arch/arm/src/stm32/stm32_usbotghost.c: The STM32 USB host driver only
+ works with debug turned on. The problem appears to be that with debug
+ OFF, there are more NAKs occuring in more places than before and this
+ reveals a variety of errors. This check in improves NAK robustness
+ for control transfers but does not resolve all of the issues.
+ * configs/stm3220g-eval/*/defconfig: Calibrated delay loop. It had
+ never been calibrated was was way off.
+
diff --git a/nuttx/Makefile b/nuttx/Makefile
index b0a17efd2..1a51ca09b 100644
--- a/nuttx/Makefile
+++ b/nuttx/Makefile
@@ -35,6 +35,7 @@
TOPDIR := ${shell pwd | sed -e 's/ /\\ /g'}
-include ${TOPDIR}/.config
+-include ${TOPDIR}/tools/Config.mk
-include ${TOPDIR}/Make.defs
# Default tools
diff --git a/nuttx/arch/arm/src/stm32/stm32_otgfshost.c b/nuttx/arch/arm/src/stm32/stm32_otgfshost.c
index 0b09070dc..ce0e9036e 100644
--- a/nuttx/arch/arm/src/stm32/stm32_otgfshost.c
+++ b/nuttx/arch/arm/src/stm32/stm32_otgfshost.c
@@ -48,6 +48,10 @@
#include <errno.h>
#include <debug.h>
+#if !defined(CONFIG_DEBUG_VERBOSE) && !defined(CONFIG_DEBUG_USB)
+# include <debug.h>
+#endif
+
#include <nuttx/arch.h>
#include <nuttx/kmalloc.h>
#include <nuttx/usb/usb.h>
@@ -141,14 +145,15 @@
#define STM32_EP0_MAX_PACKET_SIZE 64 /* EP0 FS max packet size */
#define STM32_MAX_TX_FIFOS 15 /* Max number of TX FIFOs */
#define STM32_MAX_PKTCOUNT 256 /* Max packet count */
-#define STM32_RETRY_COUNT 3 /* Number of retries */
+#define STM32_RETRY_COUNT 3 /* Number of ctrl transfer retries */
#define STM32_DEF_DEVADDR 0 /* Default device address */
/* Delays **********************************************************************/
-#define STM32_READY_DELAY 200000 /* In loop counts */
-#define STM32_FLUSH_DELAY 200000 /* In loop counts */
-#define STM32_NOTREADY_DELAY 5000 /* In frames */
+#define STM32_READY_DELAY 200000 /* In loop counts */
+#define STM32_FLUSH_DELAY 200000 /* In loop counts */
+#define STM32_SETUP_DELAY 5000 /* In frames */
+#define STM32_DATANAK_DELAY 5000 /* In frames */
/* Ever-present MIN/MAX macros */
@@ -376,10 +381,11 @@ static void stm32_disconnect(FAR struct usbhost_driver_s *drvr);
/* Initialization **************************************************************/
static void stm32_portreset(FAR struct stm32_usbhost_s *priv);
-static inline void stm32_flush_txfifos(uint32_t txfnum);
-static inline void stm32_flush_rxfifo(void);
+static void stm32_flush_txfifos(uint32_t txfnum);
+static void stm32_flush_rxfifo(void);
static void stm32_vbusdrive(FAR struct stm32_usbhost_s *priv, bool state);
static void stm32_host_initialize(FAR struct stm32_usbhost_s *priv);
+
static inline void stm32_sw_initialize(FAR struct stm32_usbhost_s *priv);
static inline int stm32_hw_initialize(FAR struct stm32_usbhost_s *priv);
@@ -1196,14 +1202,15 @@ static int stm32_ctrl_sendsetup(FAR struct stm32_usbhost_s *priv,
FAR const struct usb_ctrlreq_s *req)
{
FAR struct stm32_chan_s *chan;
- uint16_t start = stm32_getframe();
+ uint16_t start;
uint16_t elapsed;
int ret;
- chan = &priv->chan[priv->ep0out];
-
/* Loop while the device reports NAK (and a timeout is not exceeded */
+ chan = &priv->chan[priv->ep0out];
+ start = stm32_getframe();
+
do
{
/* Send the SETUP packet */
@@ -1248,11 +1255,11 @@ static int stm32_ctrl_sendsetup(FAR struct stm32_usbhost_s *priv,
return ret;
}
- /* Get the elpased time (in frames) */
+ /* Get the elapsed time (in frames) */
elapsed = stm32_getframe() - start;
}
- while (elapsed < STM32_NOTREADY_DELAY);
+ while (elapsed < STM32_SETUP_DELAY);
return -ETIMEDOUT;
}
@@ -1885,7 +1892,7 @@ static void stm32_gint_connected(FAR struct stm32_usbhost_s *priv)
if (!priv->connected)
{
/* Yes.. then now we are connected */
-
+
ullvdbg("Connected\n");
priv->connected = true;
DEBUGASSERT(priv->smstate == SMSTATE_DETACHED);
@@ -3284,6 +3291,8 @@ static int stm32_ctrlin(FAR struct usbhost_driver_s *drvr,
{
struct stm32_usbhost_s *priv = (struct stm32_usbhost_s *)drvr;
uint16_t buflen;
+ uint16_t start;
+ uint16_t elapsed;
int retries;
int ret;
@@ -3300,7 +3309,7 @@ static int stm32_ctrlin(FAR struct usbhost_driver_s *drvr,
stm32_takesem(&priv->exclsem);
- /* Loop, retrying until the retry count expires */
+ /* Loop, retrying until the retry time expires */
for (retries = 0; retries < STM32_RETRY_COUNT; retries++)
{
@@ -3308,38 +3317,55 @@ static int stm32_ctrlin(FAR struct usbhost_driver_s *drvr,
ret = stm32_ctrl_sendsetup(priv, req);
if (ret < 0)
- {
+ {
udbg("stm32_ctrl_sendsetup failed: %d\n", ret);
- return ret;
+ continue;
}
- /* Handle the IN data phase (if any) */
+ /* Get the start time. Loop again until the timeout expires */
- if (buflen > 0)
+ start = stm32_getframe();
+ do
{
- ret = stm32_ctrl_recvdata(priv, buffer, buflen);
- if (ret < 0)
+ /* Handle the IN data phase (if any) */
+
+ if (buflen > 0)
{
- udbg("stm32_ctrl_recvdata failed: %d\n", ret);
- continue;
+ ret = stm32_ctrl_recvdata(priv, buffer, buflen);
+ if (ret < 0)
+ {
+ udbg("stm32_ctrl_recvdata failed: %d\n", ret);
+ }
}
- }
- /* Handle the status OUT phase */
+ /* Handle the status OUT phase */
- priv->chan[priv->ep0out].outdata1 ^= true;
- ret = stm32_ctrl_senddata(priv, NULL, 0);
- if (ret == OK)
- {
- break;
- }
+ if (ret == OK)
+ {
+ priv->chan[priv->ep0out].outdata1 ^= true;
+ ret = stm32_ctrl_senddata(priv, NULL, 0);
+ if (ret == OK)
+ {
+ /* All success transactions exit here */
+
+ stm32_givesem(&priv->exclsem);
+ return OK;
+ }
- udbg("stm32_ctrl_senddata failed: %d\n", ret);
- ret = -ETIMEDOUT;
+ udbg("stm32_ctrl_senddata failed: %d\n", ret);
+ }
+
+ /* Get the elapsed time (in frames) */
+
+ elapsed = stm32_getframe() - start;
+ }
+ while (elapsed < STM32_DATANAK_DELAY);
}
+ /* All failures exit here after all retries and timeouts have been exhausted */
+
stm32_givesem(&priv->exclsem);
- return ret;
+ return -ETIMEDOUT;
}
static int stm32_ctrlout(FAR struct usbhost_driver_s *drvr,
@@ -3348,6 +3374,8 @@ static int stm32_ctrlout(FAR struct usbhost_driver_s *drvr,
{
struct stm32_usbhost_s *priv = (struct stm32_usbhost_s *)drvr;
uint16_t buflen;
+ uint16_t start;
+ uint16_t elapsed;
int retries;
int ret;
@@ -3364,12 +3392,14 @@ static int stm32_ctrlout(FAR struct usbhost_driver_s *drvr,
stm32_takesem(&priv->exclsem);
- /* Loop, retrying until the retry count expires */
+ /* Loop, retrying until the retry time expires */
for (retries = 0; retries < STM32_RETRY_COUNT; retries++)
{
/* Send the SETUP request */
+ /* Send the SETUP request */
+
ret = stm32_ctrl_sendsetup(priv, req);
if (ret < 0)
{
@@ -3377,35 +3407,52 @@ static int stm32_ctrlout(FAR struct usbhost_driver_s *drvr,
continue;
}
- /* Handle the data OUT phase (if any) */
+ /* Get the start time. Loop again until the timeout expires */
- if (buflen > 0)
+ start = stm32_getframe();
+ do
{
- /* Start DATA out transfer (only one DATA packet) */
+ /* Handle the data OUT phase (if any) */
- priv->chan[priv->ep0out].outdata1 = true;
- ret = stm32_ctrl_senddata(priv, NULL, 0);
- if (ret < 0)
+ if (buflen > 0)
{
- udbg("stm32_ctrl_senddata failed: %d\n", ret);
- continue;
+ /* Start DATA out transfer (only one DATA packet) */
+
+ priv->chan[priv->ep0out].outdata1 = true;
+ ret = stm32_ctrl_senddata(priv, NULL, 0);
+ if (ret < 0)
+ {
+ udbg("stm32_ctrl_senddata failed: %d\n", ret);
+ }
}
- }
- /* Handle the status IN phase */
+ /* Handle the status IN phase */
- ret = stm32_ctrl_recvdata(priv, NULL, 0);
- if (ret == OK)
- {
- break;
- }
+ if (ret == OK)
+ {
+ ret = stm32_ctrl_recvdata(priv, NULL, 0);
+ if (ret == OK)
+ {
+ /* All success transactins exit here */
+
+ stm32_givesem(&priv->exclsem);
+ return OK;
+ }
- udbg("stm32_ctrl_recvdata failed: %d\n", ret);
- ret = -ETIMEDOUT;
+ udbg("stm32_ctrl_recvdata failed: %d\n", ret);
+ }
+
+ /* Get the elapsed time (in frames) */
+
+ elapsed = stm32_getframe() - start;
+ }
+ while (elapsed < STM32_DATANAK_DELAY);
}
+ /* All failures exit here after all retries and timeouts have been exhausted */
+
stm32_givesem(&priv->exclsem);
- return ret;
+ return -ETIMEDOUT;
}
/*******************************************************************************
@@ -3552,8 +3599,19 @@ static int stm32_transfer(FAR struct usbhost_driver_s *drvr, usbhost_ep_t ep,
}
}
+ /* There is a bug in the code at present. With debug OFF, this driver
+ * overruns the typical FLASH device and there are many problems with
+ * NAKS sticking a big delay here allows the driver to work but with
+ * very poor performance when debug is off.
+ */
+
+#if !defined(CONFIG_DEBUG_VERBOSE) && !defined(CONFIG_DEBUG_USB)
+#warning "REVISIT this delay"
+ usleep(100*1000);
+#endif
+
/* Start the transfer */
-
+
stm32_transfer_start(priv, chidx);
/* Wait for the transfer to complete and get the result */
@@ -3653,14 +3711,14 @@ static void stm32_portreset(FAR struct stm32_usbhost_s *priv)
* Flush the selected Tx FIFO.
*
* Input Parameters:
- * priv -- USB host driver private data structure.
+ * txfnum -- USB host driver private data structure.
*
* Returned Value:
* None.
*
*******************************************************************************/
-static inline void stm32_flush_txfifos(uint32_t txfnum)
+static void stm32_flush_txfifos(uint32_t txfnum)
{
uint32_t regval;
uint32_t timeout;
@@ -3700,7 +3758,7 @@ static inline void stm32_flush_txfifos(uint32_t txfnum)
*
*******************************************************************************/
-static inline void stm32_flush_rxfifo(void)
+static void stm32_flush_rxfifo(void)
{
uint32_t regval;
uint32_t timeout;
diff --git a/nuttx/configs/README.txt b/nuttx/configs/README.txt
index 87725bf58..7da0aa062 100644
--- a/nuttx/configs/README.txt
+++ b/nuttx/configs/README.txt
@@ -323,13 +323,17 @@ defconfig -- This is a configuration file similar to the Linux
set to zero if priority inheritance is disabled OR if you
are only using semaphores as mutexes (only one holder) OR
if no more than two threads participate using a counting
- semaphore.
+ semaphore. If defined, then this should be a relatively
+ large number because this is the total number of counts on
+ the total number of semaphores (like 64 or 100).
CONFIG_SEM_NNESTPRIO. If priority inheritance is enabled,
then this setting is the maximum number of higher priority
threads (minus 1) than can be waiting for another thread
to release a count on a semaphore. This value may be set
to zero if no more than one thread is expected to wait for
- a semaphore.
+ a semaphore. If defined, then this should be a relatively
+ small number because this the number of maximumum of waiters
+ on one semaphore (like 4 or 8).
CONFIG_FDCLONE_DISABLE. Disable cloning of all file descriptors
by task_create() when a new task is started. If set, all
files/drivers will appear to be closed in the new task.
diff --git a/nuttx/fs/nxffs/README.txt b/nuttx/fs/nxffs/README.txt
index a25735110..a10fb97a5 100755
--- a/nuttx/fs/nxffs/README.txt
+++ b/nuttx/fs/nxffs/README.txt
@@ -154,7 +154,7 @@ Things to Do
- The file name is always extracted and held in allocated, variable-length
memory. The file name is not used during reading and eliminating the
file name in the entry structure would improve performance.
-- There is a big inefficient in reading. On each read, the logic searches
+- There is a big inefficiency in reading. On each read, the logic searches
for the read position from the beginning of the file each time. This
may be necessary whenever an lseek() is done, but not in general. Read
performance could be improved by keeping FLASH offset and read positional
@@ -168,4 +168,13 @@ Things to Do
FLASH. As the file system becomes more filled with fixed files at the
front of the device, the level of wear on the blocks at the end of the
FLASH increases.
+- When the time comes to reorganization the FLASH, the system may be
+ inavailable for a long time. That is a bad behavior. What is needed,
+ I think, is a garbage collection task that runs periodically so that
+ when the big reorganizaiton event occurs, most of the work is already
+ done. That garbarge collection should search for valid blocks that no
+ longer contain valid data. It should pre-erase them, put them in
+ a good but empty state... all ready for file system re-organization.
+
+
diff --git a/nuttx/fs/romfs/fs_romfsutil.c b/nuttx/fs/romfs/fs_romfsutil.c
index ec009da89..cb3f9f9ac 100644
--- a/nuttx/fs/romfs/fs_romfsutil.c
+++ b/nuttx/fs/romfs/fs_romfsutil.c
@@ -351,7 +351,7 @@ static inline int romfs_searchdir(struct romfs_mountpt_s *rm,
}
while (next != 0);
- /* There is nothing in this directoy with that name */
+ /* There is nothing in this directory with that name */
return -ENOENT;
}
diff --git a/nuttx/sched/sched_setuptaskfiles.c b/nuttx/sched/sched_setuptaskfiles.c
index 7f754e151..fe0b14143 100644
--- a/nuttx/sched/sched_setuptaskfiles.c
+++ b/nuttx/sched/sched_setuptaskfiles.c
@@ -148,8 +148,8 @@ static inline void sched_dupsockets(FAR _TCB *tcb)
/* The parent task is the one at the head of the ready-to-run list */
FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
- FAR struct sockets *parent;
- FAR struct sockets *child;
+ FAR struct socket *parent;
+ FAR struct socket *child;
int i;
/* Duplicate the socket descriptors of all sockets opened by the parent
diff --git a/nuttx/sched/sem_holder.c b/nuttx/sched/sem_holder.c
index 34f88185a..abe7e9e28 100644
--- a/nuttx/sched/sem_holder.c
+++ b/nuttx/sched/sem_holder.c
@@ -275,10 +275,10 @@ static int sem_boostholderprio(FAR struct semholder_s *pholder,
FAR _TCB *htcb = (FAR _TCB *)pholder->htcb;
FAR _TCB *rtcb = (FAR _TCB*)arg;
- /* Make sure that the thread is still active. If it exited without releasing
- * its counts, then that would be a bad thing. But we can take no real
- * action because we don't know know that the program is doing. Perhaps its
- * plan is to kill a thread, then destroy the semaphore.
+ /* Make sure that the holder thread is still active. If it exited without
+ * releasing its counts, then that would be a bad thing. But we can take no
+ * real action because we don't know know that the program is doing. Perhaps
+ * its plan is to kill a thread, then destroy the semaphore.
*/
if (!sched_verifytcb(htcb))
@@ -303,15 +303,16 @@ static int sem_boostholderprio(FAR struct semholder_s *pholder,
if (rtcb->sched_priority > htcb->sched_priority)
{
- /* If the current priority has already been boosted, then add the
- * boost priority to the list of restoration priorities. When the
- * higher priority thread gets its count, then we need to revert
- * to this saved priority, not to the base priority.
+ /* If the current priority of holder thread has already been
+ * boosted, then add the boost priority to the list of restoration
+ * priorities. When the higher priority waiter thread gets its
+ * count, then we need to revert the holder thread to this saved
+ * priority (not to its base priority).
*/
if (htcb->sched_priority > htcb->base_priority)
{
- /* Save the current, boosted priority */
+ /* Save the current, boosted priority of the holder thread. */
if (htcb->npend_reprio < CONFIG_SEM_NNESTPRIO)
{
@@ -324,10 +325,10 @@ static int sem_boostholderprio(FAR struct semholder_s *pholder,
}
}
- /* Raise the priority of the holder of the semaphore. This
- * cannot cause a context switch because we have preemption
- * disabled. The task will be marked "pending" and the switch
- * will occur during up_block_task() processing.
+ /* Raise the priority of the thread holding of the semaphore.
+ * This cannot cause a context switch because we have preemption
+ * disabled. The holder thread may be marked "pending" and the
+ * switch may occur during up_block_task() processing.
*/
(void)sched_setpriority(htcb, rtcb->sched_priority);
@@ -422,10 +423,10 @@ static int sem_restoreholderprio(FAR struct semholder_s *pholder, FAR sem_t *sem
int j;
#endif
- /* Make sure that the thread is still active. If it exited without releasing
- * its counts, then that would be a bad thing. But we can take no real
- * action because we don't know know that the program is doing. Perhaps its
- * plan is to kill a thread, then destroy the semaphore.
+ /* Make sure that the hdoler thread is still active. If it exited without
+ * releasing its counts, then that would be a bad thing. But we can take no
+ * real action because we don't know know that the program is doing. Perhaps
+ * its plan is to kill a thread, then destroy the semaphore.
*/
if (!sched_verifytcb(htcb))
@@ -434,8 +435,8 @@ static int sem_restoreholderprio(FAR struct semholder_s *pholder, FAR sem_t *sem
sem_freeholder(sem, pholder);
}
- /* Was the priority of this thread boosted? If so, then drop its priority
- * back to the correct level.
+ /* Was the priority of the holder thread boosted? If so, then drop its
+ * priority back to the correct level. What is the correct level?
*/
else if (htcb->sched_priority != htcb->base_priority)
@@ -445,23 +446,23 @@ static int sem_restoreholderprio(FAR struct semholder_s *pholder, FAR sem_t *sem
if (htcb->npend_reprio < 1)
{
- /* No... the thread has only been boosted once. Reset all priorities
- * back to the base priority.
+ /* No... the holder thread has only been boosted once. Reset all
+ * priorities back to the base priority.
*/
DEBUGASSERT(htcb->sched_priority == stcb->sched_priority && htcb->npend_reprio == 0);
sched_reprioritize(htcb, htcb->base_priority);
}
- /* There are multiple pending priority levels. The thread's "boosted"
+ /* There are multiple pending priority levels. The holder thread's "boosted"
* priority could greater than or equal to "stcb->sched_priority" (it could be
- * greater if its priority we boosted becuase it also holds another semaphore.
+ * greater if its priority we boosted becuase it also holds another semaphore).
*/
else if (htcb->sched_priority <= stcb->sched_priority)
{
- /* The thread has been boosted to the same priority as the task
- * that just received the count. We will simply reprioritized
+ /* The holder thread has been boosted to the same priority as the waiter
+ * thread that just received the count. We will simply reprioritize
* to the next highest priority that we have in rpriority.
*/
@@ -492,9 +493,10 @@ static int sem_restoreholderprio(FAR struct semholder_s *pholder, FAR sem_t *sem
}
else
{
- /* The thread has been boosted to a higher priority than the task. The
- * pending priority should be in he list (unless it was lost because of
- * of list overflow).
+ /* The holder thread has been boosted to a higher priority than the
+ * waiter task. The pending priority should be in the list (unless it
+ * was lost because of of list overflow or because the holder was
+ * reporioritize again unbeknownst to the priority inheritance logic).
*
* Search the list for the matching priority.
*/
@@ -522,7 +524,8 @@ static int sem_restoreholderprio(FAR struct semholder_s *pholder, FAR sem_t *sem
}
#else
/* There is no alternative restore priorities, drop the priority
- * all the way back to the threads "base" priority.
+ * of the holder thread all the way back to the threads "base"
+ * priority.
*/
sched_reprioritize(htcb, htcb->base_priority);
@@ -533,10 +536,15 @@ static int sem_restoreholderprio(FAR struct semholder_s *pholder, FAR sem_t *sem
}
/****************************************************************************
- * Name: sem_restoreholderprioA & B
+ * Name: sem_restoreholderprioA
+ *
+ * Description:
+ * Reprioritize all holders except the currently executing task
+ *
****************************************************************************/
-static int sem_restoreholderprioA(FAR struct semholder_s *pholder, FAR sem_t *sem, FAR void *arg)
+static int sem_restoreholderprioA(FAR struct semholder_s *pholder,
+ FAR sem_t *sem, FAR void *arg)
{
FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
if (pholder->htcb != rtcb)
@@ -547,7 +555,16 @@ static int sem_restoreholderprioA(FAR struct semholder_s *pholder, FAR sem_t *se
return 0;
}
-static int sem_restoreholderprioB(FAR struct semholder_s *pholder, FAR sem_t *sem, FAR void *arg)
+/****************************************************************************
+ * Name: sem_restoreholderprioB
+ *
+ * Description:
+ * Reprioritize only the currently executing task
+ *
+ ****************************************************************************/
+
+static int sem_restoreholderprioB(FAR struct semholder_s *pholder,
+ FAR sem_t *sem, FAR void *arg)
{
FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
if (pholder->htcb == rtcb)
@@ -560,6 +577,158 @@ static int sem_restoreholderprioB(FAR struct semholder_s *pholder, FAR sem_t *se
}
/****************************************************************************
+ * Name: sem_restorebaseprio_irq
+ *
+ * Description:
+ * This function is called after the an interrupt handler posts a count on
+ * the semaphore. It will check if we need to drop the priority of any
+ * threads holding a count on the semaphore. Their priority could have
+ * been boosted while they held the count.
+ *
+ * Parameters:
+ * stcb - The TCB of the task that was just started (if any). If the
+ * post action caused a count to be given to another thread, then stcb
+ * is the TCB that received the count. Note, just because stcb received
+ * the count, it does not mean that it it is higher priority than other
+ * threads.
+ * sem - A reference to the semaphore being posted.
+ * - If the semaphore count is <0 then there are still threads waiting
+ * for a count. stcb should be non-null and will be higher priority
+ * than all of the other threads still waiting.
+ * - If it is ==0 then stcb refers to the thread that got the last count;
+ * no other threads are waiting.
+ * - If it is >0 then there should be no threads waiting for counts and
+ * stcb should be null.
+ *
+ * Return Value:
+ * None
+ *
+ * Assumptions:
+ * The scheduler is locked.
+ *
+ ****************************************************************************/
+
+static inline void sem_restorebaseprio_irq(FAR _TCB *stcb, FAR sem_t *sem)
+{
+ /* Perfom the following actions only if a new thread was given a count.
+ * The thread that received the count should be the highest priority
+ * of all threads waiting for a count from the semphore. So in that
+ * case, the priority of all holder threads should be dropped to the
+ * next highest pending priority.
+ */
+
+ if (stcb)
+ {
+ /* Drop the priority of all holder threads */
+
+ (void)sem_foreachholder(sem, sem_restoreholderprio, stcb);
+ }
+
+ /* If there are no tasks waiting for available counts, then all holders
+ * should be at their base priority.
+ */
+
+#ifdef CONFIG_DEBUG
+ else
+ {
+ (void)sem_foreachholder(sem, sem_verifyholder, NULL);
+ }
+#endif
+}
+
+/****************************************************************************
+ * Name: sem_restorebaseprio_task
+ *
+ * Description:
+ * This function is called after the current running task releases a
+ * count on the semaphore. It will check if we need to drop the priority
+ * of any threads holding a count on the semaphore. Their priority could
+ * have been boosted while they held the count.
+ *
+ * Parameters:
+ * stcb - The TCB of the task that was just started (if any). If the
+ * post action caused a count to be given to another thread, then stcb
+ * is the TCB that received the count. Note, just because stcb received
+ * the count, it does not mean that it it is higher priority than other
+ * threads.
+ * sem - A reference to the semaphore being posted.
+ * - If the semaphore count is <0 then there are still threads waiting
+ * for a count. stcb should be non-null and will be higher priority
+ * than all of the other threads still waiting.
+ * - If it is ==0 then stcb refers to the thread that got the last count;
+ * no other threads are waiting.
+ * - If it is >0 then there should be no threads waiting for counts and
+ * stcb should be null.
+ *
+ * Return Value:
+ * None
+ *
+ * Assumptions:
+ * The scheduler is locked.
+ *
+ ****************************************************************************/
+
+static inline void sem_restorebaseprio_task(FAR _TCB *stcb, FAR sem_t *sem)
+{
+ FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
+ FAR struct semholder_s *pholder;
+
+ /* Perfom the following actions only if a new thread was given a count.
+ * The thread that received the count should be the highest priority
+ * of all threads waiting for a count from the semphore. So in that
+ * case, the priority of all holder threads should be dropped to the
+ * next highest pending priority.
+ */
+
+ if (stcb)
+ {
+ /* The currently executed thread should be the lower priority
+ * thread that just posted the count and caused this action.
+ * However, we cannot drop the priority of the currently running
+ * thread -- becuase that will cause it to be suspended.
+ *
+ * So, do this in two passes. First, reprioritizing all holders
+ * except for the running thread.
+ */
+
+ (void)sem_foreachholder(sem, sem_restoreholderprioA, stcb);
+
+ /* Now, find an reprioritize only the ready to run task */
+
+ (void)sem_foreachholder(sem, sem_restoreholderprioB, stcb);
+ }
+
+ /* If there are no tasks waiting for available counts, then all holders
+ * should be at their base priority.
+ */
+
+#ifdef CONFIG_DEBUG
+ else
+ {
+ (void)sem_foreachholder(sem, sem_verifyholder, NULL);
+ }
+#endif
+
+ /* In any case, the currently executing task should have an entry in the
+ * list. Its counts were previously decremented; if it now holds no
+ * counts, then we need to remove it from the list of holders.
+ */
+
+ pholder = sem_findholder(sem, rtcb);
+ if (pholder)
+ {
+ /* When no more counts are held, remove the holder from the list. The
+ * count was decremented in sem_releaseholder.
+ */
+
+ if (pholder->counts <= 0)
+ {
+ sem_freeholder(sem, pholder);
+ }
+ }
+}
+
+/****************************************************************************
* Public Functions
****************************************************************************/
@@ -743,9 +912,10 @@ void sem_releaseholder(FAR sem_t *sem)
*
* Description:
* This function is called after the current running task releases a
- * count on the semaphore. It will check if we need to drop the priority
- * of any threads holding a count on the semaphore. Their priority could
- * have been boosted while they held the count.
+ * count on the semaphore or an interrupt handler posts a new count. It
+ * will check if we need to drop the priority of any threads holding a
+ * count on the semaphore. Their priority could have been boosted while
+ * they held the count.
*
* Parameters:
* stcb - The TCB of the task that was just started (if any). If the
@@ -763,7 +933,7 @@ void sem_releaseholder(FAR sem_t *sem)
* stcb should be null.
*
* Return Value:
- * 0 (OK) or -1 (ERROR) if unsuccessful
+ * None
*
* Assumptions:
* The scheduler is locked.
@@ -772,61 +942,25 @@ void sem_releaseholder(FAR sem_t *sem)
void sem_restorebaseprio(FAR _TCB *stcb, FAR sem_t *sem)
{
- FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
- FAR struct semholder_s *pholder;
-
/* Check our assumptions */
DEBUGASSERT((sem->semcount > 0 && stcb == NULL) ||
(sem->semcount <= 0 && stcb != NULL));
- /* Perfom the following actions only if a new thread was given a count. */
-
- if (stcb)
- {
- /* The currently executed thread should be the low priority
- * thread that just posted the count and caused this action.
- * However, we cannot drop the priority of the currently running
- * thread -- becuase that will cause it to be suspended.
- *
- * So, do this in two passes. First, reprioritizing all holders
- * except for the running thread.
- */
-
- (void)sem_foreachholder(sem, sem_restoreholderprioA, stcb);
-
- /* Now, find an reprioritize only the ready to run task */
-
- (void)sem_foreachholder(sem, sem_restoreholderprioB, stcb);
- }
-
- /* If there are no tasks waiting for available counts, then all holders
- * should be at their base priority.
+ /* Handler semaphore counts posed from an interrupt handler differently
+ * from interrupts posted from threads. The priority difference is that
+ * if the semaphore is posted from a thread, then the poster thread is
+ * a player in the priority inheritance scheme. The interrupt handler
+ * externally injects the new count without participated itself.
*/
-#ifdef CONFIG_DEBUG
- else
+ if (up_interrupt_context())
{
- (void)sem_foreachholder(sem, sem_verifyholder, NULL);
+ sem_restorebaseprio_irq(stcb, sem);
}
-#endif
-
- /* In any case, the currently execuing task should have an entry in the
- * list. Its counts were previously decremented; if it now holds no
- * counts, then we need to remove it from the list of holders.
- */
-
- pholder = sem_findholder(sem, rtcb);
- if (pholder)
+ else
{
- /* When no more counts are held, remove the holder from the list. The
- * count was decremented in sem_releaseholder.
- */
-
- if (pholder->counts <= 0)
- {
- sem_freeholder(sem, pholder);
- }
+ sem_restorebaseprio_task(stcb, sem);
}
}
diff --git a/nuttx/sched/sem_post.c b/nuttx/sched/sem_post.c
index b3780db1f..1c694b68c 100644
--- a/nuttx/sched/sem_post.c
+++ b/nuttx/sched/sem_post.c
@@ -123,17 +123,21 @@ int sem_post(FAR sem_t *sem)
sem_releaseholder(sem);
sem->semcount++;
- /* If the result of of semaphore unlock is non-positive, then
- * there must be some task waiting for the semaphore.
- */
-
#ifdef CONFIG_PRIORITY_INHERITANCE
- /* Don't let it run until we complete the priority restoration
- * steps.
+ /* Don't let any unblocked tasks run until we complete any priority
+ * restoration steps. Interrupts are disabled, but we do not want
+ * the head of the read-to-run list to be modified yet.
+ *
+ * NOTE: If this sched_lock is called from an interrupt handler, it
+ * will do nothing.
*/
sched_lock();
#endif
+ /* If the result of of semaphore unlock is non-positive, then
+ * there must be some task waiting for the semaphore.
+ */
+
if (sem->semcount <= 0)
{
/* Check if there are any tasks in the waiting for semaphore
diff --git a/nuttx/syscall/syscall.csv b/nuttx/syscall/syscall.csv
index 22b45df9d..4ccd53f9d 100644
--- a/nuttx/syscall/syscall.csv
+++ b/nuttx/syscall/syscall.csv
@@ -40,7 +40,7 @@
"open","fcntl.h","CONFIG_NFILE_DESCRIPTORS > 0","int","const char*","int","..."
"opendir","dirent.h","CONFIG_NFILE_DESCRIPTORS > 0","FAR DIR*","FAR const char*"
"pipe","unistd.h","CONFIG_NFILE_DESCRIPTORS > 0","int","int [2]|int*"
-"prctl", sys/prctl.h, "CONFIG_TASK_NAME_SIZE > 0","int","int","..."
+"prctl","sys/prctl.h", "CONFIG_TASK_NAME_SIZE > 0","int","int","..."
"clock_systimer","nuttx/clock.h","!defined(CONFIG_DISABLE_CLOCK)","uint32_t"
"poll","poll.h","!defined(CONFIG_DISABLE_POLL) && (CONFIG_NSOCKET_DESCRIPTORS > 0 || CONFIG_NFILE_DESCRIPTORS > 0)","int","FAR struct pollfd*","nfds_t","int"
"pthread_barrier_destroy","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_barrier_t*"
@@ -135,7 +135,7 @@
#"up_assert","assert.h","","void"
"up_assert_code","assert.h","","void","FAR const uint8_t*","int","int"
#"up_assert_code","assert.h","","void","int"
-"usleep","unistd.h","!defined(CONFIG_DISABLE_SIGNALS)","void","useconds_t"
+"usleep","unistd.h","!defined(CONFIG_DISABLE_SIGNALS)","int","useconds_t"
#"wait","sys/wait.h","","pid_t","int*"
#"waitid","sys/wait.h","","int","idtype_t","id_t id","siginfo_t*","int"
"waitpid","sys/wait.h","defined(CONFIG_SCHED_WAITPID)","pid_t","pid_t","int*","int"
diff --git a/nuttx/tools/Config.mk b/nuttx/tools/Config.mk
new file mode 100644
index 000000000..004a7e5bd
--- /dev/null
+++ b/nuttx/tools/Config.mk
@@ -0,0 +1,38 @@
+############################################################################
+# Config.mk
+# Strip quotes from Kconfig strings.
+#
+# Author: Richard Cochran
+#
+# 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.
+#
+############################################################################
+
+CONFIG_ARCH := $(shell echo $(CONFIG_ARCH))
+CONFIG_ARCH_CHIP := $(shell echo $(CONFIG_ARCH_CHIP))
+CONFIG_ARCH_BOARD := $(shell echo $(CONFIG_ARCH_BOARD))