mq_sndinternal.c 13 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446
  1. /****************************************************************************
  2. * sched/mqueue/mq_sndinternal.c
  3. *
  4. * Copyright (C) 2007, 2009, 2013-2017 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 <fcntl.h>
  42. #include <mqueue.h>
  43. #include <string.h>
  44. #include <errno.h>
  45. #include <sched.h>
  46. #include <debug.h>
  47. #include <nuttx/irq.h>
  48. #include <nuttx/kmalloc.h>
  49. #include <nuttx/arch.h>
  50. #include <nuttx/sched.h>
  51. #include <nuttx/cancelpt.h>
  52. #include "sched/sched.h"
  53. #include "mqueue/mqueue.h"
  54. /****************************************************************************
  55. * Public Functions
  56. ****************************************************************************/
  57. /****************************************************************************
  58. * Name: nxmq_verify_send
  59. *
  60. * Description:
  61. * This is internal, common logic shared by both [nx]mq_send and
  62. * [nx]mq_timesend. This function verifies the input parameters that are
  63. * common to both functions.
  64. *
  65. * Input Parameters:
  66. * mqdes - Message queue descriptor
  67. * msg - Message to send
  68. * msglen - The length of the message in bytes
  69. * prio - The priority of the message
  70. *
  71. * Returned Value:
  72. * One success, 0 (OK) is returned. On failure, a negated errno value is
  73. * returned.
  74. *
  75. * EINVAL Either msg or mqdes is NULL or the value of prio is invalid.
  76. * EPERM Message queue opened not opened for writing.
  77. * EMSGSIZE 'msglen' was greater than the maxmsgsize attribute of the
  78. * message queue.
  79. *
  80. ****************************************************************************/
  81. int nxmq_verify_send(mqd_t mqdes, FAR const char *msg, size_t msglen,
  82. unsigned int prio)
  83. {
  84. /* Verify the input parameters */
  85. if (msg == NULL || mqdes == NULL || prio > MQ_PRIO_MAX)
  86. {
  87. return -EINVAL;
  88. }
  89. if ((mqdes->oflags & O_WROK) == 0)
  90. {
  91. return -EPERM;
  92. }
  93. if (msglen > (size_t)mqdes->msgq->maxmsgsize)
  94. {
  95. return -EMSGSIZE;
  96. }
  97. return OK;
  98. }
  99. /****************************************************************************
  100. * Name: nxmq_alloc_msg
  101. *
  102. * Description:
  103. * The nxmq_alloc_msg function will get a free message for use by the
  104. * operating system. The message will be allocated from the g_msgfree
  105. * list.
  106. *
  107. * If the list is empty AND the message is NOT being allocated from the
  108. * interrupt level, then the message will be allocated. If a message
  109. * cannot be obtained, the operating system is dead and therefore cannot
  110. * continue.
  111. *
  112. * If the list is empty AND the message IS being allocated from the
  113. * interrupt level. This function will attempt to get a message from
  114. * the g_msgfreeirq list. If this is unsuccessful, the calling interrupt
  115. * handler will be notified.
  116. *
  117. * Input Parameters:
  118. * None
  119. *
  120. * Returned Value:
  121. * A reference to the allocated msg structure. On a failure to allocate,
  122. * this function PANICs.
  123. *
  124. ****************************************************************************/
  125. FAR struct mqueue_msg_s *nxmq_alloc_msg(void)
  126. {
  127. FAR struct mqueue_msg_s *mqmsg;
  128. irqstate_t flags;
  129. /* If we were called from an interrupt handler, then try to get the message
  130. * from generally available list of messages. If this fails, then try the
  131. * list of messages reserved for interrupt handlers
  132. */
  133. if (up_interrupt_context())
  134. {
  135. /* Try the general free list */
  136. mqmsg = (FAR struct mqueue_msg_s *)sq_remfirst(&g_msgfree);
  137. if (mqmsg == NULL)
  138. {
  139. /* Try the free list reserved for interrupt handlers */
  140. mqmsg = (FAR struct mqueue_msg_s *)sq_remfirst(&g_msgfreeirq);
  141. }
  142. }
  143. /* We were not called from an interrupt handler. */
  144. else
  145. {
  146. /* Try to get the message from the generally available free list.
  147. * Disable interrupts -- we might be called from an interrupt handler.
  148. */
  149. flags = enter_critical_section();
  150. mqmsg = (FAR struct mqueue_msg_s *)sq_remfirst(&g_msgfree);
  151. leave_critical_section(flags);
  152. /* If we cannot a message from the free list, then we will have to
  153. * allocate one.
  154. */
  155. if (mqmsg == NULL)
  156. {
  157. mqmsg = (FAR struct mqueue_msg_s *)
  158. kmm_malloc((sizeof (struct mqueue_msg_s)));
  159. /* Check if we allocated the message */
  160. if (mqmsg != NULL)
  161. {
  162. /* Yes... remember that this message was dynamically allocated */
  163. mqmsg->type = MQ_ALLOC_DYN;
  164. }
  165. }
  166. }
  167. return mqmsg;
  168. }
  169. /****************************************************************************
  170. * Name: nxmq_wait_send
  171. *
  172. * Description:
  173. * This is internal, common logic shared by both [nx]mq_send and
  174. * [nx]mq_timesend. This function waits until the message queue is not
  175. * full.
  176. *
  177. * Input Parameters:
  178. * mqdes - Message queue descriptor
  179. *
  180. * Returned Value:
  181. * On success, nxmq_wait_send() returns 0 (OK); a negated errno value is
  182. * returned on any failure:
  183. *
  184. * EAGAIN The queue was full and the O_NONBLOCK flag was set for the
  185. * message queue description referred to by mqdes.
  186. * EINTR The call was interrupted by a signal handler.
  187. * ETIMEOUT A timeout expired before the message queue became non-full
  188. * (mq_timedsend only).
  189. *
  190. * Assumptions/restrictions:
  191. * - The caller has verified the input parameters using nxmq_verify_send().
  192. * - Executes within a critical section established by the caller.
  193. *
  194. ****************************************************************************/
  195. int nxmq_wait_send(mqd_t mqdes)
  196. {
  197. FAR struct tcb_s *rtcb;
  198. FAR struct mqueue_inode_s *msgq;
  199. int ret;
  200. #ifdef CONFIG_CANCELLATION_POINTS
  201. /* nxmq_wait_send() is not a cancellation point, but may be called via
  202. * mq_send() or mq_timedsend() which are cancellation points.
  203. */
  204. if (check_cancellation_point())
  205. {
  206. /* If there is a pending cancellation, then do not perform
  207. * the wait. Exit now with ECANCELED.
  208. */
  209. return -ECANCELED;
  210. }
  211. #endif
  212. /* Get a pointer to the message queue */
  213. msgq = mqdes->msgq;
  214. /* Verify that the queue is indeed full as the caller thinks */
  215. if (msgq->nmsgs >= msgq->maxmsgs)
  216. {
  217. /* Should we block until there is sufficient space in the
  218. * message queue?
  219. */
  220. if ((mqdes->oflags & O_NONBLOCK) != 0)
  221. {
  222. /* No... We will return an error to the caller. */
  223. return -EAGAIN;
  224. }
  225. /* Yes... We will not return control until the message queue is
  226. * available or we receive a signal or at timout occurs.
  227. */
  228. else
  229. {
  230. /* Loop until there are fewer than max allowable messages in the
  231. * receiving message queue
  232. */
  233. while (msgq->nmsgs >= msgq->maxmsgs)
  234. {
  235. int saved_errno;
  236. /* Block until the message queue is no longer full.
  237. * When we are unblocked, we will try again
  238. */
  239. rtcb = this_task();
  240. rtcb->msgwaitq = msgq;
  241. msgq->nwaitnotfull++;
  242. /* "Borrow" the per-task errno to communication wake-up error
  243. * conditions.
  244. */
  245. saved_errno = rtcb->pterrno;
  246. rtcb->pterrno = OK;
  247. /* Make sure this is not the idle task, descheduling that
  248. * isn't going to end well.
  249. */
  250. DEBUGASSERT(NULL != rtcb->flink);
  251. up_block_task(rtcb, TSTATE_WAIT_MQNOTFULL);
  252. /* When we resume at this point, either (1) the message queue
  253. * is no longer empty, or (2) the wait has been interrupted by
  254. * a signal. We can detect the latter case be examining the
  255. * per-task errno value (should be EINTR or ETIMEOUT).
  256. */
  257. ret = rtcb->pterrno;
  258. rtcb->pterrno = saved_errno;
  259. if (ret != OK)
  260. {
  261. return -ret;
  262. }
  263. }
  264. }
  265. }
  266. return OK;
  267. }
  268. /****************************************************************************
  269. * Name: nxmq_do_send
  270. *
  271. * Description:
  272. * This is internal, common logic shared by both [nx]mq_send and
  273. * [nx]mq_timesend. This function adds the specified message (msg) to the
  274. * message queue (mqdes). Then it notifies any tasks that were waiting
  275. * for message queue notifications setup by mq_notify. And, finally, it
  276. * awakens any tasks that were waiting for the message not empty event.
  277. *
  278. * Input Parameters:
  279. * mqdes - Message queue descriptor
  280. * msg - Message to send
  281. * msglen - The length of the message in bytes
  282. * prio - The priority of the message
  283. *
  284. * Returned Value:
  285. * This function always returns OK.
  286. *
  287. ****************************************************************************/
  288. int nxmq_do_send(mqd_t mqdes, FAR struct mqueue_msg_s *mqmsg,
  289. FAR const char *msg, size_t msglen, unsigned int prio)
  290. {
  291. FAR struct tcb_s *btcb;
  292. FAR struct mqueue_inode_s *msgq;
  293. FAR struct mqueue_msg_s *next;
  294. FAR struct mqueue_msg_s *prev;
  295. irqstate_t flags;
  296. /* Get a pointer to the message queue */
  297. sched_lock();
  298. msgq = mqdes->msgq;
  299. /* Construct the message header info */
  300. mqmsg->priority = prio;
  301. mqmsg->msglen = msglen;
  302. /* Copy the message data into the message */
  303. memcpy((FAR void *)mqmsg->mail, (FAR const void *)msg, msglen);
  304. /* Insert the new message in the message queue */
  305. flags = enter_critical_section();
  306. /* Search the message list to find the location to insert the new
  307. * message. Each is list is maintained in ascending priority order.
  308. */
  309. for (prev = NULL, next = (FAR struct mqueue_msg_s *)msgq->msglist.head;
  310. next && prio <= next->priority;
  311. prev = next, next = next->next);
  312. /* Add the message at the right place */
  313. if (prev)
  314. {
  315. sq_addafter((FAR sq_entry_t *)prev, (FAR sq_entry_t *)mqmsg,
  316. &msgq->msglist);
  317. }
  318. else
  319. {
  320. sq_addfirst((FAR sq_entry_t *)mqmsg, &msgq->msglist);
  321. }
  322. /* Increment the count of messages in the queue */
  323. msgq->nmsgs++;
  324. leave_critical_section(flags);
  325. /* Check if we need to notify any tasks that are attached to the
  326. * message queue
  327. */
  328. if (msgq->ntmqdes)
  329. {
  330. struct sigevent event;
  331. pid_t pid;
  332. /* Remove the message notification data from the message queue. */
  333. memcpy(&event, &msgq->ntevent, sizeof(struct sigevent));
  334. pid = msgq->ntpid;
  335. /* Detach the notification */
  336. memset(&msgq->ntevent, 0, sizeof(struct sigevent));
  337. msgq->ntpid = INVALID_PROCESS_ID;
  338. msgq->ntmqdes = NULL;
  339. /* Notification the client */
  340. DEBUGVERIFY(nxsig_notification(pid, &event,
  341. SI_MESGQ, &msgq->ntwork));
  342. }
  343. /* Check if any tasks are waiting for the MQ not empty event. */
  344. flags = enter_critical_section();
  345. if (msgq->nwaitnotempty > 0)
  346. {
  347. /* Find the highest priority task that is waiting for
  348. * this queue to be non-empty in g_waitingformqnotempty
  349. * list. sched_lock() should give us sufficent protection since
  350. * interrupts should never cause a change in this list
  351. */
  352. for (btcb = (FAR struct tcb_s *)g_waitingformqnotempty.head;
  353. btcb && btcb->msgwaitq != msgq;
  354. btcb = btcb->flink);
  355. /* If one was found, unblock it */
  356. DEBUGASSERT(btcb);
  357. btcb->msgwaitq = NULL;
  358. msgq->nwaitnotempty--;
  359. up_unblock_task(btcb);
  360. }
  361. leave_critical_section(flags);
  362. sched_unlock();
  363. return OK;
  364. }