task_delete.c 7.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214
  1. /****************************************************************************
  2. * sched/task/task_delete.c
  3. *
  4. * Copyright (C) 2007-2009, 2011-2013, 2016-2017 Gregory Nutt. All rights
  5. * reserved.
  6. * Author: Gregory Nutt <gnutt@nuttx.org>
  7. *
  8. * Redistribution and use in source and binary forms, with or without
  9. * modification, are permitted provided that the following conditions
  10. * are met:
  11. *
  12. * 1. Redistributions of source code must retain the above copyright
  13. * notice, this list of conditions and the following disclaimer.
  14. * 2. Redistributions in binary form must reproduce the above copyright
  15. * notice, this list of conditions and the following disclaimer in
  16. * the documentation and/or other materials provided with the
  17. * distribution.
  18. * 3. Neither the name NuttX nor the names of its contributors may be
  19. * used to endorse or promote products derived from this software
  20. * without specific prior written permission.
  21. *
  22. * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
  23. * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
  24. * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
  25. * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
  26. * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
  27. * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
  28. * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
  29. * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
  30. * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
  31. * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
  32. * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
  33. * POSSIBILITY OF SUCH DAMAGE.
  34. *
  35. ****************************************************************************/
  36. /****************************************************************************
  37. * Included Files
  38. ****************************************************************************/
  39. #include <nuttx/config.h>
  40. #include <stdlib.h>
  41. #include <errno.h>
  42. #include <nuttx/sched.h>
  43. #include "sched/sched.h"
  44. #include "task/task.h"
  45. /****************************************************************************
  46. * Public Functions
  47. ****************************************************************************/
  48. /****************************************************************************
  49. * Name: task_delete
  50. *
  51. * Description:
  52. * This function causes a specified task to cease to exist. Its stack and
  53. * TCB will be deallocated. This function is the companion to
  54. * task_create(). This is the version of the function exposed to the
  55. * user; it is simply a wrapper around the internal, nxtask_terminate
  56. * function.
  57. *
  58. * The logic in this function only deletes non-running tasks. If the
  59. * 'pid' parameter refers to to the currently runing task, then processing
  60. * is redirected to exit(). This can only happen if a task calls
  61. * task_delete()in order to delete itself.
  62. *
  63. * This function obeys the semantics of pthread cancellation: task
  64. * deletion is deferred if cancellation is disabled or if deferred
  65. * cancellation is supported (with cancellation points enabled).
  66. *
  67. * Input Parameters:
  68. * pid - The task ID of the task to delete. A pid of zero
  69. * signifies the calling task.
  70. *
  71. * Returned Value:
  72. * OK on success; or ERROR on failure with the errno variable set
  73. * appropriately.
  74. *
  75. ****************************************************************************/
  76. int task_delete(pid_t pid)
  77. {
  78. FAR struct tcb_s *dtcb;
  79. FAR struct tcb_s *rtcb;
  80. int errcode;
  81. int ret;
  82. /* Check if the task to delete is the calling task: PID=0 means to delete
  83. * the calling task. In this case, task_delete() is much like exit()
  84. * except that it obeys the cancellation semantics.
  85. */
  86. rtcb = this_task();
  87. if (pid == 0)
  88. {
  89. pid = rtcb->pid;
  90. }
  91. /* Get the TCB of the task to be deleted */
  92. dtcb = (FAR struct tcb_s *)sched_gettcb(pid);
  93. if (dtcb == NULL)
  94. {
  95. /* The pid does not correspond to any known thread. The task
  96. * has probably already exited.
  97. */
  98. errcode = ESRCH;
  99. goto errout;
  100. }
  101. /* Only tasks and kernel threads can be deleted with this interface
  102. * (The semantics of the call should be sufficient to prohibit this).
  103. */
  104. DEBUGASSERT((dtcb->flags & TCB_FLAG_TTYPE_MASK) != TCB_FLAG_TTYPE_PTHREAD);
  105. /* Non-privileged tasks and pthreads may not delete privileged kernel
  106. * threads.
  107. *
  108. * REVISIT: We will need to look at this again in the future if/when
  109. * permissions are supported and a user task might also be priveleged.
  110. */
  111. if (((rtcb->flags & TCB_FLAG_TTYPE_MASK) != TCB_FLAG_TTYPE_KERNEL) &&
  112. ((dtcb->flags & TCB_FLAG_TTYPE_MASK) == TCB_FLAG_TTYPE_KERNEL))
  113. {
  114. errcode = EACCES;
  115. goto errout;
  116. }
  117. /* Check to see if this task has the non-cancelable bit set in its
  118. * flags. Suppress context changes for a bit so that the flags are stable.
  119. * (the flags should not change in interrupt handling).
  120. */
  121. sched_lock();
  122. if ((dtcb->flags & TCB_FLAG_NONCANCELABLE) != 0)
  123. {
  124. /* Then we cannot cancel the thread now. Here is how this is
  125. * supposed to work:
  126. *
  127. * "When cancelability is disabled, all cancels are held pending
  128. * in the target thread until the thread changes the cancelability.
  129. * When cancelability is deferred, all cancels are held pending in
  130. * the target thread until the thread changes the cancelability, calls
  131. * a function which is a cancellation point or calls pthread_testcancel(),
  132. * thus creating a cancellation point. When cancelability is asynchronous,
  133. * all cancels are acted upon immediately, interrupting the thread with its
  134. * processing."
  135. */
  136. dtcb->flags |= TCB_FLAG_CANCEL_PENDING;
  137. sched_unlock();
  138. return OK;
  139. }
  140. #ifdef CONFIG_CANCELLATION_POINTS
  141. /* Check if this task supports deferred cancellation */
  142. if ((dtcb->flags & TCB_FLAG_CANCEL_DEFERRED) != 0)
  143. {
  144. /* Then we cannot cancel the task asynchronously. Mark the cancellation
  145. * as pending.
  146. */
  147. dtcb->flags |= TCB_FLAG_CANCEL_PENDING;
  148. /* If the task is waiting at a cancellation point, then notify of the
  149. * cancellation thereby waking the task up with an ECANCELED error.
  150. */
  151. if (dtcb->cpcount > 0)
  152. {
  153. nxnotify_cancellation(dtcb);
  154. }
  155. sched_unlock();
  156. return OK;
  157. }
  158. #endif
  159. /* Check if the task to delete is the calling task */
  160. sched_unlock();
  161. if (pid == rtcb->pid)
  162. {
  163. /* If it is, then what we really wanted to do was exit. Note that we
  164. * don't bother to unlock the TCB since it will be going away.
  165. */
  166. exit(EXIT_SUCCESS);
  167. }
  168. /* Otherwise, perform the asynchronous cancellation, letting
  169. * nxtask_terminate() do all of the heavy lifting.
  170. */
  171. ret = nxtask_terminate(pid, false);
  172. if (ret < 0)
  173. {
  174. errcode = -ret;
  175. goto errout;
  176. }
  177. return OK;
  178. errout:
  179. set_errno(errcode);
  180. return ERROR;
  181. }