summaryrefslogtreecommitdiff
path: root/nuttx/fs
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/fs
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/fs')
-rw-r--r--nuttx/fs/mqueue/mq_open.c186
-rw-r--r--nuttx/fs/mqueue/mqueue.h77
-rw-r--r--nuttx/fs/semaphore/sem_open.c2
3 files changed, 203 insertions, 62 deletions
diff --git a/nuttx/fs/mqueue/mq_open.c b/nuttx/fs/mqueue/mq_open.c
index e0d47aa46..299afc4fd 100644
--- a/nuttx/fs/mqueue/mq_open.c
+++ b/nuttx/fs/mqueue/mq_open.c
@@ -1,7 +1,7 @@
/****************************************************************************
* sched/mqueue/mq_open.c
*
- * Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009, 2011, 2014 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -39,24 +39,36 @@
#include <nuttx/config.h>
-#include <sys/types.h>
-#include <stdint.h>
#include <stdarg.h>
+#include <stdio.h>
+#include <sched.h>
#include <mqueue.h>
#include <fcntl.h>
-#include <string.h>
-#include <sched.h>
#include <errno.h>
+
+#include <nuttx/mqueue.h>
+#include <nuttx/fs/fs.h>
+
+#include "inode/inode.h"
+#include "mqueue/mqueue.h"
+
+#if 0
+#include <sys/types.h>
+#include <stdint.h>
#include <debug.h>
-#include <nuttx/kmalloc.h>
#include "sched/sched.h"
-#include "mqueue/mqueue.h"
+#endif
/****************************************************************************
* Pre-procesor Definitions
****************************************************************************/
+/* Configuration ************************************************************/
+
+#ifndef CONFIG_FS_MQUEUE_MPATH
+# define CONFIG_FS_MQUEUE_MPATH "/var/mqueue"
+#endif
/****************************************************************************
* Private Type Declarations
@@ -109,83 +121,135 @@
mqd_t mq_open(const char *mq_name, int oflags, ...)
{
- FAR struct tcb_s *rtcb = (FAR struct tcb_s*)g_readytorun.head;
+ FAR struct inode *inode;
+ FAR const char *relpath = NULL;
FAR struct mqueue_inode_s *msgq;
- mqd_t mqdes = NULL;
- va_list arg;
+ char fullpath[MAX_MQUEUE_PATH];
+ va_list ap;
struct mq_attr *attr;
+ mqd_t mqdes;
mode_t mode;
- int namelen;
+ int errcode;
+ int ret;
/* Make sure that a non-NULL name is supplied */
if (mq_name)
{
+ /* Make sure that the check for the existence of the message queue
+ * and the creation of the message queue are atomic with respect to
+ * other processes executing mq_open(). A simple sched_lock() should
+ * be sufficientt.
+ */
+
sched_lock();
- namelen = strlen(mq_name);
- if (namelen > 0)
+
+ /* Get the full path to the message queue */
+
+ snprintf(fullpath, MAX_MQUEUE_PATH, CONFIG_FS_MQUEUE_MPATH "/%s", mq_name);
+
+ /* Get the inode for this mqueue. This should succeed if the message
+ * queue has already been created.
+ */
+
+ inode = inode_find(fullpath, &relpath);
+ if (inode)
{
- /* See if the message queue already exists */
+ /* It exists. Verify that the inode is a message queue */
+
+ if (!INODE_IS_MQUEUE(inode))
+ {
+ errcode = ENXIO;
+ goto errout_with_inode;
+ }
+
+ /* It exists and is a message queue. Check if the caller wanted to
+ * create a new mqueue with this name.
+ */
- msgq = mq_findnamed(mq_name);
- if (msgq)
+ if ((oflags & (O_CREAT|O_EXCL)) == (O_CREAT|O_EXCL))
{
- /* It does. Check if the caller wanted to create a new
- * message queue with this name (i.e., O_CREAT|O_EXCL)
- */
-
- if ((oflags & O_CREAT) == 0 || (oflags & O_EXCL) == 0)
- {
- /* Create a message queue descriptor for the TCB */
-
- mqdes = mq_descreate(rtcb, msgq, oflags);
- if (mqdes)
- {
- /* Allow a new connection to the message queue */
-
- msgq->nconnect++;
- }
- }
+ errcode = EEXIST;
+ goto errout_with_inode;
}
- /* It doesn't exist. Should we create one? */
+ /* Create a message queue descriptor for the current thread */
- else if ((oflags & O_CREAT) != 0)
+ msgq = inode->u.i_mqueue;
+ mqdes = mq_descreate(NULL, msgq, oflags);
+ if (!mqdes)
{
- /* Yes.. Get the optional arguments needed to create a message
- * queue.
- */
+ errcode = ENOMEM;
+ goto errout_with_inode;
+ }
+ }
+ else
+ {
+ /* The mqueue does not exists. Were we asked to create it? */
- va_start(arg, oflags);
- mode = va_arg(arg, mode_t);
- attr = va_arg(arg, struct mq_attr*);
+ if ((oflags & O_CREAT) == 0)
+ {
+ /* The mqueue does not exist and O_CREAT is not set */
+
+ errcode = ENOENT;
+ goto errout_with_lock;
+ }
- /* Allocate memory for the new message queue. The size to
- * allocate is the size of the struct mqueue_inode_s header
- * plus the size of the message queue name+1.
- */
+ /* Create the mqueue. First we have to extract the additional
+ * parameters from the variable argument list.
+ */
- msgq = (FAR struct mqueue_inode_s*)mq_msgqalloc(oflags, mode, attr);
- if (msgq)
- {
-#warning Missing logic
- }
+ va_start(ap, oflags);
+ mode = va_arg(ap, mode_t);
+ attr = va_arg(ap, FAR struct mq_attr*);
+ va_end(ap);
- /* Clean-up variable argument stuff */
+ /* Create an inode in the pseudo-filesystem at this path */
- va_end(arg);
+ inode_semtake();
+ ret = inode_reserve(fullpath, &inode);
+ inode_semgive();
+
+ if (ret < 0)
+ {
+ errcode = -ret;
+ goto errout_with_lock;
}
- }
- sched_unlock();
- }
+ /* Allocate memory for the new message queue. */
- if (mqdes == NULL)
- {
- return (mqd_t)ERROR;
- }
- else
- {
- return mqdes;
+ msgq = (FAR struct mqueue_inode_s*)mq_msgqalloc(mode, attr);
+ if (!msgq)
+ {
+ errcode = ENOMEM;
+ goto errout_with_inode;
+ }
+
+ /* Create a message queue descriptor for the TCB */
+
+ mqdes = mq_descreate(NULL, msgq, oflags);
+ if (!mqdes)
+ {
+ errcode = ENOMEM;
+ goto errout_with_msgq;
+ }
+
+ /* Save the message queue in the inode structure */
+
+ inode->u.i_mqueue = msgq;
+ }
}
+
+ sched_unlock();
+ return mqdes;
+
+errout_with_msgq:
+ mq_msgqfree(msgq);
+ inode->u.i_mqueue = NULL;
+errout_with_inode:
+ inode_release(inode);
+errout_with_lock:
+ sched_unlock();
+ set_errno(errcode);
+ return (mqd_t)ERROR;
}
diff --git a/nuttx/fs/mqueue/mqueue.h b/nuttx/fs/mqueue/mqueue.h
new file mode 100644
index 000000000..e18302188
--- /dev/null
+++ b/nuttx/fs/mqueue/mqueue.h
@@ -0,0 +1,77 @@
+/****************************************************************************
+ * fs/mqueue/mqueue.h
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+#ifndef __FS_MQUEUE_MQUEUE_H
+#define __FS_MQUEUE_MQUEUE_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#define MAX_MQUEUE_PATH 64
+
+/****************************************************************************
+ * Public Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C"
+{
+#else
+#define EXTERN extern
+#endif
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __FS_MQUEUE_MQUEUE_H */
+
diff --git a/nuttx/fs/semaphore/sem_open.c b/nuttx/fs/semaphore/sem_open.c
index e4a7da417..579a94455 100644
--- a/nuttx/fs/semaphore/sem_open.c
+++ b/nuttx/fs/semaphore/sem_open.c
@@ -234,7 +234,7 @@ FAR sem_t *sem_open (FAR const char *name, int oflags, ...)
if (!nsem)
{
errcode = ENOMEM;
- goto errout_with_lock;
+ goto errout_with_inode;
}
/* Link to the inode */