forked from Archive/PX4-Autopilot
Merge Nuttx r5554
This commit is contained in:
commit
35febbe844
|
@ -485,3 +485,10 @@
|
|||
argument is now optional. Many files systems do not need
|
||||
a source and it is really stupid to have to enter a bogus
|
||||
source parameter.
|
||||
* apps/nshlib/nsh_fileapp.c: Add the ability to execute a file
|
||||
from a file system using posix_spawn().
|
||||
* apps/builtin/: Extensions from Mike Smith.
|
||||
* apps/examples/ftpd/Makefile: Name ftpd_start is not the name of
|
||||
the entrypoint. Should be ftpd_main (from Yan T.)
|
||||
* apps/netutils/telnetd/telnetd_driver: Was stuck in a loop if
|
||||
recv[from]() ever returned a value <= 0.
|
||||
|
|
|
@ -39,7 +39,7 @@ include $(APPDIR)/Make.defs
|
|||
# Source and object files
|
||||
|
||||
ASRCS =
|
||||
CSRCS = builtin.c exec_builtin.c
|
||||
CSRCS = builtin.c builtin_list.c exec_builtin.c
|
||||
|
||||
AOBJS = $(ASRCS:.S=$(OBJEXT))
|
||||
COBJS = $(CSRCS:.c=$(OBJEXT))
|
||||
|
|
|
@ -55,27 +55,8 @@
|
|||
* Public Data
|
||||
****************************************************************************/
|
||||
|
||||
#undef EXTERN
|
||||
#if defined(__cplusplus)
|
||||
#define EXTERN extern "C"
|
||||
extern "C" {
|
||||
#else
|
||||
#define EXTERN extern
|
||||
#endif
|
||||
|
||||
#include "builtin_proto.h"
|
||||
|
||||
const struct builtin_s g_builtins[] =
|
||||
{
|
||||
# include "builtin_list.h"
|
||||
{ NULL, 0, 0, 0 }
|
||||
};
|
||||
|
||||
#undef EXTERN
|
||||
#if defined(__cplusplus)
|
||||
}
|
||||
#endif
|
||||
|
||||
extern const struct builtin_s g_builtins[];
|
||||
extern const int g_builtin_count;
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
|
@ -89,9 +70,11 @@ const struct builtin_s g_builtins[] =
|
|||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
int number_builtins(void)
|
||||
FAR const struct builtin_s *builtin_for_index(int index)
|
||||
{
|
||||
return sizeof(g_builtins)/sizeof(struct builtin_s) - 1;
|
||||
if (index < g_builtin_count)
|
||||
{
|
||||
return &g_builtins[index];
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
|
||||
|
||||
|
|
|
@ -0,0 +1,79 @@
|
|||
/****************************************************************************
|
||||
* apps/builtin/builtin_list.c
|
||||
*
|
||||
* Copyright (C) 2011 Uros Platise. All rights reserved.
|
||||
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
||||
* Authors: Uros Platise <uros.platise@isotel.eu>
|
||||
* 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 <nuttx/binfmt/builtin.h>
|
||||
|
||||
/****************************************************************************
|
||||
* Private Types
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Function Prototypes
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Data
|
||||
****************************************************************************/
|
||||
|
||||
#include "builtin_proto.h"
|
||||
|
||||
const struct builtin_s g_builtins[] =
|
||||
{
|
||||
# include "builtin_list.h"
|
||||
{ NULL, 0, 0, 0 }
|
||||
};
|
||||
|
||||
const int g_builtin_count = sizeof(g_builtins) / sizeof(g_builtins[0]);
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
|
@ -46,6 +46,7 @@
|
|||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <sys/wait.h>
|
||||
#include <sched.h>
|
||||
#include <string.h>
|
||||
#include <fcntl.h>
|
||||
|
@ -92,7 +93,9 @@ struct builtin_parms_s
|
|||
****************************************************************************/
|
||||
|
||||
static sem_t g_builtin_parmsem = SEM_INITIALIZER(1);
|
||||
#ifndef CONFIG_SCHED_WAITPID
|
||||
static sem_t g_builtin_execsem = SEM_INITIALIZER(0);
|
||||
#endif
|
||||
static struct builtin_parms_s g_builtin_parms;
|
||||
|
||||
/****************************************************************************
|
||||
|
@ -121,7 +124,7 @@ static void bultin_semtake(FAR sem_t *sem)
|
|||
do
|
||||
{
|
||||
ret = sem_wait(sem);
|
||||
ASSERT(ret == 0 || errno == EINTR);
|
||||
ASSERT(ret == 0 || get_errno() == EINTR);
|
||||
}
|
||||
while (ret != 0);
|
||||
}
|
||||
|
@ -142,8 +145,17 @@ static void bultin_semtake(FAR sem_t *sem)
|
|||
|
||||
static int builtin_taskcreate(int index, FAR const char **argv)
|
||||
{
|
||||
FAR const struct builtin_s *b;
|
||||
int ret;
|
||||
|
||||
b = builtin_for_index(index);
|
||||
|
||||
if (b == NULL)
|
||||
{
|
||||
set_errno(ENOENT);
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
/* Disable pre-emption. This means that although we start the builtin
|
||||
* application here, it will not actually run until pre-emption is
|
||||
* re-enabled below.
|
||||
|
@ -153,8 +165,7 @@ static int builtin_taskcreate(int index, FAR const char **argv)
|
|||
|
||||
/* Start the builtin application task */
|
||||
|
||||
ret = TASK_CREATE(g_builtins[index].name, g_builtins[index].priority,
|
||||
g_builtins[index].stacksize, g_builtins[index].main,
|
||||
ret = TASK_CREATE(b->name, b->priority, b->stacksize, b->main,
|
||||
(argv) ? &argv[1] : (FAR const char **)NULL);
|
||||
|
||||
/* If robin robin scheduling is enabled, then set the scheduling policy
|
||||
|
@ -171,7 +182,7 @@ static int builtin_taskcreate(int index, FAR const char **argv)
|
|||
* new task cannot yet have changed from its initial value.
|
||||
*/
|
||||
|
||||
param.sched_priority = g_builtins[index].priority;
|
||||
param.sched_priority = b->priority;
|
||||
(void)sched_setscheduler(ret, SCHED_RR, ¶m);
|
||||
}
|
||||
#endif
|
||||
|
@ -217,7 +228,7 @@ static int builtin_proxy(int argc, char *argv[])
|
|||
{
|
||||
/* Remember the errno value. ret is already set to ERROR */
|
||||
|
||||
g_builtin_parms.errcode = errno;
|
||||
g_builtin_parms.errcode = get_errno();
|
||||
sdbg("ERROR: open of %s failed: %d\n",
|
||||
g_builtin_parms.redirfile, g_builtin_parms.errcode);
|
||||
}
|
||||
|
@ -235,7 +246,7 @@ static int builtin_proxy(int argc, char *argv[])
|
|||
ret = dup2(fd, 1);
|
||||
if (ret < 0)
|
||||
{
|
||||
g_builtin_parms.errcode = errno;
|
||||
g_builtin_parms.errcode = get_errno();
|
||||
sdbg("ERROR: dup2 failed: %d\n", g_builtin_parms.errcode);
|
||||
}
|
||||
|
||||
|
@ -255,18 +266,26 @@ static int builtin_proxy(int argc, char *argv[])
|
|||
ret = builtin_taskcreate(g_builtin_parms.index, g_builtin_parms.argv);
|
||||
if (ret < 0)
|
||||
{
|
||||
g_builtin_parms.errcode = errno;
|
||||
g_builtin_parms.errcode = get_errno();
|
||||
sdbg("ERROR: builtin_taskcreate failed: %d\n",
|
||||
g_builtin_parms.errcode);
|
||||
}
|
||||
}
|
||||
|
||||
/* NOTE: There is a logical error here if CONFIG_SCHED_HAVE_PARENT is
|
||||
* defined: The new task is the child of this proxy task, not the
|
||||
* original caller. As a consequence, operations like waitpid() will
|
||||
* fail on the caller's thread.
|
||||
*/
|
||||
|
||||
/* Post the semaphore to inform the parent task that we have completed
|
||||
* what we need to do.
|
||||
*/
|
||||
|
||||
g_builtin_parms.result = ret;
|
||||
#ifndef CONFIG_SCHED_WAITPID
|
||||
builtin_semgive(&g_builtin_execsem);
|
||||
#endif
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
@ -291,10 +310,11 @@ static inline int builtin_startproxy(int index, FAR const char **argv,
|
|||
struct sched_param param;
|
||||
pid_t proxy;
|
||||
int errcode;
|
||||
#ifdef CONFIG_SCHED_WAITPID
|
||||
int status;
|
||||
#endif
|
||||
int ret;
|
||||
|
||||
// DEBUGASSERT(path);
|
||||
|
||||
svdbg("index=%d argv=%p redirfile=%s oflags=%04x\n",
|
||||
index, argv, redirfile, oflags);
|
||||
|
||||
|
@ -326,11 +346,21 @@ static inline int builtin_startproxy(int index, FAR const char **argv,
|
|||
ret = sched_getparam(0, ¶m);
|
||||
if (ret < 0)
|
||||
{
|
||||
errcode = errno;
|
||||
errcode = get_errno();
|
||||
sdbg("ERROR: sched_getparam failed: %d\n", errcode);
|
||||
goto errout;
|
||||
goto errout_with_sem;
|
||||
}
|
||||
|
||||
/* Disable pre-emption so that the proxy does not run until we waitpid
|
||||
* is called. This is probably unnecessary since the builtin_proxy has
|
||||
* the same priority as this thread; it should be schedule behind this
|
||||
* task in the ready-to-run list.
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_SCHED_WAITPID
|
||||
sched_lock();
|
||||
#endif
|
||||
|
||||
/* Start the intermediary/proxy task at the same priority as the parent task. */
|
||||
|
||||
proxy = TASK_CREATE("builtin_proxy", param.sched_priority,
|
||||
|
@ -338,16 +368,25 @@ static inline int builtin_startproxy(int index, FAR const char **argv,
|
|||
(FAR const char **)NULL);
|
||||
if (proxy < 0)
|
||||
{
|
||||
errcode = errno;
|
||||
errcode = get_errno();
|
||||
sdbg("ERROR: Failed to start builtin_proxy: %d\n", errcode);
|
||||
goto errout;
|
||||
goto errout_with_lock;
|
||||
}
|
||||
|
||||
/* Wait for the proxy to complete its job. We could use waitpid()
|
||||
* for this.
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_SCHED_WAITPID
|
||||
ret = waitpid(proxy, &status, 0);
|
||||
if (ret < 0)
|
||||
{
|
||||
sdbg("ERROR: waitpid() failed: %d\n", get_errno());
|
||||
goto errout_with_lock;
|
||||
}
|
||||
#else
|
||||
bultin_semtake(&g_builtin_execsem);
|
||||
#endif
|
||||
|
||||
/* Get the result and relinquish our access to the parameter structure */
|
||||
|
||||
|
@ -355,7 +394,12 @@ static inline int builtin_startproxy(int index, FAR const char **argv,
|
|||
builtin_semgive(&g_builtin_parmsem);
|
||||
return g_builtin_parms.result;
|
||||
|
||||
errout:
|
||||
errout_with_lock:
|
||||
#ifdef CONFIG_SCHED_WAITPID
|
||||
sched_unlock();
|
||||
#endif
|
||||
|
||||
errout_with_sem:
|
||||
set_errno(errcode);
|
||||
builtin_semgive(&g_builtin_parmsem);
|
||||
return ERROR;
|
||||
|
|
|
@ -46,6 +46,12 @@
|
|||
#include <errno.h>
|
||||
|
||||
#include <nuttx/arch.h>
|
||||
#if defined(CONFIG_FS_BINFS) && (CONFIG_BUILTIN)
|
||||
#include <nuttx/binfmt/builtin.h>
|
||||
#endif
|
||||
#if defined(CONFIG_LIBC_EXECFUNCS) && defined(CONFIG_EXECFUNCS_SYMTAB)
|
||||
#include <nuttx/binfmt/symtab.h>
|
||||
#endif
|
||||
|
||||
#include <apps/nsh.h>
|
||||
|
||||
|
@ -75,6 +81,21 @@
|
|||
* Public Data
|
||||
****************************************************************************/
|
||||
|
||||
/* If posix_spawn() is enabled as required for CONFIG_NSH_FILE_APPS, then
|
||||
* a symbol table is needed by the internals of posix_spawn(). The symbol
|
||||
* table is needed to support ELF and NXFLAT binaries to dynamically link to
|
||||
* the base code. However, if only the BINFS file system is supported, then
|
||||
* no Makefile is needed.
|
||||
*
|
||||
* This is a kludge to plug the missing file system in the case where BINFS
|
||||
* is used. REVISIT: This will, of course, be in the way if you want to
|
||||
* support ELF or NXFLAT binaries!
|
||||
*/
|
||||
|
||||
#if defined(CONFIG_LIBC_EXECFUNCS) && defined(CONFIG_EXECFUNCS_SYMTAB)
|
||||
const struct symtab_s CONFIG_EXECFUNCS_SYMTAB[1];
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
@ -98,6 +119,23 @@ int nsh_main(int argc, char *argv[])
|
|||
up_cxxinitialize();
|
||||
#endif
|
||||
|
||||
/* Make sure that we are using our symbol take */
|
||||
|
||||
#if defined(CONFIG_LIBC_EXECFUNCS) && defined(CONFIG_EXECFUNCS_SYMTAB)
|
||||
exec_setsymtab(CONFIG_EXECFUNCS_SYMTAB, 0);
|
||||
#endif
|
||||
|
||||
/* Register the BINFS file system */
|
||||
|
||||
#if defined(CONFIG_FS_BINFS) && (CONFIG_BUILTIN)
|
||||
ret = builtin_initialize();
|
||||
if (ret < 0)
|
||||
{
|
||||
fprintf(stderr, "ERROR: builtin_initialize failed: %d\n", ret);
|
||||
exitval = 1;
|
||||
}
|
||||
#endif
|
||||
|
||||
/* Initialize the NSH library */
|
||||
|
||||
nsh_initialize();
|
||||
|
|
|
@ -14,7 +14,7 @@ config NSH_LIBRARY
|
|||
if NSH_LIBRARY
|
||||
config NSH_BUILTIN_APPS
|
||||
bool "Enable built-in applications"
|
||||
default y
|
||||
default n
|
||||
depends on BUILTIN
|
||||
---help---
|
||||
Support external registered, "built-in" applications that can be
|
||||
|
@ -22,6 +22,15 @@ config NSH_BUILTIN_APPS
|
|||
more information). This options requires support for builtin
|
||||
applications (BUILTIN).
|
||||
|
||||
config NSH_FILE_APPS
|
||||
bool "Enable execution of program files"
|
||||
default n
|
||||
depends on LIBC_EXECFUNCS
|
||||
---help---
|
||||
Support execution of program files residing within a file
|
||||
system. This options requires support for the posix_spawn()
|
||||
interface (LIBC_EXECFUNCS).
|
||||
|
||||
menu "Disable Individual commands"
|
||||
|
||||
config NSH_DISABLE_BASE64DEC
|
||||
|
|
|
@ -47,6 +47,10 @@ ifeq ($(CONFIG_NSH_BUILTIN_APPS),y)
|
|||
CSRCS += nsh_builtin.c
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_NSH_FILE_APPS),y)
|
||||
CSRCS += nsh_fileapps.c
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_NSH_ROMFSETC),y)
|
||||
CSRCS += nsh_romfsetc.c
|
||||
endif
|
||||
|
|
|
@ -495,6 +495,11 @@ int nsh_builtin(FAR struct nsh_vtbl_s *vtbl, FAR const char *cmd,
|
|||
FAR char **argv, FAR const char *redirfile, int oflags);
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_NSH_FILE_APPS
|
||||
int nsh_fileapp(FAR struct nsh_vtbl_s *vtbl, FAR const char *cmd,
|
||||
FAR char **argv, FAR const char *redirfile, int oflags);
|
||||
#endif
|
||||
|
||||
/* Working directory support */
|
||||
|
||||
#if CONFIG_NFILE_DESCRIPTORS > 0 && !defined(CONFIG_DISABLE_ENVIRON)
|
||||
|
|
|
@ -116,8 +116,8 @@ int nsh_builtin(FAR struct nsh_vtbl_s *vtbl, FAR const char *cmd,
|
|||
{
|
||||
int ret = OK;
|
||||
|
||||
/* Lock the scheduler to prevent the application from running until the
|
||||
* waitpid() has been called.
|
||||
/* Lock the scheduler in an attempt to prevent the application from
|
||||
* running until waitpid() has been called.
|
||||
*/
|
||||
|
||||
sched_lock();
|
||||
|
@ -129,16 +129,20 @@ int nsh_builtin(FAR struct nsh_vtbl_s *vtbl, FAR const char *cmd,
|
|||
ret = exec_builtin(cmd, (FAR const char **)argv, redirfile, oflags);
|
||||
if (ret >= 0)
|
||||
{
|
||||
/* The application was successfully started (but still blocked because
|
||||
* the scheduler is locked). If the application was not backgrounded,
|
||||
* then we need to wait here for the application to exit. These really
|
||||
* only works works with the following options:
|
||||
/* The application was successfully started with pre-emption disabled.
|
||||
* In the simplest cases, the application will not have run because the
|
||||
* the scheduler is locked. But in the case where I/O was redirected, a
|
||||
* proxy task ran and broke our lock. As result, the application may
|
||||
* have aso ran if its priority was higher than than the priority of
|
||||
* this thread.
|
||||
*
|
||||
* If the application did not run to completion and if the application
|
||||
* was not backgrounded, then we need to wait here for the application
|
||||
* to exit. This only works works with the following options:
|
||||
*
|
||||
* - CONFIG_NSH_DISABLEBG - Do not run commands in background
|
||||
* - CONFIG_SCHED_WAITPID - Required to run external commands in
|
||||
* foreground
|
||||
*
|
||||
* These concepts do not apply cleanly to the external applications.
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_SCHED_WAITPID
|
||||
|
@ -154,15 +158,46 @@ int nsh_builtin(FAR struct nsh_vtbl_s *vtbl, FAR const char *cmd,
|
|||
{
|
||||
int rc = 0;
|
||||
|
||||
/* Wait for the application to exit. Since we have locked the
|
||||
* scheduler above, we know that the application has not yet
|
||||
* started and there is no possibility that it has already exited.
|
||||
* The scheduler will be unlocked while waitpid is waiting and the
|
||||
* application will be able to run.
|
||||
/* Wait for the application to exit. We did lock the scheduler
|
||||
* above, but that does not guarantee that the application did not
|
||||
* already run to completion in the case where I/O was redirected.
|
||||
* Here the scheduler will be unlocked while waitpid is waiting
|
||||
* and if the application has not yet run, it will now be able to
|
||||
* do so.
|
||||
*
|
||||
* Also, if CONFIG_SCHED_HAVE_PARENT is defined waitpid() might fail
|
||||
* even if task is still active: If the I/O was re-directed by a
|
||||
* proxy task, then the ask is a child of the proxy, and not this
|
||||
* task. waitpid() fails with ECHILD in either case.
|
||||
*/
|
||||
|
||||
ret = waitpid(ret, &rc, 0);
|
||||
if (ret >= 0)
|
||||
if (ret < 0)
|
||||
{
|
||||
/* If the child thread does not exist, waitpid() will return
|
||||
* the error ECHLD. Since we know that the task was successfully
|
||||
* started, this must be one of the cases described above; we
|
||||
* have to assume that the task already exit'ed. In this case,
|
||||
* we have no idea if the application ran successfully or not
|
||||
* (because NuttX does not retain exit status of child tasks).
|
||||
* Let's assume that is did run successfully.
|
||||
*/
|
||||
|
||||
int errcode = errno;
|
||||
if (errcode == ECHILD)
|
||||
{
|
||||
ret = OK;
|
||||
}
|
||||
else
|
||||
{
|
||||
nsh_output(vtbl, g_fmtcmdfailed, cmd, "waitpid",
|
||||
NSH_ERRNO_OF(errcode));
|
||||
}
|
||||
}
|
||||
|
||||
/* Waitpid completed the wait successfully */
|
||||
|
||||
else
|
||||
{
|
||||
/* We can't return the exact status (nsh has nowhere to put it)
|
||||
* so just pass back zero/nonzero in a fashion that doesn't look
|
||||
|
|
|
@ -0,0 +1,314 @@
|
|||
/****************************************************************************
|
||||
* apps/nshlib/nsh_fileapps.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>
|
||||
|
||||
#ifdef CONFIG_SCHED_WAITPID
|
||||
# include <sys/wait.h>
|
||||
#endif
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <spawn.h>
|
||||
#include <errno.h>
|
||||
#include <string.h>
|
||||
|
||||
#include "nsh.h"
|
||||
#include "nsh_console.h"
|
||||
|
||||
#ifdef CONFIG_NSH_FILE_APPS
|
||||
|
||||
/****************************************************************************
|
||||
* Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Types
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Function Prototypes
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Data
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: nsh_fileapp
|
||||
*
|
||||
* Description:
|
||||
* Attempt to execute the application task whose name is 'cmd'
|
||||
*
|
||||
* Returned Value:
|
||||
* <0 If exec_builtin() fails, then the negated errno value
|
||||
* is returned.
|
||||
* -1 (ERROR) if the application task corresponding to 'cmd' could not
|
||||
* be started (possibly because it doesn not exist).
|
||||
* 0 (OK) if the application task corresponding to 'cmd' was
|
||||
* and successfully started. If CONFIG_SCHED_WAITPID is
|
||||
* defined, this return value also indicates that the
|
||||
* application returned successful status (EXIT_SUCCESS)
|
||||
* 1 If CONFIG_SCHED_WAITPID is defined, then this return value
|
||||
* indicates that the application task was spawned successfully
|
||||
* but returned failure exit status.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
int nsh_fileapp(FAR struct nsh_vtbl_s *vtbl, FAR const char *cmd,
|
||||
FAR char **argv, FAR const char *redirfile, int oflags)
|
||||
{
|
||||
posix_spawn_file_actions_t file_actions;
|
||||
posix_spawnattr_t attr;
|
||||
pid_t pid;
|
||||
int ret;
|
||||
|
||||
/* Initialize the attributes file actions structure */
|
||||
|
||||
ret = posix_spawn_file_actions_init(&file_actions);
|
||||
if (ret != 0)
|
||||
{
|
||||
/* posix_spawn_file_actions_init returns a positive errno value on
|
||||
* failure.
|
||||
*/
|
||||
|
||||
nsh_output(vtbl, g_fmtcmdfailed, cmd, "posix_spawn_file_actions_init",
|
||||
NSH_ERRNO_OF(ret));
|
||||
goto errout;
|
||||
}
|
||||
|
||||
ret = posix_spawnattr_init(&attr);
|
||||
if (ret != 0)
|
||||
{
|
||||
/* posix_spawnattr_init returns a positive errno value on failure. */
|
||||
|
||||
nsh_output(vtbl, g_fmtcmdfailed, cmd, "posix_spawnattr_init",
|
||||
NSH_ERRNO);
|
||||
goto errout_with_actions;
|
||||
}
|
||||
|
||||
/* Handle re-direction of output */
|
||||
|
||||
if (redirfile)
|
||||
{
|
||||
ret = posix_spawn_file_actions_addopen(&file_actions, 1, redirfile,
|
||||
oflags, 0644);
|
||||
if (ret != 0)
|
||||
{
|
||||
/* posix_spawn_file_actions_addopen returns a positive errno
|
||||
* value on failure.
|
||||
*/
|
||||
|
||||
nsh_output(vtbl, g_fmtcmdfailed, cmd,
|
||||
"posix_spawn_file_actions_addopen",
|
||||
NSH_ERRNO);
|
||||
goto errout_with_attrs;
|
||||
}
|
||||
}
|
||||
|
||||
/* Lock the scheduler in an attempt to prevent the application from
|
||||
* running until waitpid() has been called.
|
||||
*/
|
||||
|
||||
sched_lock();
|
||||
|
||||
/* Execute the program. posix_spawnp returns a positive errno value on
|
||||
* failure.
|
||||
*/
|
||||
|
||||
ret = posix_spawnp(&pid, cmd, &file_actions, &attr, &argv[1], NULL);
|
||||
if (ret == OK)
|
||||
{
|
||||
/* The application was successfully started with pre-emption disabled.
|
||||
* In the simplest cases, the application will not have run because the
|
||||
* the scheduler is locked. But in the case where I/O was redirected, a
|
||||
* proxy task ran and broke our lock. As result, the application may
|
||||
* have aso ran if its priority was higher than than the priority of
|
||||
* this thread.
|
||||
*
|
||||
* If the application did not run to completion and if the application
|
||||
* was not backgrounded, then we need to wait here for the application
|
||||
* to exit. This only works works with the following options:
|
||||
*
|
||||
* - CONFIG_NSH_DISABLEBG - Do not run commands in background
|
||||
* - CONFIG_SCHED_WAITPID - Required to run external commands in
|
||||
* foreground
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_SCHED_WAITPID
|
||||
|
||||
/* CONFIG_SCHED_WAITPID is selected, so we may run the command in
|
||||
* foreground unless we were specifically requested to run the command
|
||||
* in background (and running commands in background is enabled).
|
||||
*/
|
||||
|
||||
# ifndef CONFIG_NSH_DISABLEBG
|
||||
if (vtbl->np.np_bg == false)
|
||||
# endif /* CONFIG_NSH_DISABLEBG */
|
||||
{
|
||||
int rc = 0;
|
||||
|
||||
/* Wait for the application to exit. We did lock the scheduler
|
||||
* above, but that does not guarantee that the application did not
|
||||
* already run to completion in the case where I/O was redirected.
|
||||
* Here the scheduler will be unlocked while waitpid is waiting
|
||||
* and if the application has not yet run, it will now be able to
|
||||
* do so.
|
||||
*/
|
||||
|
||||
ret = waitpid(pid, &rc, 0);
|
||||
if (ret < 0)
|
||||
{
|
||||
/* If the child thread does not exist, waitpid() will return
|
||||
* the error ECHLD. Since we know that the task was successfully
|
||||
* started, this must be one of the cases described above; we
|
||||
* have to assume that the task already exit'ed. In this case,
|
||||
* we have no idea if the application ran successfully or not
|
||||
* (because NuttX does not retain exit status of child tasks).
|
||||
* Let's assume that is did run successfully.
|
||||
*/
|
||||
|
||||
int errcode = errno;
|
||||
if (errcode == ECHILD)
|
||||
{
|
||||
ret = OK;
|
||||
}
|
||||
else
|
||||
{
|
||||
nsh_output(vtbl, g_fmtcmdfailed, cmd, "waitpid",
|
||||
NSH_ERRNO_OF(errcode));
|
||||
}
|
||||
}
|
||||
|
||||
/* Waitpid completed the wait successfully */
|
||||
|
||||
else
|
||||
{
|
||||
/* We can't return the exact status (nsh has nowhere to put it)
|
||||
* so just pass back zero/nonzero in a fashion that doesn't look
|
||||
* like an error.
|
||||
*/
|
||||
|
||||
ret = (rc == 0) ? OK : 1;
|
||||
|
||||
/* TODO: Set the environment variable '?' to a string corresponding
|
||||
* to WEXITSTATUS(rc) so that $? will expand to the exit status of
|
||||
* the most recently executed task.
|
||||
*/
|
||||
}
|
||||
}
|
||||
# ifndef CONFIG_NSH_DISABLEBG
|
||||
else
|
||||
# endif /* CONFIG_NSH_DISABLEBG */
|
||||
#endif /* CONFIG_SCHED_WAITPID */
|
||||
|
||||
/* We get here if either:
|
||||
*
|
||||
* - CONFIG_SCHED_WAITPID is not selected meaning that all commands
|
||||
* have to be run in background, or
|
||||
* - CONFIG_SCHED_WAITPID and CONFIG_NSH_DISABLEBG are both selected, but the
|
||||
* user requested to run the command in background.
|
||||
*
|
||||
* NOTE that the case of a) CONFIG_SCHED_WAITPID is not selected and
|
||||
* b) CONFIG_NSH_DISABLEBG selected cannot be supported. In that event, all
|
||||
* commands will have to run in background. The waitpid() API must be
|
||||
* available to support running the command in foreground.
|
||||
*/
|
||||
|
||||
#if !defined(CONFIG_SCHED_WAITPID) || !defined(CONFIG_NSH_DISABLEBG)
|
||||
{
|
||||
struct sched_param param;
|
||||
sched_getparam(ret, ¶m);
|
||||
nsh_output(vtbl, "%s [%d:%d]\n", cmd, ret, param.sched_priority);
|
||||
|
||||
/* Backgrounded commands always 'succeed' as long as we can start
|
||||
* them.
|
||||
*/
|
||||
|
||||
ret = OK;
|
||||
}
|
||||
#endif /* !CONFIG_SCHED_WAITPID || !CONFIG_NSH_DISABLEBG */
|
||||
}
|
||||
|
||||
sched_unlock();
|
||||
|
||||
/* Free attibutes and file actions. Ignoring return values in the case
|
||||
* of an error.
|
||||
*/
|
||||
|
||||
errout_with_actions:
|
||||
(void)posix_spawn_file_actions_destroy(&file_actions);
|
||||
|
||||
errout_with_attrs:
|
||||
(void)posix_spawnattr_destroy(&attr);
|
||||
|
||||
errout:
|
||||
/* Most posix_spawn interfaces return a positive errno value on failure
|
||||
* and do not set the errno variable.
|
||||
*/
|
||||
|
||||
if (ret > 0)
|
||||
{
|
||||
/* Set the errno value and return -1 */
|
||||
|
||||
set_errno(ret);
|
||||
ret = ERROR;
|
||||
}
|
||||
else if (ret < 0)
|
||||
{
|
||||
/* Return -1 on failure. errno should have been set. */
|
||||
|
||||
ret = ERROR;
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
#endif /* CONFIG_NSH_FILE_APPS */
|
|
@ -53,12 +53,13 @@
|
|||
#include <errno.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <net/ethernet.h>
|
||||
#include <netinet/ether.h>
|
||||
|
||||
#include <nuttx/net/net.h>
|
||||
#include <nuttx/clock.h>
|
||||
#include <net/ethernet.h>
|
||||
#include <nuttx/net/uip/uip.h>
|
||||
#include <nuttx/net/uip/uip-arch.h>
|
||||
#include <netinet/ether.h>
|
||||
|
||||
#ifdef CONFIG_NET_STATISTICS
|
||||
# include <nuttx/net/uip/uip.h>
|
||||
|
|
|
@ -61,6 +61,7 @@
|
|||
#ifdef CONFIG_NSH_BUILTIN_APPS
|
||||
# include <nuttx/binfmt/builtin.h>
|
||||
#endif
|
||||
|
||||
#include <apps/nsh.h>
|
||||
|
||||
#include "nsh.h"
|
||||
|
@ -1398,6 +1399,40 @@ int nsh_parse(FAR struct nsh_vtbl_s *vtbl, char *cmdline)
|
|||
nsh_output(vtbl, g_fmttoomanyargs, cmd);
|
||||
}
|
||||
|
||||
/* Does this command correspond to an application filename?
|
||||
* nsh_fileapp() returns:
|
||||
*
|
||||
* -1 (ERROR) if the application task corresponding to 'argv[0]' could not
|
||||
* be started (possibly because it doesn not exist).
|
||||
* 0 (OK) if the application task corresponding to 'argv[0]' was
|
||||
* and successfully started. If CONFIG_SCHED_WAITPID is
|
||||
* defined, this return value also indicates that the
|
||||
* application returned successful status (EXIT_SUCCESS)
|
||||
* 1 If CONFIG_SCHED_WAITPID is defined, then this return value
|
||||
* indicates that the application task was spawned successfully
|
||||
* but returned failure exit status.
|
||||
*
|
||||
* Note the priority if not effected by nice-ness.
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_NSH_FILE_APPS
|
||||
ret = nsh_fileapp(vtbl, argv[0], argv, redirfile, oflags);
|
||||
if (ret >= 0)
|
||||
{
|
||||
/* nsh_fileapp() returned 0 or 1. This means that the builtin
|
||||
* command was successfully started (although it may not have ran
|
||||
* successfully). So certainly it is not an NSH command.
|
||||
*/
|
||||
|
||||
return nsh_saveresult(vtbl, ret != OK);
|
||||
}
|
||||
|
||||
/* No, not a built in command (or, at least, we were unable to start a
|
||||
* builtin command of that name). Treat it like an NSH command.
|
||||
*/
|
||||
|
||||
#endif
|
||||
|
||||
/* Does this command correspond to a builtin command?
|
||||
* nsh_builtin() returns:
|
||||
*
|
||||
|
@ -1414,7 +1449,7 @@ int nsh_parse(FAR struct nsh_vtbl_s *vtbl, char *cmdline)
|
|||
* Note the priority if not effected by nice-ness.
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_NSH_BUILTIN_APPS
|
||||
#if defined(CONFIG_NSH_BUILTIN_APPS) && (!defined(CONFIG_NSH_FILE_APPS) || !defined(CONFIG_FS_BINFS))
|
||||
ret = nsh_builtin(vtbl, argv[0], argv, redirfile, oflags);
|
||||
if (ret >= 0)
|
||||
{
|
||||
|
|
|
@ -3967,4 +3967,55 @@
|
|||
file system.
|
||||
* configs/sim/nsh: Convert to use kconfig-frontends configuration
|
||||
tool.
|
||||
* binfmt/binfmt_schedunload.c: Add logic based on SIGCHLD to
|
||||
automatically unload and clean-up after running a task that
|
||||
was loaded into memory.
|
||||
* binfmt/libbuiltin: Extensions from Mike Smith
|
||||
* sched/task_reparent.c: Add internal interface to change the
|
||||
parent task.
|
||||
* sched/task_posixspawn(): Move libc/spawn/lib_ps.c to
|
||||
sched/task_posixspawn() now it requires internal, reparenting
|
||||
interfaces
|
||||
* include/nuttx/spawn(): Move libc/spawn.h to include/nuttx/spawn.h
|
||||
* arch/arm/include/lpc17xx/chip.h, irq178x.h: Integrate Marcelo
|
||||
Rommel's LPC1788 definitions into the base LPC17xx.
|
||||
* configs/olimex-lpc1766stk/nsh: Convert configuration to use
|
||||
the kconfig-frontends tools.
|
||||
* sched/task_reparent.c: Simplify reparenting interface.
|
||||
* arch/arm/src/[many]: More LPC1788 definitions from Rommel
|
||||
Marcelo incorporated.
|
||||
* configs/open1788: Board configuration for the Wave Share
|
||||
Open1788 board. Still fragmentary (contribnuted by Rommel
|
||||
Marcelo, adapted to use kconfig-frontends.
|
||||
* net/send(): Add logic to work around delayed ACKs by splitting
|
||||
packets (contributed by Yan T.).
|
||||
* net/recvfrom(): Fix a bug. When the host closes a connection
|
||||
(gracefully). recv[from]() returned success and the closure
|
||||
was never detected. Hmmm.. I don't know why the network monitor
|
||||
did not catch this event. This is an important bug fix.
|
||||
* net/recvfrom(): Fix a introduced with the last bugfix. If
|
||||
the peer does an orderly closure of the socket, report 0 not
|
||||
-ENOTCONN
|
||||
* configs/lm3s6965-ek/README.txt and tools/: Add an OpenOCD
|
||||
configuration for the LM3S (from Jose Pablo Carballo).
|
||||
* nuttx/lcd/hd4478ou.h and configs/pcblogic-pic32mx/src/up_lcd1602:
|
||||
Start of support of LCD1602 alphanumeric LCD. I need a few
|
||||
more parts before I can finish integrating this one.
|
||||
* arch/arm/src/*/chip.h and arch/arm/include/*/chip.h: Move all
|
||||
priority ranges from the src to the include chip.h header file.
|
||||
* arch/arm/include/armv7-m/irq.h: Add inline functions to enable
|
||||
and disable interrupts via the BASEPRI register.
|
||||
* arch/arm/Kconfig: Add new option CONFIG_ARM7VM_USEBASEI
|
||||
* arch/arm/src/*/*_irq.c: Set the priority of the SVCALL exception
|
||||
to the highest possible value.
|
||||
* arch/armv7-m/up_hardfault.c: Fail if a hardfault occurs
|
||||
while CONFIG_ARM7VM_USEBASEPRI=y.
|
||||
* arch/arm/src/stm32/stm32_serial.c: Add support for USART
|
||||
single wire more (Contributed by the PX4 team).
|
||||
* sched/: Implement support for retaining child task status after
|
||||
the child task exists. This is behavior required by POSIX.
|
||||
But in NuttX is only enabled with CONFIG_SCHED_HAVE_PARENT and
|
||||
CONFIG_SCHED_CHILD_STATUS
|
||||
* Add support for keyboard encode to the keypad test (from
|
||||
Denis Carikli).
|
||||
|
||||
|
|
167
nuttx/TODO
167
nuttx/TODO
|
@ -1,4 +1,4 @@
|
|||
NuttX TODO List (Last updated January 14, 2013)
|
||||
NuttX TODO List (Last updated January 23, 2013)
|
||||
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
|
||||
|
||||
This file summarizes known NuttX bugs, limitations, inconsistencies with
|
||||
|
@ -6,7 +6,7 @@ standards, things that could be improved, and ideas for enhancements.
|
|||
|
||||
nuttx/
|
||||
|
||||
(10) Task/Scheduler (sched/)
|
||||
(11) Task/Scheduler (sched/)
|
||||
(1) Memory Managment (mm/)
|
||||
(3) Signals (sched/, arch/)
|
||||
(2) pthreads (sched/)
|
||||
|
@ -21,7 +21,7 @@ nuttx/
|
|||
(1) Documentation (Documentation/)
|
||||
(7) Build system / Toolchains
|
||||
(5) Linux/Cywgin simulation (arch/sim)
|
||||
(6) ARM (arch/arm/)
|
||||
(5) ARM (arch/arm/)
|
||||
(1) ARM/C5471 (arch/arm/src/c5471/)
|
||||
(3) ARM/DM320 (arch/arm/src/dm320/)
|
||||
(2) ARM/i.MX (arch/arm/src/imx/)
|
||||
|
@ -38,14 +38,14 @@ nuttx/
|
|||
(3) MIPS/PIC32 (arch/mips)
|
||||
(1) Hitachi/Renesas SH-1 (arch/sh/src/sh1)
|
||||
(4) Renesas M16C/26 (arch/sh/src/m16c)
|
||||
(10) z80/z8/ez80 (arch/z80/)
|
||||
(11) z80/z8/ez80/z180 (arch/z80/)
|
||||
(9) z16 (arch/z16/)
|
||||
(1) mc68hc1x (arch/hc)
|
||||
|
||||
apps/
|
||||
|
||||
(5) Network Utilities (apps/netutils/)
|
||||
(4) NuttShell (NSH) (apps/nshlib)
|
||||
(5) NuttShell (NSH) (apps/nshlib)
|
||||
(1) System libraries apps/system (apps/system)
|
||||
(5) Other Applications & Tests (apps/examples/)
|
||||
|
||||
|
@ -161,39 +161,8 @@ o Task/Scheduler (sched/)
|
|||
Status: Open
|
||||
Priority: Medium Low for now
|
||||
|
||||
Title: RETAINING TASK EXIT STATUS
|
||||
Description: When a task exists, its exit status should be retained in
|
||||
so data structure until it is reaped (via waitpid(), or
|
||||
similar interface) or until the parent thread exists.
|
||||
|
||||
You would think that this should be a clone of the existing
|
||||
pthread join logic. Howver there is no need for zombies
|
||||
in NuttX so no need to keep the status if the parent has
|
||||
already exit'ed. Other simplifications:
|
||||
|
||||
1. Keep the array/list of return status in the parent
|
||||
tasks TCB.
|
||||
2. Use a fixed size array of return status (perhaps the
|
||||
the enire array is allocated so that that is con
|
||||
penalty for tasks that have no childre.
|
||||
|
||||
At present, exit status is not retained. If waitpid()
|
||||
is called after the child task has exit'ed it simpley
|
||||
returns with the ECHLD error. That is not too bad, but
|
||||
does not tell you what the exit status was.
|
||||
|
||||
A work-around is to:
|
||||
1) Call sched_lock() to disable pre-emption.
|
||||
2) Start the task (it cannot run because pre-emption is
|
||||
disbled.
|
||||
3) Call waitpid();
|
||||
4) Call sched_unlock() to re-enable pre-emption.
|
||||
|
||||
Status: Open
|
||||
Priority: Low
|
||||
|
||||
Title: IMPROVED TASK CONTROL BLOCK STRUCTURE
|
||||
All task resources that are shared amongst threads have
|
||||
Description: All task resources that are shared amongst threads have
|
||||
their own "break-away", reference-counted structure. The
|
||||
Task Control Block (TCB) of each thread holds a reference
|
||||
to each breakaway structure (see include/nuttx/sched.h).
|
||||
|
@ -206,11 +175,43 @@ o Task/Scheduler (sched/)
|
|||
- File descriptors (struct filelist)
|
||||
- FILE streams (struct streamlist)
|
||||
- Sockets (struct socketlist)
|
||||
Status: Open
|
||||
Priority: Low. This is an enhancement. It would slight reduce
|
||||
Status: Open
|
||||
Priority: Low. This is an enhancement. It would slight reduce
|
||||
memory usage but would also increase coupling. These
|
||||
resources are nicely modular now.
|
||||
|
||||
Title: ISSUES WITH atexit() AND on_exit()
|
||||
Description: These functions execute with the following bad properties:
|
||||
|
||||
1. They run with interrupts disabled,
|
||||
2. They run in supervisor mode (if applicable), and
|
||||
3. They do not obey any setup of PIC or address
|
||||
environments. Do they need to?
|
||||
|
||||
The fix for all of these issues it to have the callbacks
|
||||
run on the caller's thread (as with signal handlers).
|
||||
Status: Open
|
||||
Priority: Medium Low. This is an important change to some less
|
||||
important interfaces. For the average user, these
|
||||
functions are just fine the way they are.
|
||||
|
||||
Title: execv() AND vfork()
|
||||
Description: There is a problem when vfork() calls execv() (or execl()) to
|
||||
start a new appliction: When the parent thread calls vfork()
|
||||
it receives and gets the pid of the vforked task, and *not*
|
||||
the pid of the desired execv'ed application.
|
||||
|
||||
The same tasking arrangement is used by the standard function
|
||||
posix_spawn(). However, posix_spawn uses the non-standard, internal
|
||||
NuttX interface task_reparent() to replace the childs parent task
|
||||
with the caller of posix_spawn(). That cannot be done with vfork()
|
||||
because we don't know what vfor() is going to do.
|
||||
|
||||
Any solution to this is either very difficult or impossible with
|
||||
an MMU.
|
||||
Status: Open
|
||||
Priority: Low (it might as well be low since it isn't going to be fixed).
|
||||
|
||||
o Memory Managment (mm/)
|
||||
^^^^^^^^^^^^^^^^^^^^^^
|
||||
|
||||
|
@ -516,7 +517,7 @@ o Network (net/, drivers/net)
|
|||
Status: Open. No changes are planned.
|
||||
Priority: Low
|
||||
|
||||
Tile: MULTIPLE NETWORK INTERFACE SUPPORT
|
||||
Title: MULTIPLE NETWORK INTERFACE SUPPORT
|
||||
Description: uIP polling issues / Multiple network interface support:
|
||||
|
||||
(1) Current logic will not support multiple ethernet drivers.
|
||||
|
@ -666,6 +667,21 @@ o Network (net/, drivers/net)
|
|||
Status: Open
|
||||
Priority: Low... fix defconfig files as necessary.
|
||||
|
||||
Title: net_poll() DOES NOT HANDLE LOSS-OF-CONNECTION CORRECTLY
|
||||
Description: When a loss of connection is detected by any logic waiting on the
|
||||
networking events, the function net_lostconnection() must be called.
|
||||
That function just sets some bits in the socket structure so that
|
||||
it remembers that the connection is lost.
|
||||
|
||||
That is currently done in recvfrom(), send(), and net_monitor.c. But
|
||||
it is not done in the net_poll() logic; that logic correctly sets
|
||||
the POLLHUP status, but it does not call net_lostconnection(). As a
|
||||
result, if recv() is called after the poll() or select(), the system
|
||||
will hang because the recv() does not know that the connection has
|
||||
been lost.
|
||||
Status: Open
|
||||
Priority: High
|
||||
|
||||
o USB (drivers/usbdev, drivers/usbhost)
|
||||
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
|
||||
|
||||
|
@ -1059,13 +1075,13 @@ o Build system
|
|||
Priority: Low -- the kernel build configuration is not fully fielded
|
||||
yet.
|
||||
|
||||
Title: mconf NOT AVAILABLE IN NATIVE WINDOWS BUILD
|
||||
Description: NuttX is migrating to the use of the kconfig-frontends mconf
|
||||
Title: kconfig-mconf NOT AVAILABLE IN NATIVE WINDOWS BUILD
|
||||
Description: NuttX is migrating to the use of the kconfig-frontends kconfig-mconf
|
||||
tool for all configurations. In NuttX 6.24, support for native
|
||||
Windows builds was added. However, the mconf tool does not
|
||||
Windows builds was added. However, thekconfig- mconf tool does not
|
||||
build to run natively under Windows.
|
||||
|
||||
Some effort was spent trying to get a clean mconf build under
|
||||
Some effort was spent trying to get a clean kconfig-mconf build under
|
||||
Windows. This is documented in the message thread beginning
|
||||
here: http://tech.groups.yahoo.com/group/nuttx/message/2900.
|
||||
The build was successfully completed using: MinGW-GCC, MSYS,
|
||||
|
@ -1077,8 +1093,8 @@ o Build system
|
|||
was considered a show stopper and the changs were not checked
|
||||
in.
|
||||
|
||||
Options: (1) Use conf (not mconf). confis the text-only
|
||||
configuration tool, (2) fix mconf, (3) write another variant
|
||||
Options: (1) Use kconfigs-conf (not kconfig-mconf). confis the text-only
|
||||
configuration tool, (2) fix kconfig-mconf, (3) write another variant
|
||||
of the configuration tool for windows, or (4) do all configuration
|
||||
under Cygwin or MSYS. I am doing (4) now, but this is very
|
||||
awkward because I have to set the apps path to ../apps (vs
|
||||
|
@ -1161,27 +1177,6 @@ o ARM (arch/arm/)
|
|||
Status: Open
|
||||
Priority: Low
|
||||
|
||||
Title: SVCALLS AND HARDFAULTS
|
||||
Description: The Cortex-M3 user context switch logic uses SVCall instructions.
|
||||
This user context switching time could be improved by eliminating
|
||||
the SVCalls and developing assembly language implementations
|
||||
of the context save and restore logic.
|
||||
Also, because interrupts are always disabled when the SVCall is
|
||||
executed, the SVC goes to the hard fault handler where it must
|
||||
be handled as a special case. I recall seeing some controls
|
||||
somewhere that will allow to suppress one hard fault. I don't
|
||||
recall the control, but something like this should be used before
|
||||
executing the SVCall so that it vectors directly to the SVC
|
||||
handler.
|
||||
Another, more standard option would be to use interrupt priority
|
||||
levels to control interrupts. In that case, (1) The SVC would
|
||||
be the highest priority interrupt (0), (2) irqsave() would set
|
||||
the interrupt mask level to just above that, and (2) irqrestore
|
||||
would restore the interrupt level. This would not be diffult,
|
||||
but does affect a lot of files!
|
||||
Status: Open
|
||||
Priority: Low
|
||||
|
||||
Title: ARM INTERRUPTS AND USER MODE
|
||||
Description: The ARM interrupt handling (arch/arm/src/arm/up_vectors.S) returns
|
||||
using 'ldmia sp, {r0-r15}^' My understanding is that this works
|
||||
|
@ -1769,8 +1764,8 @@ o Renesas M16C/26 (arch/sh/src/m16c)
|
|||
Status: Open
|
||||
Priority: Medium
|
||||
|
||||
o z80/z8/ez80 (arch/z80)
|
||||
^^^^^^^^^^^^^^^^^^^^^^^
|
||||
o z80/z8/ez80/z180 (arch/z80)
|
||||
^^^^^^^^^^^^^^^^^^^^^^^^^^^^
|
||||
|
||||
Title: SDCC INTEGER OVERFLOWS
|
||||
Description: The SDCC version the same problems with integer overflow during
|
||||
|
@ -1860,6 +1855,14 @@ o z80/z8/ez80 (arch/z80)
|
|||
Status: Open
|
||||
Priority: Med
|
||||
|
||||
Title: UNFINISHED Z180 LOGIC NEEDED BY THE P112 BOARD
|
||||
Description: 1) Need to revist the start-up logic. Looking at the P112 Bios
|
||||
(Bios.mcd), I see that quite of bit of register setup is done
|
||||
there.
|
||||
2) Finish ESCC driver logic.
|
||||
Status: Open
|
||||
Priority: Low (at least until I get P112 hardware)
|
||||
|
||||
o z16 (arch/z16)
|
||||
^^^^^^^^^^^^^^^^
|
||||
|
||||
|
@ -2051,6 +2054,32 @@ o NuttShell (NSH) (apps/nshlib)
|
|||
Status: Open
|
||||
Priority: Low (enhancement)
|
||||
|
||||
Title: RE-DIRECTION OF BUILTIN APPLICATONS
|
||||
Description: There is a problem with the re-direction of output form built-in
|
||||
applications in NSH. When output is re-directed, exec_builtin()
|
||||
spawns a tiny trampoline task that re-directs the output as
|
||||
requested, starts the built-in task and then exit.
|
||||
|
||||
The problem is that when exec_builtin() starts the trampoline task,
|
||||
it receives and returns the pid of the trampoline task, and *not*
|
||||
the pid of the desired builtin application. This bad pid is returned
|
||||
to NSH and when NSH tries to use that pid in the waitpid() call, it
|
||||
fails because the trampoline task no longer exists.
|
||||
|
||||
The same tasking arrangement is used by the standard function
|
||||
posix_spawn(). However, posix_spawn uses the non-standard, internal
|
||||
NuttX interface task_reparent() to replace the childs parent task
|
||||
with the caller of posix_spawn().
|
||||
|
||||
exec_builtin() should not use this internal interface, however,
|
||||
since it resides in the application space. The suggested solution
|
||||
is (1) move the exec_builtin() logic into nuttx/sched, (2) make it
|
||||
a semi-standard interface renamed to task_spawn() and prototyped
|
||||
in nuttx/include/sched.h, and then (2) use task_reparent to solve
|
||||
the parental problem in the same way that posix_spawn does.
|
||||
Status: Open
|
||||
Priority: Medium
|
||||
|
||||
o System libraries apps/system (apps/system)
|
||||
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
|
||||
|
||||
|
|
|
@ -103,6 +103,131 @@ source arch/x86/Kconfig
|
|||
source arch/z16/Kconfig
|
||||
source arch/z80/Kconfig
|
||||
|
||||
comment "External Memory Configuration"
|
||||
|
||||
config ARCH_HAVE_EXTNAND
|
||||
bool
|
||||
|
||||
config ARCH_HAVE_EXTNOR
|
||||
bool
|
||||
|
||||
config ARCH_HAVE_EXTDRAM
|
||||
bool
|
||||
|
||||
config ARCH_HAVE_EXTSRAM0
|
||||
bool
|
||||
|
||||
config ARCH_HAVE_EXTSRAM1
|
||||
bool
|
||||
|
||||
config ARCH_EXTNAND
|
||||
bool "Configure external NAND"
|
||||
default n
|
||||
depends on ARCH_HAVE_EXTNAND
|
||||
---help---
|
||||
Configure external NAND memory and, if applicable, map then external
|
||||
NAND into the memory map.
|
||||
|
||||
if ARCH_EXTNAND
|
||||
|
||||
config ARCH_EXTNANDSIZE
|
||||
int "External NAND size"
|
||||
default 0
|
||||
---help---
|
||||
Size of the external NAND in bytes.
|
||||
|
||||
endif
|
||||
|
||||
config ARCH_EXTNOR
|
||||
bool "Configure external NOR memory"
|
||||
default n
|
||||
depends on ARCH_HAVE_EXTNOR
|
||||
---help---
|
||||
Configure external NOR memory and, if applicable, map then external
|
||||
NOR into the memory map.
|
||||
|
||||
if ARCH_EXTNOR
|
||||
|
||||
config ARCH_EXTNORSIZE
|
||||
int "External NOR size"
|
||||
default 0
|
||||
---help---
|
||||
Size of the external NOR in bytes.
|
||||
|
||||
endif
|
||||
|
||||
config ARCH_EXTDRAM
|
||||
bool "Configure external DRAM"
|
||||
default n
|
||||
depends on ARCH_HAVE_EXTDRAM
|
||||
---help---
|
||||
Configure external DRAM memory and, if applicable, map then external
|
||||
DRAM into the memory map.
|
||||
|
||||
if ARCH_EXTDRAM
|
||||
|
||||
config ARCH_EXTDRAMSIZE
|
||||
int "External SDRAM size"
|
||||
default 0
|
||||
---help---
|
||||
Size of the external SDRAM in bytes.
|
||||
|
||||
config ARCH_EXTDRAMHEAP
|
||||
bool "Add external SDRAM to the heap"
|
||||
default y
|
||||
---help---
|
||||
Add the external SDRAM into the heap.
|
||||
|
||||
endif
|
||||
|
||||
config ARCH_EXTSRAM0
|
||||
bool "Configure external SRAM (Bank 0)"
|
||||
default n
|
||||
depends on ARCH_HAVE_EXTSRAM0
|
||||
---help---
|
||||
Configure external SRAM Bank 0 memory and, if applicable, map then
|
||||
external SRAM Bank 0 into the memory map.
|
||||
|
||||
if ARCH_EXTSRAM0
|
||||
|
||||
config ARCH_EXTSRAM0SIZE
|
||||
int "External SRAM size"
|
||||
default 0
|
||||
---help---
|
||||
Size of the external SRAM Bank 0 in bytes.
|
||||
|
||||
config ARCH_EXTSRAM0HEAP
|
||||
bool "Add external SRAM (Bank 0) to the heap"
|
||||
default y
|
||||
---help---
|
||||
Add external SRAM Bank 0 into the heap.
|
||||
|
||||
endif
|
||||
|
||||
config ARCH_EXTSRAM1
|
||||
bool "Configure external SRAM (Bank 1)"
|
||||
default n
|
||||
depends on ARCH_HAVE_EXTSRAM1
|
||||
---help---
|
||||
Configure external SRAM Bank 1 memory and, if applicable, map then
|
||||
external SRAM Bank 1 into the memory map.
|
||||
|
||||
if ARCH_EXTSRAM1
|
||||
|
||||
config ARCH_EXTSRAM1SIZE
|
||||
int "External SRAM1 size"
|
||||
default 0
|
||||
---help---
|
||||
Size of the external SRAM Bank 1 in bytes.
|
||||
|
||||
config ARCH_EXTSRAM1HEAP
|
||||
bool "Add external SRAM (Bank 1) to the heap"
|
||||
default y
|
||||
---help---
|
||||
Add external SRAM Bank 1 into the heap.
|
||||
|
||||
endif
|
||||
|
||||
comment "Architecture Options"
|
||||
|
||||
config ARCH_NOINTC
|
||||
|
|
|
@ -46,7 +46,6 @@ config ARCH_CHIP_KINETIS
|
|||
bool "Freescale Kinetis"
|
||||
select ARCH_CORTEXM4
|
||||
select ARCH_HAVE_MPU
|
||||
select ARCH_IRQPRIO
|
||||
select ARCH_HAVE_RAMFUNCS
|
||||
select ARCH_RAMFUNCS
|
||||
---help---
|
||||
|
@ -55,7 +54,6 @@ config ARCH_CHIP_KINETIS
|
|||
config ARCH_CHIP_LM
|
||||
bool "TI Stellaris"
|
||||
select ARCH_HAVE_MPU
|
||||
select ARCH_IRQPRIO
|
||||
---help---
|
||||
TI Stellaris LMS3 architecutres (ARM Cortex-M3)
|
||||
|
||||
|
@ -63,7 +61,6 @@ config ARCH_CHIP_LPC17XX
|
|||
bool "NXP LPC17xx"
|
||||
select ARCH_CORTEXM3
|
||||
select ARCH_HAVE_MPU
|
||||
select ARCH_IRQPRIO
|
||||
---help---
|
||||
NXP LPC17xx architectures (ARM Cortex-M3)
|
||||
|
||||
|
@ -95,7 +92,6 @@ config ARCH_CHIP_LPC43XX
|
|||
select ARCH_HAVE_CMNVECTOR
|
||||
select ARMV7M_CMNVECTOR
|
||||
select ARCH_HAVE_MPU
|
||||
select ARCH_IRQPRIO
|
||||
---help---
|
||||
NPX LPC43XX architectures (ARM Cortex-M4).
|
||||
|
||||
|
@ -103,7 +99,6 @@ config ARCH_CHIP_SAM3U
|
|||
bool "Atmel AT91SAM3U"
|
||||
select ARCH_CORTEXM3
|
||||
select ARCH_HAVE_MPU
|
||||
select ARCH_IRQPRIO
|
||||
---help---
|
||||
Atmel AT91SAM3U architectures (ARM Cortex-M3)
|
||||
|
||||
|
@ -112,7 +107,6 @@ config ARCH_CHIP_STM32
|
|||
select ARCH_HAVE_CMNVECTOR
|
||||
select ARCH_HAVE_MPU
|
||||
select ARCH_HAVE_I2CRESET
|
||||
select ARCH_IRQPRIO
|
||||
---help---
|
||||
STMicro STM32 architectures (ARM Cortex-M3/4).
|
||||
|
||||
|
@ -136,9 +130,11 @@ config ARCH_ARM920T
|
|||
|
||||
config ARCH_CORTEXM3
|
||||
bool
|
||||
select ARCH_IRQPRIO
|
||||
|
||||
config ARCH_CORTEXM4
|
||||
bool
|
||||
select ARCH_IRQPRIO
|
||||
|
||||
config ARCH_FAMILY
|
||||
string
|
||||
|
@ -162,6 +158,17 @@ config ARCH_CHIP
|
|||
default "stm32" if ARCH_CHIP_STM32
|
||||
default "str71x" if ARCH_CHIP_STR71X
|
||||
|
||||
config ARMV7M_USEBASEPRI
|
||||
bool "Use BASEPRI Register"
|
||||
default n
|
||||
depends on ARCH_CORTEXM3 || ARCH_CORTEXM4
|
||||
---help---
|
||||
Use the BASEPRI register to enable and disable able interrupts. By
|
||||
default, the PRIMASK register is used for this purpose. This
|
||||
usually results in hardfaults that are properly handling by the
|
||||
RTOS. Using the BASEPRI register will avoid these hardfault.
|
||||
That is needed primarily for integration with some toolchains.
|
||||
|
||||
config ARCH_HAVE_CMNVECTOR
|
||||
bool
|
||||
|
||||
|
|
|
@ -60,6 +60,10 @@
|
|||
# include <arch/armv7-m/irq_lazyfpu.h>
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_ARMV7M_USEBASEPRI
|
||||
# include <arch/chip/chip.h>
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
@ -114,7 +118,11 @@ struct xcptcontext
|
|||
*/
|
||||
|
||||
uint32_t saved_pc;
|
||||
#ifdef CONFIG_ARMV7M_USEBASEPRI
|
||||
uint32_t saved_basepri;
|
||||
#else
|
||||
uint32_t saved_primask;
|
||||
#endif
|
||||
uint32_t saved_xpsr;
|
||||
#endif
|
||||
|
||||
|
@ -130,65 +138,7 @@ struct xcptcontext
|
|||
|
||||
#ifndef __ASSEMBLY__
|
||||
|
||||
/* Disable IRQs */
|
||||
|
||||
static inline void irqdisable(void) inline_function;
|
||||
static inline void irqdisable(void)
|
||||
{
|
||||
__asm__ __volatile__ ("\tcpsid i\n");
|
||||
}
|
||||
|
||||
/* Save the current primask state & disable IRQs */
|
||||
|
||||
static inline irqstate_t irqsave(void) inline_function;
|
||||
static inline irqstate_t irqsave(void)
|
||||
{
|
||||
unsigned short primask;
|
||||
|
||||
/* Return the current value of primask register and set
|
||||
* bit 0 of the primask register to disable interrupts
|
||||
*/
|
||||
|
||||
__asm__ __volatile__
|
||||
(
|
||||
"\tmrs %0, primask\n"
|
||||
"\tcpsid i\n"
|
||||
: "=r" (primask)
|
||||
:
|
||||
: "memory");
|
||||
|
||||
return primask;
|
||||
}
|
||||
|
||||
/* Enable IRQs */
|
||||
|
||||
static inline void irqenable(void) inline_function;
|
||||
static inline void irqenable(void)
|
||||
{
|
||||
__asm__ __volatile__ ("\tcpsie i\n");
|
||||
}
|
||||
|
||||
/* Restore saved primask state */
|
||||
|
||||
static inline void irqrestore(irqstate_t primask) inline_function;
|
||||
static inline void irqrestore(irqstate_t primask)
|
||||
{
|
||||
/* If bit 0 of the primask is 0, then we need to restore
|
||||
* interupts.
|
||||
*/
|
||||
|
||||
__asm__ __volatile__
|
||||
(
|
||||
"\ttst %0, #1\n"
|
||||
"\tbne 1f\n"
|
||||
"\tcpsie i\n"
|
||||
"1:\n"
|
||||
:
|
||||
: "r" (primask)
|
||||
: "memory");
|
||||
}
|
||||
|
||||
/* Get/set the primask register */
|
||||
/* Get/set the PRIMASK register */
|
||||
|
||||
static inline uint8_t getprimask(void) inline_function;
|
||||
static inline uint8_t getprimask(void)
|
||||
|
@ -215,7 +165,11 @@ static inline void setprimask(uint32_t primask)
|
|||
: "memory");
|
||||
}
|
||||
|
||||
/* Get/set the basepri register */
|
||||
/* Get/set the BASEPRI register. The BASEPRI register defines the minimum
|
||||
* priority for exception processing. When BASEPRI is set to a nonzero
|
||||
* value, it prevents the activation of all exceptions with the same or
|
||||
* lower priority level as the BASEPRI value.
|
||||
*/
|
||||
|
||||
static inline uint8_t getbasepri(void) inline_function;
|
||||
static inline uint8_t getbasepri(void)
|
||||
|
@ -243,6 +197,82 @@ static inline void setbasepri(uint32_t basepri)
|
|||
: "memory");
|
||||
}
|
||||
|
||||
/* Disable IRQs */
|
||||
|
||||
static inline void irqdisable(void) inline_function;
|
||||
static inline void irqdisable(void)
|
||||
{
|
||||
#ifdef CONFIG_ARMV7M_USEBASEPRI
|
||||
setbasepri(NVIC_SYSH_DISABLE_PRIORITY);
|
||||
#else
|
||||
__asm__ __volatile__ ("\tcpsid i\n");
|
||||
#endif
|
||||
}
|
||||
|
||||
/* Save the current primask state & disable IRQs */
|
||||
|
||||
static inline irqstate_t irqsave(void) inline_function;
|
||||
static inline irqstate_t irqsave(void)
|
||||
{
|
||||
#ifdef CONFIG_ARMV7M_USEBASEPRI
|
||||
|
||||
uint8_t basepri = getbasepri();
|
||||
setbasepri(NVIC_SYSH_DISABLE_PRIORITY);
|
||||
return (irqstate_t)basepri;
|
||||
|
||||
#else
|
||||
|
||||
unsigned short primask;
|
||||
|
||||
/* Return the current value of primask register and set
|
||||
* bit 0 of the primask register to disable interrupts
|
||||
*/
|
||||
|
||||
__asm__ __volatile__
|
||||
(
|
||||
"\tmrs %0, primask\n"
|
||||
"\tcpsid i\n"
|
||||
: "=r" (primask)
|
||||
:
|
||||
: "memory");
|
||||
|
||||
return primask;
|
||||
#endif
|
||||
}
|
||||
|
||||
/* Enable IRQs */
|
||||
|
||||
static inline void irqenable(void) inline_function;
|
||||
static inline void irqenable(void)
|
||||
{
|
||||
setbasepri(0);
|
||||
__asm__ __volatile__ ("\tcpsie i\n");
|
||||
}
|
||||
|
||||
/* Restore saved primask state */
|
||||
|
||||
static inline void irqrestore(irqstate_t flags) inline_function;
|
||||
static inline void irqrestore(irqstate_t flags)
|
||||
{
|
||||
#ifdef CONFIG_ARMV7M_USEBASEPRI
|
||||
setbasepri((uint32_t)flags);
|
||||
#else
|
||||
/* If bit 0 of the primask is 0, then we need to restore
|
||||
* interupts.
|
||||
*/
|
||||
|
||||
__asm__ __volatile__
|
||||
(
|
||||
"\ttst %0, #1\n"
|
||||
"\tbne 1f\n"
|
||||
"\tcpsie i\n"
|
||||
"1:\n"
|
||||
:
|
||||
: "r" (flags)
|
||||
: "memory");
|
||||
#endif
|
||||
}
|
||||
|
||||
/* Get/set IPSR */
|
||||
|
||||
static inline uint32_t getipsr(void) inline_function;
|
||||
|
|
|
@ -51,7 +51,11 @@
|
|||
*/
|
||||
|
||||
#define REG_R13 (0) /* R13 = SP at time of interrupt */
|
||||
#define REG_PRIMASK (1) /* PRIMASK */
|
||||
#ifdef CONFIG_ARMV7M_USEBASEPRI
|
||||
# define REG_BASEPRI (1) /* BASEPRI */
|
||||
#else
|
||||
# define REG_PRIMASK (1) /* PRIMASK */
|
||||
#endif
|
||||
#define REG_R4 (2) /* R4 */
|
||||
#define REG_R5 (3) /* R5 */
|
||||
#define REG_R6 (4) /* R6 */
|
||||
|
|
|
@ -51,7 +51,11 @@
|
|||
*/
|
||||
|
||||
#define REG_R13 (0) /* R13 = SP at time of interrupt */
|
||||
#define REG_PRIMASK (1) /* PRIMASK */
|
||||
#ifdef CONFIG_ARMV7M_USEBASEPRI
|
||||
# define REG_BASEPRI (1) /* BASEPRI */
|
||||
#else
|
||||
# define REG_PRIMASK (1) /* PRIMASK */
|
||||
#endif
|
||||
#define REG_R4 (2) /* R4 */
|
||||
#define REG_R5 (3) /* R5 */
|
||||
#define REG_R6 (4) /* R6 */
|
||||
|
|
|
@ -183,9 +183,43 @@
|
|||
# define STM32_NRNG 0 /* No random number generator (RNG) */
|
||||
# define STM32_NDCMI 0 /* No digital camera interface (DCMI) */
|
||||
|
||||
/* STM32 F103 Medium Density Family *************************************************/
|
||||
/* STM32F103RB is in the Medium-density performance line and is provided in 64 pin
|
||||
* packages with 128K Flash, USB, CAN, 7 timers, 2 ADCs, 9 com. interfaces
|
||||
*/
|
||||
|
||||
#elif defined(CONFIG_ARCH_CHIP_STM32F103RBT6)
|
||||
# define CONFIG_STM32_STM32F10XX 1 /* STM32F10xxx family */
|
||||
# undef CONFIG_STM32_LOWDENSITY /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 16/32 Kbytes */
|
||||
# define CONFIG_STM32_MEDIUMDENSITY 1 /* STM32F100x, STM32F101x, STM32F102x and STM32F103x w/ 64/128 Kbytes */
|
||||
# undef CONFIG_STM32_HIGHDENSITY /* STM32F100x, STM32F101x, and STM32F103x w/ 256/512 Kbytes */
|
||||
# undef CONFIG_STM32_VALUELINE /* STM32F100x */
|
||||
# undef CONFIG_STM32_CONNECTIVITYLINE /* STM32F105x and STM32F107x */
|
||||
# undef CONFIG_STM32_STM32F20XX /* STM32F205x and STM32F207x */
|
||||
# undef CONFIG_STM32_STM32F40XX /* STM32F405xx and STM32407xx families */
|
||||
# define STM32_NFSMC 0 /* FSMC */
|
||||
# define STM32_NATIM 1 /* One advanced timer TIM1 */
|
||||
# define STM32_NGTIM 3 /* General timers TIM2,3,4 */
|
||||
# define STM32_NBTIM 0 /* Two basic timers TIM6 and TIM7 */
|
||||
# define STM32_NDMA 1 /* DMA1 */
|
||||
# define STM32_NSPI 2 /* SPI1-2 */
|
||||
# define STM32_NI2S 0 /* No I2S (?) */
|
||||
# define STM32_NUSART 3 /* USART1-3 */
|
||||
# define STM32_NI2C 2 /* I2C1-2 */
|
||||
# define STM32_NCAN 1 /* bxCAN1 */
|
||||
# define STM32_NSDIO 0 /* No SDIO */
|
||||
# define STM32_NUSBOTG 0 /* No USB OTG FS/HS */
|
||||
# define STM32_NGPIO 51 /* GPIOA-E */
|
||||
# define STM32_NADC 2 /* ADC1-2 */
|
||||
# define STM32_NDAC 0 /* No DAC */
|
||||
# define STM32_NCRC 1 /* CRC */
|
||||
# define STM32_NTHERNET 0 /* No ethernet */
|
||||
# define STM32_NRNG 0 /* No random number generator (RNG) */
|
||||
# define STM32_NDCMI 0 /* No digital camera interface (DCMI) */
|
||||
|
||||
/* STM32 F103 High Density Family ***************************************************/
|
||||
/* STM32F103RC, STM32F103RD, and STM32F103RE are all provided in 64 pin packages and differ
|
||||
* only in the available FLASH and SRAM.
|
||||
/* STM32F103RC, STM32F103RD, and STM32F103RE are all provided in 64 pin packages and
|
||||
* differ only in the available FLASH and SRAM.
|
||||
*/
|
||||
|
||||
#elif defined(CONFIG_ARCH_CHIP_STM32F103RET6)
|
||||
|
@ -658,5 +692,15 @@
|
|||
# error "Unsupported STM32 chip"
|
||||
#endif
|
||||
|
||||
/* NVIC priority levels *************************************************************/
|
||||
|
||||
#define NVIC_SYSH_PRIORITY_MIN 0xf0 /* All bits set in minimum priority */
|
||||
#define NVIC_SYSH_PRIORITY_DEFAULT 0x80 /* Midpoint is the default */
|
||||
#define NVIC_SYSH_PRIORITY_MAX 0x00 /* Zero is maximum priority */
|
||||
#define NVIC_SYSH_PRIORITY_STEP 0x10 /* Four bits of interrupt priority used */
|
||||
|
||||
#define NVIC_SYSH_DISABLE_PRIORITY (NVIC_SYSH_PRIORITY_MAX + NVIC_SYSH_PRIORITY_STEP)
|
||||
#define NVIC_SYSH_SVCALL_PRIORITY NVIC_SYSH_PRIORITY_MAX
|
||||
|
||||
#endif /* __ARCH_ARM_INCLUDE_STM32_CHIP_H */
|
||||
|
||||
|
|
|
@ -44,6 +44,8 @@
|
|||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
/****************************************************************************
|
||||
* Definitions
|
||||
****************************************************************************/
|
||||
|
@ -87,7 +89,11 @@ typedef unsigned int _uintptr_t;
|
|||
*/
|
||||
|
||||
#ifdef __thumb2__
|
||||
#ifdef CONFIG_ARMV7M_USEBASEPRI
|
||||
typedef unsigned char irqstate_t;
|
||||
#else
|
||||
typedef unsigned short irqstate_t;
|
||||
#endif
|
||||
#else /* __thumb2__ */
|
||||
typedef unsigned int irqstate_t;
|
||||
#endif /* __thumb2__ */
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
/****************************************************************************
|
||||
* arch/arm/src/armv7-m/up_assert.c
|
||||
*
|
||||
* Copyright (C) 2009-2010, 2012 Gregory Nutt. All rights reserved.
|
||||
* Copyright (C) 2009-2010, 2012-2013 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
|
@ -147,8 +147,13 @@ static inline void up_registerdump(void)
|
|||
current_regs[REG_R10], current_regs[REG_R11],
|
||||
current_regs[REG_R12], current_regs[REG_R13],
|
||||
current_regs[REG_R14], current_regs[REG_R15]);
|
||||
#ifdef CONFIG_ARMV7M_USEBASEPRI
|
||||
lldbg("xPSR: %08x BASEPRI: %08x\n",
|
||||
current_regs[REG_XPSR], current_regs[REG_BASEPRI]);
|
||||
#else
|
||||
lldbg("xPSR: %08x PRIMASK: %08x\n",
|
||||
current_regs[REG_XPSR], current_regs[REG_PRIMASK]);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
#else
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/stm32/up_exception.S
|
||||
* arch/arm/src/chip/up_exception.S
|
||||
*
|
||||
* Copyright (C) 2009-2012 Gregory Nutt. All rights reserved.
|
||||
* Copyright (C) 2009-2013 Gregory Nutt. All rights reserved.
|
||||
* Copyright (C) 2012 Michael Smith. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
|
@ -100,7 +100,11 @@ exception_common:
|
|||
mov r2, r1 /* R2=Copy of the main/process stack pointer */
|
||||
add r2, #HW_XCPT_SIZE /* R2=MSP/PSP before the interrupt was taken */
|
||||
/* (ignoring the xPSR[9] alignment bit) */
|
||||
#ifdef CONFIG_ARMV7M_USEBASEPRI
|
||||
mrs r3, basepri /* R3=Current BASEPRI setting */
|
||||
#else
|
||||
mrs r3, primask /* R3=Current PRIMASK setting */
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_ARCH_FPU
|
||||
|
||||
|
@ -205,7 +209,12 @@ exception_common:
|
|||
|
||||
/* Restore the interrupt state */
|
||||
|
||||
#ifdef CONFIG_ARMV7M_USEBASEPRI
|
||||
msr basepri, r3 /* Restore interrupts priority masking*/
|
||||
cpsie i /* Re-enable interrupts */
|
||||
#else
|
||||
msr primask, r3 /* Restore interrupts */
|
||||
#endif
|
||||
|
||||
/* Always return with R14 containing the special value that will: (1)
|
||||
* return to thread mode, and (2) select the correct stack.
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
/****************************************************************************
|
||||
* arch/arm/src/armv7-m/up_hardfault.c
|
||||
*
|
||||
* Copyright (C) 2009 Gregory Nutt. All rights reserved.
|
||||
* Copyright (C) 2009, 2013 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
|
@ -55,7 +55,9 @@
|
|||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/* Debug output from this file may interfere with context switching! */
|
||||
/* If CONFIG_ARMV7M_USEBASEPRI=n, then debug output from this file may
|
||||
* interfere with context switching!
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_DEBUG_HARDFAULT
|
||||
# define hfdbg(format, arg...) lldbg(format, ##arg)
|
||||
|
@ -92,18 +94,19 @@
|
|||
|
||||
int up_hardfault(int irq, FAR void *context)
|
||||
{
|
||||
#if defined(CONFIG_DEBUG_HARDFAULT) || !defined(CONFIG_ARMV7M_USEBASEPRI)
|
||||
uint32_t *regs = (uint32_t*)context;
|
||||
uint16_t *pc;
|
||||
uint16_t insn;
|
||||
#endif
|
||||
|
||||
/* Get the value of the program counter where the fault occurred */
|
||||
|
||||
pc = (uint16_t*)regs[REG_PC] - 1;
|
||||
#ifndef CONFIG_ARMV7M_USEBASEPRI
|
||||
uint16_t *pc = (uint16_t*)regs[REG_PC] - 1;
|
||||
if ((void*)pc >= (void*)&_stext && (void*)pc < (void*)&_etext)
|
||||
{
|
||||
/* Fetch the instruction that caused the Hard fault */
|
||||
|
||||
insn = *pc;
|
||||
uint16_t insn = *pc;
|
||||
hfdbg(" PC: %p INSN: %04x\n", pc, insn);
|
||||
|
||||
/* If this was the instruction 'svc 0', then forward processing
|
||||
|
@ -116,6 +119,7 @@ int up_hardfault(int irq, FAR void *context)
|
|||
return up_svcall(irq, context);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
/* Dump some hard fault info */
|
||||
|
||||
|
@ -133,7 +137,13 @@ int up_hardfault(int irq, FAR void *context)
|
|||
hfdbg(" R8: %08x %08x %08x %08x %08x %08x %08x %08x\n",
|
||||
regs[REG_R8], regs[REG_R9], regs[REG_R10], regs[REG_R11],
|
||||
regs[REG_R12], regs[REG_R13], regs[REG_R14], regs[REG_R15]);
|
||||
hfdbg(" PSR=%08x\n", regs[REG_XPSR]);
|
||||
#ifdef CONFIG_ARMV7M_USEBASEPRI
|
||||
hfdbg(" xPSR: %08x BASEPRI: %08x (saved)\n",
|
||||
current_regs[REG_XPSR], current_regs[REG_BASEPRI]);
|
||||
#else
|
||||
hfdbg(" xPSR: %08x PRIMASK: %08x (saved)\n",
|
||||
current_regs[REG_XPSR], current_regs[REG_PRIMASK]);
|
||||
#endif
|
||||
|
||||
(void)irqsave();
|
||||
lldbg("PANIC!!! Hard fault: %08x\n", getreg32(NVIC_HFAULTS));
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
/****************************************************************************
|
||||
* arch/arm/src/armv7-m/up_initialstate.c
|
||||
*
|
||||
* Copyright (C) 2009, 2011-2 Gregory Nutt. All rights reserved.
|
||||
* Copyright (C) 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
|
||||
|
@ -156,7 +156,7 @@ void up_initial_state(_TCB *tcb)
|
|||
xcp->regs[REG_FPSCR] = 0; // XXX initial FPSCR should be configurable
|
||||
xcp->regs[REG_FPReserved] = 0;
|
||||
|
||||
#endif
|
||||
#endif /* CONFIG_ARCH_FPU */
|
||||
|
||||
#ifdef CONFIG_NUTTX_KERNEL
|
||||
if ((tcb->flags & TCB_FLAG_TTYPE_MASK) != TCB_FLAG_TTYPE_KERNEL)
|
||||
|
@ -165,7 +165,7 @@ void up_initial_state(_TCB *tcb)
|
|||
|
||||
xcp->regs[REG_EXC_RETURN] = EXC_RETURN_PROCESS_STACK;
|
||||
}
|
||||
#endif
|
||||
#endif /* CONFIG_NUTTX_KERNEL */
|
||||
|
||||
#else /* CONFIG_ARMV7M_CMNVECTOR */
|
||||
|
||||
|
@ -189,12 +189,16 @@ void up_initial_state(_TCB *tcb)
|
|||
|
||||
xcp->regs[REG_EXC_RETURN] = EXC_RETURN_UNPRIVTHR;
|
||||
}
|
||||
#endif
|
||||
#endif /* CONFIG_NUTTX_KERNEL */
|
||||
#endif /* CONFIG_ARMV7M_CMNVECTOR */
|
||||
|
||||
/* Enable or disable interrupts, based on user configuration */
|
||||
|
||||
#ifdef CONFIG_SUPPRESS_INTERRUPTS
|
||||
#ifdef CONFIG_ARMV7M_USEBASEPRI
|
||||
xcp->regs[REG_BASEPRI] = NVIC_SYSH_DISABLE_PRIORITY;
|
||||
#else
|
||||
xcp->regs[REG_PRIMASK] = 1;
|
||||
#endif
|
||||
#endif /* CONFIG_SUPPRESS_INTERRUPTS */
|
||||
}
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
/****************************************************************************
|
||||
* arch/arm/src/armv7-m/up_schedulesigaction.c
|
||||
*
|
||||
* Copyright (C) 2009-2012 Gregory Nutt. All rights reserved.
|
||||
* Copyright (C) 2009-2013 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
|
@ -155,7 +155,11 @@ void up_schedule_sigaction(_TCB *tcb, sig_deliver_t sigdeliver)
|
|||
|
||||
tcb->xcp.sigdeliver = sigdeliver;
|
||||
tcb->xcp.saved_pc = current_regs[REG_PC];
|
||||
#ifdef CONFIG_ARMV7M_USEBASEPRI
|
||||
tcb->xcp.saved_basepri = current_regs[REG_BASEPRI];
|
||||
#else
|
||||
tcb->xcp.saved_primask = current_regs[REG_PRIMASK];
|
||||
#endif
|
||||
tcb->xcp.saved_xpsr = current_regs[REG_XPSR];
|
||||
|
||||
/* Then set up to vector to the trampoline with interrupts
|
||||
|
@ -163,7 +167,11 @@ void up_schedule_sigaction(_TCB *tcb, sig_deliver_t sigdeliver)
|
|||
*/
|
||||
|
||||
current_regs[REG_PC] = (uint32_t)up_sigdeliver;
|
||||
#ifdef CONFIG_ARMV7M_USEBASEPRI
|
||||
current_regs[REG_BASEPRI] = NVIC_SYSH_DISABLE_PRIORITY;
|
||||
#else
|
||||
current_regs[REG_PRIMASK] = 1;
|
||||
#endif
|
||||
current_regs[REG_XPSR] = ARMV7M_XPSR_T;
|
||||
|
||||
/* And make sure that the saved context in the TCB
|
||||
|
@ -189,7 +197,11 @@ void up_schedule_sigaction(_TCB *tcb, sig_deliver_t sigdeliver)
|
|||
|
||||
tcb->xcp.sigdeliver = sigdeliver;
|
||||
tcb->xcp.saved_pc = tcb->xcp.regs[REG_PC];
|
||||
#ifdef CONFIG_ARMV7M_USEBASEPRI
|
||||
tcb->xcp.saved_basepri = tcb->xcp.regs[REG_BASEPRI];
|
||||
#else
|
||||
tcb->xcp.saved_primask = tcb->xcp.regs[REG_PRIMASK];
|
||||
#endif
|
||||
tcb->xcp.saved_xpsr = tcb->xcp.regs[REG_XPSR];
|
||||
|
||||
/* Then set up to vector to the trampoline with interrupts
|
||||
|
@ -197,7 +209,11 @@ void up_schedule_sigaction(_TCB *tcb, sig_deliver_t sigdeliver)
|
|||
*/
|
||||
|
||||
tcb->xcp.regs[REG_PC] = (uint32_t)up_sigdeliver;
|
||||
#ifdef CONFIG_ARMV7M_USEBASEPRI
|
||||
tcb->xcp.regs[REG_BASEPRI] = NVIC_SYSH_DISABLE_PRIORITY;
|
||||
#else
|
||||
tcb->xcp.regs[REG_PRIMASK] = 1;
|
||||
#endif
|
||||
tcb->xcp.regs[REG_XPSR] = ARMV7M_XPSR_T;
|
||||
}
|
||||
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
/****************************************************************************
|
||||
* arch/arm/src/armv7-m/up_sigdeliver.c
|
||||
*
|
||||
* Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
|
||||
* Copyright (C) 2009-2010, 2013 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
|
@ -102,7 +102,11 @@ void up_sigdeliver(void)
|
|||
|
||||
up_copystate(regs, rtcb->xcp.regs);
|
||||
regs[REG_PC] = rtcb->xcp.saved_pc;
|
||||
#ifdef CONFIG_ARMV7M_USEBASEPRI
|
||||
regs[REG_BASEPRI] = rtcb->xcp.saved_basepri;
|
||||
#else
|
||||
regs[REG_PRIMASK] = rtcb->xcp.saved_primask;
|
||||
#endif
|
||||
regs[REG_XPSR] = rtcb->xcp.saved_xpsr;
|
||||
|
||||
/* Get a local copy of the sigdeliver function pointer. We do this so that
|
||||
|
@ -115,7 +119,11 @@ void up_sigdeliver(void)
|
|||
|
||||
/* Then restore the task interrupt state */
|
||||
|
||||
#ifdef CONFIG_ARMV7M_USEBASEPRI
|
||||
irqrestore((uint8_t)regs[REG_BASEPRI]);
|
||||
#else
|
||||
irqrestore((uint16_t)regs[REG_PRIMASK]);
|
||||
#endif
|
||||
|
||||
/* Deliver the signals */
|
||||
|
||||
|
|
|
@ -457,32 +457,38 @@ config STM32_USART1
|
|||
bool "USART1"
|
||||
default n
|
||||
select ARCH_HAVE_USART1
|
||||
select STM32_USART
|
||||
|
||||
config STM32_USART2
|
||||
bool "USART2"
|
||||
default n
|
||||
select ARCH_HAVE_USART2
|
||||
select STM32_USART
|
||||
|
||||
config STM32_USART3
|
||||
bool "USART3"
|
||||
default n
|
||||
select ARCH_HAVE_USART3
|
||||
select STM32_USART
|
||||
|
||||
config STM32_UART4
|
||||
bool "UART4"
|
||||
default n
|
||||
select ARCH_HAVE_UART4
|
||||
select STM32_USART
|
||||
|
||||
config STM32_UART5
|
||||
bool "UART5"
|
||||
default n
|
||||
select ARCH_HAVE_UART5
|
||||
select STM32_USART
|
||||
|
||||
config STM32_USART6
|
||||
bool "USART6"
|
||||
default n
|
||||
depends on STM32_STM32F20XX || STM32_STM32F40XX
|
||||
select ARCH_HAVE_USART6
|
||||
select STM32_USART
|
||||
|
||||
config STM32_USB
|
||||
bool "USB Device"
|
||||
|
@ -1804,8 +1810,11 @@ config STM32_TIM14_DAC2
|
|||
|
||||
endchoice
|
||||
|
||||
config STM32_USART
|
||||
bool
|
||||
|
||||
menu "U[S]ART Configuration"
|
||||
depends on STM32_USART1 || STM32_USART2 || STM32_USART3 || STM32_USART4 || STM32_USART5 || STM32_USART6
|
||||
depends on STM32_USART
|
||||
|
||||
config USART1_RS485
|
||||
bool "RS-485 on USART1"
|
||||
|
@ -1968,6 +1977,14 @@ config SERIAL_TERMIOS
|
|||
|
||||
endmenu
|
||||
|
||||
config STM32_USART_SINGLEWIRE
|
||||
bool "Single Wire Support"
|
||||
default n
|
||||
depends on STM32_USART
|
||||
---help---
|
||||
Enable single wire UART support. The option enables support for the
|
||||
TIOCSSINGLEWIRE ioctl in the STM32 serial driver.
|
||||
|
||||
menu "SPI Configuration"
|
||||
depends on STM32_SPI
|
||||
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
/************************************************************************************
|
||||
* arch/arm/src/stm32/chip.h
|
||||
*
|
||||
* Copyright (C) 2009, 2011-2012 Gregory Nutt. All rights reserved.
|
||||
* Copyright (C) 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
|
||||
|
|
|
@ -68,12 +68,6 @@
|
|||
# undef CONFIG_DEBUG_QENCODER
|
||||
#endif
|
||||
|
||||
/* NVIC priority levels *************************************************************/
|
||||
|
||||
#define NVIC_SYSH_PRIORITY_MIN 0xff /* All bits set in minimum priority */
|
||||
#define NVIC_SYSH_PRIORITY_DEFAULT 0x80 /* Midpoint is the default */
|
||||
#define NVIC_SYSH_PRIORITY_MAX 0x00 /* Zero is maximum priority */
|
||||
|
||||
/* Peripherals **********************************************************************/
|
||||
|
||||
#include "chip.h"
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/stm32/stm32_irq.c
|
||||
* arch/arm/src/chip/stm32_irq.c
|
||||
*
|
||||
* Copyright (C) 2009-2012 Gregory Nutt. All rights reserved.
|
||||
* Copyright (C) 2009-2013 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
|
@ -194,6 +194,29 @@ static int stm32_reserved(int irq, FAR void *context)
|
|||
}
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Name: stm32_prioritize_syscall
|
||||
*
|
||||
* Description:
|
||||
* Set the priority of an exception. This function may be needed
|
||||
* internally even if support for prioritized interrupts is not enabled.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef CONFIG_ARMV7M_USEBASEPRI
|
||||
static inline void stm32_prioritize_syscall(int priority)
|
||||
{
|
||||
uint32_t regval;
|
||||
|
||||
/* SVCALL is system handler 11 */
|
||||
|
||||
regval = getreg32(NVIC_SYSH8_11_PRIORITY);
|
||||
regval &= ~NVIC_SYSH_PRIORITY_PR11_MASK;
|
||||
regval |= (priority << NVIC_SYSH_PRIORITY_PR11_SHIFT);
|
||||
putreg32(regval, NVIC_SYSH8_11_PRIORITY);
|
||||
}
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Name: stm32_irqinfo
|
||||
*
|
||||
|
@ -334,6 +357,9 @@ void up_irqinitialize(void)
|
|||
|
||||
#ifdef CONFIG_ARCH_IRQPRIO
|
||||
/* up_prioritize_irq(STM32_IRQ_PENDSV, NVIC_SYSH_PRIORITY_MIN); */
|
||||
#endif
|
||||
#ifdef CONFIG_ARMV7M_USEBASEPRI
|
||||
stm32_prioritize_syscall(NVIC_SYSH_SVCALL_PRIORITY);
|
||||
#endif
|
||||
|
||||
/* If the MPU is enabled, then attach and enable the Memory Management
|
||||
|
@ -365,8 +391,7 @@ void up_irqinitialize(void)
|
|||
|
||||
/* And finally, enable interrupts */
|
||||
|
||||
setbasepri(NVIC_SYSH_PRIORITY_MAX);
|
||||
irqrestore(0);
|
||||
irqenable();
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@ -451,15 +476,28 @@ int up_prioritize_irq(int irq, int priority)
|
|||
uint32_t regval;
|
||||
int shift;
|
||||
|
||||
DEBUGASSERT(irq >= STM32_IRQ_MEMFAULT && irq < NR_IRQS && (unsigned)priority <= NVIC_SYSH_PRIORITY_MIN);
|
||||
#ifdef CONFIG_ARMV7M_USEBASEPRI
|
||||
DEBUGASSERT(irq >= STM32_IRQ_MEMFAULT && irq < NR_IRQS &&
|
||||
priority >= NVIC_SYSH_DISABLE_PRIORITY &&
|
||||
priority <= NVIC_SYSH_PRIORITY_MIN);
|
||||
#else
|
||||
DEBUGASSERT(irq >= STM32_IRQ_MEMFAULT && irq < NR_IRQS &&
|
||||
(unsigned)priority <= NVIC_SYSH_PRIORITY_MIN);
|
||||
#endif
|
||||
|
||||
if (irq < STM32_IRQ_INTERRUPTS)
|
||||
{
|
||||
irq -= 4;
|
||||
/* NVIC_SYSH_PRIORITY() maps {0..15} to one of three priority
|
||||
* registers (0-3 are invalid)
|
||||
*/
|
||||
|
||||
regaddr = NVIC_SYSH_PRIORITY(irq);
|
||||
irq -= 4;
|
||||
}
|
||||
else
|
||||
{
|
||||
/* NVIC_IRQ_PRIORITY() maps {0..} to one of many priority registers */
|
||||
|
||||
irq -= STM32_IRQ_INTERRUPTS;
|
||||
regaddr = NVIC_IRQ_PRIORITY(irq);
|
||||
}
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
/****************************************************************************
|
||||
* arch/arm/src/stm32/stm32_serial.c
|
||||
*
|
||||
* Copyright (C) 2009-2012 Gregory Nutt. All rights reserved.
|
||||
* Copyright (C) 2009-2013 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
|
@ -1439,6 +1439,31 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
|
|||
}
|
||||
break;
|
||||
|
||||
#ifdef CONFIG_STM32_USART_SINGLEWIRE
|
||||
case TIOCSSINGLEWIRE:
|
||||
{
|
||||
/* Change the TX port to be open-drain/push-pull and enable/disable
|
||||
* half-duplex mode.
|
||||
*/
|
||||
|
||||
uint32_t cr = up_serialin(priv, STM32_USART_CR3_OFFSET);
|
||||
|
||||
if (arg == SER_SINGLEWIRE_ENABLED)
|
||||
{
|
||||
stm32_configgpio(priv->tx_gpio | GPIO_OPENDRAIN);
|
||||
cr |= USART_CR3_HDSEL;
|
||||
}
|
||||
else
|
||||
{
|
||||
stm32_configgpio(priv->tx_gpio | GPIO_PUSHPULL);
|
||||
cr &= ~USART_CR3_HDSEL;
|
||||
}
|
||||
|
||||
up_serialout(priv, STM32_USART_CR3_OFFSET, cr);
|
||||
}
|
||||
break;
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_SERIAL_TERMIOS
|
||||
case TCGETS:
|
||||
{
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/stm32/stm32_vectors.S
|
||||
* arch/arm/src/chip/stm32_vectors.S
|
||||
*
|
||||
* Copyright (C) 2009-2012 Gregory Nutt. All rights reserved.
|
||||
* Copyright (C) 2009-2013 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
|
@ -235,7 +235,11 @@ stm32_common:
|
|||
|
||||
mov r2, r1 /* R2=Copy of the main/process stack pointer */
|
||||
add r2, #HW_XCPT_SIZE /* R2=MSP/PSP before the interrupt was taken */
|
||||
#ifdef CONFIG_ARMV7M_USEBASEPRI
|
||||
mrs r3, basepri /* R3=Current BASEPRI setting */
|
||||
#else
|
||||
mrs r3, primask /* R3=Current PRIMASK setting */
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_ARCH_FPU
|
||||
/* Skip over the block of memory reserved for floating pointer register save.
|
||||
|
@ -248,8 +252,8 @@ stm32_common:
|
|||
#endif
|
||||
|
||||
/* Save the the remaining registers on the stack after the registers pushed
|
||||
* by the exception handling logic. r2=SP and r3=primask, r4-r11,r14=register
|
||||
* values.
|
||||
* by the exception handling logic. r2=SP and r3=primask or basepri, r4-r11,
|
||||
* r14=register values.
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_NUTTX_KERNEL
|
||||
|
@ -349,7 +353,7 @@ stm32_common:
|
|||
* Here:
|
||||
* r1 = Address on the target thread's stack position at the start of
|
||||
* the registers saved by hardware
|
||||
* r3 = primask
|
||||
* r3 = primask or basepri
|
||||
* r4-r11 = restored register values
|
||||
*/
|
||||
2:
|
||||
|
@ -375,7 +379,12 @@ stm32_common:
|
|||
|
||||
/* Restore the interrupt state */
|
||||
|
||||
#ifdef CONFIG_ARMV7M_USEBASEPRI
|
||||
msr basepri, r3 /* Restore interrupts priority masking*/
|
||||
cpsie i /* Re-enable interrupts */
|
||||
#else
|
||||
msr primask, r3 /* Restore interrupts */
|
||||
#endif
|
||||
|
||||
/* Always return with R14 containing the special value that will: (1)
|
||||
* return to thread mode, and (2) continue to use the MSP
|
||||
|
|
|
@ -52,6 +52,10 @@ ifeq ($(CONFIG_BINFMT_EXEPATH),y)
|
|||
BINFMT_CSRCS += binfmt_exepath.c
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_SCHED_HAVE_PARENT),y)
|
||||
BINFMT_CSRCS += binfmt_schedunload.c
|
||||
endif
|
||||
|
||||
# Symbol table source files
|
||||
|
||||
BINFMT_CSRCS += symtab_findbyname.c symtab_findbyvalue.c
|
||||
|
|
|
@ -43,6 +43,7 @@
|
|||
#include <debug.h>
|
||||
#include <errno.h>
|
||||
|
||||
#include <nuttx/kmalloc.h>
|
||||
#include <nuttx/binfmt/binfmt.h>
|
||||
|
||||
#include "binfmt_internal.h"
|
||||
|
@ -74,7 +75,9 @@
|
|||
*
|
||||
* Description:
|
||||
* This is a convenience function that wraps load_ and exec_module into
|
||||
* one call.
|
||||
* one call. If CONFIG_SCHED_ONEXIT is also defined, this function will
|
||||
* automatically call schedule_unload() to unload the module when task
|
||||
* exits.
|
||||
*
|
||||
* Input Parameter:
|
||||
* filename - Fulll path to the binary to be loaded
|
||||
|
@ -84,7 +87,7 @@
|
|||
*
|
||||
* Returned Value:
|
||||
* This is an end-user function, so it follows the normal convention:
|
||||
* Returns the PID of the exec'ed module. On failure, it.returns
|
||||
* It returns the PID of the exec'ed module. On failure, it returns
|
||||
* -1 (ERROR) and sets errno appropriately.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
@ -92,6 +95,66 @@
|
|||
int exec(FAR const char *filename, FAR const char **argv,
|
||||
FAR const struct symtab_s *exports, int nexports)
|
||||
{
|
||||
#ifdef CONFIG_SCHED_ONEXIT
|
||||
FAR struct binary_s *bin;
|
||||
int pid;
|
||||
int ret;
|
||||
|
||||
/* Allocate the load information */
|
||||
|
||||
bin = (FAR struct binary_s *)kzalloc(sizeof(struct binary_s));
|
||||
if (!bin)
|
||||
{
|
||||
set_errno(ENOMEM);
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
/* Load the module into memory */
|
||||
|
||||
bin->filename = filename;
|
||||
bin->exports = exports;
|
||||
bin->nexports = nexports;
|
||||
|
||||
ret = load_module(bin);
|
||||
if (ret < 0)
|
||||
{
|
||||
bdbg("ERROR: Failed to load program '%s'\n", filename);
|
||||
kfree(bin);
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
/* Disable pre-emption so that the executed module does
|
||||
* not return until we get a chance to connect the on_exit
|
||||
* handler.
|
||||
*/
|
||||
|
||||
sched_lock();
|
||||
|
||||
/* Then start the module */
|
||||
|
||||
pid = exec_module(bin);
|
||||
if (pid < 0)
|
||||
{
|
||||
bdbg("ERROR: Failed to execute program '%s'\n", filename);
|
||||
sched_unlock();
|
||||
unload_module(bin);
|
||||
kfree(bin);
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
/* Set up to unload the module (and free the binary_s structure)
|
||||
* when the task exists.
|
||||
*/
|
||||
|
||||
ret = schedule_unload(pid, bin);
|
||||
if (ret < 0)
|
||||
{
|
||||
bdbg("ERROR: Failed to schedul unload '%s'\n", filename);
|
||||
}
|
||||
|
||||
sched_unlock();
|
||||
return pid;
|
||||
#else
|
||||
struct binary_s bin;
|
||||
int ret;
|
||||
|
||||
|
@ -119,7 +182,10 @@ int exec(FAR const char *filename, FAR const char **argv,
|
|||
return ERROR;
|
||||
}
|
||||
|
||||
/* TODO: How does the module get unloaded in this case? */
|
||||
|
||||
return ret;
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif /* CONFIG_BINFMT_DISABLE */
|
||||
|
|
|
@ -84,6 +84,7 @@
|
|||
static int load_default_priority(FAR struct binary_s *bin)
|
||||
{
|
||||
struct sched_param param;
|
||||
int ret;
|
||||
|
||||
/* Get the priority of this thread */
|
||||
|
||||
|
@ -97,6 +98,7 @@ static int load_default_priority(FAR struct binary_s *bin)
|
|||
/* Save that as the priority of child thread */
|
||||
|
||||
bin->priority = param.sched_priority;
|
||||
return ret;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
|
@ -180,7 +182,7 @@ int load_module(FAR struct binary_s *bin)
|
|||
{
|
||||
/* Set the default priority of the new program. */
|
||||
|
||||
ret = load_default_priority(bin)
|
||||
ret = load_default_priority(bin);
|
||||
if (ret < 0)
|
||||
{
|
||||
/* The errno is already set in this case */
|
||||
|
|
|
@ -0,0 +1,333 @@
|
|||
/****************************************************************************
|
||||
* binfmt/binfmt_schedunload.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 <sched.h>
|
||||
#include <debug.h>
|
||||
#include <errno.h>
|
||||
|
||||
#include <nuttx/kmalloc.h>
|
||||
#include <nuttx/binfmt/binfmt.h>
|
||||
|
||||
#include "binfmt_internal.h"
|
||||
|
||||
#if !defined(CONFIG_BINFMT_DISABLE) && defined(CONFIG_SCHED_HAVE_PARENT)
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Function Prototypes
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
|
||||
FAR struct binary_s *g_unloadhead;
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: unload_list_add
|
||||
*
|
||||
* Description:
|
||||
* If CONFIG_SCHED_HAVE_PARENT is defined then schedul_unload() will
|
||||
* manage instances of struct binary_s allocated with kmalloc. It
|
||||
* will keep the binary data in a link list and when SIGCHLD is received
|
||||
* (meaning that the task has exit'ed, schedul_unload() will find the
|
||||
* data, unload the module, and free the structure.
|
||||
*
|
||||
* This function will add one structure to the linked list
|
||||
*
|
||||
* Input Parameter:
|
||||
* pid - The task ID of the child task
|
||||
* bin - This structure must have been allocated with kmalloc() and must
|
||||
* persist until the task unloads
|
||||
|
||||
*
|
||||
* Returned Value:
|
||||
* None
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static void unload_list_add(pid_t pid, FAR struct binary_s *bin)
|
||||
{
|
||||
irqstate_t flags;
|
||||
|
||||
/* Save the PID in the structure so that we recover it later */
|
||||
|
||||
bin->pid = pid;
|
||||
|
||||
/* Disable deliver of any signals while we muck with the list. The graceful
|
||||
* way to do this would be block delivery of SIGCHLD would be with
|
||||
* sigprocmask. Here we do it the quick'n'dirty way by just disabling
|
||||
* interrupts.
|
||||
*/
|
||||
|
||||
flags = irqsave();
|
||||
bin->flink = g_unloadhead;
|
||||
g_unloadhead = bin;
|
||||
irqrestore(flags);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: unload_list_remove
|
||||
*
|
||||
* Description:
|
||||
* If CONFIG_SCHED_HAVE_PARENT is defined then schedul_unload() will
|
||||
* manage instances of struct binary_s allocated with kmalloc. It
|
||||
* will keep the binary data in a link list and when SIGCHLD is received
|
||||
* (meaning that the task has exit'ed, schedul_unload() will find the
|
||||
* data, unload the module, and free the structure.
|
||||
*
|
||||
* This function will remove one structure to the linked list
|
||||
*
|
||||
* Input Parameter:
|
||||
* pid - The task ID of the child task
|
||||
*
|
||||
* Returned Value:
|
||||
* On success, the load structure is returned. NULL is returned on
|
||||
* failure.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static FAR struct binary_s *unload_list_remove(pid_t pid)
|
||||
{
|
||||
FAR struct binary_s *curr;
|
||||
FAR struct binary_s *prev;
|
||||
|
||||
/* Note the asymmetry. We do not have to disable interrupts here because
|
||||
* the main thread cannot run while we are in the interrupt handler. Here,
|
||||
* it should be sufficient to disable pre-emption so that no other thread
|
||||
* can run.
|
||||
*/
|
||||
|
||||
sched_lock();
|
||||
|
||||
/* Find the structure in the unload list with the matching PID */
|
||||
|
||||
for (prev = NULL, curr = g_unloadhead;
|
||||
curr && (curr->pid != pid);
|
||||
prev = curr, curr = curr->flink);
|
||||
|
||||
/* Did we find it? It must be there. Hmmm.. we should probably ASSERT if
|
||||
* we do not!
|
||||
*/
|
||||
|
||||
if (curr)
|
||||
{
|
||||
/* Was there another entry before this one? */
|
||||
|
||||
if (prev)
|
||||
{
|
||||
/* Yes.. remove the current entry from after the previous entry */
|
||||
|
||||
prev->flink = curr->flink;
|
||||
}
|
||||
else
|
||||
{
|
||||
/* No.. remove the current entry from the head of the list */
|
||||
|
||||
g_unloadhead = curr->flink;
|
||||
}
|
||||
|
||||
/* Nullify the forward link ... superstitious */
|
||||
|
||||
curr->flink = NULL;
|
||||
}
|
||||
|
||||
sched_unlock();
|
||||
return curr;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: unload_callback
|
||||
*
|
||||
* Description:
|
||||
* If CONFIG_SCHED_HAVE_PARENT is defined, this function may be called to
|
||||
* automatically unload the module when task exits. It assumes that
|
||||
* bin was allocated with kmalloc() or friends and will also automatically
|
||||
* free the structure with kfree() when the task exists.
|
||||
*
|
||||
* Input Parameter:
|
||||
* pid - The ID of the task that just exited
|
||||
* arg - A reference to the load structure cast to FAR void *
|
||||
*
|
||||
* Returned Value:
|
||||
* None
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static void unload_callback(int signo, siginfo_t *info, void *ucontext)
|
||||
{
|
||||
FAR struct binary_s *bin;
|
||||
int ret;
|
||||
|
||||
/* Sanity checking */
|
||||
|
||||
if (!info || signo != SIGCHLD)
|
||||
{
|
||||
blldbg("ERROR:Bad signal callback: signo=%d info=%p\n", signo, callback);
|
||||
return;
|
||||
}
|
||||
|
||||
/* Get the load information for this pid */
|
||||
|
||||
bin = unload_list_remove(info->si_pid);
|
||||
if (!bin)
|
||||
{
|
||||
blldbg("ERROR: Could not find load info for PID=%d\n", info->si_pid);
|
||||
return;
|
||||
}
|
||||
|
||||
/* Unload the module */
|
||||
|
||||
ret = unload_module(bin);
|
||||
if (ret < 0)
|
||||
{
|
||||
blldbg("ERROR: unload_module failed: %d\n", get_errno());
|
||||
}
|
||||
|
||||
/* Free the load structure */
|
||||
|
||||
kfree(bin);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: schedule_unload
|
||||
*
|
||||
* Description:
|
||||
* If CONFIG_SCHED_HAVE_PARENT is defined, this function may be called by
|
||||
* the parent of the the newly created task to automatically unload the
|
||||
* module when the task exits. This assumes that (1) the caller is the
|
||||
* parent of the created task, (2) that bin was allocated with kmalloc()
|
||||
* or friends. It will also automatically free the structure with kfree()
|
||||
* after unloading the module.
|
||||
*
|
||||
* Input Parameter:
|
||||
* pid - The task ID of the child task
|
||||
* bin - This structure must have been allocated with kmalloc() and must
|
||||
* persist until the task unloads
|
||||
*
|
||||
* Returned Value:
|
||||
* This is an end-user function, so it follows the normal convention:
|
||||
* It returns 0 (OK) if the callback was successfully scheduled. On
|
||||
* failure, it returns -1 (ERROR) and sets errno appropriately.
|
||||
*
|
||||
* On failures, the 'bin' structure will not be deallocated and the
|
||||
* module not not be unloaded.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
int schedule_unload(pid_t pid, FAR struct binary_s *bin)
|
||||
{
|
||||
struct sigaction act;
|
||||
struct sigaction oact;
|
||||
sigset_t sigset;
|
||||
irqstate_t flags;
|
||||
int errorcode;
|
||||
int ret;
|
||||
|
||||
/* Make sure that SIGCHLD is unmasked */
|
||||
|
||||
(void)sigemptyset(&sigset);
|
||||
(void)sigaddset(&sigset, SIGCHLD);
|
||||
ret = sigprocmask(SIG_UNBLOCK, &sigset, NULL);
|
||||
if (ret != OK)
|
||||
{
|
||||
/* The errno value will get trashed by the following debug output */
|
||||
|
||||
errorcode = get_errno();
|
||||
bvdbg("ERROR: sigprocmask failed: %d\n", ret);
|
||||
goto errout;
|
||||
}
|
||||
|
||||
/* Add the structure to the list. We want to do this *before* connecting
|
||||
* the signal handler. This does, however, make error recovery more
|
||||
* complex if sigaction() fails below because then we have to remove the
|
||||
* unload structure for the list in an unexpected context.
|
||||
*/
|
||||
|
||||
unload_list_add(pid, bin);
|
||||
|
||||
/* Register the SIGCHLD handler */
|
||||
|
||||
act.sa_sigaction = unload_callback;
|
||||
act.sa_flags = SA_SIGINFO;
|
||||
|
||||
(void)sigfillset(&act.sa_mask);
|
||||
(void)sigdelset(&act.sa_mask, SIGCHLD);
|
||||
|
||||
ret = sigaction(SIGCHLD, &act, &oact);
|
||||
if (ret != OK)
|
||||
{
|
||||
/* The errno value will get trashed by the following debug output */
|
||||
|
||||
errorcode = get_errno();
|
||||
bvdbg("ERROR: sigaction failed: %d\n" , ret);
|
||||
|
||||
/* Emergency removal from the list */
|
||||
|
||||
flags = irqsave();
|
||||
if (unload_list_remove(pid) != bin)
|
||||
{
|
||||
blldbg("ERROR: Failed to remove structure\n");
|
||||
}
|
||||
|
||||
goto errout;
|
||||
}
|
||||
|
||||
return OK;
|
||||
|
||||
errout:
|
||||
set_errno(errorcode);
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
#endif /* !CONFIG_BINFMT_DISABLE && CONFIG_SCHED_HAVE_PARENT */
|
||||
|
|
@ -89,6 +89,7 @@ static struct binfmt_s g_builtin_binfmt =
|
|||
static int builtin_loadbinary(struct binary_s *binp)
|
||||
{
|
||||
FAR const char *filename;
|
||||
FAR const struct builtin_s *b;
|
||||
int fd;
|
||||
int index;
|
||||
int ret;
|
||||
|
@ -97,11 +98,11 @@ static int builtin_loadbinary(struct binary_s *binp)
|
|||
|
||||
/* Open the binary file for reading (only) */
|
||||
|
||||
fd = open(filename, O_RDONLY);
|
||||
fd = open(binp->filename, O_RDONLY);
|
||||
if (fd < 0)
|
||||
{
|
||||
int errval = errno;
|
||||
bdbg("ERROR: Failed to open binary %s: %d\n", filename, errval);
|
||||
bdbg("ERROR: Failed to open binary %s: %d\n", binp->filename, errval);
|
||||
return -errval;
|
||||
}
|
||||
|
||||
|
@ -134,9 +135,10 @@ static int builtin_loadbinary(struct binary_s *binp)
|
|||
* the priority. That is a bug and needs to be fixed.
|
||||
*/
|
||||
|
||||
binp->entrypt = g_builtins[index].main;
|
||||
binp->stacksize = g_builtins[index].stacksize;
|
||||
binp->priority = g_builtins[index].priority;
|
||||
b = builtin_for_index(index);
|
||||
binp->entrypt = b->main;
|
||||
binp->stacksize = b->stacksize;
|
||||
binp->priority = b->priority;
|
||||
return OK;
|
||||
}
|
||||
|
||||
|
|
|
@ -83,10 +83,14 @@
|
|||
|
||||
FAR const char *builtin_getname(int index)
|
||||
{
|
||||
if (index < 0 || index >= number_builtins())
|
||||
{
|
||||
return NULL;
|
||||
}
|
||||
FAR const struct builtin_s *builtin;
|
||||
|
||||
return g_builtins[index].name;
|
||||
builtin = builtin_for_index(index);
|
||||
|
||||
if (builtin != NULL)
|
||||
{
|
||||
return builtin->name;
|
||||
}
|
||||
|
||||
return NULL;
|
||||
}
|
||||
|
|
|
@ -80,18 +80,19 @@
|
|||
* Name: builtin_isavail
|
||||
*
|
||||
* Description:
|
||||
* Return the index into the table of applications for the applicaiton with
|
||||
* Return the index into the table of applications for the application with
|
||||
* the name 'appname'.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
int builtin_isavail(FAR const char *appname)
|
||||
{
|
||||
FAR const char *name;
|
||||
int i;
|
||||
|
||||
for (i = 0; g_builtins[i].name; i++)
|
||||
for (i = 0; (name = builtin_getname(i)); i++)
|
||||
{
|
||||
if (!strncmp(g_builtins[i].name, appname, NAME_MAX))
|
||||
if (!strncmp(name, appname, NAME_MAX))
|
||||
{
|
||||
return i;
|
||||
}
|
||||
|
|
|
@ -334,12 +334,79 @@ defconfig -- This is a configuration file similar to the Linux
|
|||
CONFIG_TASK_NAME_SIZE - Specifies that maximum size of a
|
||||
task name to save in the TCB. Useful if scheduler
|
||||
instrumentation is selected. Set to zero to disable.
|
||||
CONFIG_SCHED_HAVE_PARENT - Remember the ID of the parent thread
|
||||
when a new child thread is created. This support enables some
|
||||
CONFIG_SCHED_HAVE_PARENT - Remember the ID of the parent task
|
||||
when a new child task is created. This support enables some
|
||||
additional features (such as SIGCHLD) and modifies the behavior
|
||||
of other interfaces. For example, it makes waitpid() more
|
||||
standards complete by restricting the waited-for tasks to the
|
||||
children of the caller. Default: disabled.
|
||||
CONFIG_SCHED_CHILD_STATUS
|
||||
If this option is selected, then the exit status of the child task
|
||||
will be retained after the child task exits. This option should be
|
||||
selected if you require knowledge of a child process' exit status.
|
||||
Without this setting, wait(), waitpid() or waitid() may fail. For
|
||||
example, if you do:
|
||||
|
||||
1) Start child task
|
||||
2) Wait for exit status (using wait(), waitpid(), or waitid()).
|
||||
|
||||
This can fail because the child task may run to completion before
|
||||
the wait begins. There is a non-standard work-around in this case:
|
||||
The above sequence will work if you disable pre-emption using
|
||||
sched_lock() prior to starting the child task, then re-enable pre-
|
||||
emption with sched_unlock() after the wait completes. This works
|
||||
because the child task is not permitted to run until the wait is in
|
||||
place.
|
||||
|
||||
The standard solution would be to enable CONFIG_SCHED_CHILD_STATUS. In
|
||||
this case the exit status of the child task is retained after the
|
||||
child exits and the wait will successful obtain the child task's
|
||||
exit status whether it is called before the child task exits or not.
|
||||
|
||||
Warning: If you enable this feature, then your application must
|
||||
either (1) take responsibility for reaping the child status with wait(),
|
||||
waitpid(), or waitid(), or (2) suppress retention of child status.
|
||||
If you do not reap the child status, then you have a memory leak and
|
||||
your system will eventually fail.
|
||||
|
||||
Retention of child status can be suppressed on the parent using logic like:
|
||||
|
||||
struct sigaction sa;
|
||||
|
||||
sa.sa_handler = SIG_IGN;
|
||||
sa.sa_flags = SA_NOCLDWAIT;
|
||||
int ret = sigaction(SIGCHLD, &sa, NULL);
|
||||
|
||||
CONFIG_PREALLOC_CHILDSTATUS
|
||||
To prevent runaway child status allocations and to improve
|
||||
allocation performance, child task exit status structures are pre-
|
||||
allocated when the system boots. This setting determines the number
|
||||
of child status structures that will be pre-allocated. If this
|
||||
setting is not defined or if it is defined to be zero then a value
|
||||
of 2*MAX_TASKS is used.
|
||||
|
||||
Note that there cannot be more that CONFIG_MAX_TASKS tasks in total.
|
||||
However, the number of child status structures may need to be
|
||||
significantly larger because this number includes the maximum number
|
||||
of tasks that are running PLUS the number of tasks that have exit'ed
|
||||
without having their exit status reaped (via wait(), waitid(), or
|
||||
waitpid()).
|
||||
|
||||
Obviously, if tasks spawn children indefinitely and never have the
|
||||
exit status reaped, then you may have a memory leak! If you enable
|
||||
the SCHED_CHILD_STATUS feature, then your application must take
|
||||
responsibility for either (1) reaping the child status with wait(),
|
||||
waitpid(), or waitid() or it must (2) suppress retention of child
|
||||
status. Otherwise, your system will eventually fail.
|
||||
|
||||
Retention of child status can be suppressed on the parent using logic like:
|
||||
|
||||
struct sigaction sa;
|
||||
|
||||
sa.sa_handler = SIG_IGN;
|
||||
sa.sa_flags = SA_NOCLDWAIT;
|
||||
int ret = sigaction(SIGCHLD, &sa, NULL);
|
||||
|
||||
CONFIG_START_YEAR, CONFIG_START_MONTH, CONFIG_START_DAY -
|
||||
Used to initialize the internal time logic.
|
||||
CONFIG_GREGORIAN_TIME - Enables Gregorian time conversions.
|
||||
|
|
|
@ -119,47 +119,71 @@ that support additional LCDs. LCD drivers in the configuration directory
|
|||
if they support some differ LCD interface (such as a parallel interface)
|
||||
that makes then less re-usable:
|
||||
|
||||
configs/compal_e99/src/ssd1783.c
|
||||
SSD1783 Drivers:
|
||||
|
||||
SSD1783
|
||||
configs/compal_e99/src/ssd1783.c
|
||||
|
||||
configs/hymini-stm32v/src/ssd1289.c. See also drivers/lcd/ssd1298.c
|
||||
above.
|
||||
SSD1289 Drivers:
|
||||
|
||||
configs/hymini-stm32v/src/ssd1289.c. See also drivers/lcd/ssd1298.c
|
||||
above.
|
||||
configs/stm32f4discovery/src/up_ssd1289.c. This examples is the
|
||||
bottom half for the SSD1289 driver at drivers/lcd/ssd1289.c
|
||||
configs/hymini-stm32v/src/ssd1289.c. See also drivers/lcd/ssd1298.c
|
||||
above.
|
||||
configs/shenzhou/src/up_ssd1289.c
|
||||
|
||||
kwikstik-k40:
|
||||
|
||||
SSD1289
|
||||
configs/kwikstik-k40/src/up_lcd.c. Don't waste your time. This is
|
||||
just a stub.
|
||||
|
||||
configs/kwikstik-k40/src/up_lcd.c. Don't waste your time. This is
|
||||
just a stub.
|
||||
Nokia LCD Drivers:
|
||||
|
||||
configs/olimex-lpc1766stk/src/up_lcd.c. This examples is the
|
||||
bottom half for the SSD1289 driver at drivers/lcd/nokia6100.c.
|
||||
This was never completedly debugged ... there are probably issues
|
||||
with that nasty 9-bit SPI interfaces.
|
||||
configs/olimex-lpc1766stk/src/up_lcd.c. This examples is the
|
||||
bottom half for the driver at drivers/lcd/nokia6100.c.
|
||||
This was never completedly debugged ... there are probably issues
|
||||
with that nasty 9-bit SPI interfaces.
|
||||
|
||||
configs/sam3u-ek/src/up_lcd.c
|
||||
|
||||
The SAM3U-EK developement board features a TFT/Transmissive color
|
||||
LCD module with touch-screen, FTM280C12D, with integrated driver IC
|
||||
HX8346.
|
||||
HX8346:
|
||||
|
||||
configs/skp16c26/src/up_lcd.c. Untested alphanumeric LCD driver.
|
||||
configs/sam3u-ek/src/up_lcd.c. The SAM3U-EK developement board features
|
||||
a TFT/Transmissive color LCD module with touch-screen, FTM280C12D,
|
||||
with integrated driver IC HX8346.
|
||||
|
||||
configs/stm3210e-eval/src/up_lcd.c
|
||||
HX8347:
|
||||
|
||||
This driver supports the following LCDs:
|
||||
configs/pic32mx7mmb/src/up_mio283qt2.c. This driver is for the MI0283QT-2
|
||||
LCD from Multi-Inno Technology Co., Ltd. This LCD is based on the Himax
|
||||
HX8347-D LCD controller.
|
||||
|
||||
ILI93xx and Similar:
|
||||
|
||||
1. Ampire AM-240320LTNQW00H
|
||||
2. Orise Tech SPFD5408B
|
||||
3. RenesasSP R61580
|
||||
configs/stm3210e-eval/src/up_lcd.c. This driver supports the following
|
||||
LCDs:
|
||||
|
||||
configs/stm3220g-eval/src/up_lcd.c and configs/stm3240g-eval/src/up_lcd.c.
|
||||
AM-240320L8TNQW00H (LCD_ILI9320 or LCD_ILI9321) and
|
||||
AM-240320D5TOQW01H (LCD_ILI9325)
|
||||
1. Ampire AM-240320LTNQW00H
|
||||
2. Orise Tech SPFD5408B
|
||||
3. RenesasSP R61580
|
||||
|
||||
configs/stm32f4discovery/src/up_ssd1289.c. This examples is the
|
||||
bottom half for the SSD1289 driver at drivers/lcd/ssd1289.c
|
||||
configs/stm3220g-eval/src/up_lcd.c and configs/stm3240g-eval/src/up_lcd.c.
|
||||
AM-240320L8TNQW00H (LCD_ILI9320 or LCD_ILI9321) and
|
||||
AM-240320D5TOQW01H (LCD_ILI9325)
|
||||
configs/shenzhou/src/up_ili93xx.c. Another ILI93xx driver.
|
||||
|
||||
OLEDs:
|
||||
|
||||
configs/stm32f4discovery/src/up_ug2864ambag01.c
|
||||
configs/stm32f4discovery/src/up_ug2864hsweg01.c
|
||||
configs/zp214xpa/src/up_ug2864ambag01.c
|
||||
|
||||
Alphnumeric LCD Displays:
|
||||
|
||||
configs/skp16c26/src/up_lcd.c. Untested alphanumeric LCD driver.
|
||||
configs/pcblogic-pic32/src/up_lcd1602.c
|
||||
|
||||
graphics/
|
||||
=========
|
||||
|
||||
See also the usage of the LCD driver in the graphics/ directory.
|
||||
|
||||
|
|
|
@ -53,7 +53,7 @@ config MMCSD_SPICLOCK
|
|||
|
||||
config MMCSD_SDIO
|
||||
bool "MMC/SD sdio transfer support"
|
||||
default y
|
||||
default n
|
||||
|
||||
if MMCSD_SDIO
|
||||
config SDIO_DMA
|
||||
|
|
|
@ -222,7 +222,7 @@ static int binfs_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
|
|||
}
|
||||
else
|
||||
{
|
||||
*ptr = g_builtins[(int)filep->f_priv].name;
|
||||
*ptr = builtin_getname((int)filep->f_priv);
|
||||
ret = OK;
|
||||
}
|
||||
}
|
||||
|
@ -287,13 +287,15 @@ static int binfs_opendir(struct inode *mountpt, const char *relpath,
|
|||
|
||||
static int binfs_readdir(struct inode *mountpt, struct fs_dirent_s *dir)
|
||||
{
|
||||
FAR const char *name;
|
||||
unsigned int index;
|
||||
int ret;
|
||||
|
||||
/* Have we reached the end of the directory */
|
||||
|
||||
index = dir->u.binfs.fb_index;
|
||||
if (g_builtins[index].name == NULL)
|
||||
name = builtin_getname(index);
|
||||
if (name == NULL)
|
||||
{
|
||||
/* We signal the end of the directory by returning the
|
||||
* special error -ENOENT
|
||||
|
@ -306,9 +308,9 @@ static int binfs_readdir(struct inode *mountpt, struct fs_dirent_s *dir)
|
|||
{
|
||||
/* Save the filename and file type */
|
||||
|
||||
fvdbg("Entry %d: \"%s\"\n", index, g_builtins[index].name);
|
||||
fvdbg("Entry %d: \"%s\"\n", index, name);
|
||||
dir->fd_dir.d_type = DTYPE_FILE;
|
||||
strncpy(dir->fd_dir.d_name, g_builtins[index].name, NAME_MAX+1);
|
||||
strncpy(dir->fd_dir.d_name, name, NAME_MAX+1);
|
||||
|
||||
/* The application list is terminated by an entry with a NULL name.
|
||||
* Therefore, there is at least one more entry in the list.
|
||||
|
|
|
@ -82,6 +82,18 @@ typedef FAR void (*binfmt_dtor_t)(void);
|
|||
struct symtab_s;
|
||||
struct binary_s
|
||||
{
|
||||
/* If CONFIG_SCHED_HAVE_PARENT is defined then schedul_unload() will
|
||||
* manage instances of struct binary_s allocated with kmalloc. It
|
||||
* will keep the binary data in a link list and when SIGCHLD is received
|
||||
* (meaning that the task has exit'ed, schedul_unload() will find the
|
||||
* data, unload the module, and free the structure.
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_SCHED_HAVE_PARENT
|
||||
FAR struct binary_s *flink; /* Supports a singly linked list */
|
||||
pid_t pid; /* Task ID of the child task */
|
||||
#endif
|
||||
|
||||
/* Information provided to the loader to load and bind a module */
|
||||
|
||||
FAR const char *filename; /* Full path to the binary to be loaded (See NOTE 1 above) */
|
||||
|
@ -222,19 +234,48 @@ int unload_module(FAR const struct binary_s *bin);
|
|||
*
|
||||
* Returned Value:
|
||||
* This is an end-user function, so it follows the normal convention:
|
||||
* Returns the PID of the exec'ed module. On failure, it.returns
|
||||
* Returns the PID of the exec'ed module. On failure, it returns
|
||||
* -1 (ERROR) and sets errno appropriately.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
int exec_module(FAR const struct binary_s *bin);
|
||||
|
||||
/****************************************************************************
|
||||
* Name: schedule_unload
|
||||
*
|
||||
* Description:
|
||||
* If CONFIG_SCHED_HAVE_PARENT is defined, this function may be called by
|
||||
* the parent of the the newly created task to automatically unload the
|
||||
* module when the task exits. This assumes that (1) the caller is the
|
||||
* parent of the created task, (2) that bin was allocated with kmalloc()
|
||||
* or friends. It will also automatically free the structure with kfree()
|
||||
* after unloading the module.
|
||||
*
|
||||
* Input Parameter:
|
||||
* pid - The task ID of the child task
|
||||
* bin - This structure must have been allocated with kmalloc() and must
|
||||
* persist until the task unloads
|
||||
*
|
||||
* Returned Value:
|
||||
* This is an end-user function, so it follows the normal convention:
|
||||
* It returns 0 (OK) if the callback was successfully scheduled. On
|
||||
* failure, it returns -1 (ERROR) and sets errno appropriately.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef CONFIG_SCHED_HAVE_PARENT
|
||||
int schedule_unload(pid_t pid, FAR struct binary_s *bin);
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Name: exec
|
||||
*
|
||||
* Description:
|
||||
* This is a convenience function that wraps load_ and exec_module into
|
||||
* one call.
|
||||
* one call. If CONFIG_SCHED_ONEXIT is also defined, this function will
|
||||
* automatically call schedule_unload() to unload the module when task
|
||||
* exits.
|
||||
*
|
||||
* Input Parameter:
|
||||
* filename - Fulll path to the binary to be loaded
|
||||
|
@ -244,7 +285,7 @@ int exec_module(FAR const struct binary_s *bin);
|
|||
*
|
||||
* Returned Value:
|
||||
* This is an end-user function, so it follows the normal convention:
|
||||
* Returns the PID of the exec'ed module. On failure, it.returns
|
||||
* It returns the PID of the exec'ed module. On failure, it returns
|
||||
* -1 (ERROR) and sets errno appropriately.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
|
|
@ -73,18 +73,40 @@ extern "C" {
|
|||
#define EXTERN extern
|
||||
#endif
|
||||
|
||||
/* The g_builtins[] array holds information about each builtin function. If
|
||||
* support for builtin functions is enabled in the NuttX configuration, then
|
||||
* this arrary (along with the number_builtins() function) must be provided
|
||||
* by the application code.
|
||||
*/
|
||||
|
||||
EXTERN const struct builtin_s g_builtins[];
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: builtin_initialize
|
||||
*
|
||||
* Description:
|
||||
* Builtin support is built unconditionally. However, it order to
|
||||
* use this binary format, this function must be called during system
|
||||
* format in order to register the builtin binary format.
|
||||
*
|
||||
* Returned Value:
|
||||
* This is a NuttX internal function so it follows the convention that
|
||||
* 0 (OK) is returned on success and a negated errno is returned on
|
||||
* failure.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
int builtin_initialize(void);
|
||||
|
||||
/****************************************************************************
|
||||
* Name: builtin_uninitialize
|
||||
*
|
||||
* Description:
|
||||
* Unregister the builtin binary loader
|
||||
*
|
||||
* Returned Value:
|
||||
* None
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void builtin_uninitialize(void);
|
||||
|
||||
/****************************************************************************
|
||||
* Utility Functions Provided to Applications by binfmt/libbuiltin
|
||||
****************************************************************************/
|
||||
|
@ -128,24 +150,24 @@ FAR const char *builtin_getname(int index);
|
|||
* Data Set Access Functions Provided to Applications by binfmt/libbuiltin
|
||||
****************************************************************************/
|
||||
/****************************************************************************
|
||||
* Name: number_builtins
|
||||
* Name: builtin_for_index
|
||||
*
|
||||
* Description:
|
||||
* Returns the number of builtin functions in the g_builtins[] array. If
|
||||
* support for builtin functions is enabled in the NuttX configuration,
|
||||
* then this function (along with g_builtins[]) must be provided by the
|
||||
* application code.
|
||||
* Returns the builtin_s structure for the selected builtin.
|
||||
* If support for builtin functions is enabled in the NuttX configuration,
|
||||
* then this function must be provided by the application code.
|
||||
*
|
||||
* Input Parameter:
|
||||
* None
|
||||
* index, from 0 and on...
|
||||
*
|
||||
* Returned Value:
|
||||
* The number of entries in the g_builtins[] array. This function does
|
||||
* not return failures.
|
||||
* Returns valid pointer pointing to the builtin_s structure if index is
|
||||
* valid.
|
||||
* Otherwise, NULL is returned.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
int number_builtins(void);
|
||||
EXTERN FAR const struct builtin_s *builtin_for_index(int index);
|
||||
|
||||
#undef EXTERN
|
||||
#if defined(__cplusplus)
|
||||
|
|
|
@ -0,0 +1,118 @@
|
|||
/********************************************************************************************
|
||||
* include/nuttx/lcd/hd4478ou.h
|
||||
*
|
||||
* Definitions for the Hitachi HD44780U LCD controller (as used in the
|
||||
* LCD1602).
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
********************************************************************************************/
|
||||
|
||||
#ifndef __INCLUDE_NUTTX_HD4478OU_H
|
||||
#define __INCLUDE_NUTTX_HD4478OU_H
|
||||
|
||||
/********************************************************************************************
|
||||
* Included Files
|
||||
********************************************************************************************/
|
||||
/* Command set:
|
||||
*
|
||||
* RS=0 R/W=0 : Command
|
||||
* RS=0 R/W=1 : Busy/AD, Read CT (see below)
|
||||
* RS=1 R/W=0 : Write data to CGRAM or DDRAM
|
||||
* RS=1 R/W=0 : Read data from CGRAM or DDRAM
|
||||
*/
|
||||
|
||||
#define HD4478OU_CLEAR (0x01) /* Screen Clear, Set AC to 0 */
|
||||
#define HD4478OU_RETURN (0x02) /* DDRAM AD=0, return */
|
||||
#define HD4478OU_INPUT (0x04) /* Set moving direction of cursor */
|
||||
# define HD4478OU_INPUT_SHIFT (1 << 0) /* Shift */
|
||||
# define HD4478OU_INPUT_INCR (1 << 1) /* Increment mode */
|
||||
# define HD4478OU_INPUT_DECR (0x00) /* Decrement mode */
|
||||
#define HD4478OU_DISPLAY (0x08) /* Set display, cursor, blink on/off */
|
||||
# define HD4478OU_DISPLAY_BLINK (1 << 0) /* Blink on/off */
|
||||
# define HD4478OU_DISPLAY_CURSOR (1 << 1) /* Cursor on/off */
|
||||
# define HD4478OU_DISPLAY_ON (1 << 2) /* Display on/off */
|
||||
#define HD4478OU_SHIFT (0x10) /* Remove cursor and whole diplay */
|
||||
# define HD4478OU_SHIFT_RIGHT (1 << 2) /* Shift right */
|
||||
# define HD4478OU_SHIFT_LEFT (0x00) /* Shift right */
|
||||
# define HD4478OU_SHIFT_DISPLAY (1 << 3) /* Display shift */
|
||||
# define HD4478OU_SHIFT_CURSOR (0x00) /* Cursor shift */
|
||||
#define HD4478OU_FUNC (0x20) /* Set DL, display line, font */
|
||||
# define HD4478OU_FUNC_F5x10 (1 << 2) /* 5x10 Style */
|
||||
# define HD4478OU_FUNC_F5x7 (0x00) /* 5x7 Style */
|
||||
# define HD4478OU_FUNC_N1 (1 << 3) /* N=2R */
|
||||
# define HD4478OU_FUNC_N0 (0x00) /* N=1R */
|
||||
# define HD4478OU_FUNC_DL8D (1 << 4) /* DL=8D, 8-bit interface */
|
||||
# define HD4478OU_FUNC_DL4D (0x00) /* DL=4D, 4-bit interface */
|
||||
#define HD4478OU_CGRAM_AD(a) (0x40|(a)) /* Set CGRAM AD, send receive data */
|
||||
#define HD4478OU_DDRAM_AD(a) (0x80|(a)) /* Set DDRAM AD, send receive data */
|
||||
|
||||
/* RS=0 R/W=1 : Execute internal function, read AD of CT */
|
||||
|
||||
#define HD4478OU_BUSY(bf,ac) ((bf) << 7 | (ac))
|
||||
|
||||
/********************************************************************************************
|
||||
* Pre-processor Definitions
|
||||
********************************************************************************************/
|
||||
|
||||
/********************************************************************************************
|
||||
* Public Types
|
||||
********************************************************************************************/
|
||||
|
||||
/********************************************************************************************
|
||||
* Public Data
|
||||
********************************************************************************************/
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
/********************************************************************************************
|
||||
* Public Function Prototypes
|
||||
********************************************************************************************/
|
||||
|
||||
/********************************************************************************************
|
||||
* Name: up_lcd1602_initialize
|
||||
*
|
||||
* Description:
|
||||
* the LCD1602 is an HD4478OU-based LCD from Wave share. This function initializes the
|
||||
* LCD1602 hardware and registers the character driver as /dev/lcd1602.
|
||||
*
|
||||
********************************************************************************************/
|
||||
|
||||
int up_lcd1602_initialize(void);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* __INCLUDE_NUTTX_HD4478OU_H */
|
|
@ -1,5 +1,6 @@
|
|||
/**************************************************************************************
|
||||
* include/nuttx/lcd/ug-2864ambag01.h
|
||||
*
|
||||
* Driver for Univision UG-2864AMBAG01 OLED display (wih SH1101A controller) in SPI
|
||||
* mode
|
||||
*
|
||||
|
|
|
@ -1,5 +1,6 @@
|
|||
/**************************************************************************************
|
||||
* include/nuttx/lcd/ug-2864hsweg01.h
|
||||
*
|
||||
* Driver for Univision UG-2864HSWEG01 OLED display (wih SSD1306 controller) in SPI
|
||||
* mode
|
||||
*
|
||||
|
|
|
@ -1,5 +1,6 @@
|
|||
/****************************************************************************
|
||||
* include/nuttx/lcd/ug-9664hswag01.h
|
||||
*
|
||||
* Driver for the Univision UG-9664HSWAG01 Display with the Solomon Systech
|
||||
* SSD1305 LCD controller.
|
||||
*
|
||||
|
|
|
@ -62,21 +62,31 @@
|
|||
|
||||
/* This is the maximum number of times that a lock can be set */
|
||||
|
||||
#define MAX_LOCK_COUNT 127
|
||||
#define MAX_LOCK_COUNT 127
|
||||
|
||||
/* Values for the _TCB flags flag bits */
|
||||
|
||||
#define TCB_FLAG_TTYPE_SHIFT (0) /* Bits 0-1: thread type */
|
||||
#define TCB_FLAG_TTYPE_MASK (3 << TCB_FLAG_TTYPE_SHIFT)
|
||||
# define TCB_FLAG_TTYPE_TASK (0 << TCB_FLAG_TTYPE_SHIFT) /* Normal user task */
|
||||
# define TCB_FLAG_TTYPE_PTHREAD (1 << TCB_FLAG_TTYPE_SHIFT) /* User pthread */
|
||||
# define TCB_FLAG_TTYPE_KERNEL (2 << TCB_FLAG_TTYPE_SHIFT) /* Kernel thread */
|
||||
#define TCB_FLAG_NONCANCELABLE (1 << 2) /* Bit 2: Pthread is non-cancelable */
|
||||
#define TCB_FLAG_CANCEL_PENDING (1 << 3) /* Bit 3: Pthread cancel is pending */
|
||||
#define TCB_FLAG_ROUND_ROBIN (1 << 4) /* Bit 4: Round robin sched enabled */
|
||||
#define TCB_FLAG_TTYPE_SHIFT (0) /* Bits 0-1: thread type */
|
||||
#define TCB_FLAG_TTYPE_MASK (3 << TCB_FLAG_TTYPE_SHIFT)
|
||||
# define TCB_FLAG_TTYPE_TASK (0 << TCB_FLAG_TTYPE_SHIFT) /* Normal user task */
|
||||
# define TCB_FLAG_TTYPE_PTHREAD (1 << TCB_FLAG_TTYPE_SHIFT) /* User pthread */
|
||||
# define TCB_FLAG_TTYPE_KERNEL (2 << TCB_FLAG_TTYPE_SHIFT) /* Kernel thread */
|
||||
#define TCB_FLAG_NONCANCELABLE (1 << 2) /* Bit 2: Pthread is non-cancelable */
|
||||
#define TCB_FLAG_CANCEL_PENDING (1 << 3) /* Bit 3: Pthread cancel is pending */
|
||||
#define TCB_FLAG_ROUND_ROBIN (1 << 4) /* Bit 4: Round robin sched enabled */
|
||||
#define TCB_FLAG_NOCLDWAIT (1 << 5) /* Bit 5: Do not retain child exit status */
|
||||
|
||||
/* Values for struct child_status_s ch_flags */
|
||||
|
||||
#define CHILD_FLAG_TTYPE_SHIFT (0) /* Bits 0-1: child thread type */
|
||||
#define CHILD_FLAG_TTYPE_MASK (3 << CHILD_FLAG_TTYPE_SHIFT)
|
||||
# define CHILD_FLAG_TTYPE_TASK (0 << CHILD_FLAG_TTYPE_SHIFT) /* Normal user task */
|
||||
# define CHILD_FLAG_TTYPE_PTHREAD (1 << CHILD_FLAG_TTYPE_SHIFT) /* User pthread */
|
||||
# define CHILD_FLAG_TTYPE_KERNEL (2 << CHILD_FLAG_TTYPE_SHIFT) /* Kernel thread */
|
||||
#define CHILD_FLAG_EXITED (1 << 0) /* Bit 2: The child thread has exit'ed */
|
||||
|
||||
/********************************************************************************
|
||||
* Global Type Definitions
|
||||
* Public Type Definitions
|
||||
********************************************************************************/
|
||||
|
||||
#ifndef __ASSEMBLY__
|
||||
|
@ -163,6 +173,22 @@ typedef struct environ_s environ_t;
|
|||
# define SIZEOF_ENVIRON_T(alloc) (sizeof(environ_t) + alloc - 1)
|
||||
#endif
|
||||
|
||||
/* This structure is used to maintin information about child tasks.
|
||||
* pthreads work differently, they have join information. This is
|
||||
* only for child tasks.
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_SCHED_CHILD_STATUS
|
||||
struct child_status_s
|
||||
{
|
||||
FAR struct child_status_s *flink;
|
||||
|
||||
uint8_t ch_flags; /* Child status: See CHILD_FLAG_* definitions */
|
||||
pid_t ch_pid; /* Child task ID */
|
||||
int ch_status; /* Child exit status */
|
||||
};
|
||||
#endif
|
||||
|
||||
/* This structure describes a reference counted D-Space region. This must be a
|
||||
* separately allocated "break-away" structure that can be owned by a task and
|
||||
* any pthreads created by the task.
|
||||
|
@ -202,9 +228,13 @@ struct _TCB
|
|||
/* Task Management Fields *****************************************************/
|
||||
|
||||
pid_t pid; /* This is the ID of the thread */
|
||||
#ifdef CONFIG_SCHED_HAVE_PARENT
|
||||
#ifdef CONFIG_SCHED_HAVE_PARENT /* Support parent-child relationship */
|
||||
pid_t parent; /* This is the ID of the parent thread */
|
||||
#ifdef CONFIG_SCHED_CHILD_STATUS /* Retain child thread status */
|
||||
FAR struct child_status_s *children; /* Head of a list of child status */
|
||||
#else
|
||||
uint16_t nchildren; /* This is the number active children */
|
||||
#endif
|
||||
#endif
|
||||
start_t start; /* Thread start function */
|
||||
entry_t entry; /* Entry Point into the thread */
|
||||
|
@ -357,33 +387,38 @@ typedef void (*sched_foreach_t)(FAR _TCB *tcb, FAR void *arg);
|
|||
#endif /* __ASSEMBLY__ */
|
||||
|
||||
/********************************************************************************
|
||||
* Global Function Prototypes
|
||||
* Public Data
|
||||
********************************************************************************/
|
||||
|
||||
#ifndef __ASSEMBLY__
|
||||
#undef EXTERN
|
||||
#if defined(__cplusplus)
|
||||
#define EXTERN extern "C"
|
||||
extern "C" {
|
||||
extern "C"
|
||||
{
|
||||
#else
|
||||
#define EXTERN extern
|
||||
#endif
|
||||
|
||||
/********************************************************************************
|
||||
* Public Function Prototypes
|
||||
********************************************************************************/
|
||||
|
||||
/* TCB helpers */
|
||||
|
||||
EXTERN FAR _TCB *sched_self(void);
|
||||
FAR _TCB *sched_self(void);
|
||||
|
||||
/* File system helpers */
|
||||
|
||||
#if CONFIG_NFILE_DESCRIPTORS > 0
|
||||
EXTERN FAR struct filelist *sched_getfiles(void);
|
||||
FAR struct filelist *sched_getfiles(void);
|
||||
#if CONFIG_NFILE_STREAMS > 0
|
||||
EXTERN FAR struct streamlist *sched_getstreams(void);
|
||||
FAR struct streamlist *sched_getstreams(void);
|
||||
#endif /* CONFIG_NFILE_STREAMS */
|
||||
#endif /* CONFIG_NFILE_DESCRIPTORS */
|
||||
|
||||
#if CONFIG_NSOCKET_DESCRIPTORS > 0
|
||||
EXTERN FAR struct socketlist *sched_getsockets(void);
|
||||
FAR struct socketlist *sched_getsockets(void);
|
||||
#endif /* CONFIG_NSOCKET_DESCRIPTORS */
|
||||
|
||||
/* Internal vfork support.The overall sequence is:
|
||||
|
@ -417,7 +452,7 @@ void task_vforkabort(FAR _TCB *child, int errcode);
|
|||
* will be disabled throughout this enumeration!
|
||||
*/
|
||||
|
||||
EXTERN void sched_foreach(sched_foreach_t handler, FAR void *arg);
|
||||
void sched_foreach(sched_foreach_t handler, FAR void *arg);
|
||||
|
||||
#undef EXTERN
|
||||
#if defined(__cplusplus)
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
/********************************************************************************************
|
||||
* include/nuttx/serial/tioctl.h
|
||||
*
|
||||
* Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
|
||||
* Copyright (C) 2011-2013 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
|
@ -165,16 +165,23 @@
|
|||
#define TIOCSRS485 _TIOC(0x002a) /* Set RS485 mode, arg: pointer to struct serial_rs485 */
|
||||
#define TIOCGRS485 _TIOC(0x002b) /* Get RS485 mode, arg: pointer to struct serial_rs485 */
|
||||
|
||||
/* Definitions for flags used in struct serial_rs485 (Linux compatible) */
|
||||
|
||||
# define SER_RS485_ENABLED (1 << 0) /* Enable/disble RS-485 support */
|
||||
# define SER_RS485_RTS_ON_SEND (1 << 1) /* Logic level for RTS pin when sending */
|
||||
# define SER_RS485_RTS_AFTER_SEND (1 << 2) /* Logic level for RTS pin after sent */
|
||||
# define SER_RS485_RX_DURING_TX (1 << 4)
|
||||
|
||||
/* Single-wire UART support */
|
||||
|
||||
#define TIOCSSINGLEWIRE _TIOC(0x002c) /* Set single-wire mode */
|
||||
#define TIOCGSINGLEWIRE _TIOC(0x002d) /* Get single-wire mode */
|
||||
|
||||
# define SER_SINGLEWIRE_ENABLED (1 << 0) /* Enable/disable single-wire support */
|
||||
|
||||
/* Debugging */
|
||||
|
||||
#define TIOCSERGSTRUCT _TIOC(0x002c) /* Get device TTY structure */
|
||||
|
||||
/* Definitions used in struct serial_rs485 (Linux compatible) */
|
||||
|
||||
#define SER_RS485_ENABLED (1 << 0) /* Enable/disble RS-485 support */
|
||||
#define SER_RS485_RTS_ON_SEND (1 << 1) /* Logic level for RTS pin when sending */
|
||||
#define SER_RS485_RTS_AFTER_SEND (1 << 2) /* Logic level for RTS pin after sent */
|
||||
#define SER_RS485_RX_DURING_TX (1 << 4)
|
||||
#define TIOCSERGSTRUCT _TIOC(0x002e) /* Get device TTY structure */
|
||||
|
||||
/********************************************************************************************
|
||||
* Public Type Definitions
|
||||
|
|
|
@ -1,5 +1,5 @@
|
|||
/****************************************************************************
|
||||
* libc/spawn/spawn.h
|
||||
* include/nuttx/spawn.h
|
||||
*
|
||||
* Copyright (C) 2013 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
|
@ -33,8 +33,8 @@
|
|||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifndef __LIBC_SPAWN_SPAWN_H
|
||||
#define __LIBC_SPAWN_SPAWN_H
|
||||
#ifndef __INCLUDE_NUTTX_SPAWN_H
|
||||
#define __INCLUDE_NUTTX_SPAWN_H
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
|
@ -118,4 +118,4 @@ void add_file_action(FAR posix_spawn_file_actions_t *file_action,
|
|||
}
|
||||
#endif
|
||||
|
||||
#endif /* __LIBC_SPAWN_SPAWN_H */
|
||||
#endif /* __INCLUDE_NUTTX_SPAWN_H */
|
|
@ -79,7 +79,7 @@
|
|||
#endif
|
||||
|
||||
/********************************************************************************
|
||||
* Global Type Definitions
|
||||
* Public Type Definitions
|
||||
********************************************************************************/
|
||||
|
||||
/* This is the POSIX-like scheduling parameter structure */
|
||||
|
@ -90,56 +90,61 @@ struct sched_param
|
|||
};
|
||||
|
||||
/********************************************************************************
|
||||
* Global Function Prototypes
|
||||
* Public Data
|
||||
********************************************************************************/
|
||||
|
||||
#ifndef __ASSEMBLY__
|
||||
#undef EXTERN
|
||||
#if defined(__cplusplus)
|
||||
#define EXTERN extern "C"
|
||||
extern "C" {
|
||||
extern "C"
|
||||
{
|
||||
#else
|
||||
#define EXTERN extern
|
||||
#endif
|
||||
|
||||
/********************************************************************************
|
||||
* Public Function Prototypes
|
||||
********************************************************************************/
|
||||
|
||||
/* Task Control Interfaces (non-standard) */
|
||||
|
||||
#ifndef CONFIG_CUSTOM_STACK
|
||||
EXTERN int task_init(FAR _TCB *tcb, const char *name, int priority,
|
||||
FAR uint32_t *stack, uint32_t stack_size,
|
||||
main_t entry, const char *argv[]);
|
||||
int task_init(FAR _TCB *tcb, const char *name, int priority,
|
||||
FAR uint32_t *stack, uint32_t stack_size, main_t entry,
|
||||
FAR const char *argv[]);
|
||||
#else
|
||||
EXTERN int task_init(FAR _TCB *tcb, const char *name, int priority,
|
||||
main_t entry, const char *argv[]);
|
||||
int task_init(FAR _TCB *tcb, const char *name, int priority, main_t entry,
|
||||
FAR const char *argv[]);
|
||||
#endif
|
||||
EXTERN int task_activate(FAR _TCB *tcb);
|
||||
int task_activate(FAR _TCB *tcb);
|
||||
#ifndef CONFIG_CUSTOM_STACK
|
||||
EXTERN int task_create(const char *name, int priority, int stack_size,
|
||||
main_t entry, const char *argv[]);
|
||||
int task_create(FAR const char *name, int priority, int stack_size, main_t entry,
|
||||
FAR const char *argv[]);
|
||||
#else
|
||||
EXTERN int task_create(const char *name, int priority,
|
||||
main_t entry, const char *argv[]);
|
||||
int task_create(FAR const char *name, int priority, main_t entry,
|
||||
FAR const char *argv[]);
|
||||
#endif
|
||||
EXTERN int task_delete(pid_t pid);
|
||||
EXTERN int task_restart(pid_t pid);
|
||||
int task_delete(pid_t pid);
|
||||
int task_restart(pid_t pid);
|
||||
|
||||
/* Task Scheduling Interfaces (based on POSIX APIs) */
|
||||
|
||||
EXTERN int sched_setparam(pid_t pid, const struct sched_param *param);
|
||||
EXTERN int sched_getparam(pid_t pid, struct sched_param *param);
|
||||
EXTERN int sched_setscheduler(pid_t pid, int policy,
|
||||
const struct sched_param *param);
|
||||
EXTERN int sched_getscheduler(pid_t pid);
|
||||
EXTERN int sched_yield(void);
|
||||
EXTERN int sched_get_priority_max(int policy);
|
||||
EXTERN int sched_get_priority_min(int policy);
|
||||
EXTERN int sched_rr_get_interval(pid_t pid, struct timespec *interval);
|
||||
int sched_setparam(pid_t pid, const struct sched_param *param);
|
||||
int sched_getparam(pid_t pid, struct sched_param *param);
|
||||
int sched_setscheduler(pid_t pid, int policy,
|
||||
FAR const struct sched_param *param);
|
||||
int sched_getscheduler(pid_t pid);
|
||||
int sched_yield(void);
|
||||
int sched_get_priority_max(int policy);
|
||||
int sched_get_priority_min(int policy);
|
||||
int sched_rr_get_interval(pid_t pid, FAR struct timespec *interval);
|
||||
|
||||
/* Task Switching Interfaces (non-standard) */
|
||||
|
||||
EXTERN int sched_lock(void);
|
||||
EXTERN int sched_unlock(void);
|
||||
EXTERN int sched_lockcount(void);
|
||||
int sched_lock(void);
|
||||
int sched_unlock(void);
|
||||
int sched_lockcount(void);
|
||||
|
||||
/* If instrumentation of the scheduler is enabled, then some outboard logic
|
||||
* must provide the following interfaces.
|
||||
|
@ -147,9 +152,9 @@ EXTERN int sched_lockcount(void);
|
|||
|
||||
#ifdef CONFIG_SCHED_INSTRUMENTATION
|
||||
|
||||
EXTERN void sched_note_start(FAR _TCB *tcb);
|
||||
EXTERN void sched_note_stop(FAR _TCB *tcb);
|
||||
EXTERN void sched_note_switch(FAR _TCB *pFromTcb, FAR _TCB *pToTcb);
|
||||
void sched_note_start(FAR _TCB *tcb);
|
||||
void sched_note_stop(FAR _TCB *tcb);
|
||||
void sched_note_switch(FAR _TCB *pFromTcb, FAR _TCB *pToTcb);
|
||||
|
||||
#else
|
||||
# define sched_note_start(t)
|
||||
|
|
|
@ -61,14 +61,17 @@
|
|||
|
||||
/* All signals are "real time" signals */
|
||||
|
||||
#define SIGRTMIN 0 /* First real time signal */
|
||||
#define SIGRTMAX 31 /* Last real time signal */
|
||||
#define SIGRTMIN MIN_SIGNO /* First real time signal */
|
||||
#define SIGRTMAX MAX_SIGNO /* Last real time signal */
|
||||
|
||||
/* A few of the real time signals are used within the OS. They have
|
||||
* default values that can be overridden from the configuration file. The
|
||||
* rest are all user signals.
|
||||
*
|
||||
* These are semi-standard signal definitions:
|
||||
* The signal number zero is wasted for the most part. It is a valid
|
||||
* signal number, but has special meaning at many interfaces (e.g., Kill()).
|
||||
*
|
||||
* These are the semi-standard signal definitions:
|
||||
*/
|
||||
|
||||
#ifndef CONFIG_SIG_SIGUSR1
|
||||
|
@ -126,11 +129,13 @@
|
|||
|
||||
/* struct sigaction flag values */
|
||||
|
||||
#define SA_NOCLDSTOP 1 /* Do not generate SIGCHILD when
|
||||
* children stop (ignored) */
|
||||
#define SA_SIGINFO 2 /* Invoke the signal-catching function
|
||||
* with 3 args instead of 1
|
||||
* (always assumed) */
|
||||
#define SA_NOCLDSTOP (1 << 0) /* Do not generate SIGCHILD when
|
||||
* children stop (ignored) */
|
||||
#define SA_SIGINFO (1 << 1) /* Invoke the signal-catching function
|
||||
* with 3 args instead of 1
|
||||
* (always assumed) */
|
||||
#define SA_NOCLDWAIT (1 << 2) /* If signo=SIGCHLD, exit status of child
|
||||
* processes will be discarded */
|
||||
|
||||
/* These are the possible values of the signfo si_code field */
|
||||
|
||||
|
|
|
@ -158,13 +158,13 @@ typedef uint16_t ino_t;
|
|||
* negative PID values are used to represent invalid PIDs.
|
||||
*/
|
||||
|
||||
typedef int pid_t;
|
||||
typedef int16_t pid_t;
|
||||
|
||||
/* id_t is a general identifier that can be used to contain at least a pid_t,
|
||||
* uid_t, or gid_t.
|
||||
*/
|
||||
|
||||
typedef unsigned int id_t;
|
||||
typedef int16_t id_t;
|
||||
|
||||
/* Signed integral type of the result of subtracting two pointers */
|
||||
|
||||
|
|
|
@ -37,8 +37,6 @@
|
|||
|
||||
ifeq ($(CONFIG_LIBC_EXECFUNCS),y)
|
||||
|
||||
CSRCS += lib_ps.c
|
||||
|
||||
CSRCS += lib_psfa_addaction.c lib_psfa_addclose.c lib_psfa_adddup2.c
|
||||
CSRCS += lib_psfa_addopen.c lib_psfa_destroy.c lib_psfa_init.c
|
||||
|
||||
|
|
|
@ -41,7 +41,7 @@
|
|||
|
||||
#include <spawn.h>
|
||||
|
||||
#include "spawn/spawn.h"
|
||||
#include <nuttx/spawn.h>
|
||||
|
||||
/****************************************************************************
|
||||
* Global Functions
|
||||
|
|
|
@ -44,7 +44,7 @@
|
|||
#include <assert.h>
|
||||
#include <errno.h>
|
||||
|
||||
#include "spawn/spawn.h"
|
||||
#include <nuttx/spawn.h>
|
||||
|
||||
/****************************************************************************
|
||||
* Global Functions
|
||||
|
|
|
@ -44,7 +44,7 @@
|
|||
#include <assert.h>
|
||||
#include <errno.h>
|
||||
|
||||
#include "spawn/spawn.h"
|
||||
#include <nuttx/spawn.h>
|
||||
|
||||
/****************************************************************************
|
||||
* Global Functions
|
||||
|
|
|
@ -45,7 +45,7 @@
|
|||
#include <assert.h>
|
||||
#include <errno.h>
|
||||
|
||||
#include "spawn/spawn.h"
|
||||
#include <nuttx/spawn.h>
|
||||
|
||||
/****************************************************************************
|
||||
* Global Functions
|
||||
|
|
|
@ -43,7 +43,7 @@
|
|||
#include <spawn.h>
|
||||
#include <assert.h>
|
||||
|
||||
#include "spawn/spawn.h"
|
||||
#include <nuttx/spawn.h>
|
||||
|
||||
/****************************************************************************
|
||||
* Global Functions
|
||||
|
|
|
@ -43,7 +43,7 @@
|
|||
#include <assert.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include "spawn/spawn.h"
|
||||
#include <nuttx/spawn.h>
|
||||
|
||||
#ifdef CONFIG_DEBUG
|
||||
|
||||
|
|
|
@ -97,14 +97,14 @@ config NET_TCPURGDATA
|
|||
compiled in. Urgent data (out-of-band data) is a rarely used TCP feature
|
||||
that is very seldom would be required.
|
||||
|
||||
menu "TCP/IP Networking"
|
||||
|
||||
config NET_TCP
|
||||
bool "TCP/IP Networking"
|
||||
default n
|
||||
---help---
|
||||
TCP support on or off
|
||||
|
||||
endif
|
||||
|
||||
if NET_TCP
|
||||
config NET_TCP_CONNS
|
||||
int "Number of TCP/IP connections"
|
||||
|
@ -164,7 +164,36 @@ config NET_TCPBACKLOG
|
|||
Incoming connections pend in a backlog until accept() is called.
|
||||
The size of the backlog is selected when listen() is called.
|
||||
|
||||
config NET_TCP_SPLIT
|
||||
bool "Enable packet splitting"
|
||||
default n
|
||||
---help---
|
||||
send() will not return until the the transfer has been ACKed by the
|
||||
recipient. But under RFC 1122, the host need not ACK each packet
|
||||
immediately; the host may wait for 500 MS before ACKing. This
|
||||
combination can cause very slow performance with small transfers are
|
||||
made to an RFC 1122 client. However, the RFC 1122 must ACK at least
|
||||
every second (odd) packet.
|
||||
|
||||
This option enables logic to trick the RFC 1122 host be exploiting
|
||||
this last RFC 1122 requirement: If an odd number of packets were to
|
||||
be sent, then send() will split the last even packet to guarantee
|
||||
that an even number of packets will be sent and the RFC 1122 host
|
||||
will ACK the final packet immediately.
|
||||
|
||||
if NET_TCP_SPLIT
|
||||
|
||||
config NET_TCP_SPLIT_SIZE
|
||||
int "Split size threshold"
|
||||
default 40
|
||||
---help---
|
||||
Packets of this size or smaller than this will not be split.
|
||||
|
||||
endif
|
||||
endif
|
||||
endmenu
|
||||
|
||||
menu "UDP Networking"
|
||||
|
||||
config NET_UDP
|
||||
bool "UDP Networking"
|
||||
|
@ -193,6 +222,7 @@ config NET_BROADCAST
|
|||
Incoming UDP broadcast support
|
||||
|
||||
endif
|
||||
endmenu
|
||||
|
||||
config NET_ICMP
|
||||
bool "ICMP networking support"
|
||||
|
@ -321,3 +351,4 @@ config SLIP_DEFPRIO
|
|||
The priority of the SLIP RX and TX tasks. Default: 128
|
||||
|
||||
endif
|
||||
endif
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
/****************************************************************************
|
||||
* net/net_internal.h
|
||||
*
|
||||
* Copyright (C) 2007-2009, 2011-2012 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
|
||||
|
@ -139,94 +139,96 @@
|
|||
* Public Variables
|
||||
****************************************************************************/
|
||||
|
||||
#undef EXTERN
|
||||
#if defined(__cplusplus)
|
||||
#define EXTERN extern "C"
|
||||
extern "C"
|
||||
{
|
||||
#else
|
||||
#define EXTERN extern
|
||||
#endif
|
||||
|
||||
/* List of registered ethernet device drivers */
|
||||
|
||||
#if CONFIG_NSOCKET_DESCRIPTORS > 0
|
||||
extern struct uip_driver_s *g_netdevices;
|
||||
EXTERN struct uip_driver_s *g_netdevices;
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Public Function Prototypes
|
||||
****************************************************************************/
|
||||
|
||||
#undef EXTERN
|
||||
#if defined(__cplusplus)
|
||||
#define EXTERN extern "C"
|
||||
extern "C" {
|
||||
#else
|
||||
#define EXTERN extern
|
||||
#endif
|
||||
|
||||
/* net_sockets.c *************************************************************/
|
||||
|
||||
EXTERN int sockfd_allocate(int minsd);
|
||||
EXTERN void sock_release(FAR struct socket *psock);
|
||||
EXTERN void sockfd_release(int sockfd);
|
||||
EXTERN FAR struct socket *sockfd_socket(int sockfd);
|
||||
int sockfd_allocate(int minsd);
|
||||
void sock_release(FAR struct socket *psock);
|
||||
void sockfd_release(int sockfd);
|
||||
FAR struct socket *sockfd_socket(int sockfd);
|
||||
|
||||
/* net_connect.c *************************************************************/
|
||||
|
||||
#ifdef CONFIG_NET_TCP
|
||||
EXTERN int net_startmonitor(FAR struct socket *psock);
|
||||
EXTERN void net_stopmonitor(FAR struct uip_conn *conn);
|
||||
int net_startmonitor(FAR struct socket *psock);
|
||||
void net_stopmonitor(FAR struct uip_conn *conn);
|
||||
void net_lostconnection(FAR struct socket *psock, uint16_t flags);
|
||||
#endif
|
||||
|
||||
/* net_close.c ***************************************************************/
|
||||
|
||||
EXTERN int psock_close(FAR struct socket *psock);
|
||||
int psock_close(FAR struct socket *psock);
|
||||
|
||||
/* sockopt support ***********************************************************/
|
||||
|
||||
#if defined(CONFIG_NET_SOCKOPTS) && !defined(CONFIG_DISABLE_CLOCK)
|
||||
EXTERN int net_timeo(uint32_t start_time, socktimeo_t timeo);
|
||||
EXTERN socktimeo_t net_timeval2dsec(struct timeval *tv);
|
||||
EXTERN void net_dsec2timeval(uint16_t dsec, struct timeval *tv);
|
||||
int net_timeo(uint32_t start_time, socktimeo_t timeo);
|
||||
socktimeo_t net_timeval2dsec(FAR struct timeval *tv);
|
||||
void net_dsec2timeval(uint16_t dsec, FAR struct timeval *tv);
|
||||
#endif
|
||||
|
||||
/* net_register.c ************************************************************/
|
||||
|
||||
#if CONFIG_NSOCKET_DESCRIPTORS > 0
|
||||
EXTERN void netdev_seminit(void);
|
||||
EXTERN void netdev_semtake(void);
|
||||
EXTERN void netdev_semgive(void);
|
||||
void netdev_seminit(void);
|
||||
void netdev_semtake(void);
|
||||
void netdev_semgive(void);
|
||||
#endif
|
||||
|
||||
/* net_findbyname.c **********************************************************/
|
||||
|
||||
#if CONFIG_NSOCKET_DESCRIPTORS > 0
|
||||
EXTERN FAR struct uip_driver_s *netdev_findbyname(const char *ifname);
|
||||
FAR struct uip_driver_s *netdev_findbyname(FAR const char *ifname);
|
||||
#endif
|
||||
|
||||
/* net_findbyaddr.c **********************************************************/
|
||||
|
||||
#if CONFIG_NSOCKET_DESCRIPTORS > 0
|
||||
EXTERN FAR struct uip_driver_s *netdev_findbyaddr(const uip_ipaddr_t *raddr);
|
||||
FAR struct uip_driver_s *netdev_findbyaddr(FAR const uip_ipaddr_t *raddr);
|
||||
#endif
|
||||
|
||||
/* net_txnotify.c ************************************************************/
|
||||
|
||||
#if CONFIG_NSOCKET_DESCRIPTORS > 0
|
||||
EXTERN void netdev_txnotify(const uip_ipaddr_t *raddr);
|
||||
void netdev_txnotify(const uip_ipaddr_t *raddr);
|
||||
#endif
|
||||
|
||||
/* net_count.c ***************************************************************/
|
||||
|
||||
#if CONFIG_NSOCKET_DESCRIPTORS > 0
|
||||
EXTERN int netdev_count(void);
|
||||
int netdev_count(void);
|
||||
#endif
|
||||
|
||||
/* net_arptimer.c ************************************************************/
|
||||
|
||||
#ifdef CONFIG_NET_ARP
|
||||
EXTERN void arptimer_init(void);
|
||||
void arptimer_init(void);
|
||||
#else
|
||||
# define arptimer_init()
|
||||
#endif
|
||||
|
||||
/* send.c ********************************************************************/
|
||||
|
||||
EXTERN ssize_t psock_send(FAR struct socket *psock, const void *buf,
|
||||
size_t len, int flags);
|
||||
ssize_t psock_send(FAR struct socket *psock, FAR const void *buf, size_t len,
|
||||
int flags);
|
||||
|
||||
#undef EXTERN
|
||||
#if defined(__cplusplus)
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
/****************************************************************************
|
||||
* net/net_monitor.c
|
||||
*
|
||||
* Copyright (C) 2007-2012 Gregory Nutt. All rights reserved.
|
||||
* Copyright (C) 2007-2013 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
|
@ -67,7 +67,6 @@ static void connection_event(struct uip_conn *conn, uint16_t flags);
|
|||
* Some connection related event has occurred
|
||||
*
|
||||
* Parameters:
|
||||
* dev The sructure of the network driver that caused the interrupt
|
||||
* conn The connection structure associated with the socket
|
||||
* flags Set of events describing why the callback was invoked
|
||||
*
|
||||
|
@ -79,7 +78,7 @@ static void connection_event(struct uip_conn *conn, uint16_t flags);
|
|||
*
|
||||
****************************************************************************/
|
||||
|
||||
static void connection_event(struct uip_conn *conn, uint16_t flags)
|
||||
static void connection_event(FAR struct uip_conn *conn, uint16_t flags)
|
||||
{
|
||||
FAR struct socket *psock = (FAR struct socket *)conn->connection_private;
|
||||
|
||||
|
@ -87,37 +86,11 @@ static void connection_event(struct uip_conn *conn, uint16_t flags)
|
|||
{
|
||||
nllvdbg("flags: %04x s_flags: %02x\n", flags, psock->s_flags);
|
||||
|
||||
/* These loss-of-connection events may be reported:
|
||||
*
|
||||
* UIP_CLOSE: The remote host has closed the connection
|
||||
* UIP_ABORT: The remote host has aborted the connection
|
||||
* UIP_TIMEDOUT: Connection aborted due to too many retransmissions.
|
||||
*
|
||||
* And we need to set these two socket status bits appropriately:
|
||||
*
|
||||
* _SF_CONNECTED==1 && _SF_CLOSED==0 - the socket is connected
|
||||
* _SF_CONNECTED==0 && _SF_CLOSED==1 - the socket was gracefully disconnected
|
||||
* _SF_CONNECTED==0 && _SF_CLOSED==0 - the socket was rudely disconnected
|
||||
*/
|
||||
/* UIP_CLOSE, UIP_ABORT, or UIP_TIMEDOUT: Loss-of-connection events */
|
||||
|
||||
if ((flags & UIP_CLOSE) != 0)
|
||||
if ((flags & (UIP_CLOSE|UIP_ABORT|UIP_TIMEDOUT)) != 0)
|
||||
{
|
||||
/* The peer gracefully closed the connection. Marking the
|
||||
* connection as disconnected will suppress some subsequent
|
||||
* ENOTCONN errors from receive. A graceful disconnection is
|
||||
* not handle as an error but as an "end-of-file"
|
||||
*/
|
||||
|
||||
psock->s_flags &= ~_SF_CONNECTED;
|
||||
psock->s_flags |= _SF_CLOSED;
|
||||
}
|
||||
else if ((flags & (UIP_ABORT|UIP_TIMEDOUT)) != 0)
|
||||
{
|
||||
/* The loss of connection was less than graceful. This will (eventually)
|
||||
* be reported as an ENOTCONN error.
|
||||
*/
|
||||
|
||||
psock->s_flags &= ~(_SF_CONNECTED |_SF_CLOSED);
|
||||
net_lostconnection(psock, flags);
|
||||
}
|
||||
|
||||
/* UIP_CONNECTED: The socket is successfully connected */
|
||||
|
@ -184,4 +157,60 @@ void net_stopmonitor(FAR struct uip_conn *conn)
|
|||
conn->connection_event = NULL;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: net_lostconnection
|
||||
*
|
||||
* Description:
|
||||
* Called when a loss-of-connection event has occurred.
|
||||
*
|
||||
* Parameters:
|
||||
* psock The TCP socket structure associated.
|
||||
* flags Set of connection events events
|
||||
*
|
||||
* Returned Value:
|
||||
* None
|
||||
*
|
||||
* Assumptions:
|
||||
* Running at the interrupt level
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void net_lostconnection(FAR struct socket *psock, uint16_t flags)
|
||||
{
|
||||
DEBUGASSERT(psock)
|
||||
|
||||
/* These loss-of-connection events may be reported:
|
||||
*
|
||||
* UIP_CLOSE: The remote host has closed the connection
|
||||
* UIP_ABORT: The remote host has aborted the connection
|
||||
* UIP_TIMEDOUT: Connection aborted due to too many retransmissions.
|
||||
*
|
||||
* And we need to set these two socket status bits appropriately:
|
||||
*
|
||||
* _SF_CONNECTED==1 && _SF_CLOSED==0 - the socket is connected
|
||||
* _SF_CONNECTED==0 && _SF_CLOSED==1 - the socket was gracefully disconnected
|
||||
* _SF_CONNECTED==0 && _SF_CLOSED==0 - the socket was rudely disconnected
|
||||
*/
|
||||
|
||||
if ((flags & UIP_CLOSE) != 0)
|
||||
{
|
||||
/* The peer gracefully closed the connection. Marking the
|
||||
* connection as disconnected will suppress some subsequent
|
||||
* ENOTCONN errors from receive. A graceful disconnection is
|
||||
* not handle as an error but as an "end-of-file"
|
||||
*/
|
||||
|
||||
psock->s_flags &= ~_SF_CONNECTED;
|
||||
psock->s_flags |= _SF_CLOSED;
|
||||
}
|
||||
else if ((flags & (UIP_ABORT|UIP_TIMEDOUT)) != 0)
|
||||
{
|
||||
/* The loss of connection was less than graceful. This will (eventually)
|
||||
* be reported as an ENOTCONN error.
|
||||
*/
|
||||
|
||||
psock->s_flags &= ~(_SF_CONNECTED |_SF_CLOSED);
|
||||
}
|
||||
}
|
||||
|
||||
#endif /* CONFIG_NET && CONFIG_NET_TCP */
|
||||
|
|
|
@ -125,16 +125,22 @@ static uint16_t poll_interrupt(struct uip_driver_s *dev, FAR void *conn,
|
|||
|
||||
if ((flags & UIP_POLL) != 0)
|
||||
{
|
||||
eventset |= POLLOUT & fds->events;
|
||||
eventset |= (POLLOUT & fds->events);
|
||||
}
|
||||
|
||||
/* Check for a loss of connection events */
|
||||
/* Check for a loss of connection events.
|
||||
*
|
||||
* REVISIT: Need to call net_lostconnection() here, but don't have
|
||||
* the psock instance. What should we do?
|
||||
*/
|
||||
|
||||
if ((flags & (UIP_CLOSE|UIP_ABORT|UIP_TIMEDOUT)) != 0)
|
||||
{
|
||||
eventset |= (POLLERR|POLLHUP);
|
||||
eventset |= (POLLERR | POLLHUP);
|
||||
}
|
||||
|
||||
/* Awaken the caller of poll() is requested event occurred. */
|
||||
|
||||
if (eventset)
|
||||
{
|
||||
fds->revents |= eventset;
|
||||
|
@ -192,9 +198,9 @@ static inline int net_pollsetup(FAR struct socket *psock, struct pollfd *fds)
|
|||
goto errout_with_irq;
|
||||
}
|
||||
|
||||
/* Initialize the callbcack structure */
|
||||
/* Initialize the callback structure */
|
||||
|
||||
cb->flags = UIP_NEWDATA|UIP_BACKLOG|UIP_POLL|UIP_CLOSE|UIP_ABORT|UIP_TIMEDOUT;
|
||||
cb->flags = (UIP_NEWDATA|UIP_BACKLOG|UIP_POLL|UIP_CLOSE|UIP_ABORT|UIP_TIMEDOUT);
|
||||
cb->priv = (FAR void *)fds;
|
||||
cb->event = poll_interrupt;
|
||||
|
||||
|
@ -212,13 +218,23 @@ static inline int net_pollsetup(FAR struct socket *psock, struct pollfd *fds)
|
|||
if (!sq_empty(&conn->readahead))
|
||||
#endif
|
||||
{
|
||||
fds->revents = fds->events & POLLIN;
|
||||
if (fds->revents != 0)
|
||||
{
|
||||
/* If data is available now, the signal the poll logic */
|
||||
fds->revents |= (POLLOUT & fds->events);
|
||||
}
|
||||
|
||||
sem_post(fds->sem);
|
||||
}
|
||||
/* Check for a loss of connection events */
|
||||
|
||||
if (!_SS_ISCONNECTED(psock->s_flags))
|
||||
{
|
||||
fds->revents |= (POLLERR | POLLHUP);
|
||||
}
|
||||
|
||||
/* Check if any requested events are already in effect */
|
||||
|
||||
if (fds->revents != 0)
|
||||
{
|
||||
/* Yes.. then signal the poll logic */
|
||||
|
||||
sem_post(fds->sem);
|
||||
}
|
||||
|
||||
uip_unlock(flags);
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
/****************************************************************************
|
||||
* net/recvfrom.c
|
||||
*
|
||||
* Copyright (C) 2007-2009, 2011-2012 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
|
||||
|
@ -83,7 +83,7 @@ struct recvfrom_s
|
|||
FAR struct sockaddr_in *rf_from; /* Address of sender */
|
||||
#endif
|
||||
size_t rf_recvlen; /* The received length */
|
||||
int rf_result; /* OK:success, failure:negated errno */
|
||||
int rf_result; /* Success:OK, failure:negated errno */
|
||||
};
|
||||
#endif /* CONFIG_NET_UDP || CONFIG_NET_TCP */
|
||||
|
||||
|
@ -464,10 +464,11 @@ static inline void recvfrom_tcpsender(struct uip_driver_s *dev, struct recvfrom_
|
|||
****************************************************************************/
|
||||
|
||||
#ifdef CONFIG_NET_TCP
|
||||
static uint16_t recvfrom_tcpinterrupt(struct uip_driver_s *dev, void *conn,
|
||||
void *pvpriv, uint16_t flags)
|
||||
static uint16_t recvfrom_tcpinterrupt(FAR struct uip_driver_s *dev,
|
||||
FAR void *conn, FAR void *pvpriv,
|
||||
uint16_t flags)
|
||||
{
|
||||
struct recvfrom_s *pstate = (struct recvfrom_s *)pvpriv;
|
||||
FAR struct recvfrom_s *pstate = (struct recvfrom_s *)pvpriv;
|
||||
|
||||
nllvdbg("flags: %04x\n", flags);
|
||||
|
||||
|
@ -553,7 +554,7 @@ static uint16_t recvfrom_tcpinterrupt(struct uip_driver_s *dev, void *conn,
|
|||
|
||||
else if ((flags & (UIP_CLOSE|UIP_ABORT|UIP_TIMEDOUT)) != 0)
|
||||
{
|
||||
nllvdbg("error\n");
|
||||
nllvdbg("Lost connection\n");
|
||||
|
||||
/* Stop further callbacks */
|
||||
|
||||
|
@ -561,17 +562,40 @@ static uint16_t recvfrom_tcpinterrupt(struct uip_driver_s *dev, void *conn,
|
|||
pstate->rf_cb->priv = NULL;
|
||||
pstate->rf_cb->event = NULL;
|
||||
|
||||
/* If the peer gracefully closed the connection, then return zero
|
||||
* (end-of-file). Otherwise, report a not-connected error
|
||||
*/
|
||||
/* Handle loss-of-connection event */
|
||||
|
||||
net_lostconnection(pstate->rf_sock, flags);
|
||||
|
||||
/* Check if the peer gracefully closed the connection. */
|
||||
|
||||
if ((flags & UIP_CLOSE) != 0)
|
||||
{
|
||||
/* This case should always return success (zero)! The value of
|
||||
* rf_recvlen, if zero, will indicate that the connection was
|
||||
* gracefully closed.
|
||||
*/
|
||||
|
||||
pstate->rf_result = 0;
|
||||
}
|
||||
else
|
||||
{
|
||||
/* If no data has been received, then return ENOTCONN.
|
||||
* Otherwise, let this return success. The failure will
|
||||
* be reported the next time that recv[from]() is called.
|
||||
*/
|
||||
|
||||
#if CONFIG_NET_TCP_RECVDELAY > 0
|
||||
if (pstate->rf_recvlen > 0)
|
||||
{
|
||||
pstate->rf_result = 0;
|
||||
}
|
||||
else
|
||||
{
|
||||
pstate->rf_result = -ENOTCONN;
|
||||
}
|
||||
#else
|
||||
pstate->rf_result = -ENOTCONN;
|
||||
#endif
|
||||
}
|
||||
|
||||
/* Wake up the waiting thread */
|
||||
|
|
104
nuttx/net/send.c
104
nuttx/net/send.c
|
@ -1,7 +1,7 @@
|
|||
/****************************************************************************
|
||||
* net/send.c
|
||||
*
|
||||
* Copyright (C) 2007-2012 Gregory Nutt. All rights reserved.
|
||||
* Copyright (C) 2007-2013 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
|
@ -42,7 +42,9 @@
|
|||
|
||||
#include <sys/types.h>
|
||||
#include <sys/socket.h>
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <string.h>
|
||||
#include <errno.h>
|
||||
#include <debug.h>
|
||||
|
@ -62,6 +64,10 @@
|
|||
* Definitions
|
||||
****************************************************************************/
|
||||
|
||||
#if defined(CONFIG_NET_TCP_SPLIT) && !defined(CONFIG_NET_TCP_SPLIT_SIZE)
|
||||
# define CONFIG_NET_TCP_SPLIT_SIZE 40
|
||||
#endif
|
||||
|
||||
#define TCPBUF ((struct uip_tcpip_hdr *)&dev->d_buf[UIP_LLH_LEN])
|
||||
|
||||
/****************************************************************************
|
||||
|
@ -85,6 +91,9 @@ struct send_s
|
|||
#if defined(CONFIG_NET_SOCKOPTS) && !defined(CONFIG_DISABLE_CLOCK)
|
||||
uint32_t snd_time; /* last send time for determining timeout */
|
||||
#endif
|
||||
#if defined(CONFIG_NET_TCP_SPLIT)
|
||||
bool snd_odd; /* True: Odd packet in pair transaction */
|
||||
#endif
|
||||
};
|
||||
|
||||
/****************************************************************************
|
||||
|
@ -200,6 +209,14 @@ static uint16_t send_interrupt(struct uip_driver_s *dev, void *pvconn,
|
|||
|
||||
pstate->snd_sent = pstate->snd_acked;
|
||||
|
||||
#if defined(CONFIG_NET_TCP_SPLIT)
|
||||
/* Reset the the even/odd indicator to even since we need to
|
||||
* retransmit.
|
||||
*/
|
||||
|
||||
pstate->snd_odd = false;
|
||||
#endif
|
||||
|
||||
/* Fall through to re-send data from the last that was ACKed */
|
||||
}
|
||||
|
||||
|
@ -210,6 +227,8 @@ static uint16_t send_interrupt(struct uip_driver_s *dev, void *pvconn,
|
|||
/* Report not connected */
|
||||
|
||||
nllvdbg("Lost connection\n");
|
||||
|
||||
net_lostconnection(pstate->snd_sock, flags);
|
||||
pstate->snd_sent = -ENOTCONN;
|
||||
goto end_wait;
|
||||
}
|
||||
|
@ -242,6 +261,89 @@ static uint16_t send_interrupt(struct uip_driver_s *dev, void *pvconn,
|
|||
/* Get the amount of data that we can send in the next packet */
|
||||
|
||||
uint32_t sndlen = pstate->snd_buflen - pstate->snd_sent;
|
||||
|
||||
|
||||
#if defined(CONFIG_NET_TCP_SPLIT)
|
||||
|
||||
/* RFC 1122 states that a host may delay ACKing for up to 500ms but
|
||||
* must respond to every second segment). This logic here will trick
|
||||
* the RFC 1122 recipient into responding sooner. This logic will be
|
||||
* activated if:
|
||||
*
|
||||
* 1. An even number of packets has been send (where zero is an even
|
||||
* number),
|
||||
* 2. There is more data be sent (more than or equal to
|
||||
* CONFIG_NET_TCP_SPLIT_SIZE), but
|
||||
* 3. Not enough data for two packets.
|
||||
*
|
||||
* Then we will split the remaining, single packet into two partial
|
||||
* packets. This will stimulate the RFC 1122 peer to ACK sooner.
|
||||
*
|
||||
* Don't try to split very small packets (less than CONFIG_NET_TCP_SPLIT_SIZE).
|
||||
* Only the first even packet and the last odd packets could have
|
||||
* sndlen less than CONFIG_NET_TCP_SPLIT_SIZE. The value of sndlen on
|
||||
* the last even packet is guaranteed to be at least MSS/2 by the
|
||||
* logic below.
|
||||
*/
|
||||
|
||||
if (sndlen >= CONFIG_NET_TCP_SPLIT_SIZE)
|
||||
{
|
||||
/* sndlen is the number of bytes remaining to be sent.
|
||||
* uip_mss(conn) will return the number of bytes that can sent
|
||||
* in one packet. The difference, then, is the number of bytes
|
||||
* that would be sent in the next packet after this one.
|
||||
*/
|
||||
|
||||
int32_t next_sndlen = sndlen - uip_mss(conn);
|
||||
|
||||
/* Is this the even packet in the packet pair transaction? */
|
||||
|
||||
if (!pstate->snd_odd)
|
||||
{
|
||||
/* next_sndlen <= 0 means that the entire remaining data
|
||||
* could fit into this single packet. This is condition
|
||||
* in which we must do the split.
|
||||
*/
|
||||
|
||||
if (next_sndlen <= 0)
|
||||
{
|
||||
/* Split so that there will be an odd packet. Here
|
||||
* we know that 0 < sndlen <= MSS
|
||||
*/
|
||||
|
||||
sndlen = (sndlen / 2) + 1;
|
||||
}
|
||||
}
|
||||
|
||||
/* No... this is the odd packet in the packet pair transaction */
|
||||
|
||||
else
|
||||
{
|
||||
/* Will there be another (even) packet afer this one?
|
||||
* (next_sndlen > 0) Will the split conidition occur on that
|
||||
* next, even packet? ((next_sndlen - uip_mss(conn)) < 0) If
|
||||
* so, then perform the split now to avoid the case where the
|
||||
* byte count is less than CONFIG_NET_TCP_SPLIT_SIZE on the
|
||||
* next pair.
|
||||
*/
|
||||
|
||||
if (next_sndlen > 0 && (next_sndlen - uip_mss(conn)) < 0)
|
||||
{
|
||||
/* Here, we know that sndlen must be MSS < sndlen <= 2*MSS
|
||||
* and so (sndlen / 2) is <= MSS.
|
||||
*/
|
||||
|
||||
sndlen /= 2;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* Toggle the even/odd indicator */
|
||||
|
||||
pstate->snd_odd ^= true;
|
||||
|
||||
#endif /* CONFIG_NET_TCP_SPLIT */
|
||||
|
||||
if (sndlen > uip_mss(conn))
|
||||
{
|
||||
sndlen = uip_mss(conn);
|
||||
|
|
|
@ -4,7 +4,7 @@
|
|||
#
|
||||
|
||||
config MSEC_PER_TICK
|
||||
int "tick timer"
|
||||
int "Milliseconds per system timer tick"
|
||||
default 10
|
||||
---help---
|
||||
The default system timer is 100Hz or MSEC_PER_TICK=10. This setting
|
||||
|
@ -12,7 +12,7 @@ config MSEC_PER_TICK
|
|||
system timer interrupts at some interrupt interval other than 10 msec.
|
||||
|
||||
config RR_INTERVAL
|
||||
int "round robin timeslice"
|
||||
int "Round robin timeslice (MSEC)"
|
||||
default 0
|
||||
---help---
|
||||
The round robin timeslice will be set this number of milliseconds;
|
||||
|
@ -39,16 +39,91 @@ config TASK_NAME_SIZE
|
|||
disable.
|
||||
|
||||
config SCHED_HAVE_PARENT
|
||||
bool "Remember Parent"
|
||||
bool "Support parent/child task relationships"
|
||||
default n
|
||||
---help---
|
||||
Remember the ID of the parent thread when a new child thread is
|
||||
Remember the ID of the parent task when a new child task is
|
||||
created. This support enables some additional features (such as
|
||||
SIGCHLD) and modifies the behavior of other interfaces. For
|
||||
example, it makes waitpid() more standards complete by restricting
|
||||
the waited-for tasks to the children of the caller. Default:
|
||||
disabled.
|
||||
|
||||
config SCHED_CHILD_STATUS
|
||||
bool "Retain child exit status"
|
||||
default n
|
||||
depends on SCHED_HAVE_PARENT
|
||||
---help---
|
||||
If this option is selected, then the exit status of the child task
|
||||
will be retained after the child task exits. This option should be
|
||||
selected if you require knowledge of a child process' exit status.
|
||||
Without this setting, wait(), waitpid() or waitid() may fail. For
|
||||
example, if you do:
|
||||
|
||||
1) Start child task
|
||||
2) Wait for exit status (using wait(), waitpid(), or waitid()).
|
||||
|
||||
This can fail because the child task may run to completion before
|
||||
the wait begins. There is a non-standard work-around in this case:
|
||||
The above sequence will work if you disable pre-emption using
|
||||
sched_lock() prior to starting the child task, then re-enable pre-
|
||||
emption with sched_unlock() after the wait completes. This works
|
||||
because the child task is not permitted to run until the wait is in
|
||||
place.
|
||||
|
||||
The standard solution would be to enable SCHED_CHILD_STATUS. In
|
||||
this case the exit status of the child task is retained after the
|
||||
child exits and the wait will successful obtain the child task's
|
||||
exit status whether it is called before the child task exits or not.
|
||||
|
||||
Warning: If you enable this feature, then your application must
|
||||
either (1) take responsibility for reaping the child status with wait(),
|
||||
waitpid(), or waitid(), or (2) suppress retention of child status.
|
||||
If you do not reap the child status, then you have a memory leak and
|
||||
your system will eventually fail.
|
||||
|
||||
Retention of child status can be suppressed on the parent using logic like:
|
||||
|
||||
struct sigaction sa;
|
||||
|
||||
sa.sa_handler = SIG_IGN;
|
||||
sa.sa_flags = SA_NOCLDWAIT;
|
||||
int ret = sigaction(SIGCHLD, &sa, NULL);
|
||||
|
||||
config PREALLOC_CHILDSTATUS
|
||||
int "Number of pre-allocated child status"
|
||||
default 0
|
||||
depends on SCHED_CHILD_STATUS
|
||||
---help---
|
||||
To prevent runaway child status allocations and to improve
|
||||
allocation performance, child task exit status structures are pre-
|
||||
allocated when the system boots. This setting determines the number
|
||||
of child status structures that will be pre-allocated. If this
|
||||
setting is not defined or if it is defined to be zero then a value
|
||||
of 2*MAX_TASKS is used.
|
||||
|
||||
Note that there cannot be more that CONFIG_MAX_TASKS tasks in total.
|
||||
However, the number of child status structures may need to be
|
||||
significantly larger because this number includes the maximum number
|
||||
of tasks that are running PLUS the number of tasks that have exit'ed
|
||||
without having their exit status reaped (via wait(), waitid(), or
|
||||
waitpid()).
|
||||
|
||||
Obviously, if tasks spawn children indefinitely and never have the
|
||||
exit status reaped, then you may have a memory leak! If you enable
|
||||
the SCHED_CHILD_STATUS feature, then your application must take
|
||||
responsibility for either (1) reaping the child status with wait(),
|
||||
waitpid(), or waitid() or it must (2) suppress retention of child
|
||||
status. Otherwise, your system will eventually fail.
|
||||
|
||||
Retention of child status can be suppressed on the parent using logic like:
|
||||
|
||||
struct sigaction sa;
|
||||
|
||||
sa.sa_handler = SIG_IGN;
|
||||
sa.sa_flags = SA_NOCLDWAIT;
|
||||
int ret = sigaction(SIGCHLD, &sa, NULL);
|
||||
|
||||
config JULIAN_TIME
|
||||
bool "Enables Julian time conversions"
|
||||
default n
|
||||
|
@ -56,15 +131,15 @@ config JULIAN_TIME
|
|||
Enables Julian time conversions
|
||||
|
||||
config START_YEAR
|
||||
int "start year"
|
||||
int "Start year"
|
||||
default 2013
|
||||
|
||||
config START_MONTH
|
||||
int "start month"
|
||||
int "Start month"
|
||||
default 1
|
||||
|
||||
config START_DAY
|
||||
int "start day"
|
||||
int "Start day"
|
||||
default 1
|
||||
|
||||
config DEV_CONSOLE
|
||||
|
@ -88,7 +163,7 @@ config PRIORITY_INHERITANCE
|
|||
Set to enable support for priority inheritance on mutexes and semaphores.
|
||||
|
||||
config SEM_PREALLOCHOLDERS
|
||||
int "Pre-allocated holders"
|
||||
int "Number of pre-allocated holders"
|
||||
default 16
|
||||
depends on PRIORITY_INHERITANCE
|
||||
---help---
|
||||
|
@ -372,7 +447,7 @@ endif
|
|||
comment "Sizes of configurable things (0 disables)"
|
||||
|
||||
config MAX_TASKS
|
||||
int "Max tasks"
|
||||
int "Max number of tasks"
|
||||
default 32
|
||||
---help---
|
||||
The maximum number of simultaneously active tasks. This value must be
|
||||
|
@ -386,33 +461,32 @@ config MAX_TASK_ARGS
|
|||
receive (i.e., maxmum value of 'argc')
|
||||
|
||||
config NPTHREAD_KEYS
|
||||
int "Number of pthread keys"
|
||||
int "Maximum number of pthread keys"
|
||||
default 4
|
||||
---help---
|
||||
The number of items of thread-
|
||||
specific data that can be retained
|
||||
|
||||
config NFILE_DESCRIPTORS
|
||||
int "Max file descriptors"
|
||||
int "Maximum number of file descriptors per task"
|
||||
default 16
|
||||
---help---
|
||||
The maximum number of file
|
||||
descriptors (one for each open)
|
||||
The maximum number of file descriptors per task (one for each open)
|
||||
|
||||
config NFILE_STREAMS
|
||||
int "Max file streams"
|
||||
int "Maximum number of FILE streams"
|
||||
default 16
|
||||
---help---
|
||||
The maximum number of streams that can be fopen'ed
|
||||
|
||||
config NAME_MAX
|
||||
int "name max"
|
||||
int "Maximum size of a file name"
|
||||
default 32
|
||||
---help---
|
||||
The maximum size of a file name.
|
||||
|
||||
config PREALLOC_MQ_MSGS
|
||||
int "Pre-allocated messages"
|
||||
int "Number of pre-allocated messages"
|
||||
default 32
|
||||
---help---
|
||||
The number of pre-allocated message structures. The system manages
|
||||
|
@ -426,21 +500,20 @@ config MQ_MAXMSGSIZE
|
|||
setting (does not include other message structure overhead.
|
||||
|
||||
config MAX_WDOGPARMS
|
||||
int "max watchdog parms"
|
||||
int "Maximum number of watchdog parameters"
|
||||
default 4
|
||||
---help---
|
||||
Maximum number of parameters that
|
||||
can be passed to a watchdog handler
|
||||
Maximum number of parameters that can be passed to a watchdog handler
|
||||
|
||||
config PREALLOC_WDOGS
|
||||
int "Pre-allocated watchdogs"
|
||||
int "Number of pre-allocated watchdog timers"
|
||||
default 32
|
||||
---help---
|
||||
The number of pre-allocated watchdog structures. The system manages a
|
||||
pool of preallocated watchdog structures to minimize dynamic allocations
|
||||
|
||||
config PREALLOC_TIMERS
|
||||
int "Pre-allocated timers"
|
||||
int "Number of pre-allocated POSIX timers"
|
||||
default 8
|
||||
---help---
|
||||
The number of pre-allocated POSIX timer structures. The system manages a
|
||||
|
|
|
@ -35,162 +35,175 @@
|
|||
|
||||
-include $(TOPDIR)/Make.defs
|
||||
|
||||
ASRCS =
|
||||
AOBJS = $(ASRCS:.S=$(OBJEXT))
|
||||
ASRCS =
|
||||
AOBJS = $(ASRCS:.S=$(OBJEXT))
|
||||
|
||||
MISC_SRCS = os_start.c os_bringup.c errno_getptr.c errno_get.c errno_set.c \
|
||||
sched_garbage.c sched_setupstreams.c sched_getfiles.c sched_getsockets.c \
|
||||
sched_getstreams.c sched_setupidlefiles.c sched_setuptaskfiles.c \
|
||||
sched_setuppthreadfiles.c sched_releasefiles.c
|
||||
MISC_SRCS = os_start.c os_bringup.c errno_getptr.c errno_get.c errno_set.c
|
||||
MISC_SRCS += sched_garbage.c sched_setupstreams.c sched_getfiles.c sched_getsockets.c
|
||||
MISC_SRCS += sched_getstreams.c sched_setupidlefiles.c sched_setuptaskfiles.c
|
||||
MISC_SRCS += sched_setuppthreadfiles.c sched_releasefiles.c
|
||||
|
||||
TSK_SRCS = prctl.c task_create.c task_init.c task_setup.c task_activate.c \
|
||||
task_start.c task_delete.c task_deletecurrent.c task_exithook.c \
|
||||
task_restart.c task_vfork.c exit.c getpid.c sched_addreadytorun.c \
|
||||
sched_removereadytorun.c sched_addprioritized.c sched_mergepending.c \
|
||||
sched_addblocked.c sched_removeblocked.c sched_free.c sched_gettcb.c \
|
||||
sched_verifytcb.c sched_releasetcb.c
|
||||
TSK_SRCS = prctl.c task_create.c task_init.c task_setup.c task_activate.c
|
||||
TSK_SRCS += task_start.c task_delete.c task_deletecurrent.c task_exithook.c
|
||||
TSK_SRCS += task_restart.c task_vfork.c exit.c getpid.c sched_addreadytorun.c
|
||||
TSK_SRCS += sched_removereadytorun.c sched_addprioritized.c sched_mergepending.c
|
||||
TSK_SRCS += sched_addblocked.c sched_removeblocked.c sched_free.c sched_gettcb.c
|
||||
TSK_SRCS += sched_verifytcb.c sched_releasetcb.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_lock.c sched_unlock.c sched_lockcount.c sched_self.c
|
||||
ifneq ($(CONFIG_BINFMT_DISABLE),y)
|
||||
ifeq ($(CONFIG_LIBC_EXECFUNCS),y)
|
||||
TSK_SRCS += task_posixspawn.c
|
||||
endif
|
||||
endif
|
||||
|
||||
SCHED_SRCS = sched_setparam.c sched_setpriority.c sched_getparam.c
|
||||
SCHED_SRCS += sched_setscheduler.c sched_getscheduler.c
|
||||
SCHED_SRCS += sched_yield.c sched_rrgetinterval.c sched_foreach.c
|
||||
SCHED_SRCS += sched_lock.c sched_unlock.c sched_lockcount.c sched_self.c
|
||||
|
||||
ifeq ($(CONFIG_SCHED_ATEXIT),y)
|
||||
SCHED_SRCS += atexit.c
|
||||
SCHED_SRCS += atexit.c
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_SCHED_ONEXIT),y)
|
||||
SCHED_SRCS += on_exit.c
|
||||
SCHED_SRCS += on_exit.c
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_PRIORITY_INHERITANCE),y)
|
||||
SCHED_SRCS += sched_reprioritize.c
|
||||
SCHED_SRCS += sched_reprioritize.c
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_SCHED_HAVE_PARENT),y)
|
||||
SCHED_SRCS += task_reparent.c
|
||||
ifeq ($(CONFIG_SCHED_CHILD_STATUS),y)
|
||||
SCHED_SRCS += task_childstatus.c
|
||||
endif
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_SCHED_WAITPID),y)
|
||||
SCHED_SRCS += sched_waitpid.c
|
||||
SCHED_SRCS += sched_waitpid.c
|
||||
ifeq ($(CONFIG_SCHED_HAVE_PARENT),y)
|
||||
SCHED_SRCS += sched_waitid.c sched_wait.c
|
||||
SCHED_SRCS += sched_waitid.c sched_wait.c
|
||||
endif
|
||||
endif
|
||||
|
||||
ENV_SRCS = env_getenvironptr.c env_dup.c env_share.c env_release.c \
|
||||
env_findvar.c env_removevar.c \
|
||||
env_clearenv.c env_getenv.c env_putenv.c env_setenv.c env_unsetenv.c
|
||||
ENV_SRCS = env_getenvironptr.c env_dup.c env_share.c env_release.c
|
||||
ENV_SRCS += env_findvar.c env_removevar.c
|
||||
ENV_SRCS += env_clearenv.c env_getenv.c env_putenv.c env_setenv.c env_unsetenv.c
|
||||
|
||||
WDOG_SRCS = wd_initialize.c wd_create.c wd_start.c wd_cancel.c wd_delete.c \
|
||||
wd_gettime.c
|
||||
WDOG_SRCS = wd_initialize.c wd_create.c wd_start.c wd_cancel.c wd_delete.c
|
||||
WDOG_SRCS += wd_gettime.c
|
||||
|
||||
TIME_SRCS = sched_processtimer.c
|
||||
TIME_SRCS = sched_processtimer.c
|
||||
|
||||
ifneq ($(CONFIG_DISABLE_SIGNALS),y)
|
||||
TIME_SRCS += sleep.c usleep.c
|
||||
TIME_SRCS += sleep.c usleep.c
|
||||
endif
|
||||
|
||||
CLOCK_SRCS = clock_initialize.c clock_settime.c clock_gettime.c clock_getres.c \
|
||||
clock_time2ticks.c clock_abstime2ticks.c clock_ticks2time.c \
|
||||
clock_gettimeofday.c clock_systimer.c
|
||||
CLOCK_SRCS = clock_initialize.c clock_settime.c clock_gettime.c clock_getres.c
|
||||
CLOCK_SRCS += clock_time2ticks.c clock_abstime2ticks.c clock_ticks2time.c
|
||||
CLOCK_SRCS += clock_gettimeofday.c clock_systimer.c
|
||||
|
||||
SIGNAL_SRCS = sig_initialize.c \
|
||||
sig_action.c sig_procmask.c sig_pending.c sig_suspend.c \
|
||||
sig_kill.c sig_queue.c sig_waitinfo.c sig_timedwait.c \
|
||||
sig_findaction.c sig_allocatependingsigaction.c \
|
||||
sig_releasependingsigaction.c sig_unmaskpendingsignal.c \
|
||||
sig_removependingsignal.c sig_releasependingsignal.c sig_lowest.c \
|
||||
sig_mqnotempty.c sig_cleanup.c sig_received.c sig_deliver.c pause.c
|
||||
SIGNAL_SRCS = sig_initialize.c
|
||||
SIGNAL_SRCS += sig_action.c sig_procmask.c sig_pending.c sig_suspend.c
|
||||
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
|
||||
|
||||
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
|
||||
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
|
||||
|
||||
ifneq ($(CONFIG_DISABLE_SIGNALS),y)
|
||||
MQUEUE_SRCS += mq_waitirq.c
|
||||
MQUEUE_SRCS += mq_waitirq.c
|
||||
endif
|
||||
|
||||
ifneq ($(CONFIG_DISABLE_SIGNALS),y)
|
||||
MQUEUE_SRCS += mq_notify.c
|
||||
MQUEUE_SRCS += mq_notify.c
|
||||
endif
|
||||
|
||||
PTHREAD_SRCS = pthread_create.c pthread_exit.c pthread_join.c pthread_detach.c \
|
||||
pthread_yield.c pthread_getschedparam.c pthread_setschedparam.c \
|
||||
pthread_mutexinit.c pthread_mutexdestroy.c \
|
||||
pthread_mutexlock.c pthread_mutextrylock.c pthread_mutexunlock.c \
|
||||
pthread_condinit.c pthread_conddestroy.c \
|
||||
pthread_condwait.c pthread_condsignal.c pthread_condbroadcast.c \
|
||||
pthread_barrierinit.c pthread_barrierdestroy.c pthread_barrierwait.c \
|
||||
pthread_cancel.c pthread_setcancelstate.c \
|
||||
pthread_keycreate.c pthread_setspecific.c pthread_getspecific.c pthread_keydelete.c \
|
||||
pthread_initialize.c pthread_completejoin.c pthread_findjoininfo.c \
|
||||
pthread_removejoininfo.c pthread_once.c pthread_setschedprio.c
|
||||
PTHREAD_SRCS = pthread_create.c pthread_exit.c pthread_join.c pthread_detach.c
|
||||
PTHREAD_SRCS += pthread_yield.c pthread_getschedparam.c pthread_setschedparam.c
|
||||
PTHREAD_SRCS += pthread_mutexinit.c pthread_mutexdestroy.c
|
||||
PTHREAD_SRCS += pthread_mutexlock.c pthread_mutextrylock.c pthread_mutexunlock.c
|
||||
PTHREAD_SRCS += pthread_condinit.c pthread_conddestroy.c
|
||||
PTHREAD_SRCS += pthread_condwait.c pthread_condsignal.c pthread_condbroadcast.c
|
||||
PTHREAD_SRCS += pthread_barrierinit.c pthread_barrierdestroy.c pthread_barrierwait.c
|
||||
PTHREAD_SRCS += pthread_cancel.c pthread_setcancelstate.c
|
||||
PTHREAD_SRCS += pthread_keycreate.c pthread_setspecific.c pthread_getspecific.c pthread_keydelete.c
|
||||
PTHREAD_SRCS += pthread_initialize.c pthread_completejoin.c pthread_findjoininfo.c
|
||||
PTHREAD_SRCS += pthread_removejoininfo.c pthread_once.c pthread_setschedprio.c
|
||||
|
||||
ifneq ($(CONFIG_DISABLE_SIGNALS),y)
|
||||
PTHREAD_SRCS += pthread_condtimedwait.c pthread_kill.c pthread_sigmask.c
|
||||
PTHREAD_SRCS += pthread_condtimedwait.c pthread_kill.c pthread_sigmask.c
|
||||
endif
|
||||
|
||||
SEM_SRCS = sem_initialize.c sem_destroy.c sem_open.c sem_close.c sem_unlink.c \
|
||||
sem_wait.c sem_trywait.c sem_timedwait.c sem_post.c sem_findnamed.c
|
||||
SEM_SRCS = sem_initialize.c sem_destroy.c sem_open.c sem_close.c sem_unlink.c
|
||||
SEM_SRCS += sem_wait.c sem_trywait.c sem_timedwait.c sem_post.c sem_findnamed.c
|
||||
|
||||
ifneq ($(CONFIG_DISABLE_SIGNALS),y)
|
||||
SEM_SRCS += sem_waitirq.c
|
||||
SEM_SRCS += sem_waitirq.c
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_PRIORITY_INHERITANCE),y)
|
||||
SEM_SRCS += sem_holder.c
|
||||
SEM_SRCS += sem_holder.c
|
||||
endif
|
||||
|
||||
ifneq ($(CONFIG_DISABLE_POSIX_TIMERS),y)
|
||||
TIMER_SRCS = timer_initialize.c timer_create.c timer_delete.c timer_getoverrun.c \
|
||||
timer_gettime.c timer_settime.c timer_release.c
|
||||
TIMER_SRCS += timer_initialize.c timer_create.c timer_delete.c timer_getoverrun.c
|
||||
TIMER_SRCS += timer_gettime.c timer_settime.c timer_release.c
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_SCHED_WORKQUEUE),y)
|
||||
WORK_SRCS = work_thread.c work_queue.c work_cancel.c work_signal.c
|
||||
WORK_SRCS = work_thread.c work_queue.c work_cancel.c work_signal.c
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_PAGING),y)
|
||||
PGFILL_SRCS = pg_miss.c pg_worker.c
|
||||
PGFILL_SRCS = pg_miss.c pg_worker.c
|
||||
endif
|
||||
|
||||
IRQ_SRCS = irq_initialize.c irq_attach.c irq_dispatch.c irq_unexpectedisr.c
|
||||
IRQ_SRCS = irq_initialize.c irq_attach.c irq_dispatch.c irq_unexpectedisr.c
|
||||
|
||||
KMM_SRCS = kmm_initialize.c kmm_addregion.c kmm_semaphore.c \
|
||||
kmm_kmalloc.c kmm_kzalloc.c kmm_krealloc.c kmm_kfree.c
|
||||
KMM_SRCS = kmm_initialize.c kmm_addregion.c kmm_semaphore.c
|
||||
KMM_SRCS = kmm_kmalloc.c kmm_kzalloc.c kmm_krealloc.c kmm_kfree.c
|
||||
|
||||
CSRCS = $(MISC_SRCS) $(TSK_SRCS) $(SCHED_SRCS) $(WDOG_SRCS) $(TIME_SRCS) \
|
||||
$(SEM_SRCS) $(TIMER_SRCS) $(WORK_SRCS) $(PGFILL_SRCS) $(IRQ_SRCS)
|
||||
CSRCS = $(MISC_SRCS) $(TSK_SRCS) $(SCHED_SRCS) $(WDOG_SRCS) $(TIME_SRCS) \
|
||||
$(SEM_SRCS) $(TIMER_SRCS) $(WORK_SRCS) $(PGFILL_SRCS) $(IRQ_SRCS)
|
||||
|
||||
ifneq ($(CONFIG_DISABLE_CLOCK),y)
|
||||
CSRCS += $(CLOCK_SRCS)
|
||||
CSRCS += $(CLOCK_SRCS)
|
||||
endif
|
||||
|
||||
ifneq ($(CONFIG_DISABLE_PTHREAD),y)
|
||||
CSRCS += $(PTHREAD_SRCS)
|
||||
CSRCS += $(PTHREAD_SRCS)
|
||||
endif
|
||||
|
||||
ifneq ($(CONFIG_DISABLE_SIGNALS),y)
|
||||
CSRCS += $(SIGNAL_SRCS)
|
||||
CSRCS += $(SIGNAL_SRCS)
|
||||
endif
|
||||
|
||||
ifneq ($(CONFIG_DISABLE_MQUEUE),y)
|
||||
CSRCS += $(MQUEUE_SRCS)
|
||||
CSRCS += $(MQUEUE_SRCS)
|
||||
endif
|
||||
|
||||
ifneq ($(CONFIG_DISABLE_ENVIRON),y)
|
||||
CSRCS += $(ENV_SRCS)
|
||||
CSRCS += $(ENV_SRCS)
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_NUTTX_KERNEL),y)
|
||||
CSRCS += $(KMM_SRCS)
|
||||
CSRCS += $(KMM_SRCS)
|
||||
endif
|
||||
|
||||
COBJS = $(CSRCS:.c=$(OBJEXT))
|
||||
COBJS = $(CSRCS:.c=$(OBJEXT))
|
||||
|
||||
SRCS = $(ASRCS) $(CSRCS)
|
||||
OBJS = $(AOBJS) $(COBJS)
|
||||
SRCS = $(ASRCS) $(CSRCS)
|
||||
OBJS = $(AOBJS) $(COBJS)
|
||||
|
||||
BIN = libsched$(LIBEXT)
|
||||
BIN = libsched$(LIBEXT)
|
||||
|
||||
all: $(BIN)
|
||||
all: $(BIN)
|
||||
.PHONY: context depend clean distclean
|
||||
|
||||
$(AOBJS): %$(OBJEXT): %.S
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
/****************************************************************************
|
||||
* sched/os_internal.h
|
||||
*
|
||||
* Copyright (C) 2007-2012 Gregory Nutt. All rights reserved.
|
||||
* Copyright (C) 2007-2013 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
|
@ -264,10 +264,22 @@ extern const tasklist_t g_tasklisttable[NUM_TASK_STATES];
|
|||
int os_bringup(void);
|
||||
void task_start(void);
|
||||
int task_schedsetup(FAR _TCB *tcb, int priority, start_t start,
|
||||
main_t main);
|
||||
main_t main, uint8_t ttype);
|
||||
int task_argsetup(FAR _TCB *tcb, FAR const char *name, FAR const char *argv[]);
|
||||
void task_exithook(FAR _TCB *tcb, int status);
|
||||
int task_deletecurrent(void);
|
||||
#ifdef CONFIG_SCHED_HAVE_PARENT
|
||||
#ifdef CONFIG_SCHED_CHILD_STATUS
|
||||
void weak_function task_initialize(void);
|
||||
FAR struct child_status_s *task_allocchild(void);
|
||||
void task_freechild(FAR struct child_status_s *status);
|
||||
void task_addchild(FAR _TCB *tcb, FAR struct child_status_s *child);
|
||||
FAR struct child_status_s *task_findchild(FAR _TCB *tcb, pid_t pid);
|
||||
FAR struct child_status_s *task_removechild(FAR _TCB *tcb, pid_t pid);
|
||||
void task_removechildren(FAR _TCB *tcb);
|
||||
#endif
|
||||
int task_reparent(pid_t ppid, pid_t chpid);
|
||||
#endif
|
||||
#ifndef CONFIG_CUSTOM_STACK
|
||||
int kernel_thread(FAR const char *name, int priority, int stack_size,
|
||||
main_t entry, FAR const char *argv[]);
|
||||
|
|
|
@ -286,7 +286,7 @@ void os_start(void)
|
|||
|
||||
/* Initialize the processor-specific portion of the TCB */
|
||||
|
||||
g_idletcb.flags = TCB_FLAG_TTYPE_KERNEL;
|
||||
g_idletcb.flags = (TCB_FLAG_TTYPE_KERNEL | TCB_FLAG_NOCLDWAIT);
|
||||
up_initial_state(&g_idletcb);
|
||||
|
||||
/* Initialize the semaphore facility(if in link). This has to be done
|
||||
|
@ -314,6 +314,17 @@ void os_start(void)
|
|||
kmm_initialize((void*)CONFIG_HEAP_BASE, CONFIG_HEAP_SIZE);
|
||||
#endif
|
||||
|
||||
/* Initialize tasking data structures */
|
||||
|
||||
#if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS)
|
||||
#ifdef CONFIG_HAVE_WEAKFUNCTIONS
|
||||
if (task_initialize != NULL)
|
||||
#endif
|
||||
{
|
||||
task_initialize();
|
||||
}
|
||||
#endif
|
||||
|
||||
/* Initialize the interrupt handling subsystem (if included) */
|
||||
|
||||
#ifdef CONFIG_HAVE_WEAKFUNCTIONS
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
/****************************************************************************
|
||||
* sched/pthread_create.c
|
||||
*
|
||||
* 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
|
||||
|
@ -354,15 +354,10 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr,
|
|||
#endif
|
||||
}
|
||||
|
||||
/* Mark this task as a pthread (this setting will be needed in
|
||||
* task_schedsetup() when up_initial_state() is called.
|
||||
*/
|
||||
|
||||
ptcb->flags |= TCB_FLAG_TTYPE_PTHREAD;
|
||||
|
||||
/* Initialize the task control block */
|
||||
|
||||
ret = task_schedsetup(ptcb, priority, pthread_start, (main_t)start_routine);
|
||||
ret = task_schedsetup(ptcb, priority, pthread_start, (main_t)start_routine,
|
||||
TCB_FLAG_TTYPE_PTHREAD);
|
||||
if (ret != OK)
|
||||
{
|
||||
sched_releasetcb(ptcb);
|
||||
|
|
|
@ -155,12 +155,33 @@ int waitid(idtype_t idtype, id_t id, siginfo_t *info, int options)
|
|||
|
||||
sched_lock();
|
||||
|
||||
/* Verify that this task actually has children and that the the requeste
|
||||
/* Verify that this task actually has children and that the the requested
|
||||
* TCB is actually a child of this task.
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_SCHED_CHILD_STATUS
|
||||
if (rtcb->children == NULL)
|
||||
{
|
||||
/* There are no children */
|
||||
|
||||
err = ECHILD;
|
||||
goto errout_with_errno;
|
||||
}
|
||||
else if (idtype == P_PID)
|
||||
{
|
||||
if (task_findchild(rtcb, (pid_t)id) == NULL)
|
||||
{
|
||||
/* This specific pid is not a child */
|
||||
|
||||
err = ECHILD;
|
||||
goto errout_with_errno;
|
||||
}
|
||||
}
|
||||
#else
|
||||
if (rtcb->nchildren == 0)
|
||||
{
|
||||
/* There are no children */
|
||||
|
||||
err = ECHILD;
|
||||
goto errout_with_errno;
|
||||
}
|
||||
|
@ -175,11 +196,64 @@ int waitid(idtype_t idtype, id_t id, siginfo_t *info, int options)
|
|||
goto errout_with_errno;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
/* Loop until the child that we are waiting for dies */
|
||||
|
||||
for (;;)
|
||||
{
|
||||
#ifdef CONFIG_SCHED_CHILD_STATUS
|
||||
/* Check if the task has already died. Signals are not queued in
|
||||
* NuttX. So a possibility is that the child has died and we
|
||||
* missed the death of child signal (we got some other signal
|
||||
* instead).
|
||||
*/
|
||||
|
||||
DEBUGASSERT(rtcb->children);
|
||||
if (rtcb->children == NULL)
|
||||
{
|
||||
/* This should not happen. I am just wasting your FLASH. */
|
||||
|
||||
err = ECHILD;
|
||||
goto errout_with_errno;
|
||||
}
|
||||
else if (idtype == P_PID)
|
||||
{
|
||||
FAR struct child_status_s *child;
|
||||
|
||||
/* We are waiting for a specific PID. Get the current status
|
||||
* of the child task.
|
||||
*/
|
||||
|
||||
child = task_findchild(rtcb, (pid_t)id);
|
||||
DEBUGASSERT(child);
|
||||
if (!child)
|
||||
{
|
||||
/* Yikes! The child status entry just disappeared! */
|
||||
|
||||
err = ECHILD;
|
||||
goto errout_with_errno;
|
||||
}
|
||||
|
||||
/* Did the child exit? */
|
||||
|
||||
if ((child->ch_flags & CHILD_FLAG_EXITED) != 0)
|
||||
{
|
||||
/* The child has exited. Return the saved exit status */
|
||||
|
||||
info->si_signo = SIGCHLD;
|
||||
info->si_code = CLD_EXITED;
|
||||
info->si_value.sival_ptr = NULL;
|
||||
info->si_pid = (pid_t)id;
|
||||
info->si_status = child->ch_status;
|
||||
|
||||
/* Discard the child entry and break out of the loop */
|
||||
|
||||
(void)task_removechild(rtcb, (pid_t)id);
|
||||
task_freechild(child);
|
||||
}
|
||||
}
|
||||
#else
|
||||
/* Check if the task has already died. Signals are not queued in
|
||||
* NuttX. So a possibility is that the child has died and we
|
||||
* missed the death of child signal (we got some other signal
|
||||
|
@ -197,6 +271,7 @@ int waitid(idtype_t idtype, id_t id, siginfo_t *info, int options)
|
|||
err = EINTR;
|
||||
goto errout_with_errno;
|
||||
}
|
||||
#endif
|
||||
|
||||
/* Wait for any death-of-child signal */
|
||||
|
||||
|
|
|
@ -274,6 +274,9 @@ errout:
|
|||
pid_t waitpid(pid_t pid, int *stat_loc, int options)
|
||||
{
|
||||
FAR _TCB *rtcb = (FAR _TCB *)g_readytorun.head;
|
||||
#ifdef CONFIG_SCHED_CHILD_STATUS
|
||||
FAR struct child_status_s *child;
|
||||
#endif
|
||||
FAR struct siginfo info;
|
||||
sigset_t sigset;
|
||||
int err;
|
||||
|
@ -300,12 +303,33 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options)
|
|||
|
||||
sched_lock();
|
||||
|
||||
/* Verify that this task actually has children and that the the requeste
|
||||
/* Verify that this task actually has children and that the the request
|
||||
* TCB is actually a child of this task.
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_SCHED_CHILD_STATUS
|
||||
if (rtcb->children == NULL)
|
||||
{
|
||||
/* There are no children */
|
||||
|
||||
err = ECHILD;
|
||||
goto errout_with_errno;
|
||||
}
|
||||
else if (pid != (pid_t)-1)
|
||||
{
|
||||
/* This specific pid is not a child */
|
||||
|
||||
if (task_findchild(rtcb, pid) == NULL)
|
||||
{
|
||||
err = ECHILD;
|
||||
goto errout_with_errno;
|
||||
}
|
||||
}
|
||||
#else
|
||||
if (rtcb->nchildren == 0)
|
||||
{
|
||||
/* There are no children */
|
||||
|
||||
err = ECHILD;
|
||||
goto errout_with_errno;
|
||||
}
|
||||
|
@ -320,6 +344,7 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options)
|
|||
goto errout_with_errno;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
/* Loop until the child that we are waiting for dies */
|
||||
|
||||
|
@ -337,7 +362,12 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options)
|
|||
* chilren.
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_SCHED_CHILD_STATUS
|
||||
DEBUGASSERT(rtcb->children);
|
||||
if (rtcb->children == NULL)
|
||||
#else
|
||||
if (rtcb->nchildren == 0)
|
||||
#endif
|
||||
{
|
||||
/* There were one or more children when we started so they
|
||||
* must have exit'ed. There are just no bread crumbs left
|
||||
|
@ -351,6 +381,35 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options)
|
|||
}
|
||||
else
|
||||
{
|
||||
#ifdef CONFIG_SCHED_CHILD_STATUS
|
||||
/* We are waiting for a specific PID. Get the current status
|
||||
* of the child task.
|
||||
*/
|
||||
|
||||
child = task_findchild(rtcb, pid);
|
||||
DEBUGASSERT(child);
|
||||
if (!child)
|
||||
{
|
||||
/* Yikes! The child status entry just disappeared! */
|
||||
|
||||
err = ECHILD;
|
||||
goto errout_with_errno;
|
||||
}
|
||||
|
||||
/* Did the child exit? */
|
||||
|
||||
if ((child->ch_flags & CHILD_FLAG_EXITED) != 0)
|
||||
{
|
||||
/* The child has exited. Return the saved exit status */
|
||||
|
||||
*stat_loc = child->ch_status;
|
||||
|
||||
/* Discard the child entry and break out of the loop */
|
||||
|
||||
(void)task_removechild(rtcb, pid);
|
||||
task_freechild(child);
|
||||
}
|
||||
#else
|
||||
/* We are waiting for a specific PID. We can use kill() with
|
||||
* signal number 0 to determine if that task is still alive.
|
||||
*/
|
||||
|
@ -368,6 +427,7 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options)
|
|||
err = ECHILD;
|
||||
goto errout_with_errno;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
/* Wait for any death-of-child signal */
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
/****************************************************************************
|
||||
* sched/sig_action.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
|
||||
|
@ -43,6 +43,7 @@
|
|||
#include <signal.h>
|
||||
#include <queue.h>
|
||||
#include <sched.h>
|
||||
#include <errno.h>
|
||||
|
||||
#include "os_internal.h"
|
||||
#include "sig_internal.h"
|
||||
|
@ -156,10 +157,11 @@ static FAR sigactq_t *sig_allocateaction(void)
|
|||
* Assumptions:
|
||||
*
|
||||
* POSIX Compatibility:
|
||||
* - Special values of sa_handler in the struct sigaction
|
||||
* act input not handled (SIG_DFL, SIG_IGN).
|
||||
* - All sa_flags in struct sigaction of act input are
|
||||
* ignored (all treated like SA_SIGINFO).
|
||||
* - There are no default actions so the special value SIG_DFL is treated
|
||||
* like SIG_IGN.
|
||||
* - All sa_flags in struct sigaction of act input are ignored (all
|
||||
* treated like SA_SIGINFO). The one exception is if CONFIG_SCHED_CHILDSTATUS
|
||||
* is defined; then SA_NOCLDWAIT is supported but only for SIGCHLD
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
|
@ -167,90 +169,129 @@ int sigaction(int signo, FAR const struct sigaction *act, FAR struct sigaction *
|
|||
{
|
||||
FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
|
||||
FAR sigactq_t *sigact;
|
||||
int ret = ERROR; /* Assume failure */
|
||||
int ret;
|
||||
|
||||
/* Since sigactions can only be installed from the running thread of
|
||||
* execution, no special precautions should be necessary.
|
||||
*/
|
||||
|
||||
/* Verify the signal */
|
||||
/* Verify the signal number */
|
||||
|
||||
if (GOOD_SIGNO(signo))
|
||||
if (!GOOD_SIGNO(signo))
|
||||
{
|
||||
ret = OK; /* Assume success */
|
||||
set_errno(EINVAL);
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
/* Find the signal in the sigactionq */
|
||||
/* Find the signal in the sigactionq */
|
||||
|
||||
sigact = sig_findaction(rtcb, signo);
|
||||
sigact = sig_findaction(rtcb, signo);
|
||||
|
||||
/* Return the old sigaction value if so requested */
|
||||
/* Return the old sigaction value if so requested */
|
||||
|
||||
if (oact)
|
||||
if (oact)
|
||||
{
|
||||
if (sigact)
|
||||
{
|
||||
if (sigact)
|
||||
{
|
||||
COPY_SIGACTION(oact, &sigact->act);
|
||||
}
|
||||
else
|
||||
{
|
||||
/* There isn't an old value */
|
||||
|
||||
oact->sa_u._sa_handler = NULL;
|
||||
oact->sa_mask = NULL_SIGNAL_SET;
|
||||
oact->sa_flags = 0;
|
||||
}
|
||||
COPY_SIGACTION(oact, &sigact->act);
|
||||
}
|
||||
else
|
||||
{
|
||||
/* There isn't an old value */
|
||||
|
||||
/* If no sigaction was found, but one is needed, then
|
||||
* allocate one.
|
||||
oact->sa_u._sa_handler = NULL;
|
||||
oact->sa_mask = NULL_SIGNAL_SET;
|
||||
oact->sa_flags = 0;
|
||||
}
|
||||
}
|
||||
|
||||
/* If the argument act is a null pointer, signal handling is unchanged;
|
||||
* thus, the call can be used to enquire about the current handling of
|
||||
* a given signal.
|
||||
*/
|
||||
|
||||
if (!act)
|
||||
{
|
||||
return OK;
|
||||
}
|
||||
|
||||
#if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS)
|
||||
|
||||
/* Handle a special case. Retention of child status can be suppressed
|
||||
* if signo == SIGCHLD and sa_flags == SA_NOCLDWAIT.
|
||||
*
|
||||
* POSIX.1 leaves it unspecified whether a SIGCHLD signal is generated
|
||||
* when a child process terminates. In NuttX, a SIGCHLD signal is
|
||||
* generated in this case; but in some other implementations, it may not
|
||||
* be.
|
||||
*/
|
||||
|
||||
if (signo == SIGCHLD && (act->sa_flags & SA_NOCLDWAIT) != 0)
|
||||
{
|
||||
irqstate_t flags;
|
||||
|
||||
/* We do require a critical section to muck with the TCB values that
|
||||
* can be modified by the child thread.
|
||||
*/
|
||||
|
||||
if (!sigact && act && act->sa_u._sa_handler)
|
||||
flags = irqsave();
|
||||
|
||||
/* Mark that status should be not be retained */
|
||||
|
||||
rtcb->flags |= TCB_FLAG_NOCLDWAIT;
|
||||
|
||||
/* Free all pending exit status */
|
||||
|
||||
task_removechildren(rtcb);
|
||||
irqrestore(flags);
|
||||
}
|
||||
#endif
|
||||
|
||||
/* Handle the case where no sigaction is supplied (SIG_IGN) */
|
||||
|
||||
if (act->sa_u._sa_handler == SIG_IGN)
|
||||
{
|
||||
/* If there is a old sigaction, remove it from sigactionq */
|
||||
|
||||
sq_rem((FAR sq_entry_t*)sigact, &rtcb->sigactionq);
|
||||
|
||||
/* And deallocate it */
|
||||
|
||||
sig_releaseaction(sigact);
|
||||
}
|
||||
|
||||
/* A sigaction has been supplied */
|
||||
|
||||
else
|
||||
{
|
||||
/* Check if a sigaction was found */
|
||||
|
||||
if (!sigact)
|
||||
{
|
||||
/* No sigaction was found, but one is needed. Allocate one. */
|
||||
|
||||
sigact = sig_allocateaction();
|
||||
|
||||
/* An error has occurred if we could not allocate the sigaction */
|
||||
|
||||
if (!sigact)
|
||||
{
|
||||
ret = ERROR;
|
||||
}
|
||||
else
|
||||
{
|
||||
/* Put the signal number in the queue entry */
|
||||
{
|
||||
set_errno(ENOMEM);
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
sigact->signo = (uint8_t)signo;
|
||||
/* Put the signal number in the queue entry */
|
||||
|
||||
/* Add the new sigaction to sigactionq */
|
||||
sigact->signo = (uint8_t)signo;
|
||||
|
||||
sq_addlast((FAR sq_entry_t*)sigact, &rtcb->sigactionq);
|
||||
}
|
||||
/* Add the new sigaction to sigactionq */
|
||||
|
||||
sq_addlast((FAR sq_entry_t*)sigact, &rtcb->sigactionq);
|
||||
}
|
||||
|
||||
/* Set the new sigaction if so requested */
|
||||
/* Set the new sigaction */
|
||||
|
||||
if ((sigact) && (act))
|
||||
{
|
||||
/* Check if it is a request to install a new handler */
|
||||
|
||||
if (act->sa_u._sa_handler)
|
||||
{
|
||||
COPY_SIGACTION(&sigact->act, act);
|
||||
}
|
||||
|
||||
/* No.. It is a request to remove the old handler */
|
||||
|
||||
else
|
||||
{
|
||||
/* Remove the old sigaction from sigactionq */
|
||||
|
||||
sq_rem((FAR sq_entry_t*)sigact, &rtcb->sigactionq);
|
||||
|
||||
/* And deallocate it */
|
||||
|
||||
sig_releaseaction(sigact);
|
||||
}
|
||||
}
|
||||
COPY_SIGACTION(&sigact->act, act);
|
||||
}
|
||||
|
||||
return ret;
|
||||
|
|
|
@ -0,0 +1,396 @@
|
|||
/*****************************************************************************
|
||||
* sched/task_childstatus.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 <sched.h>
|
||||
#include <errno.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include "os_internal.h"
|
||||
|
||||
#if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS)
|
||||
|
||||
/*****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
*****************************************************************************/
|
||||
/* Note that there cannot be more that CONFIG_MAX_TASKS tasks in total.
|
||||
* However, the number of child status structures may need to be significantly
|
||||
* larger because this number includes the maximum number of tasks that are
|
||||
* running PLUS the number of tasks that have exit'ed without having their
|
||||
* exit status reaped (via wait(), waitid(), or waitpid()).
|
||||
*
|
||||
* Obviously, if tasks spawn children indefinitely and never have the exit
|
||||
* status reaped, then you have a memory leak!
|
||||
*/
|
||||
|
||||
#if !defined(CONFIG_PREALLOC_CHILDSTATUS) || CONFIG_PREALLOC_CHILDSTATUS == 0
|
||||
# undef CONFIG_PREALLOC_CHILDSTATUS
|
||||
# define CONFIG_PREALLOC_CHILDSTATUS (2*CONFIG_MAX_TASKS)
|
||||
#endif
|
||||
|
||||
#ifndef CONFIG_DEBUG
|
||||
# undef CONFIG_DEBUG_CHILDSTATUS
|
||||
#endif
|
||||
|
||||
/*****************************************************************************
|
||||
* Private Types
|
||||
*****************************************************************************/
|
||||
/* Globals are maintained in a structure to minimize name collisions. */
|
||||
|
||||
struct child_pool_s
|
||||
{
|
||||
struct child_status_s alloc[CONFIG_PREALLOC_CHILDSTATUS];
|
||||
FAR struct child_status_s *freelist;
|
||||
};
|
||||
|
||||
/*****************************************************************************
|
||||
* Private Data
|
||||
*****************************************************************************/
|
||||
|
||||
static struct child_pool_s g_child_pool;
|
||||
|
||||
/*****************************************************************************
|
||||
* Private Functions
|
||||
*****************************************************************************/
|
||||
|
||||
/*****************************************************************************
|
||||
* Name: task_dumpchildren
|
||||
*
|
||||
* Description:
|
||||
* Dump all of the children when the part TCB list is modified.
|
||||
*
|
||||
* Parameters:
|
||||
* tcb - The parent TCB.
|
||||
*
|
||||
* Return Value:
|
||||
* None.
|
||||
*
|
||||
* Assumptions:
|
||||
* Called early in initialization. No special precautions are required.
|
||||
*
|
||||
*****************************************************************************/
|
||||
|
||||
#ifdef CONFIG_DEBUG_CHILDSTATUS
|
||||
static void task_dumpchildren(FAR _TCB *tcb, FAR const char *msg)
|
||||
{
|
||||
FAR struct child_status_s *child;
|
||||
int i;
|
||||
|
||||
dbg("Parent TCB=%p: %s\n", tcb, msg);
|
||||
for (i = 0, child = tcb->children; child; i++, child = child->flink)
|
||||
{
|
||||
dbg(" %d. ch_flags=%02x ch_pid=%d ch_status=%d\n",
|
||||
i, child->ch_flags, child->ch_pid, child->ch_status);
|
||||
}
|
||||
}
|
||||
#else
|
||||
# task_dumpchildren(t,m)
|
||||
#endif
|
||||
|
||||
/*****************************************************************************
|
||||
* Public Functions
|
||||
*****************************************************************************/
|
||||
|
||||
/*****************************************************************************
|
||||
* Name: task_initialize
|
||||
*
|
||||
* Description:
|
||||
* Initialize task related status. At present, this includes only the
|
||||
* initialize of the child status pool.
|
||||
*
|
||||
* Parameters:
|
||||
* None.
|
||||
*
|
||||
* Return Value:
|
||||
* None.
|
||||
*
|
||||
* Assumptions:
|
||||
* Called early in initialization. No special precautions are required.
|
||||
*
|
||||
*****************************************************************************/
|
||||
|
||||
void task_initialize(void)
|
||||
{
|
||||
FAR struct child_status_s *curr;
|
||||
FAR struct child_status_s *prev;
|
||||
int i;
|
||||
|
||||
/* Save all of the child status structures in a free list */
|
||||
|
||||
prev = &g_child_pool.alloc[0];
|
||||
g_child_pool.freelist = prev;
|
||||
for (i = 0; i < CONFIG_PREALLOC_CHILDSTATUS; i++)
|
||||
{
|
||||
curr = &g_child_pool.alloc[i];
|
||||
prev->flink = curr;
|
||||
prev = curr;
|
||||
}
|
||||
}
|
||||
|
||||
/*****************************************************************************
|
||||
* Name: task_allocchild
|
||||
*
|
||||
* Description:
|
||||
* Allocate a child status structure by removing the next entry from a
|
||||
* free list.
|
||||
*
|
||||
* Parameters:
|
||||
* None.
|
||||
*
|
||||
* Return Value:
|
||||
* On success, a non-NULL pointer to a child status structure. NULL is
|
||||
* returned if there are no remaining, pre-allocated child status structures.
|
||||
*
|
||||
* Assumptions:
|
||||
* Called during task creation in a safe context. No special precautions
|
||||
* are required here.
|
||||
*
|
||||
*****************************************************************************/
|
||||
|
||||
FAR struct child_status_s *task_allocchild(void)
|
||||
{
|
||||
FAR struct child_status_s *ret;
|
||||
|
||||
/* Return the status block at the head of the free list */
|
||||
|
||||
ret = g_child_pool.freelist;
|
||||
if (ret)
|
||||
{
|
||||
g_child_pool.freelist = ret->flink;
|
||||
ret->flink = NULL;
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
/*****************************************************************************
|
||||
* Name: task_freechild
|
||||
*
|
||||
* Description:
|
||||
* Release a child status structure by returning it to a free list.
|
||||
*
|
||||
* Parameters:
|
||||
* status - The child status structure to be freed.
|
||||
*
|
||||
* Return Value:
|
||||
* None.
|
||||
*
|
||||
* Assumptions:
|
||||
* Called during task creation in a safe context. No special precautions
|
||||
* are required here.
|
||||
*
|
||||
*****************************************************************************/
|
||||
|
||||
void task_freechild(FAR struct child_status_s *child)
|
||||
{
|
||||
/* Return the child status structure to the free list */
|
||||
|
||||
if (child)
|
||||
{
|
||||
child->flink = g_child_pool.freelist;
|
||||
g_child_pool.freelist = child;
|
||||
}
|
||||
}
|
||||
|
||||
/*****************************************************************************
|
||||
* Name: task_addchild
|
||||
*
|
||||
* Description:
|
||||
* Add a child status structure in the given TCB.
|
||||
*
|
||||
* Parameters:
|
||||
* tcb - The TCB of the parent task to containing the child status.
|
||||
* child - The structure to be added
|
||||
*
|
||||
* Return Value:
|
||||
* N
|
||||
*
|
||||
* Assumptions:
|
||||
* Called during task creation processing in a safe context. No special
|
||||
* precautions are required here.
|
||||
*
|
||||
*****************************************************************************/
|
||||
|
||||
void task_addchild(FAR _TCB *tcb, FAR struct child_status_s *child)
|
||||
{
|
||||
/* Add the entry into the TCB list of children */
|
||||
|
||||
child->flink = tcb->children;
|
||||
tcb->children = child;
|
||||
|
||||
task_dumpchildren(tcb, "task_addchild");
|
||||
}
|
||||
|
||||
/*****************************************************************************
|
||||
* Name: task_findchild
|
||||
*
|
||||
* Description:
|
||||
* Find a child status structure in the given TCB. A reference to the
|
||||
* child structure is returned, but the child remains the the TCB's list
|
||||
* of children.
|
||||
*
|
||||
* Parameters:
|
||||
* tcb - The TCB of the parent task to containing the child status.
|
||||
* pid - The ID of the child to find.
|
||||
*
|
||||
* Return Value:
|
||||
* On success, a non-NULL pointer to a child status structure. NULL is
|
||||
* returned if there is child status structure for that pid in the TCB.
|
||||
*
|
||||
* Assumptions:
|
||||
* Called during SIGCHLD processing in a safe context. No special precautions
|
||||
* are required here.
|
||||
*
|
||||
*****************************************************************************/
|
||||
|
||||
FAR struct child_status_s *task_findchild(FAR _TCB *tcb, pid_t pid)
|
||||
{
|
||||
FAR struct child_status_s *child;
|
||||
|
||||
/* Find the status structure with the matching PID */
|
||||
|
||||
for (child = tcb->children; child; child = child->flink)
|
||||
{
|
||||
if (child->ch_pid == pid)
|
||||
{
|
||||
return child;
|
||||
}
|
||||
}
|
||||
|
||||
return NULL;
|
||||
}
|
||||
|
||||
/*****************************************************************************
|
||||
* Name: task_removechild
|
||||
*
|
||||
* Description:
|
||||
* Remove one child structure from the TCB. The child is removed, but is
|
||||
* not yet freed. task_freechild must be called in order to free the child
|
||||
* status structure.
|
||||
*
|
||||
* Parameters:
|
||||
* tcb - The TCB of the parent task to containing the child status.
|
||||
* pid - The ID of the child to find.
|
||||
*
|
||||
* Return Value:
|
||||
* On success, a non-NULL pointer to a child status structure. NULL is
|
||||
* returned if there is child status structure for that pid in the TCB.
|
||||
*
|
||||
* Assumptions:
|
||||
* Called during SIGCHLD processing in a safe context. No special precautions
|
||||
* are required here.
|
||||
*
|
||||
*****************************************************************************/
|
||||
|
||||
FAR struct child_status_s *task_removechild(FAR _TCB *tcb, pid_t pid)
|
||||
{
|
||||
FAR struct child_status_s *curr;
|
||||
FAR struct child_status_s *prev;
|
||||
|
||||
/* Find the status structure with the matching PID */
|
||||
|
||||
for (prev = NULL, curr = tcb->children;
|
||||
curr;
|
||||
prev = curr, curr = curr->flink)
|
||||
{
|
||||
if (curr->ch_pid == pid)
|
||||
{
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
/* Did we find it? If so, remove it from the TCB. */
|
||||
|
||||
if (curr)
|
||||
{
|
||||
/* Do we remove it from mid-list? Or from the head of the list? */
|
||||
|
||||
if (prev)
|
||||
{
|
||||
prev->flink = curr->flink;
|
||||
}
|
||||
else
|
||||
{
|
||||
tcb->children = curr->flink;
|
||||
}
|
||||
|
||||
curr->flink = NULL;
|
||||
task_dumpchildren(tcb, "task_removechild");
|
||||
}
|
||||
|
||||
return curr;
|
||||
}
|
||||
|
||||
/*****************************************************************************
|
||||
* Name: task_removechildren
|
||||
*
|
||||
* Description:
|
||||
* Remove and free all child structure from the TCB.
|
||||
*
|
||||
* Parameters:
|
||||
* tcb - The TCB of the parent task to containing the child status.
|
||||
*
|
||||
* Return Value:
|
||||
* None.
|
||||
*
|
||||
* Assumptions:
|
||||
* Called during task exit processing in a safe context. No special
|
||||
* precautions are required here.
|
||||
*
|
||||
*****************************************************************************/
|
||||
|
||||
void task_removechildren(FAR _TCB *tcb)
|
||||
{
|
||||
FAR struct child_status_s *curr;
|
||||
FAR struct child_status_s *next;
|
||||
|
||||
/* Remove all child structures for the TCB and return them to the freelist */
|
||||
|
||||
for (curr = tcb->children; curr; curr = next)
|
||||
{
|
||||
next = curr->flink;
|
||||
task_freechild(curr);
|
||||
}
|
||||
|
||||
tcb->children = NULL;
|
||||
task_dumpchildren(tcb, "task_removechildren");
|
||||
}
|
||||
|
||||
#endif /* CONFIG_SCHED_HAVE_PARENT && CONFIG_SCHED_CHILD_STATUS */
|
|
@ -1,7 +1,7 @@
|
|||
/****************************************************************************
|
||||
* sched/task_create.c
|
||||
*
|
||||
* Copyright (C) 2007-2010 Gregory Nutt. All rights reserved.
|
||||
* Copyright (C) 2007-2010, 2013 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
|
@ -81,7 +81,7 @@
|
|||
*
|
||||
* Input Parameters:
|
||||
* name - Name of the new task
|
||||
* type - Type of the new task
|
||||
* ttype - Type of the new task
|
||||
* priority - Priority of the new task
|
||||
* stack_size - size (in bytes) of the stack needed
|
||||
* entry - Entry point of a new task
|
||||
|
@ -99,10 +99,10 @@
|
|||
****************************************************************************/
|
||||
|
||||
#ifndef CONFIG_CUSTOM_STACK
|
||||
static int thread_create(const char *name, uint8_t type, int priority,
|
||||
static int thread_create(const char *name, uint8_t ttype, int priority,
|
||||
int stack_size, main_t entry, const char **argv)
|
||||
#else
|
||||
static int thread_create(const char *name, uint8_t type, int priority,
|
||||
static int thread_create(const char *name, uint8_t ttype, int priority,
|
||||
main_t entry, const char **argv)
|
||||
#endif
|
||||
{
|
||||
|
@ -142,15 +142,9 @@ static int thread_create(const char *name, uint8_t type, int priority,
|
|||
}
|
||||
#endif
|
||||
|
||||
/* Mark the type of this thread (this setting will be needed in
|
||||
* task_schedsetup() when up_initial_state() is called.
|
||||
*/
|
||||
|
||||
tcb->flags |= type;
|
||||
|
||||
/* Initialize the task control block */
|
||||
|
||||
ret = task_schedsetup(tcb, priority, task_start, entry);
|
||||
ret = task_schedsetup(tcb, priority, task_start, entry, ttype);
|
||||
if (ret != OK)
|
||||
{
|
||||
goto errout_with_tcb;
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
/****************************************************************************
|
||||
* sched/task_exithook.c
|
||||
*
|
||||
* Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
|
||||
* Copyright (C) 2011-2013 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
|
@ -202,51 +202,86 @@ static inline void task_sigchild(FAR _TCB *tcb, int status)
|
|||
FAR _TCB *ptcb;
|
||||
siginfo_t info;
|
||||
|
||||
/* Keep things stationary through the following */
|
||||
/* Only exiting tasks should generate SIGCHLD. pthreads use other
|
||||
* mechansims.
|
||||
*/
|
||||
|
||||
sched_lock();
|
||||
|
||||
/* Get the TCB of the receiving task */
|
||||
|
||||
ptcb = sched_gettcb(tcb->parent);
|
||||
if (!ptcb)
|
||||
if ((tcb->flags & TCB_FLAG_TTYPE_MASK) == TCB_FLAG_TTYPE_TASK)
|
||||
{
|
||||
/* The parent no longer exists... bail */
|
||||
/* Keep things stationary through the following */
|
||||
|
||||
sched_lock();
|
||||
|
||||
/* Get the TCB of the receiving task */
|
||||
|
||||
ptcb = sched_gettcb(tcb->parent);
|
||||
if (!ptcb)
|
||||
{
|
||||
/* The parent no longer exists... bail */
|
||||
|
||||
sched_unlock();
|
||||
return;
|
||||
}
|
||||
|
||||
#ifdef CONFIG_SCHED_CHILD_STATUS
|
||||
/* Check if the parent task has suppressed retention of child exit
|
||||
* status information. Only 'tasks' report exit status, not pthreads.
|
||||
* pthreads have a different mechanism.
|
||||
*/
|
||||
|
||||
if ((ptcb->flags & TCB_FLAG_NOCLDWAIT) == 0)
|
||||
{
|
||||
FAR struct child_status_s *child;
|
||||
|
||||
/* No.. Find the exit status entry for this task in the parent TCB */
|
||||
|
||||
child = task_findchild(ptcb, getpid());
|
||||
DEBUGASSERT(child);
|
||||
if (child)
|
||||
{
|
||||
/* Mark that the child has exit'ed */
|
||||
|
||||
child->ch_flags |= CHILD_FLAG_EXITED;
|
||||
|
||||
/* Save the exit status */
|
||||
|
||||
child->ch_status = status;
|
||||
}
|
||||
}
|
||||
#else
|
||||
/* Decrement the number of children from this parent */
|
||||
|
||||
DEBUGASSERT(ptcb->nchildren > 0);
|
||||
ptcb->nchildren--;
|
||||
#endif
|
||||
|
||||
/* Set the parent to an impossible PID. We do this because under
|
||||
* certain conditions, task_exithook() can be called multiple times.
|
||||
* If this function is called again, sched_gettcb() will fail on the
|
||||
* invalid parent PID above, nchildren will be decremented once and
|
||||
* all will be well.
|
||||
*/
|
||||
|
||||
tcb->parent = INVALID_PROCESS_ID;
|
||||
|
||||
/* Create the siginfo structure. We don't actually know the cause.
|
||||
* That is a bug. Let's just say that the child task just exit-ted
|
||||
* for now.
|
||||
*/
|
||||
|
||||
info.si_signo = SIGCHLD;
|
||||
info.si_code = CLD_EXITED;
|
||||
info.si_value.sival_ptr = NULL;
|
||||
info.si_pid = tcb->pid;
|
||||
info.si_status = status;
|
||||
|
||||
/* Send the signal. We need to use this internal interface so that we
|
||||
* can provide the correct si_code value with the signal.
|
||||
*/
|
||||
|
||||
(void)sig_received(ptcb, &info);
|
||||
sched_unlock();
|
||||
return;
|
||||
}
|
||||
|
||||
/* Decrement the number of children from this parent */
|
||||
|
||||
DEBUGASSERT(ptcb->nchildren > 0);
|
||||
ptcb->nchildren--;
|
||||
|
||||
/* Set the parent to an impossible PID. We do this because under certain
|
||||
* conditions, task_exithook() can be called multiple times. If this
|
||||
* function is called again, sched_gettcb() will fail on the invalid
|
||||
* parent PID above, nchildren will be decremented once and all will be
|
||||
* well.
|
||||
*/
|
||||
|
||||
tcb->parent = INVALID_PROCESS_ID;
|
||||
|
||||
/* Create the siginfo structure. We don't actually know the cause. That
|
||||
* is a bug. Let's just say that the child task just exit-ted for now.
|
||||
*/
|
||||
|
||||
info.si_signo = SIGCHLD;
|
||||
info.si_code = CLD_EXITED;
|
||||
info.si_value.sival_ptr = NULL;
|
||||
info.si_pid = tcb->pid;
|
||||
info.si_status = status;
|
||||
|
||||
/* Send the signal. We need to use this internal interface so that we can
|
||||
* provide the correct si_code value with the signal.
|
||||
*/
|
||||
|
||||
(void)sig_received(ptcb, &info);
|
||||
sched_unlock();
|
||||
}
|
||||
#else
|
||||
# define task_sigchild(tcb,status)
|
||||
|
@ -344,6 +379,12 @@ void task_exithook(FAR _TCB *tcb, int status)
|
|||
(void)lib_flushall(tcb->streams);
|
||||
#endif
|
||||
|
||||
/* Discard any un-reaped child status (no zombies here!) */
|
||||
|
||||
#if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS)
|
||||
task_removechildren(tcb);
|
||||
#endif
|
||||
|
||||
/* Free all file-related resources now. This gets called again
|
||||
* just be be certain when the TCB is delallocated. However, we
|
||||
* really need to close files as soon as possible while we still
|
||||
|
|
|
@ -141,7 +141,8 @@ int task_init(FAR _TCB *tcb, const char *name, int priority,
|
|||
|
||||
/* Initialize the task control block */
|
||||
|
||||
ret = task_schedsetup(tcb, priority, task_start, entry);
|
||||
ret = task_schedsetup(tcb, priority, task_start, entry,
|
||||
TCB_FLAG_TTYPE_TASK);
|
||||
if (ret == OK)
|
||||
{
|
||||
/* Setup to pass parameters to the new task */
|
||||
|
|
|
@ -1,5 +1,5 @@
|
|||
/****************************************************************************
|
||||
* libc/string/lib_ps.c
|
||||
* sched/task_posixspawn.c
|
||||
*
|
||||
* Copyright (C) 2013 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
|
@ -39,6 +39,8 @@
|
|||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <sys/wait.h>
|
||||
#include <unistd.h>
|
||||
#include <semaphore.h>
|
||||
#include <signal.h>
|
||||
#include <sched.h>
|
||||
|
@ -49,8 +51,9 @@
|
|||
#include <debug.h>
|
||||
|
||||
#include <nuttx/binfmt/binfmt.h>
|
||||
#include <nuttx/spawn.h>
|
||||
|
||||
#include "spawn/spawn.h"
|
||||
#include "os_internal.h"
|
||||
|
||||
/****************************************************************************
|
||||
* Private Types
|
||||
|
@ -75,7 +78,9 @@ struct spawn_parms_s
|
|||
****************************************************************************/
|
||||
|
||||
static sem_t g_ps_parmsem = SEM_INITIALIZER(1);
|
||||
#ifndef CONFIG_SCHED_WAITPID
|
||||
static sem_t g_ps_execsem = SEM_INITIALIZER(0);
|
||||
#endif
|
||||
static struct spawn_parms_s g_ps_parms;
|
||||
|
||||
/****************************************************************************
|
||||
|
@ -83,7 +88,7 @@ static struct spawn_parms_s g_ps_parms;
|
|||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: ps_semtake and ps_semgive
|
||||
* Name: spawn_semtake and spawn_semgive
|
||||
*
|
||||
* Description:
|
||||
* Give and take semaphores
|
||||
|
@ -97,7 +102,7 @@ static struct spawn_parms_s g_ps_parms;
|
|||
*
|
||||
****************************************************************************/
|
||||
|
||||
static void ps_semtake(FAR sem_t *sem)
|
||||
static void spawn_semtake(FAR sem_t *sem)
|
||||
{
|
||||
int ret;
|
||||
|
||||
|
@ -109,10 +114,10 @@ static void ps_semtake(FAR sem_t *sem)
|
|||
while (ret != 0);
|
||||
}
|
||||
|
||||
#define ps_semgive(sem) sem_post(sem)
|
||||
#define spawn_semgive(sem) sem_post(sem)
|
||||
|
||||
/****************************************************************************
|
||||
* Name: ps_exec
|
||||
* Name: spawn_exec
|
||||
*
|
||||
* Description:
|
||||
* Execute the task from the file system.
|
||||
|
@ -150,9 +155,9 @@ static void ps_semtake(FAR sem_t *sem)
|
|||
*
|
||||
****************************************************************************/
|
||||
|
||||
static int ps_exec(FAR pid_t *pidp, FAR const char *path,
|
||||
FAR const posix_spawnattr_t *attr,
|
||||
FAR char *const argv[])
|
||||
static int spawn_exec(FAR pid_t *pidp, FAR const char *path,
|
||||
FAR const posix_spawnattr_t *attr,
|
||||
FAR char *const argv[])
|
||||
{
|
||||
struct sched_param param;
|
||||
FAR const struct symtab_s *symtab;
|
||||
|
@ -247,7 +252,7 @@ static int ps_exec(FAR pid_t *pidp, FAR const char *path,
|
|||
|
||||
errout:
|
||||
sched_unlock();
|
||||
return OK;
|
||||
return ret;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
|
@ -417,7 +422,23 @@ static int spawn_proxy(int argc, char *argv[])
|
|||
{
|
||||
/* Start the task */
|
||||
|
||||
ret = ps_exec(g_ps_parms.pid, g_ps_parms.path, attr, g_ps_parms.argv);
|
||||
ret = spawn_exec(g_ps_parms.pid, g_ps_parms.path, attr,
|
||||
g_ps_parms.argv);
|
||||
|
||||
#ifdef CONFIG_SCHED_HAVE_PARENT
|
||||
if (ret == OK)
|
||||
{
|
||||
/* Change of the parent of the task we just spawned to our parent.
|
||||
* What should we do in the event of a failure?
|
||||
*/
|
||||
|
||||
int tmp = task_reparent(0, *g_ps_parms.pid);
|
||||
if (tmp < 0)
|
||||
{
|
||||
sdbg("ERROR: task_reparent() failed: %d\n", tmp);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
/* Post the semaphore to inform the parent task that we have completed
|
||||
|
@ -425,8 +446,10 @@ static int spawn_proxy(int argc, char *argv[])
|
|||
*/
|
||||
|
||||
g_ps_parms.result = ret;
|
||||
ps_semgive(&g_ps_execsem);
|
||||
return 0;
|
||||
#ifndef CONFIG_SCHED_WAITPID
|
||||
spawn_semgive(&g_ps_execsem);
|
||||
#endif
|
||||
return OK;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
|
@ -540,6 +563,9 @@ int posix_spawn(FAR pid_t *pid, FAR const char *path,
|
|||
{
|
||||
struct sched_param param;
|
||||
pid_t proxy;
|
||||
#ifdef CONFIG_SCHED_WAITPID
|
||||
int status;
|
||||
#endif
|
||||
int ret;
|
||||
|
||||
DEBUGASSERT(path);
|
||||
|
@ -558,7 +584,7 @@ int posix_spawn(FAR pid_t *pid, FAR const char *path,
|
|||
if (file_actions == NULL || *file_actions == NULL)
|
||||
#endif
|
||||
{
|
||||
return ps_exec(pid, path, attr, argv);
|
||||
return spawn_exec(pid, path, attr, argv);
|
||||
}
|
||||
|
||||
/* Otherwise, we will have to go through an intermediary/proxy task in order
|
||||
|
@ -574,7 +600,7 @@ int posix_spawn(FAR pid_t *pid, FAR const char *path,
|
|||
|
||||
/* Get exclusive access to the global parameter structure */
|
||||
|
||||
ps_semtake(&g_ps_parmsem);
|
||||
spawn_semtake(&g_ps_parmsem);
|
||||
|
||||
/* Populate the parameter structure */
|
||||
|
||||
|
@ -593,31 +619,56 @@ int posix_spawn(FAR pid_t *pid, FAR const char *path,
|
|||
int errcode = errno;
|
||||
|
||||
sdbg("ERROR: sched_getparam failed: %d\n", errcode);
|
||||
ps_semgive(&g_ps_parmsem);
|
||||
spawn_semgive(&g_ps_parmsem);
|
||||
return errcode;
|
||||
}
|
||||
|
||||
/* Start the intermediary/proxy task at the same priority as the parent task. */
|
||||
/* Disable pre-emption so that the proxy does not run until we waitpid
|
||||
* is called. This is probably unnecessary since the spawn_proxy has
|
||||
* the same priority as this thread; it should be schedule behind this
|
||||
* task in the ready-to-run list.
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_SCHED_WAITPID
|
||||
sched_lock();
|
||||
#endif
|
||||
|
||||
/* Start the intermediary/proxy task at the same priority as the parent
|
||||
* task.
|
||||
*/
|
||||
|
||||
proxy = TASK_CREATE("spawn_proxy", param.sched_priority,
|
||||
CONFIG_POSIX_SPAWN_STACKSIZE, (main_t)spawn_proxy,
|
||||
(FAR const char **)NULL);
|
||||
if (proxy < 0)
|
||||
{
|
||||
int errcode = errno;
|
||||
ret = get_errno();
|
||||
sdbg("ERROR: Failed to start spawn_proxy: %d\n", ret);
|
||||
|
||||
sdbg("ERROR: Failed to start spawn_proxy: %d\n", errcode);
|
||||
ps_semgive(&g_ps_parmsem);
|
||||
return errcode;
|
||||
goto errout_with_lock;
|
||||
}
|
||||
|
||||
/* Wait for the proxy to complete its job */
|
||||
|
||||
ps_semtake(&g_ps_execsem);
|
||||
#ifdef CONFIG_SCHED_WAITPID
|
||||
ret = waitpid(proxy, &status, 0);
|
||||
if (ret < 0)
|
||||
{
|
||||
sdbg("ERROR: waitpid() failed: %d\n", errno);
|
||||
goto errout_with_lock;
|
||||
}
|
||||
#else
|
||||
spawn_semtake(&g_ps_execsem);
|
||||
#endif
|
||||
|
||||
/* Get the result and relinquish our access to the parameter structure */
|
||||
|
||||
ret = g_ps_parms.result;
|
||||
ps_semgive(&g_ps_parmsem);
|
||||
return ret;
|
||||
|
||||
errout_with_lock:
|
||||
#ifdef CONFIG_SCHED_WAITPID
|
||||
sched_unlock();
|
||||
#endif
|
||||
spawn_semgive(&g_ps_parmsem);
|
||||
return ret;
|
||||
}
|
|
@ -0,0 +1,163 @@
|
|||
/*****************************************************************************
|
||||
* sched/task_reparent.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 <errno.h>
|
||||
|
||||
#include "os_internal.h"
|
||||
|
||||
#ifdef CONFIG_SCHED_HAVE_PARENT
|
||||
|
||||
/*****************************************************************************
|
||||
* Private Functions
|
||||
*****************************************************************************/
|
||||
|
||||
/*****************************************************************************
|
||||
* Public Functions
|
||||
*****************************************************************************/
|
||||
|
||||
/*****************************************************************************
|
||||
* Name: task_reparent
|
||||
*
|
||||
* Description:
|
||||
* Change the parent of a task.
|
||||
*
|
||||
* Parameters:
|
||||
* ppid - PID of the new parent task (0 for grandparent, i.e. the parent
|
||||
* of the current parent task)
|
||||
* chpid - PID of the child to be reparented.
|
||||
*
|
||||
* Return Value:
|
||||
* 0 (OK) on success; A negated errno value on failure.
|
||||
*
|
||||
*****************************************************************************/
|
||||
|
||||
int task_reparent(pid_t ppid, pid_t chpid)
|
||||
{
|
||||
#ifdef CONFIG_SCHED_CHILD_STATUS
|
||||
FAR struct child_status_s *child;
|
||||
#endif
|
||||
_TCB *ptcb;
|
||||
_TCB *chtcb;
|
||||
_TCB *otcb;
|
||||
pid_t opid;
|
||||
irqstate_t flags;
|
||||
int ret;
|
||||
|
||||
/* Disable interrupts so that nothing can change in the relatinoship of
|
||||
* the three task: Child, current parent, and new parent.
|
||||
*/
|
||||
|
||||
flags = irqsave();
|
||||
|
||||
/* Get the child tasks TCB (chtcb) */
|
||||
|
||||
chtcb = sched_gettcb(chpid);
|
||||
if (!chtcb)
|
||||
{
|
||||
ret = -ECHILD;
|
||||
goto errout_with_ints;
|
||||
}
|
||||
|
||||
/* Get the PID of the child task's parent (opid) */
|
||||
|
||||
opid = chtcb->parent;
|
||||
|
||||
/* Get the TCB of the child task's parent (otcb) */
|
||||
|
||||
otcb = sched_gettcb(opid);
|
||||
if (!otcb)
|
||||
{
|
||||
ret = -ESRCH;
|
||||
goto errout_with_ints;
|
||||
}
|
||||
|
||||
/* If new parent task's PID (ppid) is zero, then new parent is the
|
||||
* grandparent will be the new parent, i.e., the parent of the current
|
||||
* parent task.
|
||||
*/
|
||||
|
||||
if (ppid == 0)
|
||||
{
|
||||
ppid = otcb->parent;
|
||||
}
|
||||
|
||||
/* Get the new parent task's TCB (ptcb) */
|
||||
|
||||
ptcb = sched_gettcb(ppid);
|
||||
if (!ptcb)
|
||||
{
|
||||
ret = -ESRCH;
|
||||
goto errout_with_ints;
|
||||
}
|
||||
|
||||
/* Then reparent the child */
|
||||
|
||||
chtcb->parent = ppid; /* The task specified by ppid is the new parent */
|
||||
|
||||
#ifdef CONFIG_SCHED_CHILD_STATUS
|
||||
/* Remove the child status entry from old parent TCB */
|
||||
|
||||
child = task_removechild(otcb, chpid);
|
||||
if (child)
|
||||
{
|
||||
/* Add the child status entry to the new parent TCB */
|
||||
|
||||
task_addchild(ptcb, child);
|
||||
ret = OK;
|
||||
}
|
||||
else
|
||||
{
|
||||
ret = -ENOENT;
|
||||
}
|
||||
#else
|
||||
DEBUGASSERT(otcb->nchildren > 0);
|
||||
|
||||
otcb->nchildren--; /* The orignal parent now has one few children */
|
||||
ptcb->nchildren++; /* The new parent has one additional child */
|
||||
ret = OK;
|
||||
#endif
|
||||
|
||||
errout_with_ints:
|
||||
irqrestore(flags);
|
||||
return ret;
|
||||
}
|
||||
|
||||
#endif /* CONFIG_SCHED_HAVE_PARENT */
|
|
@ -153,7 +153,8 @@ static int task_assignpid(FAR _TCB *tcb)
|
|||
* Save the task ID of the parent task in the child task's TCB.
|
||||
*
|
||||
* Parameters:
|
||||
* tcb - The TCB of the new, child task.
|
||||
* tcb - The TCB of the new, child task.
|
||||
* ttype - Type of the new thread: task, pthread, or kernel thread
|
||||
*
|
||||
* Returned Value:
|
||||
* None
|
||||
|
@ -165,13 +166,57 @@ static int task_assignpid(FAR _TCB *tcb)
|
|||
****************************************************************************/
|
||||
|
||||
#ifdef CONFIG_SCHED_HAVE_PARENT
|
||||
static inline void task_saveparent(FAR _TCB *tcb)
|
||||
static inline void task_saveparent(FAR _TCB *tcb, uint8_t ttype)
|
||||
{
|
||||
FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
|
||||
|
||||
DEBUGASSERT(rtcb->nchildren < UINT16_MAX);
|
||||
/* Save the parent task's ID in the child task's TCB. I am not sure if
|
||||
* this makes sense for the case of pthreads or not, but I don't think it
|
||||
* is harmful in any event.
|
||||
*/
|
||||
|
||||
tcb->parent = rtcb->pid;
|
||||
rtcb->nchildren++;
|
||||
|
||||
/* Exit status only needs to be retained for the case of tasks, however */
|
||||
|
||||
if (ttype == TCB_FLAG_TTYPE_TASK)
|
||||
{
|
||||
#ifdef CONFIG_SCHED_CHILD_STATUS
|
||||
FAR struct child_status_s *child;
|
||||
|
||||
/* Make sure that there is not already a structure for this PID in the
|
||||
* parent TCB. There should not be.
|
||||
*/
|
||||
|
||||
child = task_findchild(rtcb, tcb->pid);
|
||||
DEBUGASSERT(!child);
|
||||
if (!child)
|
||||
{
|
||||
/* Allocate a new status structure */
|
||||
|
||||
child = task_allocchild();
|
||||
}
|
||||
|
||||
/* Did we successfully find/allocate the child status structure? */
|
||||
|
||||
DEBUGASSERT(child);
|
||||
if (child)
|
||||
{
|
||||
/* Yes.. Initialize the structure */
|
||||
|
||||
child->ch_flags = ttype;
|
||||
child->ch_pid = tcb->pid;
|
||||
child->ch_status = 0;
|
||||
|
||||
/* Add the entry into the TCB list of children */
|
||||
|
||||
task_addchild(rtcb, child);
|
||||
}
|
||||
#else
|
||||
DEBUGASSERT(rtcb->nchildren < UINT16_MAX);
|
||||
rtcb->nchildren++;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
#else
|
||||
# define task_saveparent(tcb)
|
||||
|
@ -235,7 +280,7 @@ static inline void task_dupdspace(FAR _TCB *tcb)
|
|||
* priority - Priority of the new task
|
||||
* entry - Entry point of a new task
|
||||
* main - Application start point of the new task
|
||||
* type - Type of the new thread: task, pthread, or kernel thread
|
||||
* ttype - Type of the new thread: task, pthread, or kernel thread
|
||||
*
|
||||
* Return Value:
|
||||
* OK on success; ERROR on failure.
|
||||
|
@ -245,7 +290,8 @@ static inline void task_dupdspace(FAR _TCB *tcb)
|
|||
*
|
||||
****************************************************************************/
|
||||
|
||||
int task_schedsetup(FAR _TCB *tcb, int priority, start_t start, main_t main)
|
||||
int task_schedsetup(FAR _TCB *tcb, int priority, start_t start, main_t main,
|
||||
uint8_t ttype)
|
||||
{
|
||||
int ret;
|
||||
|
||||
|
@ -264,9 +310,17 @@ int task_schedsetup(FAR _TCB *tcb, int priority, start_t start, main_t main)
|
|||
tcb->start = start;
|
||||
tcb->entry.main = main;
|
||||
|
||||
/* Save the thrad type. This setting will be needed in
|
||||
* up_initial_state() is called.
|
||||
*/
|
||||
|
||||
ttype &= TCB_FLAG_TTYPE_MASK;
|
||||
tcb->flags &= ~TCB_FLAG_TTYPE_MASK;
|
||||
tcb->flags |= ttype;
|
||||
|
||||
/* Save the task ID of the parent task in the TCB */
|
||||
|
||||
task_saveparent(tcb);
|
||||
task_saveparent(tcb, ttype);
|
||||
|
||||
/* exec(), pthread_create(), task_create(), and vfork() all
|
||||
* inherit the signal mask of the parent thread.
|
||||
|
|
|
@ -136,12 +136,6 @@ FAR _TCB *task_vforksetup(start_t retaddr)
|
|||
|
||||
(void)env_dup(child);
|
||||
|
||||
/* Mark the type of this thread (this setting will be needed in
|
||||
* task_schedsetup() when up_initial_state() is called.
|
||||
*/
|
||||
|
||||
child->flags |= TCB_FLAG_TTYPE_TASK;
|
||||
|
||||
/* Get the priority of the parent task */
|
||||
|
||||
#ifdef CONFIG_PRIORITY_INHERITANCE
|
||||
|
@ -153,7 +147,8 @@ FAR _TCB *task_vforksetup(start_t retaddr)
|
|||
/* Initialize the task control block. This calls up_initial_state() */
|
||||
|
||||
svdbg("Child priority=%d start=%p\n", priority, retaddr);
|
||||
ret = task_schedsetup(child, priority, retaddr, parent->entry.main);
|
||||
ret = task_schedsetup(child, priority, retaddr, parent->entry.main,
|
||||
TCB_FLAG_TTYPE_TASK);
|
||||
if (ret != OK)
|
||||
{
|
||||
goto errout_with_tcb;
|
||||
|
|
|
@ -43,6 +43,8 @@
|
|||
"prctl","sys/prctl.h", "CONFIG_TASK_NAME_SIZE > 0","int","int","..."
|
||||
"clock_systimer","nuttx/clock.h","!defined(CONFIG_DISABLE_CLOCK)","uint32_t"
|
||||
"poll","poll.h","!defined(CONFIG_DISABLE_POLL) && (CONFIG_NSOCKET_DESCRIPTORS > 0 || CONFIG_NFILE_DESCRIPTORS > 0)","int","FAR struct pollfd*","nfds_t","int"
|
||||
"posix_spawnp", defined(CONFIG_BINFMT_EXEPATH), "int","FAR pid_t *","FAR const char *","FAR const posix_spawn_file_actions_t *","FAR const posix_spawnattr_t *","FAR char *const []","FAR char *const []"
|
||||
"posix_spawn", !defined(CONFIG_BINFMT_EXEPATH), "int","FAR pid_t *","FAR const char *","FAR const posix_spawn_file_actions_t *","FAR const posix_spawnattr_t *","FAR char *const []","FAR char *const []"
|
||||
"pthread_barrier_destroy","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_barrier_t*"
|
||||
"pthread_barrier_init","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_barrier_t*","FAR const pthread_barrierattr_t*","unsigned int"
|
||||
"pthread_barrier_wait","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_barrier_t*"
|
||||
|
|
Can't render this file because it has a wrong number of fields in line 2.
|
|
@ -37,14 +37,18 @@ include $(TOPDIR)/.config
|
|||
include $(EXPORTDIR)/Make.defs
|
||||
|
||||
ifdef ARCHSCRIPT
|
||||
#
|
||||
# ARCHSCRIPT may contain a leading -T; it must not be followed by a space
|
||||
# for this to work.
|
||||
#
|
||||
ifeq ($(WINTOOL),y)
|
||||
LDPATH = ${shell cygpath -u $(patsubst -T,,$(ARCHSCRIPT))}
|
||||
LDPATH = $(shell cygpath -u $(patsubst -T%,%,$(ARCHSCRIPT)))
|
||||
else
|
||||
LDPATH = $(patsubst -T,,$(ARCHSCRIPT))
|
||||
LDPATH = $(patsubst -T%,%,$(ARCHSCRIPT))
|
||||
endif
|
||||
|
||||
LDNAME = ${shell basename ${LDPATH}}
|
||||
LDDIR = ${shell dirname ${LDPATH}}
|
||||
LDNAME = ${notdir ${LDPATH}}
|
||||
LDDIR = ${dir ${LDPATH}}
|
||||
endif
|
||||
|
||||
ARCHSUBDIR = "arch/$(CONFIG_ARCH)/src"
|
||||
|
|
|
@ -116,7 +116,7 @@ int main(int argc, char **argv, char **envp)
|
|||
printf(" * configured (at present, NXFLAT is the only supported binary.\n");
|
||||
printf(" * format).\n");
|
||||
printf(" */\n\n");
|
||||
printf("#if !defined(CONFIG_NXFLAT) && !defined(CONFIG_ELF)\n");
|
||||
printf("#if !defined(CONFIG_NXFLAT) && !defined(CONFIG_ELF) && !defined(CONFIG_BUILTIN)\n");
|
||||
printf("# undef CONFIG_BINFMT_DISABLE\n");
|
||||
printf("# define CONFIG_BINFMT_DISABLE 1\n");
|
||||
printf("#endif\n\n");
|
||||
|
|
Loading…
Reference in New Issue