task_posixspawn.c 16 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443
  1. /****************************************************************************
  2. * sched/task/task_posixspawn.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 <spawn.h>
  41. #include <debug.h>
  42. #include <nuttx/sched.h>
  43. #include <nuttx/kthread.h>
  44. #include <nuttx/binfmt/binfmt.h>
  45. #include <nuttx/binfmt/symtab.h>
  46. #include "sched/sched.h"
  47. #include "group/group.h"
  48. #include "task/spawn.h"
  49. #include "task/task.h"
  50. /****************************************************************************
  51. * Private Functions
  52. ****************************************************************************/
  53. /****************************************************************************
  54. * Name: nxposix_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. * path - The 'path' argument identifies the file to execute. If
  65. * CONFIG_LIB_ENVPATH is defined, this may be either a relative or
  66. * or an absolute path. Otherwise, it must be an absolute path.
  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 ps_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 nxposix_spawn_exec(FAR pid_t *pidp, FAR const char *path,
  92. FAR const posix_spawnattr_t *attr,
  93. FAR char * const argv[])
  94. {
  95. FAR const struct symtab_s *symtab;
  96. int nsymbols;
  97. int pid;
  98. int ret = OK;
  99. DEBUGASSERT(path);
  100. /* Get the current symbol table selection */
  101. exec_getsymtab(&symtab, &nsymbols);
  102. /* Disable pre-emption so that we can modify the task parameters after
  103. * we start the new task; the new task will not actually begin execution
  104. * until we re-enable pre-emption.
  105. */
  106. sched_lock();
  107. /* Start the task */
  108. pid = exec(path, (FAR char * const *)argv, symtab, nsymbols);
  109. if (pid < 0)
  110. {
  111. ret = get_errno();
  112. serr("ERROR: exec failed: %d\n", ret);
  113. goto errout;
  114. }
  115. /* Return the task ID to the caller */
  116. if (pid)
  117. {
  118. *pidp = pid;
  119. }
  120. /* Now set the attributes. Note that we ignore all of the return values
  121. * here because we have already successfully started the task. If we
  122. * return an error value, then we would also have to stop the task.
  123. */
  124. if (attr)
  125. {
  126. (void)spawn_execattrs(pid, attr);
  127. }
  128. /* Re-enable pre-emption and return */
  129. errout:
  130. sched_unlock();
  131. return ret;
  132. }
  133. /****************************************************************************
  134. * Name: nxposix_spawn_proxy
  135. *
  136. * Description:
  137. * Perform file_actions, then execute the task from the file system.
  138. *
  139. * Do we really need this proxy task? Isn't that wasteful?
  140. *
  141. * Q: Why not use a starthook so that there is callout from nxtask_start()
  142. * to perform these operations after the file is loaded from
  143. * the file system?
  144. * A: That existing nxtask_starthook() implementation cannot be used in
  145. * this context; any of nxtask_starthook() will also conflict with
  146. * binfmt's use of the start hook to call C++ static initializers.
  147. * task_restart() would also be an issue.
  148. *
  149. * Input Parameters:
  150. * Standard task start-up parameters
  151. *
  152. * Returned Value:
  153. * Standard task return value.
  154. *
  155. ****************************************************************************/
  156. static int nxposix_spawn_proxy(int argc, FAR char *argv[])
  157. {
  158. int ret;
  159. /* Perform file actions and/or set a custom signal mask. We get here only
  160. * if the file_actions parameter to posix_spawn[p] was non-NULL and/or the
  161. * option to change the signal mask was selected.
  162. */
  163. DEBUGASSERT(g_spawn_parms.file_actions ||
  164. (g_spawn_parms.attr &&
  165. (g_spawn_parms.attr->flags & POSIX_SPAWN_SETSIGMASK) != 0));
  166. /* Set the attributes and perform the file actions as appropriate */
  167. ret = spawn_proxyattrs(g_spawn_parms.attr, g_spawn_parms.file_actions);
  168. if (ret == OK)
  169. {
  170. /* Start the task */
  171. ret = nxposix_spawn_exec(g_spawn_parms.pid, g_spawn_parms.u.posix.path,
  172. g_spawn_parms.attr, g_spawn_parms.argv);
  173. #ifdef CONFIG_SCHED_HAVE_PARENT
  174. if (ret == OK)
  175. {
  176. /* Change of the parent of the task we just spawned to our parent.
  177. * What should we do in the event of a failure?
  178. */
  179. int tmp = task_reparent(0, *g_spawn_parms.pid);
  180. if (tmp < 0)
  181. {
  182. serr("ERROR: task_reparent() failed: %d\n", tmp);
  183. }
  184. }
  185. #endif
  186. }
  187. /* Post the semaphore to inform the parent task that we have completed
  188. * what we need to do.
  189. */
  190. g_spawn_parms.result = ret;
  191. #ifndef CONFIG_SCHED_WAITPID
  192. spawn_semgive(&g_spawn_execsem);
  193. #endif
  194. return OK;
  195. }
  196. /****************************************************************************
  197. * Public Functions
  198. ****************************************************************************/
  199. /****************************************************************************
  200. * Name: posix_spawn
  201. *
  202. * Description:
  203. * The posix_spawn() and posix_spawnp() functions will create a new,
  204. * child task, constructed from a regular executable file.
  205. *
  206. * Input Parameters:
  207. *
  208. * pid - Upon successful completion, posix_spawn() and posix_spawnp() will
  209. * return the task ID of the child task to the parent task, in the
  210. * variable pointed to by a non-NULL 'pid' argument. If the 'pid'
  211. * argument is a null pointer, the process ID of the child is not
  212. * returned to the caller.
  213. *
  214. * path - The 'path' argument to posix_spawn() is the absolute path that
  215. * identifies the file to execute. The 'path' argument to posix_spawnp()
  216. * may also be a relative path and will be used to construct a pathname
  217. * that identifies the file to execute. In the case of a relative path,
  218. * the path prefix for the file will be obtained by a search of the
  219. * directories passed as the environment variable PATH.
  220. *
  221. * NOTE: NuttX provides only one implementation: If
  222. * CONFIG_LIB_ENVPATH is defined, then only posix_spawnp() behavior
  223. * is supported; otherwise, only posix_spawn behavior is supported.
  224. *
  225. * file_actions - If 'file_actions' is a null pointer, then file
  226. * descriptors open in the calling process will remain open in the
  227. * child process (unless CONFIG_FDCLONE_STDIO is defined). If
  228. * 'file_actions' is not NULL, then the file descriptors open in the
  229. * child process will be those open in the calling process as modified
  230. * by the spawn file actions object pointed to by file_actions.
  231. *
  232. * attr - If the value of the 'attr' parameter is NULL, the all default
  233. * values for the POSIX spawn attributes will be used. Otherwise, the
  234. * attributes will be set according to the spawn flags. The
  235. * posix_spawnattr_t spawn attributes object type is defined in spawn.h.
  236. * It will contains these attributes, not all of which are supported by
  237. * NuttX:
  238. *
  239. * - POSIX_SPAWN_SETPGROUP: Setting of the new task's process group is
  240. * not supported. NuttX does not support process groups.
  241. * - POSIX_SPAWN_SETSCHEDPARAM: Set new tasks priority to the sched_param
  242. * value.
  243. * - POSIX_SPAWN_SETSCHEDULER: Set the new task's scheduler policy to
  244. * the sched_policy value.
  245. * - POSIX_SPAWN_RESETIDS: Resetting of the effective user ID of the child
  246. * process is not supported. NuttX does not support effective user
  247. * IDs.
  248. * - POSIX_SPAWN_SETSIGMASK: Set the new task's signal mask.
  249. * - POSIX_SPAWN_SETSIGDEF: Resetting signal default actions is not
  250. * supported. NuttX does not support default signal actions.
  251. *
  252. * argv - argv[] is the argument list for the new task. argv[] is an
  253. * array of pointers to null-terminated strings. The list is terminated
  254. * with a null pointer.
  255. *
  256. * envp - The envp[] argument is not used by NuttX and may be NULL. In
  257. * standard implementations, envp[] is an array of character pointers to
  258. * null-terminated strings that provide the environment for the new
  259. * process image. The environment array is terminated by a null pointer.
  260. * In NuttX, the envp[] argument is ignored and the new task will simply
  261. * inherit the environment of the parent task.
  262. *
  263. * Returned Value:
  264. * posix_spawn() and posix_spawnp() will return zero on success.
  265. * Otherwise, an error number will be returned as the function return
  266. * value to indicate the error:
  267. *
  268. * - EINVAL: The value specified by 'file_actions' or 'attr' is invalid.
  269. * - Any errors that might have been return if vfork() and excec[l|v]()
  270. * had been called.
  271. *
  272. * Assumptions/Limitations:
  273. * - NuttX provides only posix_spawn() or posix_spawnp() behavior
  274. * depending upon the setting of CONFIG_LIB_ENVPATH: If
  275. * CONFIG_LIB_ENVPATH is defined, then only posix_spawnp() behavior
  276. * is supported; otherwise, only posix_spawn behavior is supported.
  277. * - The 'envp' argument is not used and the 'environ' variable is not
  278. * altered (NuttX does not support the 'environ' variable).
  279. * - Process groups are not supported (POSIX_SPAWN_SETPGROUP).
  280. * - Effective user IDs are not supported (POSIX_SPAWN_RESETIDS).
  281. * - Signal default actions cannot be modified in the newly task executed
  282. * because NuttX does not support default signal actions
  283. * (POSIX_SPAWN_SETSIGDEF).
  284. *
  285. * POSIX Compatibility
  286. * - The value of the argv[0] received by the child task is assigned by
  287. * NuttX. For the caller of posix_spawn(), the provided argv[0] will
  288. * correspond to argv[1] received by the new task.
  289. *
  290. ****************************************************************************/
  291. #ifdef CONFIG_LIB_ENVPATH
  292. int posix_spawnp(FAR pid_t *pid, FAR const char *path,
  293. FAR const posix_spawn_file_actions_t *file_actions,
  294. FAR const posix_spawnattr_t *attr,
  295. FAR char *const argv[], FAR char *const envp[])
  296. #else
  297. int posix_spawn(FAR pid_t *pid, FAR const char *path,
  298. FAR const posix_spawn_file_actions_t *file_actions,
  299. FAR const posix_spawnattr_t *attr,
  300. FAR char *const argv[], FAR char *const envp[])
  301. #endif
  302. {
  303. struct sched_param param;
  304. pid_t proxy;
  305. #ifdef CONFIG_SCHED_WAITPID
  306. int status;
  307. #endif
  308. int ret;
  309. DEBUGASSERT(path);
  310. sinfo("pid=%p path=%s file_actions=%p attr=%p argv=%p\n",
  311. pid, path, file_actions, attr, argv);
  312. /* If there are no file actions to be performed and there is no change to
  313. * the signal mask, then start the new child task directly from the parent
  314. * task.
  315. */
  316. if ((file_actions == NULL || *file_actions == NULL) &&
  317. (attr == NULL || (attr->flags & POSIX_SPAWN_SETSIGMASK) == 0))
  318. {
  319. return nxposix_spawn_exec(pid, path, attr, argv);
  320. }
  321. /* Otherwise, we will have to go through an intermediary/proxy task in order
  322. * to perform the I/O redirection. This would be a natural place to fork().
  323. * However, true fork() behavior requires an MMU and most implementations
  324. * of vfork() are not capable of these operations.
  325. *
  326. * Even without fork(), we can still do the job, but parameter passing is
  327. * messier. Unfortunately, there is no (clean) way to pass binary values
  328. * as a task parameter, so we will use a semaphore-protected global
  329. * structure.
  330. */
  331. /* Get exclusive access to the global parameter structure */
  332. spawn_semtake(&g_spawn_parmsem);
  333. /* Populate the parameter structure */
  334. g_spawn_parms.result = ENOSYS;
  335. g_spawn_parms.pid = pid;
  336. g_spawn_parms.file_actions = file_actions ? *file_actions : NULL;
  337. g_spawn_parms.attr = attr;
  338. g_spawn_parms.argv = argv;
  339. g_spawn_parms.u.posix.path = path;
  340. /* Get the priority of this (parent) task */
  341. ret = nxsched_getparam(0, &param);
  342. if (ret < 0)
  343. {
  344. serr("ERROR: nxsched_getparam failed: %d\n", ret);
  345. spawn_semgive(&g_spawn_parmsem);
  346. return -ret;
  347. }
  348. /* Disable pre-emption so that the proxy does not run until waitpid
  349. * is called. This is probably unnecessary since the nxposix_spawn_proxy
  350. * has the same priority as this thread; it should be schedule behind
  351. * this task in the ready-to-run list.
  352. */
  353. #ifdef CONFIG_SCHED_WAITPID
  354. sched_lock();
  355. #endif
  356. /* Start the intermediary/proxy task at the same priority as the parent
  357. * task.
  358. */
  359. proxy = kthread_create("nxposix_spawn_proxy", param.sched_priority,
  360. CONFIG_POSIX_SPAWN_PROXY_STACKSIZE,
  361. (main_t)nxposix_spawn_proxy,
  362. (FAR char * const *)NULL);
  363. if (proxy < 0)
  364. {
  365. ret = -proxy;
  366. serr("ERROR: Failed to start nxposix_spawn_proxy: %d\n", ret);
  367. goto errout_with_lock;
  368. }
  369. /* Wait for the proxy to complete its job */
  370. #ifdef CONFIG_SCHED_WAITPID
  371. ret = waitpid(proxy, &status, 0);
  372. if (ret < 0)
  373. {
  374. serr("ERROR: waitpid() failed: %d\n", errno);
  375. goto errout_with_lock;
  376. }
  377. #else
  378. spawn_semtake(&g_spawn_execsem);
  379. #endif
  380. /* Get the result and relinquish our access to the parameter structure */
  381. ret = g_spawn_parms.result;
  382. errout_with_lock:
  383. #ifdef CONFIG_SCHED_WAITPID
  384. sched_unlock();
  385. #endif
  386. spawn_semgive(&g_spawn_parmsem);
  387. return ret;
  388. }