task_spawn.c 15 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438
  1. /****************************************************************************
  2. * sched/task/task_spawn.c
  3. *
  4. * Copyright (C) 2013, 2018-2019 Gregory Nutt. All rights reserved.
  5. * Author: Gregory Nutt <gnutt@nuttx.org>
  6. *
  7. * Redistribution and use in source and binary forms, with or without
  8. * modification, are permitted provided that the following conditions
  9. * are met:
  10. *
  11. * 1. Redistributions of source code must retain the above copyright
  12. * notice, this list of conditions and the following disclaimer.
  13. * 2. Redistributions in binary form must reproduce the above copyright
  14. * notice, this list of conditions and the following disclaimer in
  15. * the documentation and/or other materials provided with the
  16. * distribution.
  17. * 3. Neither the name NuttX nor the names of its contributors may be
  18. * used to endorse or promote products derived from this software
  19. * without specific prior written permission.
  20. *
  21. * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
  22. * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
  23. * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
  24. * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
  25. * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
  26. * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
  27. * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
  28. * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
  29. * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
  30. * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
  31. * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
  32. * POSSIBILITY OF SUCH DAMAGE.
  33. *
  34. ****************************************************************************/
  35. /****************************************************************************
  36. * Included Files
  37. ****************************************************************************/
  38. #include <nuttx/config.h>
  39. #include <sys/wait.h>
  40. #include <sched.h>
  41. #include <spawn.h>
  42. #include <debug.h>
  43. #include <nuttx/sched.h>
  44. #include <nuttx/kthread.h>
  45. #include "sched/sched.h"
  46. #include "group/group.h"
  47. #include "task/spawn.h"
  48. #include "task/task.h"
  49. #ifndef CONFIG_BUILD_KERNEL
  50. /****************************************************************************
  51. * Private Functions
  52. ****************************************************************************/
  53. /****************************************************************************
  54. * Name: nxtask_spawn_exec
  55. *
  56. * Description:
  57. * Execute the task from the file system.
  58. *
  59. * Input Parameters:
  60. *
  61. * pidp - Upon successful completion, this will return the task ID of the
  62. * child task in the variable pointed to by a non-NULL 'pid' argument.|
  63. *
  64. * name - The name to assign to the child task.
  65. *
  66. * entry - The child task's entry point (an address in memory)
  67. *
  68. * attr - If the value of the 'attr' parameter is NULL, the all default
  69. * values for the POSIX spawn attributes will be used. Otherwise, the
  70. * attributes will be set according to the spawn flags. The
  71. * following spawn flags are supported:
  72. *
  73. * - POSIX_SPAWN_SETSCHEDPARAM: Set new tasks priority to the sched_param
  74. * value.
  75. * - POSIX_SPAWN_SETSCHEDULER: Set the new tasks scheduler priority to
  76. * the sched_policy value.
  77. *
  78. * NOTE: POSIX_SPAWN_SETSIGMASK is handled in nxtask_spawn_proxy().
  79. *
  80. * argv - argv[] is the argument list for the new task. argv[] is an
  81. * array of pointers to null-terminated strings. The list is terminated
  82. * with a null pointer.
  83. *
  84. * Returned Value:
  85. * This function will return zero on success. Otherwise, an error number
  86. * will be returned as the function return value to indicate the error.
  87. * This errno value may be that set by execv(), sched_setpolicy(), or
  88. * sched_setparam().
  89. *
  90. ****************************************************************************/
  91. static int nxtask_spawn_exec(FAR pid_t *pidp, FAR const char *name,
  92. main_t entry, FAR const posix_spawnattr_t *attr,
  93. FAR char * const *argv)
  94. {
  95. size_t stacksize;
  96. int priority;
  97. int pid;
  98. int ret = OK;
  99. /* Disable pre-emption so that we can modify the task parameters after
  100. * we start the new task; the new task will not actually begin execution
  101. * until we re-enable pre-emption.
  102. */
  103. sched_lock();
  104. /* Use the default task priority and stack size if no attributes are provided */
  105. if (attr)
  106. {
  107. priority = attr->priority;
  108. stacksize = attr->stacksize;
  109. }
  110. else
  111. {
  112. struct sched_param param;
  113. /* Set the default priority to the same priority as this task */
  114. ret = nxsched_getparam(0, &param);
  115. if (ret < 0)
  116. {
  117. ret = -ret;
  118. goto errout;
  119. }
  120. priority = param.sched_priority;
  121. stacksize = CONFIG_TASK_SPAWN_DEFAULT_STACKSIZE;
  122. }
  123. /* Start the task */
  124. pid = nxtask_create(name, priority, stacksize, entry, argv);
  125. if (pid < 0)
  126. {
  127. ret = -pid;
  128. serr("ERROR: nxtask_create failed: %d\n", ret);
  129. goto errout;
  130. }
  131. /* Return the task ID to the caller */
  132. if (pid)
  133. {
  134. *pidp = pid;
  135. }
  136. /* Now set the attributes. Note that we ignore all of the return values
  137. * here because we have already successfully started the task. If we
  138. * return an error value, then we would also have to stop the task.
  139. */
  140. if (attr)
  141. {
  142. (void)spawn_execattrs(pid, attr);
  143. }
  144. /* Re-enable pre-emption and return */
  145. errout:
  146. sched_unlock();
  147. return ret;
  148. }
  149. /****************************************************************************
  150. * Name: nxtask_spawn_proxy
  151. *
  152. * Description:
  153. * Perform file_actions, then execute the task from the file system.
  154. *
  155. * Do we really need a proxy task in this case? Isn't that wasteful?
  156. *
  157. * Q: Why can we do what we need to do here and the just call the
  158. * new task's entry point.
  159. * A: This would require setting up the name, priority, and stacksize from
  160. * the task_spawn, but it do-able. The only issue I can think of is
  161. * that NuttX supports task_restart(), and you would never be able to
  162. * restart a task from this point.
  163. *
  164. * Q: Why not use a starthook so that there is callout from nxtask_start()
  165. * to perform these operations?
  166. * A: Good idea, except that existing nxtask_starthook() implementation
  167. * cannot be used here unless we get rid of task_create and, instead,
  168. * use task_init() and task_activate(). start_taskhook() could then
  169. * be called between task_init() and task)activate(). task_restart()
  170. * would still be an issue.
  171. *
  172. * Input Parameters:
  173. * Standard task start-up parameters
  174. *
  175. * Returned Value:
  176. * Standard task return value.
  177. *
  178. ****************************************************************************/
  179. static int nxtask_spawn_proxy(int argc, FAR char *argv[])
  180. {
  181. int ret;
  182. /* Perform file actions and/or set a custom signal mask. We get here only
  183. * if the file_actions parameter to task_spawn[p] was non-NULL and/or the
  184. * option to change the signal mask was selected.
  185. */
  186. DEBUGASSERT(g_spawn_parms.file_actions ||
  187. (g_spawn_parms.attr &&
  188. (g_spawn_parms.attr->flags & POSIX_SPAWN_SETSIGMASK) != 0));
  189. /* Set the attributes and perform the file actions as appropriate */
  190. ret = spawn_proxyattrs(g_spawn_parms.attr, g_spawn_parms.file_actions);
  191. if (ret == OK)
  192. {
  193. /* Start the task */
  194. ret = nxtask_spawn_exec(g_spawn_parms.pid, g_spawn_parms.u.task.name,
  195. g_spawn_parms.u.task.entry, g_spawn_parms.attr,
  196. g_spawn_parms.argv);
  197. #ifdef CONFIG_SCHED_HAVE_PARENT
  198. if (ret == OK)
  199. {
  200. /* Change of the parent of the task we just spawned to our parent.
  201. * What should we do in the event of a failure?
  202. */
  203. int tmp = task_reparent(0, *g_spawn_parms.pid);
  204. if (tmp < 0)
  205. {
  206. serr("ERROR: task_reparent() failed: %d\n", tmp);
  207. }
  208. }
  209. #endif
  210. }
  211. /* Post the semaphore to inform the parent task that we have completed
  212. * what we need to do.
  213. */
  214. g_spawn_parms.result = ret;
  215. #ifndef CONFIG_SCHED_WAITPID
  216. spawn_semgive(&g_spawn_execsem);
  217. #endif
  218. return OK;
  219. }
  220. /****************************************************************************
  221. * Public Functions
  222. ****************************************************************************/
  223. /****************************************************************************
  224. * Name: task_spawn
  225. *
  226. * Description:
  227. * The task_spawn() function will create a new, child task, where the
  228. * entry point to the task is an address in memory.
  229. *
  230. * Input Parameters:
  231. *
  232. * pid - Upon successful completion, task_spawn() will return the task ID
  233. * of the child task to the parent task, in the variable pointed to by
  234. * a non-NULL 'pid' argument. If the 'pid' argument is a null pointer,
  235. * the process ID of the child is not returned to the caller.
  236. *
  237. * name - The name to assign to the child task.
  238. *
  239. * entry - The child task's entry point (an address in memory)
  240. *
  241. * file_actions - If 'file_actions' is a null pointer, then file
  242. * descriptors open in the calling process will remain open in the
  243. * child process (unless CONFIG_FDCLONE_STDIO is defined). If
  244. * 'file_actions' is not NULL, then the file descriptors open in the
  245. * child process will be those open in the calling process as modified
  246. * by the spawn file actions object pointed to by file_actions.
  247. *
  248. * attr - If the value of the 'attr' parameter is NULL, the all default
  249. * values for the POSIX spawn attributes will be used. Otherwise, the
  250. * attributes will be set according to the spawn flags. The
  251. * task_spawnattr_t spawn attributes object type is defined in spawn.h.
  252. * It will contains these attributes, not all of which are supported by
  253. * NuttX:
  254. *
  255. * - POSIX_SPAWN_SETPGROUP: Setting of the new task's process group is
  256. * not supported. NuttX does not support process groups.
  257. * - POSIX_SPAWN_SETSCHEDPARAM: Set new tasks priority to the sched_param
  258. * value.
  259. * - POSIX_SPAWN_SETSCHEDULER: Set the new task's scheduler policy to
  260. * the sched_policy value.
  261. * - POSIX_SPAWN_RESETIDS: Resetting of the effective user ID of the child
  262. * process is not supported. NuttX does not support effective user
  263. * IDs.
  264. * - POSIX_SPAWN_SETSIGMASK: Set the new task's signal mask.
  265. * - POSIX_SPAWN_SETSIGDEF: Resetting signal default actions is not
  266. * supported. NuttX does not support default signal actions.
  267. *
  268. * And the non-standard:
  269. *
  270. * - TASK_SPAWN_SETSTACKSIZE: Set the stack size for the new task.
  271. *
  272. * argv - argv[] is the argument list for the new task. argv[] is an
  273. * array of pointers to null-terminated strings. The list is terminated
  274. * with a null pointer.
  275. *
  276. * envp - The envp[] argument is not used by NuttX and may be NULL.
  277. *
  278. * Returned Value:
  279. * task_spawn() will return zero on success. Otherwise, an error number
  280. * will be returned as the function return value to indicate the error:
  281. *
  282. * - EINVAL: The value specified by 'file_actions' or 'attr' is invalid.
  283. * - Any errors that might have been return if vfork() and excec[l|v]()
  284. * had been called.
  285. *
  286. ****************************************************************************/
  287. int task_spawn(FAR pid_t *pid, FAR const char *name, main_t entry,
  288. FAR const posix_spawn_file_actions_t *file_actions,
  289. FAR const posix_spawnattr_t *attr,
  290. FAR char *const argv[], FAR char *const envp[])
  291. {
  292. struct sched_param param;
  293. pid_t proxy;
  294. #ifdef CONFIG_SCHED_WAITPID
  295. int status;
  296. #endif
  297. int ret;
  298. sinfo("pid=%p name=%s entry=%p file_actions=%p attr=%p argv=%p\n",
  299. pid, name, entry, file_actions, attr, argv);
  300. /* If there are no file actions to be performed and there is no change to
  301. * the signal mask, then start the new child task directly from the parent
  302. * task.
  303. */
  304. if ((file_actions == NULL || *file_actions == NULL) &&
  305. (attr == NULL || (attr->flags & POSIX_SPAWN_SETSIGMASK) == 0))
  306. {
  307. return nxtask_spawn_exec(pid, name, entry, attr, argv);
  308. }
  309. /* Otherwise, we will have to go through an intermediary/proxy task in order
  310. * to perform the I/O redirection. This would be a natural place to fork().
  311. * However, true fork() behavior requires an MMU and most implementations
  312. * of vfork() are not capable of these operations.
  313. *
  314. * Even without fork(), we can still do the job, but parameter passing is
  315. * messier. Unfortunately, there is no (clean) way to pass binary values
  316. * as a task parameter, so we will use a semaphore-protected global
  317. * structure.
  318. */
  319. /* Get exclusive access to the global parameter structure */
  320. spawn_semtake(&g_spawn_parmsem);
  321. /* Populate the parameter structure */
  322. g_spawn_parms.result = ENOSYS;
  323. g_spawn_parms.pid = pid;
  324. g_spawn_parms.file_actions = file_actions ? *file_actions : NULL;
  325. g_spawn_parms.attr = attr;
  326. g_spawn_parms.argv = argv;
  327. g_spawn_parms.u.task.name = name;
  328. g_spawn_parms.u.task.entry = entry;
  329. /* Get the priority of this (parent) task */
  330. ret = nxsched_getparam(0, &param);
  331. if (ret < 0)
  332. {
  333. serr("ERROR: nxsched_getparam failed: %d\n", ret);
  334. spawn_semgive(&g_spawn_parmsem);
  335. return -ret;
  336. }
  337. #ifdef CONFIG_SCHED_WAITPID
  338. /* Disable pre-emption so that the proxy does not run until waitpid
  339. * is called. This is probably unnecessary since the nxtask_spawn_proxy
  340. * has the same priority as this thread; it should be schedule behind
  341. * this task in the ready-to-run list.
  342. *
  343. * REVISIT: This will may not have the desired effect in SMP mode.
  344. */
  345. sched_lock();
  346. #endif
  347. /* Start the intermediary/proxy task at the same priority as the parent
  348. * task.
  349. */
  350. proxy = nxtask_create("nxtask_spawn_proxy", param.sched_priority,
  351. CONFIG_POSIX_SPAWN_PROXY_STACKSIZE,
  352. (main_t)nxtask_spawn_proxy,
  353. (FAR char * const *)NULL);
  354. if (proxy < 0)
  355. {
  356. ret = -proxy;
  357. serr("ERROR: Failed to start nxtask_spawn_proxy: %d\n", ret);
  358. goto errout_with_lock;
  359. }
  360. /* Wait for the proxy to complete its job */
  361. #ifdef CONFIG_SCHED_WAITPID
  362. ret = waitpid(proxy, &status, 0);
  363. if (ret < 0)
  364. {
  365. serr("ERROR: waitpid() failed: %d\n", errno);
  366. goto errout_with_lock;
  367. }
  368. #else
  369. spawn_semtake(&g_spawn_execsem);
  370. #endif
  371. /* Get the result and relinquish our access to the parameter structure */
  372. ret = g_spawn_parms.result;
  373. errout_with_lock:
  374. #ifdef CONFIG_SCHED_WAITPID
  375. sched_unlock();
  376. #endif
  377. spawn_semgive(&g_spawn_parmsem);
  378. return ret;
  379. }
  380. #endif /* CONFIG_BUILD_KERNEL */