task_init.c 5.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158
  1. /****************************************************************************
  2. * sched/task/task_init.c
  3. *
  4. * Copyright (C) 2007, 2009, 2013-2014 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/types.h>
  40. #include <stdint.h>
  41. #include <sched.h>
  42. #include <errno.h>
  43. #include <nuttx/arch.h>
  44. #include "sched/sched.h"
  45. #include "group/group.h"
  46. #include "task/task.h"
  47. /****************************************************************************
  48. * Public Functions
  49. ****************************************************************************/
  50. /****************************************************************************
  51. * Name: task_init
  52. *
  53. * Description:
  54. * This function initializes a Task Control Block (TCB) in preparation for
  55. * starting a new thread. It performs a subset of the functionality of
  56. * task_create()
  57. *
  58. * Unlike task_create():
  59. * 1. Allocate the TCB. The pre-allocated TCB is passed in the arguments.
  60. * 2. Allocate the stack. The pre-allocated stack is passed in the arguments.
  61. * 3. Activate the task. This must be done by calling task_activate().
  62. *
  63. * Input Parameters:
  64. * tcb - Address of the new task's TCB
  65. * name - Name of the new task (not used)
  66. * priority - Priority of the new task
  67. * stack - Start of the pre-allocated stack
  68. * stack_size - Size (in bytes) of the stack allocated
  69. * entry - Application start point of the new task
  70. * arg - A pointer to an array of input parameters. The array
  71. * should be terminated with a NULL argv[] value. If no
  72. * parameters are required, argv may be NULL.
  73. *
  74. * Returned Value:
  75. * OK on success; ERROR on failure with errno set appropriately. (See
  76. * nxtask_schedsetup() for possible failure conditions). On failure, the
  77. * caller is responsible for freeing the stack memory and for calling
  78. * sched_releasetcb() to free the TCB (which could be in most any state).
  79. *
  80. ****************************************************************************/
  81. int task_init(FAR struct tcb_s *tcb, const char *name, int priority,
  82. FAR uint32_t *stack, uint32_t stack_size,
  83. main_t entry, FAR char * const argv[])
  84. {
  85. FAR struct task_tcb_s *ttcb = (FAR struct task_tcb_s *)tcb;
  86. int errcode;
  87. int ret;
  88. /* Only tasks and kernel threads can be initialized in this way */
  89. #ifndef CONFIG_DISABLE_PTHREAD
  90. DEBUGASSERT(tcb &&
  91. (tcb->flags & TCB_FLAG_TTYPE_MASK) != TCB_FLAG_TTYPE_PTHREAD);
  92. #endif
  93. /* Create a new task group */
  94. ret = group_allocate(ttcb, tcb->flags);
  95. if (ret < 0)
  96. {
  97. errcode = -ret;
  98. goto errout;
  99. }
  100. /* Associate file descriptors with the new task */
  101. ret = group_setuptaskfiles(ttcb);
  102. if (ret < 0)
  103. {
  104. errcode = -ret;
  105. goto errout_with_group;
  106. }
  107. /* Configure the user provided stack region */
  108. up_use_stack(tcb, stack, stack_size);
  109. /* Initialize the task control block */
  110. ret = nxtask_schedsetup(ttcb, priority, nxtask_start, entry,
  111. TCB_FLAG_TTYPE_TASK);
  112. if (ret < OK)
  113. {
  114. errcode = -ret;
  115. goto errout_with_group;
  116. }
  117. /* Setup to pass parameters to the new task */
  118. (void)nxtask_argsetup(ttcb, name, argv);
  119. /* Now we have enough in place that we can join the group */
  120. ret = group_initialize(ttcb);
  121. if (ret < 0)
  122. {
  123. errcode = -ret;
  124. goto errout_with_group;
  125. }
  126. return OK;
  127. errout_with_group:
  128. group_leave(tcb);
  129. errout:
  130. set_errno(errcode);
  131. return ERROR;
  132. }