summaryrefslogtreecommitdiff
path: root/nuttx/sched
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-04-02 01:23:08 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-04-02 01:23:08 +0000
commit158978359318cb94de9e08900af4300bdfa5f651 (patch)
treeb09d5d3e8b437bc0a4f62ff16c32c62e73e6828d /nuttx/sched
parente3f8a9fcb39d16acdf85d8a9a8a79a1a5b75d818 (diff)
downloadpx4-nuttx-158978359318cb94de9e08900af4300bdfa5f651.tar.gz
px4-nuttx-158978359318cb94de9e08900af4300bdfa5f651.tar.bz2
px4-nuttx-158978359318cb94de9e08900af4300bdfa5f651.zip
Move more functions out of sched/ to lib/; proxies almost build
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3453 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/sched')
-rw-r--r--nuttx/sched/Makefile9
-rw-r--r--nuttx/sched/mq_getattr.c114
-rw-r--r--nuttx/sched/mq_internal.h39
-rw-r--r--nuttx/sched/mq_setattr.c117
-rw-r--r--nuttx/sched/sched_getprioritymax.c102
-rw-r--r--nuttx/sched/sched_getprioritymin.c102
6 files changed, 5 insertions, 478 deletions
diff --git a/nuttx/sched/Makefile b/nuttx/sched/Makefile
index 88911c3ac..8b8b33a58 100644
--- a/nuttx/sched/Makefile
+++ b/nuttx/sched/Makefile
@@ -53,7 +53,6 @@ TSK_SRCS = task_create.c task_init.c task_setup.c task_activate.c \
SCHED_SRCS = sched_setparam.c sched_setpriority.c sched_getparam.c \
sched_setscheduler.c sched_getscheduler.c \
sched_yield.c sched_rrgetinterval.c sched_foreach.c \
- sched_getprioritymax.c sched_getprioritymin.c \
sched_lock.c sched_unlock.c sched_lockcount.c
ifeq ($(CONFIG_PRIORITY_INHERITANCE),y)
SCHED_SRCS += sched_reprioritize.c
@@ -88,11 +87,9 @@ SIGNAL_SRCS = sig_initialize.c \
sig_releasependingsignal.c sig_lowest.c sig_mqnotempty.c \
sig_cleanup.c sig_received.c sig_deliver.c
-MQUEUE_SRCS = mq_open.c mq_close.c mq_unlink.c \
- mq_send.c mq_timedsend.c mq_sndinternal.c \
- mq_receive.c mq_timedreceive.c mq_rcvinternal.c \
- mq_setattr.c mq_getattr.c mq_initialize.c mq_descreate.c \
- mq_findnamed.c mq_msgfree.c mq_msgqfree.c
+MQUEUE_SRCS = mq_open.c mq_close.c mq_unlink.c mq_send.c mq_timedsend.c\
+ mq_sndinternal.c mq_receive.c mq_timedreceive.c mq_rcvinternal.c \
+ mq_initialize.c mq_descreate.c mq_findnamed.c mq_msgfree.c mq_msgqfree.c
ifneq ($(CONFIG_DISABLE_SIGNALS),y)
MQUEUE_SRCS += mq_waitirq.c
endif
diff --git a/nuttx/sched/mq_getattr.c b/nuttx/sched/mq_getattr.c
deleted file mode 100644
index 4094143e1..000000000
--- a/nuttx/sched/mq_getattr.c
+++ /dev/null
@@ -1,114 +0,0 @@
-/************************************************************************
- * sched/mq_getattr.c
- *
- * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
- *
- * 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 <stdarg.h> /* va_list */
-#include <unistd.h>
-#include <string.h>
-#include <assert.h>
-#include <mqueue.h>
-#include <sched.h>
-#include <debug.h>
-#include <nuttx/kmalloc.h>
-#include <nuttx/arch.h>
-#include "os_internal.h"
-#include "sig_internal.h"
-#include "mq_internal.h"
-
-/************************************************************************
- * Definitions
- ************************************************************************/
-
-/************************************************************************
- * Private Type Declarations
- ************************************************************************/
-
-/************************************************************************
- * Global Variables
- ************************************************************************/
-
-/************************************************************************
- * Private Variables
- ************************************************************************/
-
-/************************************************************************
- * Private Functions
- ************************************************************************/
-
-/************************************************************************
- * Public Functions
- ************************************************************************/
-
-/************************************************************************
- * Function: mq_getattr
- *
- * Description:
- * This functions gets status information and attributes
- * associated with the specified message queue.
- *
- * Parameters:
- * mqdes - Message queue descriptor
- * mq_stat - Buffer in which to return attributes
- *
- * Return Value:
- * 0 (OK) if attributes provided, -1 (ERROR) otherwise.
- *
- * Assumptions:
- *
- ************************************************************************/
-
-int mq_getattr(mqd_t mqdes, struct mq_attr *mq_stat)
-{
- int ret = ERROR;
-
- if (mqdes && mq_stat)
- {
- /* Return the attributes */
-
- mq_stat->mq_maxmsg = mqdes->msgq->maxmsgs;
- mq_stat->mq_msgsize = mqdes->msgq->maxmsgsize;
- mq_stat->mq_flags = mqdes->oflags;
- mq_stat->mq_curmsgs = mqdes->msgq->nmsgs;
-
- ret = OK;
- }
-
- return ret;
-}
diff --git a/nuttx/sched/mq_internal.h b/nuttx/sched/mq_internal.h
index e362ec2fb..28dd011d9 100644
--- a/nuttx/sched/mq_internal.h
+++ b/nuttx/sched/mq_internal.h
@@ -51,6 +51,8 @@
#include <sched.h>
#include <signal.h>
+#include <nuttx/mqueue.h>
+
#if CONFIG_MQ_MAXMSGSIZE > 0
/****************************************************************************
@@ -101,43 +103,6 @@ struct mqmsg
};
typedef struct mqmsg mqmsg_t;
-/* This structure defines a message queue */
-
-struct mq_des; /* forward reference */
-
-struct msgq_s
-{
- FAR struct msgq_s *flink; /* Forward link to next message queue */
- sq_queue_t msglist; /* Prioritized message list */
- int16_t maxmsgs; /* Maximum number of messages in the queue */
- int16_t nmsgs; /* Number of message in the queue */
- int16_t nconnect; /* Number of connections to message queue */
- int16_t nwaitnotfull; /* Number tasks waiting for not full */
- int16_t nwaitnotempty; /* Number tasks waiting for not empty */
- uint8_t maxmsgsize; /* Max size of message in message queue */
- bool unlinked; /* true if the msg queue has been unlinked */
-#ifndef CONFIG_DISABLE_SIGNALS
- FAR struct mq_des *ntmqdes; /* Notification: Owning mqdes (NULL if none) */
- pid_t ntpid; /* Notification: Receiving Task's PID */
- int ntsigno; /* Notification: Signal number */
- union sigval ntvalue; /* Notification: Signal value */
-#endif
- char name[1]; /* Start of the queue name */
-};
-
-#define SIZEOF_MQ_HEADER ((int)(((msgq_t*)NULL)->name))
-
-/* This describes the message queue descriptor that is held in the
- * task's TCB
- */
-
-struct mq_des
-{
- FAR struct mq_des *flink; /* Forward link to next message descriptor */
- FAR msgq_t *msgq; /* Pointer to associated message queue */
- int oflags; /* Flags set when message queue was opened */
-};
-
/****************************************************************************
* Global Variables
****************************************************************************/
diff --git a/nuttx/sched/mq_setattr.c b/nuttx/sched/mq_setattr.c
deleted file mode 100644
index 4a74e3549..000000000
--- a/nuttx/sched/mq_setattr.c
+++ /dev/null
@@ -1,117 +0,0 @@
-/************************************************************************
- * sched/mq_setattr.c
- *
- * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
- *
- * 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 <fcntl.h> /* O_NONBLOCK */
-#include <mqueue.h>
-#include "mq_internal.h"
-
-/************************************************************************
- * Definitions
- ************************************************************************/
-
-/************************************************************************
- * Private Type Declarations
- ************************************************************************/
-
-/************************************************************************
- * Global Variables
- ************************************************************************/
-
-/************************************************************************
- * Private Variables
- ************************************************************************/
-
-/************************************************************************
- * Private Functions
- ************************************************************************/
-
-/************************************************************************
- * Public Functions
- ************************************************************************/
-
-/************************************************************************
- * Function: mq_setattr
- *
- * Description:
- * This function sets the attributes associated with the
- * specified message queue "mqdes." Only the "O_NONBLOCK"
- * bit of the "mq_flags" can be changed.
- *
- * If "oldstat" is non-null, mq_setattr() will store the
- * previous message queue attributes at that location (just
- * as would have been returned by mq_getattr()).
- *
- * Parameters:
- * mqdes - Message queue descriptor
- * mq_stat - New attributes
- * oldstate - Old attributes
- *
- * Return Value:
- * 0 (OK) if attributes are set successfully, otherwise
- * -1 (ERROR).
- *
- * Assumptions:
- *
- ************************************************************************/
-
-int mq_setattr(mqd_t mqdes, const struct mq_attr *mq_stat,
- struct mq_attr *oldstat)
-{
- int ret = ERROR;
-
- if (mqdes && mq_stat)
- {
- /* Return the attributes if so requested */
-
- if (oldstat)
- {
- (void)mq_getattr(mqdes, oldstat);
- }
-
- /* Set the new value of the O_NONBLOCK flag. */
-
- mqdes->oflags = ((mq_stat->mq_flags & O_NONBLOCK) |
- (mqdes->oflags & (~O_NONBLOCK)));
- ret = OK;
- }
-
- return ret;
-}
diff --git a/nuttx/sched/sched_getprioritymax.c b/nuttx/sched/sched_getprioritymax.c
deleted file mode 100644
index 1476d0918..000000000
--- a/nuttx/sched/sched_getprioritymax.c
+++ /dev/null
@@ -1,102 +0,0 @@
-/************************************************************************
- * sched/sched_getprioritymax.c
- *
- * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
- *
- * 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 <nuttx/arch.h>
-
-#include "os_internal.h"
-
-/************************************************************************
- * Definitions
- ************************************************************************/
-
-/************************************************************************
- * Private Type Declarations
- ************************************************************************/
-
-/************************************************************************
- * Global Variables
- ************************************************************************/
-
-/************************************************************************
- * Private Variables
- ************************************************************************/
-
-/************************************************************************
- * Private Function Prototypes
- ************************************************************************/
-
-/************************************************************************
- * Private Functions
- ************************************************************************/
-
-/************************************************************************
- * Public Functions
- ************************************************************************/
-
-/************************************************************************
- * Name: ched_get_priority_max
- *
- * Description:
- * This function returns the value of the highest possible
- * task priority for a specified scheduling policy.
- *
- * Inputs:
- * policy - Scheduling policy requested.
- *
- * Return Value:
- * The maximum priority value or -1 (ERROR)
- * (errno is not set)
- *
- * Assumptions:
- *
- ************************************************************************/
-
-int sched_get_priority_max(int policy)
-{
- if (policy != SCHED_FIFO && policy != SCHED_RR)
- {
- return ERROR;
- }
- else
- {
- return SCHED_PRIORITY_MAX;
- }
-}
diff --git a/nuttx/sched/sched_getprioritymin.c b/nuttx/sched/sched_getprioritymin.c
deleted file mode 100644
index 731290135..000000000
--- a/nuttx/sched/sched_getprioritymin.c
+++ /dev/null
@@ -1,102 +0,0 @@
-/************************************************************************
- * sched/sched_getprioritymin.c
- *
- * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
- *
- * 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 <nuttx/arch.h>
-
-#include "os_internal.h"
-
-/************************************************************************
- * Definitions
- ************************************************************************/
-
-/************************************************************************
- * Private Type Declarations
- ************************************************************************/
-
-/************************************************************************
- * Global Variables
- ************************************************************************/
-
-/************************************************************************
- * Private Variables
- ************************************************************************/
-
-/************************************************************************
- * Private Function Prototypes
- ************************************************************************/
-
-/************************************************************************
- * Private Functions
- ************************************************************************/
-
-/************************************************************************
- * Public Functions
- ************************************************************************/
-
-/************************************************************************
- * Name: sched_get_priority_min
- *
- * Description:
- * This function returns the value of the lowest possible
- * task priority for a specified scheduling policy.
- *
- * Inputs:
- * policy - Scheduling policy requested.
- *
- * Return Value:
- * The minimum priority value or -1 (ERROR)
- * (errno is not set)
- *
- * Assumptions:
- *
- ************************************************************************/
-
-int sched_get_priority_min(int policy)
-{
- if (policy != SCHED_FIFO && policy != SCHED_RR)
- {
- return ERROR;
- }
- else
- {
- return SCHED_PRIORITY_MIN;
- }
-}