summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2013-04-23 16:41:43 -0600
committerGregory Nutt <gnutt@nuttx.org>2013-04-23 16:41:43 -0600
commit385413eff99d22658833085adfe30e7e451f57cd (patch)
treea4ee42b7a39886a95df289c1688acd3b3f94002d
parent663c80136e271c9a20ab7d820448334ac572275e (diff)
downloadpx4-nuttx-385413eff99d22658833085adfe30e7e451f57cd.tar.gz
px4-nuttx-385413eff99d22658833085adfe30e7e451f57cd.tar.bz2
px4-nuttx-385413eff99d22658833085adfe30e7e451f57cd.zip
Reviewed all task exit logic. For pthread_exit() moved some logic higher in the exit sequence that could be required to block. For lower level logic kicked off by _exit(), add logic to prevent blocking when the task is not in a healthy state.
-rw-r--r--nuttx/ChangeLog48
-rw-r--r--nuttx/include/nuttx/usb/usbdev.h4
-rw-r--r--nuttx/sched/exit.c5
-rw-r--r--nuttx/sched/os_internal.h3
-rw-r--r--nuttx/sched/pthread_exit.c27
-rw-r--r--nuttx/sched/task_delete.c107
-rw-r--r--nuttx/sched/task_exit.c126
-rw-r--r--nuttx/sched/task_exithook.c53
8 files changed, 174 insertions, 199 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 8b81b1989..1f9f200ed 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -563,7 +563,7 @@
types.
0.3.19 2008-11-26 Gregory Nutt <gnutt@nuttx.org>
- * Add poll() and select() APIs (in the initial check-in, these work only with character devices)
+ * Add poll() and select() APIs (in the initial check-in, these work only with character devices)
* Add poll() methods to /dev/null, /dev/zero, pipes, fifos, and serial drivers.
* Add examples/poll for testing poll() and select()
* Fix hostile behavior of getc, fgetc, getchar, etc.: the serial driver was waiting for a
@@ -612,8 +612,8 @@
0.4.2 2009-02-28 Gregory Nutt <gnutt@nuttx.org>
- * M16C: Add support for the Renesas M16C MCU and the SKP16C26 StarterKit. However,
- the target cannot be built because the GNU m16c-elf-ld link fails with
+ * M16C: Add support for the Renesas M16C MCU and the SKP16C26 StarterKit. However,
+ the target cannot be built because the GNU m16c-elf-ld link fails with
the following message:
m32c-elf-ld: BFD (GNU Binutils) 2.19 assertion fail /home/Owner/projects/nuttx/buildroot/toolchain_build_m32c/binutils-2.19/bfd/elf32-m32c.c:482
@@ -711,7 +711,7 @@
-R .note.gnu.build-id -R .comment" This has been fixed in arch/arm/src/Makefile,
but other architectures may have the same problem. Thanks to Dave Marples
for verifying this.
- * configs/eagle100/ostest: Added support for the MicroMint Eagle100 board.
+ * configs/eagle100/ostest: Added support for the MicroMint Eagle100 board.
This board has a Luminary LM3S6918 Cortex-M3. Added a configuration to build
examples/ostest.
* arch/arm/src/lpc214x: Add configuration option to enable fast GPIO (vs.
@@ -1045,7 +1045,7 @@
* configs/sam3u-3k/ostest: Completed verification of the basic NuttX
OS test for the SAM3U.
* arch/arm/src/common/up_createstack: stack was always been cleared
- when it was allocated. This is a good feature for monitoring the
+ when it was allocated. This is a good feature for monitoring the
stack during debug, but really hurts thread start-up performance.
Clearing is now done if CONFIG_DEBUG=y only. Changes was only made
for arm, but really should be made for all architectures.
@@ -1186,7 +1186,7 @@
* examples/nsh/nsh_telnetd.c: Fix compilation errors that happen
when both DHCPC and TELNETD are enabled in the Nuttshell.
* graphics/nxglib/fb/nxglib_moverectangle.c: Fix a logic error
- that caused an uninitialized variable warning. I still don't
+ that caused an uninitialized variable warning. I still don't
have a test to prove that the changes are correct.
* configs/olimex-lpc2378: Add support for the CodeSourcery toolchain
under Linux (contributed by Alan Carvalho de Assis).
@@ -1669,14 +1669,14 @@
* arch/arm/src/lpc17xx/lpc17_gpioint.c: Correct errors in logic that maps
and IRQ number into a register bit number.
* Makefile: Fix an error introduced in the top-level Makefile in NuttX-6.1.
- This error only shows up if you have a /tftpboot directory. Then the
+ This error only shows up if you have a /tftpboot directory. Then the
make will fail with an obscure error about not being able to stat pass2.
* configs/lpcxpresso-lpc1768/nsh: Add an NSH configuration for the
LPCXpresso board.
* configs/*/ld.script: Removed 'sh_link not set for section .ARM.edix' for
a few of the builds. In you have this warning, it can be removed with the
following change to the ld.script file:
-
+
+ __exidx_start = ABSOLUTE(.);
.ARM.exidx : {
- __exidx_start = ABSOLUTE(.);
@@ -1802,7 +1802,7 @@
already disconnected and the buffered data is stranded. Now, recvfrom
will continue to return success after the socket is disconnected until
the readahead buffer is drained.
- * olimex-lp1766stk/ftpc/defconfig: Many configurations have the MTU
+ * olimex-lp1766stk/ftpc/defconfig: Many configurations have the MTU
(CONFIG_NET_BUFSIZE) set to very small numbers, less then the minimum
MTU size that must be supported -- 576. This can cause problems in
some networks: CONFIG_NET_BUFSIZE should be set to at least 576 in
@@ -1915,7 +1915,7 @@
new file; Implement VFAT long file name support.
* fs/fat/fat_fat32dirent.c: The configuration CONFIG_FAT_LCNAMES has
been around for some time but never tested until now. This setting
- will mimic the NT 8.3 file name behavior: File names or extensions
+ will mimic the NT 8.3 file name behavior: File names or extensions
may be all upper or all lower case (but not mixed). If
CONFIG_FAT_LCNAMES is not selected, all filenames are strictly upper
case.
@@ -1943,7 +1943,7 @@
program. The bdf-converter program be used to convert fonts in Bitmap
Distribution Format (BDF) into fonts that can be used in the NX graphics
system.
- * include/nuttx/nx: Move all NX header files from include/nuttx to
+ * include/nuttx/nx: Move all NX header files from include/nuttx to
include/nuttx/nx.
* drivers/usbdev/usbdev_usbstorage.c and arch/arm/src/stm32/stm32_usbdev.c:
Correct a memory leak when the USB mass storage driver is connected and
@@ -2051,7 +2051,7 @@
* arch/*/src/Makefile: Use of -print-libgcc-file-name to get path to
libgcc.a may select the wrong libgcc.a if a multilib toolchain (like
CodeSourcery) is used. This can be a serious problem and can cause
- crashes on Cortex-M3 if the ARM libgcc is used, for example. The fix
+ crashes on Cortex-M3 if the ARM libgcc is used, for example. The fix
is to include ARCHCPUFLAGS on the gcc command line when asking it to
-print-libgcc-file-name.
* lib/time/lib_gmtimer.c: Correct several calculations that could lead
@@ -2280,7 +2280,7 @@
the particular condition that revealed the bug occurred. My impression is
that this latter bugfix also fixes some STM32 USB performance problems.
* configs/hymini-stm32v: A configuration for the HY-Mini STM32v board contributed
- by Laurent Latil. These changes also include support for the STM32F103VCT6.
+ by Laurent Latil. These changes also include support for the STM32F103VCT6.
* arch/configs/stm3240g-eval/src/up_pwm.c: Add hooks needed to use the new
apps/examples/pwm test of the STM32 PWM driver.
* drivers/mtd/mp25x.c: Add ability to use different SPI modes and different
@@ -2394,7 +2394,7 @@
common upper half battery driver.
* drivers/power/max1704x.c: Add a driver for MAX17040x battery "fuel gauge"
* arch/arm/src/stm32/stm32_i2c.c: Add support for I2C3
- * drivers/usbdev/: Lots of name changes: cdc_serial->cdcacm, usbstrg->usbmsc,
+ * drivers/usbdev/: Lots of name changes: cdc_serial->cdcacm, usbstrg->usbmsc,
usbser->pl2303
* drivers/usbdev/composite: Fleshed out support for a composite USB device.
* drivers/stm3210e-eval/composite and drivers/stm3210e-eval/src/up_composite.c:
@@ -2704,7 +2704,7 @@
platform did not make into all of the Make.defs files.
* graphics/nxmu/nx_move.c: Wrong opcode was being used in the server message;
Also there was an error in the offset calculation.
- * graphics/nxglib/fb/nxglib_moverectangle.c: Offset argument is really a
+ * graphics/nxglib/fb/nxglib_moverectangle.c: Offset argument is really a
position, not an offset.
* graphics/nxtk/nxtk_drawframe.c: Framed windows are now drawn in three
colors (instead of just two).
@@ -2938,7 +2938,7 @@
is slowly evolving in these directories.
* configs/stm3210e-eval/pm: Add a new configuration for testing STM32 power
management.
- * configs/stm3210e-eval/scripts: Moved all of the duplicate ST3210-EVAL
+ * configs/stm3210e-eval/scripts: Moved all of the duplicate ST3210-EVAL
linker scripts into one set of linker scripts at this location.
* configs/stm3210e-eval/src/up_buttons.c, up_lcd.c, and up_pm.c: New logic
for testing STM32 power management.
@@ -3139,7 +3139,7 @@
customize the behavior of NSH.
* arch/arm/src/stm32/chip/stm32f1*_pinmap.h: STM32 CAN TX/RX pins reversed;
inconsistent conditional compilation. Reported by Max Holtzberg.
- * arch/arm/*/stm32: Add support for STM32 F107 "Connectivity Line"
+ * arch/arm/*/stm32: Add support for STM32 F107 "Connectivity Line"
Ethernet (contributed by Max Holtzberg).
* configs/olimex-stm32-p107: Add board support for the Olimiex STM32-P107
board (contributed by Max Holtzberg).
@@ -3317,7 +3317,7 @@
to allocate the block driver I/O buffers.
* CONFIG_NET_ENC28J60 renamed CONFIG_ENC28J60 to be consistent
in all places.
- * drivers/enc28j60.c, include/nuttx/net/enc28j60.h, and
+ * drivers/enc28j60.c, include/nuttx/net/enc28j60.h, and
olimex-strp711/src/up_enc28j60.c: No longer passes IRQ number
as a parameter. Instead now passes a call table to manage
ENC28J60 GPIO interrupts. That is because GPIO interrupts are
@@ -3630,7 +3630,7 @@
just needs re-implemented.
* configs/mirtoo: Update Mirtoo pin definitions for Release 2. Provided
by Konstantin Dimitrov.
- * Fixed an uninitialized variable in the file system that can cause
+ * Fixed an uninitialized variable in the file system that can cause
assertions if DEBUG on (contributed by Lorenz Meier).
* Config.mk: Defined DELIM to be either / or \, depending upon
CONFIG_WINDOWS_NATIVE. This will allow me to eliminate a lot of
@@ -4088,7 +4088,7 @@
switched to SPI mode for first time. Having a pull-up resistor on
MISO may avoid this problem, but this patch makes it work also
without pull-up. From Petteri Aimonen.
- * fs/fat/fs_fat32.c: Fix a compilation error when FAT_DMAMEMORY=y.
+ * fs/fat/fs_fat32.c: Fix a compilation error when FAT_DMAMEMORY=y.
From Petteri Aimonen.
* arch/arm/src/stm32/chip/stm32_spi.h: STM32F4 max SPI clock freq is
37.5 MHz. Patch from Petteri Aimonen.
@@ -4599,4 +4599,10 @@
* tools/kconfig2html.c: Improve behavior of Expand/Collapse
Table of Contents; Handle errors in parsing of strings and in
some uninitialized variables. Add an option to use jQuery.
- * tools/mkconfigvar.sh: Fix make target.
+ * tools/mkconfigvar.sh: Fix make target (2014-4-23).
+ * sched/exit.c, pthread_exit.c, task_exit.c, task_delete,c and
+ task_exithook.c: For pthread_exit(), move some logic to an early
+ point in the exit sequence where the task may need to block. Add
+ conditional logic in the lower end of the eixt logic kicked off by
+ _exit() to prohibit blocking after the task has been torn down and is
+ no longer cabable of blocking (2014-4-23).
diff --git a/nuttx/include/nuttx/usb/usbdev.h b/nuttx/include/nuttx/usb/usbdev.h
index 1270fe13a..7d47055d7 100644
--- a/nuttx/include/nuttx/usb/usbdev.h
+++ b/nuttx/include/nuttx/usb/usbdev.h
@@ -289,8 +289,8 @@ struct usbdev_s
{
const struct usbdev_ops_s *ops; /* Access to hardware specific features */
struct usbdev_ep_s *ep0; /* Endpoint zero */
- uint8_t speed; /* Current speed of the host connection */
- uint8_t dualspeed:1; /* 1:supports high and full speed operation */
+ uint8_t speed; /* Current speed of the host connection */
+ uint8_t dualspeed:1; /* 1:supports high and full speed operation */
};
/* USB Device Class Implementations *************************************************/
diff --git a/nuttx/sched/exit.c b/nuttx/sched/exit.c
index 487748d3c..b88c84ec3 100644
--- a/nuttx/sched/exit.c
+++ b/nuttx/sched/exit.c
@@ -100,10 +100,11 @@ void exit(int status)
/* Perform common task termination logic. This will get called again later
* through logic kicked off by _exit(). However, we need to call it before
- * calling _exit() in order to handle atexit() and on_exit() callbacks.
+ * calling _exit() in order to handle atexit() and on_exit() callbacks and
+ * so that we can flush buffered I/O (both of which may required suspending).
*/
- task_exithook(tcb, status);
+ task_exithook(tcb, status, false);
/* Then "really" exit. Only the lower 8 bits of the exit status are used. */
diff --git a/nuttx/sched/os_internal.h b/nuttx/sched/os_internal.h
index bbfce9696..d13eb9cad 100644
--- a/nuttx/sched/os_internal.h
+++ b/nuttx/sched/os_internal.h
@@ -265,7 +265,8 @@ int task_schedsetup(FAR struct task_tcb_s *tcb, int priority, start_t start,
main_t main, uint8_t ttype);
int task_argsetup(FAR struct task_tcb_s *tcb, FAR const char *name, FAR char * const argv[]);
int task_exit(void);
-void task_exithook(FAR struct tcb_s *tcb, int status);
+int task_terminate(pid_t pid, bool nonblocking);
+void task_exithook(FAR struct tcb_s *tcb, int status, bool nonblocking);
void task_recover(FAR struct tcb_s *tcb);
#ifndef CONFIG_CUSTOM_STACK
diff --git a/nuttx/sched/pthread_exit.c b/nuttx/sched/pthread_exit.c
index db51be78f..da4a6d149 100644
--- a/nuttx/sched/pthread_exit.c
+++ b/nuttx/sched/pthread_exit.c
@@ -1,7 +1,7 @@
/************************************************************************
* sched/pthread_exit.c
*
- * Copyright (C) 2007, 2009, 2011-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 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
@@ -49,6 +49,7 @@
#include <nuttx/arch.h>
+#include "os_internal.h"
#include "pthread_internal.h"
/************************************************************************
@@ -93,7 +94,7 @@
void pthread_exit(FAR void *exit_value)
{
- int error_code = (int)((intptr_t)exit_value);
+ struct tcb_s *tcb = (struct tcb_s*)g_readytorun.head;
int status;
sdbg("exit_value=%p\n", exit_value);
@@ -115,23 +116,25 @@ void pthread_exit(FAR void *exit_value)
if (status != OK)
{
/* Assume that the join completion failured because this
- * not really a pthread. Exit by calling exit() to flush
- * and close all file descriptors and calling atexit()
- * functions.
+ * not really a pthread. Exit by calling exit().
*/
- if (error_code == EXIT_SUCCESS)
- {
- error_code = EXIT_FAILURE;
- }
-
- exit(error_code);
+ exit(EXIT_FAILURE);
}
+ /* Perform common task termination logic. This will get called again later
+ * through logic kicked off by _exit(). However, we need to call it before
+ * calling _exit() in order certain operations if this is the last thread
+ * of a task group: (2) To handle atexit() and on_exit() callbacks and
+ * (2) so that we can flush buffered I/O (which may required suspending).
+ */
+
+ task_exithook(tcb, EXIT_SUCCESS, false);
+
/* Then just exit, retaining all file descriptors and without
* calling atexit() functions.
*/
- _exit(error_code);
+ _exit(EXIT_SUCCESS);
}
diff --git a/nuttx/sched/task_delete.c b/nuttx/sched/task_delete.c
index 64830154c..f6a19a790 100644
--- a/nuttx/sched/task_delete.c
+++ b/nuttx/sched/task_delete.c
@@ -1,7 +1,7 @@
/****************************************************************************
* sched/task_delete.c
*
- * Copyright (C) 2007-2009, 2011-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-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
@@ -77,30 +77,36 @@
****************************************************************************/
/****************************************************************************
- * Name: task_delete
+ * Name: task_terminate
*
* Description:
* This function causes a specified task to cease to exist. Its stack and
- * TCB will be deallocated. This function is the companion to task_create().
+ * TCB will be deallocated. This function is the internal implementation
+ * of the task_delete() function. It includes and additional parameter
+ * to determine if blocking is permitted or not.
*
- * The logic in this function only deletes non-running tasks. If the 'pid'
- * parameter refers to to the currently runing task, then processing is
- * redirected to exit().
+ * This function is the final function called all task termination
+ * sequences. task_terminate() is called only from task_delete() (with
+ * nonblocking == false) and from task_exit() (with nonblocking == true).
*
- * Control will still be returned to task_delete() after the exit() logic
- * finishes. In fact, this function is the final function called all task
- * termination sequences. Here are all possible exit scenarios:
+ * The path through task_exit() supports the final stops of the exit(),
+ * _exit(), and pthread_exit
*
- * - pthread_exit(). Calls exit()
+ * - pthread_exit(). Calls _exit()
* - exit(). Calls _exit()
* - _exit(). Calls task_exit() making the currently running task
- * non-running then calls task_delete() to terminate the non-running
- * task.
- * - task_delete()
+ * non-running. task_exit then calls task_terminate() (with nonblocking
+ * == true) to terminate the non-running task.
+ *
+ * NOTE: that the state of non-blocking is irrelevant when called through
+ * exit() and pthread_exit(). In those cases task_exithook() has already
+ * been called with nonblocking == false;
*
* Inputs:
* pid - The task ID of the task to delete. A pid of zero
* signifies the calling task.
+ * nonblocking - True: The task is an unhealthy, partially torn down
+ * state and is not permitted to block.
*
* Return Value:
* OK on success; or ERROR on failure
@@ -110,25 +116,12 @@
*
****************************************************************************/
-int task_delete(pid_t pid)
+int task_terminate(pid_t pid, bool nonblocking)
{
- FAR struct tcb_s *rtcb;
FAR struct tcb_s *dtcb;
irqstate_t saved_state;
int ret = ERROR;
- /* Check if the task to delete is the calling task */
-
- rtcb = (FAR struct tcb_s*)g_readytorun.head;
- if (pid == 0 || pid == rtcb->pid)
- {
- /* If it is, then what we really wanted to do was exit. Note that we
- * don't bother to unlock the TCB since it will be going away.
- */
-
- exit(EXIT_SUCCESS);
- }
-
/* Make sure the task does not become ready-to-run while we are futzing with
* its TCB by locking ourselves as the executing task.
*/
@@ -166,7 +159,7 @@ int task_delete(pid_t pid)
* I suppose EXIT_SUCCESS is an appropriate return value???
*/
- task_exithook(dtcb, EXIT_SUCCESS);
+ task_exithook(dtcb, EXIT_SUCCESS, nonblocking);
/* Remove the task from the OS's tasks lists. */
@@ -192,3 +185,61 @@ int task_delete(pid_t pid)
return ret;
}
+/****************************************************************************
+ * Name: task_delete
+ *
+ * Description:
+ * This function causes a specified task to cease to exist. Its stack and
+ * TCB will be deallocated. This function is the companion to task_create().
+ * This is the version of the function exposed to the user; it is simply
+ * a wrapper around the internal, task_terminate function.
+ *
+ * The logic in this function only deletes non-running tasks. If the 'pid'
+ * parameter refers to to the currently runing task, then processing is
+ * redirected to exit(). This can only happen if a task calls task_delete()
+ * in order to delete itself.
+ *
+ * In fact, this function (and task_terminate) are the final functions
+ * called all task termination sequences. task_delete may be called
+ * from:
+ *
+ * - task_restart(),
+ * - pthread_cancel(),
+ * - and directly from user code.
+ *
+ * Other exit paths (exit(), _eixt(), and pthread_exit()) will go through
+ * task_terminate()
+ *
+ * Inputs:
+ * pid - The task ID of the task to delete. A pid of zero
+ * signifies the calling task.
+ *
+ * Return Value:
+ * OK on success; or ERROR on failure
+ *
+ * This function can fail if the provided pid does not correspond to a
+ * task (errno is not set)
+ *
+ ****************************************************************************/
+
+int task_delete(pid_t pid)
+{
+ FAR struct tcb_s *rtcb;
+
+ /* Check if the task to delete is the calling task */
+
+ rtcb = (FAR struct tcb_s*)g_readytorun.head;
+ if (pid == 0 || pid == rtcb->pid)
+ {
+ /* If it is, then what we really wanted to do was exit. Note that we
+ * don't bother to unlock the TCB since it will be going away.
+ */
+
+ DEBUGASSERT(!nonblocking);
+ exit(EXIT_SUCCESS);
+ }
+
+ /* Then let task_terminate do the heavy lifting */
+
+ return task_terminate(pid, false);
+}
diff --git a/nuttx/sched/task_exit.c b/nuttx/sched/task_exit.c
index aafe65f22..031b22ed8 100644
--- a/nuttx/sched/task_exit.c
+++ b/nuttx/sched/task_exit.c
@@ -70,116 +70,6 @@
****************************************************************************/
/****************************************************************************
- * Name: task_cancel_atexit
- *
- * Description:
- * Cncel any registerd atexit function(s)
- *
- * This function is called from task_exit() which implements the processor-
- * independent part of _exit(). _exit() is, in turn, used to implement
- * the bottom half of exit() and pthread_exit(). These cases are
- * distinguished as follows:
- *
- * 1) _exit() should be called by user logic only from tasks. In this
- * case, atexit() calls will be canceled by this function.
- * 2) If the user calls exit(), the exit() function will call task_exithook()
- * which will process all pending atexit() call. In that case, this
- * function will have no effect.
- * 3) If the user called pthread_exit(), the logic in this function will
- * do nothing. Only a task can legitimately called _exit(). atexit
- * calls will not be cleared. task_exithook() will be called later (from
- * task_delete()) and if this is the final thread of the group, any
- * registered atexit() calls will be performed.
- *
- ****************************************************************************/
-
-#if defined(CONFIG_SCHED_ATEXIT) && !defined(CONFIG_SCHED_ONEXIT)
-static inline void task_cancel_atexit(FAR struct tcb_s *tcb)
-{
- FAR struct task_group_s *group = tcb->group;
- DEBUGASSERT(group);
-
- /* This behavior applies only to tasks that call _exit() */
-
-#ifndef CONFIG_DISABLE_PTHREAD
- if ((tcb->flags & TCB_FLAG_TTYPE_MASK) != TCB_FLAG_TTYPE_PTHREAD)
-#endif
- {
-#if defined(CONFIG_SCHED_ATEXIT_MAX) && CONFIG_SCHED_ATEXIT_MAX > 1
- int index;
-
- /* Nullify each atexit function pointer */
-
- for (index = 0; index < CONFIG_SCHED_ATEXIT_MAX; index++)
- {
- group->tg_atexitfunc[index] = NULL;
- }
-#else
- /* Nullify the atexit function to prevent its reuse. */
-
- group->tg_atexitfunc = NULL;
-#endif
- }
-}
-#else
-# define task_cancel_atexit(tcb)
-#endif
-
-/****************************************************************************
- * Name: task_cancel_onexit
- *
- * Description:
- * Cancel any registerd on)exit function(s).
- *
- * This function is called from task_exit() which implements the processor-
- * independent part of _exit(). _exit() is, in turn, used to implement
- * the bottom half of exit() and pthread_exit(). These cases are
- * distinguished as follows:
- *
- * 1) _exit() should be called by user logic only from tasks. In this
- * case, on_exit() calls will be canceled by this function.
- * 2) If the user calls exit(), the exit() function will call task_exithook()
- * which will process all pending on_exit() call. In that case, this
- * function will have no effect.
- * 3) If the user called pthread_exit(), the logic in this function will
- * do nothing. Only a task can legitimately called _exit(). on_exit
- * calls will not be cleared. task_exithook() will be called later (from
- * task_delete()) and if this is the final thread of the group, any
- * registered on_exit() calls will be performed.
- *
- ****************************************************************************/
-
-#ifdef CONFIG_SCHED_ONEXIT
-static inline void task_cancel_onexit(FAR struct tcb_s *tcb)
-{
- FAR struct task_group_s *group = tcb->group;
- DEBUGASSERT(group);
-
- /* This behavior applies only to tasks that call _exit() */
-
-#ifndef CONFIG_DISABLE_PTHREAD
- if ((tcb->flags & TCB_FLAG_TTYPE_MASK) != TCB_FLAG_TTYPE_PTHREAD)
-#endif
- {
-#if defined(CONFIG_SCHED_ONEXIT_MAX) && CONFIG_SCHED_ONEXIT_MAX > 1
- int index;
-
- /* Nullify each atexit function pointer */
-
- for (index = 0; index < CONFIG_SCHED_ONEXIT_MAX; index++)
- {
- group->tg_onexitfunc[index] = NULL;
- }
-#else
- group->tg_onexitfunc = NULL;
-#endif
- }
-}
-#else
-# define task_cancel_onexit(tcb)
-#endif
-
-/****************************************************************************
* Public Functions
****************************************************************************/
@@ -227,14 +117,6 @@ int task_exit(void)
(void)sched_removereadytorun(dtcb);
rtcb = (FAR struct tcb_s*)g_readytorun.head;
- /* Cancel any pending atexit() or on_exit() calls. These are not performed
- * when performing _exit(). Different implementations of _exit() may or may
- * not* flush buffered I/O. This implemenation *will* flush buffered I/O.
- */
-
- task_cancel_atexit(rtcb);
- task_cancel_onexit(rtcb);
-
/* We are now in a bad state -- the head of the ready to run task list
* does not correspond to the thread that is running. Disabling pre-
* emption on this TCB and marking the new ready-to-run task as not
@@ -247,10 +129,14 @@ int task_exit(void)
rtcb->lockcount++;
rtcb->task_state = TSTATE_TASK_READYTORUN;
- /* Move the TCB to the specified blocked task list and delete it */
+ /* Move the TCB to the specified blocked task list and delete it. Calling
+ * task_terminate with non-blocking true will suppress atexit() and on-exit()
+ * calls and will cause buffered I/O to fail to be flushed. The former
+ * is required _exit() behavior; the latter is optional _exit() behavior.
+ */
sched_addblocked(dtcb, TSTATE_TASK_INACTIVE);
- task_delete(dtcb->pid);
+ task_terminate(dtcb->pid, true);
rtcb->task_state = TSTATE_TASK_RUNNING;
/* If there are any pending tasks, then add them to the ready-to-run
diff --git a/nuttx/sched/task_exithook.c b/nuttx/sched/task_exithook.c
index 71cc13250..b59f8e5ba 100644
--- a/nuttx/sched/task_exithook.c
+++ b/nuttx/sched/task_exithook.c
@@ -143,7 +143,7 @@ static inline void task_atexit(FAR struct tcb_s *tcb)
* Call any registerd on_exit function(s)
*
****************************************************************************/
-
+
#ifdef CONFIG_SCHED_ONEXIT
static inline void task_onexit(FAR struct tcb_s *tcb, int status)
{
@@ -298,7 +298,7 @@ static inline void task_sigchild(gid_t pgid, FAR struct tcb_s *ctcb, int status)
DEBUGASSERT(chgrp);
/* Get the parent task group. It is possible that all of the members of
- * the parent task group have exited. This would not be an error. In
+ * the parent task group have exited. This would not be an error. In
* this case, the child task group has been orphaned.
*/
@@ -508,8 +508,8 @@ static inline void task_exitwakeup(FAR struct tcb_s *tcb, int status)
*
* "If more than one thread is suspended in waitpid() awaiting
* termination of the same process, exactly one thread will
- * return the process status at the time of the target process
- * termination."
+ * return the process status at the time of the target process
+ * termination."
*
* Hmmm.. what do we return to the others?
*/
@@ -528,7 +528,7 @@ static inline void task_exitwakeup(FAR struct tcb_s *tcb, int status)
group->tg_statloc = NULL;
while (group->tg_exitsem.semcount < 0)
- {
+ {
/* Wake up the thread */
sem_post(&group->tg_exitsem);
@@ -588,14 +588,18 @@ static inline void task_flushstreams(FAR struct tcb_s *tcb)
* to-run list. The following logic is safe because we will not be
* returning from the exit() call.
*
- * When called from task_delete() we are operating on a different thread;
+ * When called from task_terminate() we are operating on a different thread;
* on the thread that called task_delete(). In this case, task_delete
* will have already removed the tcb from the ready-to-run list to prevent
* any further action on this task.
*
+ * nonblocking will be set true only when we are called from task_terminate()
+ * via _exit(). In that case, we must be careful to do nothing that can
+ * cause the cause the thread to block.
+ *
****************************************************************************/
-void task_exithook(FAR struct tcb_s *tcb, int status)
+void task_exithook(FAR struct tcb_s *tcb, int status, bool nonblocking)
{
/* Under certain conditions, task_exithook() can be called multiple times.
* A bit in the TCB was set the first time this function was called. If
@@ -608,15 +612,28 @@ void task_exithook(FAR struct tcb_s *tcb, int status)
}
/* If exit function(s) were registered, call them now before we do any un-
- * initialization. NOTE: In the case of task_delete(), the exit function
- * will *not* be called on the thread execution of the task being deleted!
+ * initialization.
+ *
+ * NOTES:
+ *
+ * 1. In the case of task_delete(), the exit function will *not* be called
+ * on the thread execution of the task being deleted! That is probably
+ * a bug.
+ * 2. We cannot call the exit functions if nonblocking is requested: These
+ * functions might block.
+ * 3. This function will only be called with with non-blocking == true
+ * only when called through _exit(). _exit() behaviors requires that
+ * the exit functions *not* be called.
*/
- task_atexit(tcb);
+ if (!nonblocking)
+ {
+ task_atexit(tcb);
- /* Call any registered on_exit function(s) */
+ /* Call any registered on_exit function(s) */
- task_onexit(tcb, status);
+ task_onexit(tcb, status);
+ }
/* If the task was terminated by another task, it may be in an unknown
* state. Make some feeble effort to recover the state.
@@ -634,9 +651,19 @@ void task_exithook(FAR struct tcb_s *tcb, int status)
/* If this is the last thread in the group, then flush all streams (File
* descriptors will be closed when the TCB is deallocated).
+ *
+ * NOTES:
+ * 1. We cannot flush the buffered I/O if nonblocking is requested.
+ * that might cause this logic to block.
+ * 2. This function will only be called with with non-blocking == true
+ * only when called through _exit(). _exit() behavior does not
+ * require that the streams be flushed
*/
- task_flushstreams(tcb);
+ if (!nonblocking)
+ {
+ task_flushstreams(tcb);
+ }
/* Leave the task group. Perhaps discarding any un-reaped child
* status (no zombies here!)