summaryrefslogtreecommitdiff
path: root/nuttx/sched
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-02-04 16:55:38 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-02-04 16:55:38 +0000
commit09afe06037de8f89b2cfa4f1765be407bf1783a2 (patch)
tree06197cd080eb563e39763b8d88f285c9a2e9f632 /nuttx/sched
parentc94d7c870c456005b3e87d71acba8f7f9ea2b5ec (diff)
downloadpx4-nuttx-09afe06037de8f89b2cfa4f1765be407bf1783a2.tar.gz
px4-nuttx-09afe06037de8f89b2cfa4f1765be407bf1783a2.tar.bz2
px4-nuttx-09afe06037de8f89b2cfa4f1765be407bf1783a2.zip
Move list of open message queues to task group. Now message queues opened by members of the group will be closed when the last member of the group exits.
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5609 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/sched')
-rw-r--r--nuttx/sched/Makefile6
-rw-r--r--nuttx/sched/group_leave.c7
-rw-r--r--nuttx/sched/mq_close.c14
-rw-r--r--nuttx/sched/mq_descreate.c7
-rw-r--r--nuttx/sched/mq_internal.h62
-rw-r--r--nuttx/sched/mq_release.c92
6 files changed, 150 insertions, 38 deletions
diff --git a/nuttx/sched/Makefile b/nuttx/sched/Makefile
index 6a9c62d29..488943688 100644
--- a/nuttx/sched/Makefile
+++ b/nuttx/sched/Makefile
@@ -122,11 +122,13 @@ SIGNAL_SRCS += sig_kill.c sig_queue.c sig_waitinfo.c sig_timedwait.c
SIGNAL_SRCS += sig_findaction.c sig_allocatependingsigaction.c
SIGNAL_SRCS += sig_releasependingsigaction.c sig_unmaskpendingsignal.c
SIGNAL_SRCS += sig_removependingsignal.c sig_releasependingsignal.c sig_lowest.c
-SIGNAL_SRCS += sig_mqnotempty.c sig_cleanup.c sig_received.c sig_deliver.c pause.c
+SIGNAL_SRCS += sig_mqnotempty.c sig_cleanup.c sig_received.c sig_deliver.c
+SIGNAL_SRCS += pause.c
MQUEUE_SRCS = mq_open.c mq_close.c mq_unlink.c mq_send.c mq_timedsend.c
MQUEUE_SRCS += mq_sndinternal.c mq_receive.c mq_timedreceive.c mq_rcvinternal.c
-MQUEUE_SRCS += mq_initialize.c mq_descreate.c mq_findnamed.c mq_msgfree.c mq_msgqfree.c
+MQUEUE_SRCS += mq_initialize.c mq_descreate.c mq_findnamed.c mq_msgfree.c
+MQUEUE_SRCS += mq_msgqfree.c mq_release.c
ifneq ($(CONFIG_DISABLE_SIGNALS),y)
MQUEUE_SRCS += mq_waitirq.c
diff --git a/nuttx/sched/group_leave.c b/nuttx/sched/group_leave.c
index e56952a7b..30faafa4f 100644
--- a/nuttx/sched/group_leave.c
+++ b/nuttx/sched/group_leave.c
@@ -50,6 +50,7 @@
#include "env_internal.h"
#include "pthread_internal.h"
+#include "mq_internal.h"
#include "group_internal.h"
#ifdef HAVE_TASK_GROUP
@@ -190,6 +191,12 @@ static inline void group_release(FAR struct task_group_s *group)
env_release(group);
#endif
+ /* Close message queues opened by members of the group */
+
+#ifndef CONFIG_DISABLE_MQUEUE
+ mq_release(group);
+#endif
+
#ifdef HAVE_GROUP_MEMBERS
/* Remove the group from the list of groups */
diff --git a/nuttx/sched/mq_close.c b/nuttx/sched/mq_close.c
index 57780a8e6..464056ce0 100644
--- a/nuttx/sched/mq_close.c
+++ b/nuttx/sched/mq_close.c
@@ -1,7 +1,7 @@
/****************************************************************************
* sched/mq_close.c
*
- * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -41,6 +41,7 @@
#include <mqueue.h>
#include <sched.h>
+#include <assert.h>
#include "os_internal.h"
#include "mq_internal.h"
@@ -112,10 +113,13 @@
int mq_close(mqd_t mqdes)
{
- FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
+ FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
+ FAR struct task_group_s *group = rtcb->group;
FAR msgq_t *msgq;
- irqstate_t saved_state;
- int ret = ERROR;
+ irqstate_t saved_state;
+ int ret = ERROR;
+
+ DEBUGASSERT(group);
/* Verify the inputs */
@@ -127,7 +131,7 @@ int mq_close(mqd_t mqdes)
* list of message descriptors.
*/
- sq_rem((FAR sq_entry_t*)mqdes, &rtcb->msgdesq);
+ sq_rem((FAR sq_entry_t*)mqdes, &group->tg_msgdesq);
/* Find the message queue associated with the message descriptor */
diff --git a/nuttx/sched/mq_descreate.c b/nuttx/sched/mq_descreate.c
index 14937888c..3fe696fc5 100644
--- a/nuttx/sched/mq_descreate.c
+++ b/nuttx/sched/mq_descreate.c
@@ -1,7 +1,7 @@
/****************************************************************************
* sched/mq_descreate.c
*
- * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -137,8 +137,11 @@ static mqd_t mq_desalloc(void)
mqd_t mq_descreate(FAR _TCB* mtcb, FAR msgq_t* msgq, int oflags)
{
+ FAR struct task_group_s *group = mtcb->group;
mqd_t mqdes;
+ DEBUGASSERT(group);
+
/* Create a message queue descriptor for the TCB */
mqdes = mq_desalloc();
@@ -152,7 +155,7 @@ mqd_t mq_descreate(FAR _TCB* mtcb, FAR msgq_t* msgq, int oflags)
/* And add it to the specified tasks's TCB */
- sq_addlast((FAR sq_entry_t*)mqdes, &mtcb->msgdesq);
+ sq_addlast((FAR sq_entry_t*)mqdes, &group->tg_msgdesq);
}
return mqdes;
diff --git a/nuttx/sched/mq_internal.h b/nuttx/sched/mq_internal.h
index 6135bfaef..90072cb60 100644
--- a/nuttx/sched/mq_internal.h
+++ b/nuttx/sched/mq_internal.h
@@ -1,7 +1,7 @@
/****************************************************************************
* sched/mq_internal.h
*
- * Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009, 2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -109,69 +109,73 @@ typedef struct mqmsg mqmsg_t;
* Global Variables
****************************************************************************/
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C"
+{
+#else
+#define EXTERN extern
+#endif
+
/* This is a list of all opened message queues */
-extern sq_queue_t g_msgqueues;
+EXTERN sq_queue_t g_msgqueues;
/* The g_msgfree is a list of messages that are available for general use.
* The number of messages in this list is a system configuration item.
*/
-extern sq_queue_t g_msgfree;
+EXTERN sq_queue_t g_msgfree;
/* The g_msgfreeInt is a list of messages that are reserved for use by
* interrupt handlers.
*/
-extern sq_queue_t g_msgfreeirq;
+EXTERN sq_queue_t g_msgfreeirq;
/* The g_desfree data structure is a list of message descriptors available
* to the operating system for general use. The number of messages in the
* pool is a constant.
*/
-extern sq_queue_t g_desfree;
+EXTERN sq_queue_t g_desfree;
/****************************************************************************
* Global Function Prototypes
****************************************************************************/
-#ifdef __cplusplus
-#define EXTERN extern "C"
-extern "C" {
-#else
-#define EXTERN extern
-#endif
-
/* Functions defined in mq_initialize.c ************************************/
-EXTERN void weak_function mq_initialize(void);
-EXTERN void mq_desblockalloc(void);
+void weak_function mq_initialize(void);
+void mq_desblockalloc(void);
-EXTERN mqd_t mq_descreate(FAR _TCB* mtcb, FAR msgq_t* msgq, int oflags);
-EXTERN FAR msgq_t *mq_findnamed(const char *mq_name);
-EXTERN void mq_msgfree(FAR mqmsg_t *mqmsg);
-EXTERN void mq_msgqfree(FAR msgq_t *msgq);
+mqd_t mq_descreate(FAR _TCB* mtcb, FAR msgq_t* msgq, int oflags);
+FAR msgq_t *mq_findnamed(const char *mq_name);
+void mq_msgfree(FAR mqmsg_t *mqmsg);
+void mq_msgqfree(FAR msgq_t *msgq);
/* mq_waitirq.c ************************************************************/
-EXTERN void mq_waitirq(FAR _TCB *wtcb, int errcode);
+void mq_waitirq(FAR _TCB *wtcb, int errcode);
/* mq_rcvinternal.c ********************************************************/
-EXTERN int mq_verifyreceive(mqd_t mqdes, void *msg, size_t msglen);
-EXTERN FAR mqmsg_t *mq_waitreceive(mqd_t mqdes);
-EXTERN ssize_t mq_doreceive(mqd_t mqdes, mqmsg_t *mqmsg, void *ubuffer,
- int *prio);
+int mq_verifyreceive(mqd_t mqdes, void *msg, size_t msglen);
+FAR mqmsg_t *mq_waitreceive(mqd_t mqdes);
+ssize_t mq_doreceive(mqd_t mqdes, mqmsg_t *mqmsg, void *ubuffer, int *prio);
/* mq_sndinternal.c ********************************************************/
-EXTERN int mq_verifysend(mqd_t mqdes, const void *msg, size_t msglen,
- int prio);
-EXTERN FAR mqmsg_t *mq_msgalloc(void);
-EXTERN int mq_waitsend(mqd_t mqdes);
-EXTERN int mq_dosend(mqd_t mqdes, FAR mqmsg_t *mqmsg, const void *msg,
- size_t msglen, int prio);
+int mq_verifysend(mqd_t mqdes, const void *msg, size_t msglen, int prio);
+FAR mqmsg_t *mq_msgalloc(void);
+int mq_waitsend(mqd_t mqdes);
+int mq_dosend(mqd_t mqdes, FAR mqmsg_t *mqmsg, const void *msg,
+ size_t msglen, int prio);
+
+/* mq_release.c ************************************************************/
+
+struct task_group_s; /* Forward reference */
+void mq_release(FAR struct task_group_s *group);
#undef EXTERN
#ifdef __cplusplus
diff --git a/nuttx/sched/mq_release.c b/nuttx/sched/mq_release.c
new file mode 100644
index 000000000..c1d59b0ce
--- /dev/null
+++ b/nuttx/sched/mq_release.c
@@ -0,0 +1,92 @@
+/************************************************************************
+ * sched/mq_release.c
+ *
+ * Copyright (C) 2013 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 <string.h>
+
+#include "mq_internal.h"
+
+/************************************************************************
+ * Definitions
+ ************************************************************************/
+
+/************************************************************************
+ * Private Type Declarations
+ ************************************************************************/
+
+/************************************************************************
+ * Global Variables
+ ************************************************************************/
+
+/************************************************************************
+ * Private Variables
+ ************************************************************************/
+
+/************************************************************************
+ * Private Functions
+ ************************************************************************/
+
+/************************************************************************
+ * Public Functions
+ ************************************************************************/
+
+/************************************************************************
+ * Name: mq_release
+ *
+ * Description:
+ * This function is called when the final member of a task group exits.
+ * This function closes all of the message queues opened by members of
+ * the task group.
+ *
+ * Inputs:
+ * group - The task group that is terminating.
+ *
+ * Return Value:
+ * None
+ *
+ ************************************************************************/
+
+void mq_release(FAR struct task_group_s *group)
+{
+ while (group->tg_msgdesq.head)
+ {
+ mq_close((mqd_t)group->tg_msgdesq.head);
+ }
+}