summaryrefslogtreecommitdiff
path: root/nuttx/sched
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2014-09-29 14:59:31 -0600
committerGregory Nutt <gnutt@nuttx.org>2014-09-29 14:59:31 -0600
commit92b3c77f738b63b1eedc4977f1c68a1fdcc74268 (patch)
treed2b94ae762cc25fcc1543393cf069cebfaba7eb1 /nuttx/sched
parent96c1138b01020dee669415d903f0af8e9d31f137 (diff)
downloadpx4-nuttx-92b3c77f738b63b1eedc4977f1c68a1fdcc74268.tar.gz
px4-nuttx-92b3c77f738b63b1eedc4977f1c68a1fdcc74268.tar.bz2
px4-nuttx-92b3c77f738b63b1eedc4977f1c68a1fdcc74268.zip
Complete re-implementation of mq_open()
Diffstat (limited to 'nuttx/sched')
-rw-r--r--nuttx/sched/mqueue/mq_descreate.c23
-rw-r--r--nuttx/sched/mqueue/mq_msgqalloc.c131
-rw-r--r--nuttx/sched/mqueue/mqueue.h2
3 files changed, 148 insertions, 8 deletions
diff --git a/nuttx/sched/mqueue/mq_descreate.c b/nuttx/sched/mqueue/mq_descreate.c
index 237085d71..1320fb165 100644
--- a/nuttx/sched/mqueue/mq_descreate.c
+++ b/nuttx/sched/mqueue/mq_descreate.c
@@ -50,6 +50,7 @@
#include <nuttx/arch.h>
#include <nuttx/kmalloc.h>
+#include <nuttx/mqueue.h>
#include "signal/signal.h"
@@ -124,8 +125,8 @@ static mqd_t mq_desalloc(void)
* Create a message queue descriptor for the specified TCB
*
* Inputs:
- * TCB - task that needs the descriptor.
- * msgq - Named message queue containing the message
+ * mtcb - task that needs the descriptor.
+ * msgq - Named message queue containing the message
* oflags - access rights for the descriptor
*
* Return Value:
@@ -134,12 +135,22 @@ static mqd_t mq_desalloc(void)
*
****************************************************************************/
-mqd_t mq_descreate(FAR struct tcb_s* mtcb, FAR struct mqueue_inode_s* msgq,
+mqd_t mq_descreate(FAR struct tcb_s *mtcb, FAR struct mqueue_inode_s *msgq,
int oflags)
{
- FAR struct task_group_s *group = mtcb->group;
+ FAR struct task_group_s *group;
mqd_t mqdes;
+ /* A NULL TCB pointer means to use the TCB of the currently executing
+ * task/thread.
+ */
+
+ if (!mtcb)
+ {
+ mtcb = sched_self();
+ }
+
+ group = mtcb->group;
DEBUGASSERT(group);
/* Create a message queue descriptor for the TCB */
@@ -147,13 +158,13 @@ mqd_t mq_descreate(FAR struct tcb_s* mtcb, FAR struct mqueue_inode_s* msgq,
mqdes = mq_desalloc();
if (mqdes)
{
- /* Initialize the MQ descriptor */
+ /* Initialize the message queue descriptor */
memset(mqdes, 0, sizeof(struct mq_des));
mqdes->msgq = msgq;
mqdes->oflags = oflags;
- /* And add it to the specified tasks's TCB */
+ /* And add it to the specified task's TCB */
sq_addlast((FAR sq_entry_t*)mqdes, &group->tg_msgdesq);
}
diff --git a/nuttx/sched/mqueue/mq_msgqalloc.c b/nuttx/sched/mqueue/mq_msgqalloc.c
new file mode 100644
index 000000000..f0ddd15dc
--- /dev/null
+++ b/nuttx/sched/mqueue/mq_msgqalloc.c
@@ -0,0 +1,131 @@
+/****************************************************************************
+ * sched/mqueue/mq_msgqalloc.c
+ *
+ * Copyright (C) 2014 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <mqueue.h>
+
+#include <nuttx/kmalloc.h>
+#include <nuttx/sched.h>
+#include <nuttx/mqueue.h>
+
+#include "sched/sched.h"
+#include "mqueue/mqueue.h"
+
+/****************************************************************************
+ * Pre-procesor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: mq_msgqalloc
+ *
+ * Description:
+ * This function implements a part of the POSIX message queue open logic.
+ * It allocates and initializes a structu mqueue_inode_s structure.
+ *
+ * Parameters:
+ * mode - mode_t value is ignored
+ * attr - The mq_maxmsg attribute is used at the time that the message
+ * queue is created to determine the maximum number of
+ * messages that may be placed in the message queue.
+ *
+ * Return Value:
+ * The allocated and initalized message queue structure or NULL in the
+ * event of a failure.
+ *
+ ****************************************************************************/
+
+FAR struct mqueue_inode_s *mq_msgqalloc(mode_t mode,
+ FAR struct mq_attr *attr)
+{
+ FAR struct mqueue_inode_s *msgq;
+
+ /* Allocate memory for the new message queue. */
+
+ msgq = (FAR struct mqueue_inode_s*)kmm_zalloc(sizeof(struct mqueue_inode_s));
+ if (msgq)
+ {
+ /* Initialize the new named message queue */
+
+ sq_init(&msgq->msglist);
+ if (attr)
+ {
+ msgq->maxmsgs = (int16_t)attr->mq_maxmsg;
+ if (attr->mq_msgsize <= MQ_MAX_BYTES)
+ {
+ msgq->maxmsgsize = (int16_t)attr->mq_msgsize;
+ }
+ else
+ {
+ msgq->maxmsgsize = MQ_MAX_BYTES;
+ }
+ }
+ else
+ {
+ msgq->maxmsgs = MQ_MAX_MSGS;
+ msgq->maxmsgsize = MQ_MAX_BYTES;
+ }
+
+#ifndef CONFIG_DISABLE_SIGNALS
+ msgq->ntpid = INVALID_PROCESS_ID;
+#endif
+ }
+
+ return msgq;
+}
diff --git a/nuttx/sched/mqueue/mqueue.h b/nuttx/sched/mqueue/mqueue.h
index 4b382b8b0..f44d7654d 100644
--- a/nuttx/sched/mqueue/mqueue.h
+++ b/nuttx/sched/mqueue/mqueue.h
@@ -141,8 +141,6 @@ EXTERN sq_queue_t g_desfree;
void weak_function mq_initialize(void);
void mq_desblockalloc(void);
-mqd_t mq_descreate(FAR struct tcb_s* mtcb, FAR struct mqueue_inode_s* msgq,
- int oflags);
FAR struct mqueue_inode_s *mq_findnamed(FAR const char *mq_name);
void mq_msgfree(FAR struct mqueue_msg_s *mqmsg);