From ad65a046170ddff04e8257597197b3df758fa0a9 Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 24 Jan 2013 14:14:44 +0000 Subject: Convert configs/olimex-lpc1766stk/nettest to use kconfig-frontends git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5555 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/sched/task_setup.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) (limited to 'nuttx/sched') diff --git a/nuttx/sched/task_setup.c b/nuttx/sched/task_setup.c index 80aefded3..8f54b2e93 100644 --- a/nuttx/sched/task_setup.c +++ b/nuttx/sched/task_setup.c @@ -219,7 +219,7 @@ static inline void task_saveparent(FAR _TCB *tcb, uint8_t ttype) } } #else -# define task_saveparent(tcb) +# define task_saveparent(tcb,ttype) #endif /**************************************************************************** -- cgit v1.2.3 From f914a905566ed97b414c4475a22ff8a7a6f222a0 Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 24 Jan 2013 16:28:15 +0000 Subject: apps/examples/nettest and poll: Complete Kconfig files git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5556 42af7a65-404d-4744-a932-0658087f49c3 --- apps/ChangeLog.txt | 1 + apps/examples/README.txt | 4 ++-- apps/examples/nettest/Kconfig | 43 +++++++++++++++++++++++++++++++++++++++++ apps/examples/nettest/Makefile | 2 +- apps/examples/nettest/nettest.h | 4 ++-- apps/examples/poll/Kconfig | 18 +++++++++++++++++ nuttx/drivers/Kconfig | 8 ++++++++ nuttx/drivers/loop.c | 2 +- nuttx/fs/Kconfig | 4 ++++ nuttx/sched/Kconfig | 10 ---------- 10 files changed, 80 insertions(+), 16 deletions(-) (limited to 'nuttx/sched') diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt index bcc0ac172..5f3440897 100644 --- a/apps/ChangeLog.txt +++ b/apps/ChangeLog.txt @@ -492,3 +492,4 @@ 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. + * apps/examples/nettest and poll: Complete Kconfig files. diff --git a/apps/examples/README.txt b/apps/examples/README.txt index 5996cbb70..03d43f1a0 100644 --- a/apps/examples/README.txt +++ b/apps/examples/README.txt @@ -675,8 +675,8 @@ examples/mount when CONFIG_EXAMPLES_MOUNT_DEVNAME is not defined. The default is zero (meaning that "/dev/ram0" will be used). -examples/netttest -^^^^^^^^^^^^^^^^^ +examples/nettest +^^^^^^^^^^^^^^^^ This is a simple network test for verifying client- and server- functionality in a TCP/IP connection. diff --git a/apps/examples/nettest/Kconfig b/apps/examples/nettest/Kconfig index 63d34ec3f..613b8ea91 100644 --- a/apps/examples/nettest/Kconfig +++ b/apps/examples/nettest/Kconfig @@ -6,8 +6,51 @@ config EXAMPLES_NETTEST bool "Network test example" default n + depends on NET_TCP ---help--- Enable the network test example if EXAMPLES_NETTEST + +config EXAMPLES_NETTEST_SERVER + bool "Target is server" + default n + ---help--- + Select to use the host as the client side of the test. Default: The + target is the client side of the test + +config EXAMPLES_NETTEST_PERFORMANCE + bool "Test for Performance" + default n + ---help--- + Configure the example to test for network performance. Default: Test + is for network functionality. + +config EXAMPLES_NETTEST_NOMAC + bool "Use Canned MAC Address" + default n + +config EXAMPLES_NETTEST_IPADDR + hex "Target IP address" + default 0x0a000002 + +config EXAMPLES_NETTEST_DRIPADDR + hex "Default Router IP address (Gateway)" + default 0x0a000001 + +config EXAMPLES_NETTEST_NETMASK + hex "Network Mask" + default 0xffffff00 + +config EXAMPLES_NETTEST_CLIENTIP + hex "Client IP Address" + default 0x0a000001 if !EXAMPLES_NETTEST_SERVER + default 0x0a000002 if EXAMPLES_NETTEST_SERVER + ---help--- + IP address of the client. If the target is the client, then + EXAMPLES_NETTEST_CLIENTIP should be the same as + EXAMPLES_NETTEST_IPADDR (default). If the target is the server, + then the default value of EXAMPLES_NETTEST_CLIENTIP is set to the + gateway address, EXAMPLES_NETTEST_DRIPADDR. + endif diff --git a/apps/examples/nettest/Makefile b/apps/examples/nettest/Makefile index 5368bdefc..c533c9dd5 100644 --- a/apps/examples/nettest/Makefile +++ b/apps/examples/nettest/Makefile @@ -64,7 +64,7 @@ else endif endif -HOSTCFLAGS += -DCONFIG_EXAMPLES_NETTEST_HOST=1 +HOSTCFLAGS += -DNETTEST_HOST=1 ifeq ($(CONFIG_EXAMPLES_NETTEST_SERVER),y) HOSTCFLAGS += -DCONFIG_EXAMPLES_NETTEST_SERVER=1 -DCONFIG_EXAMPLES_NETTEST_CLIENTIP="$(CONFIG_EXAMPLES_NETTEST_CLIENTIP)" endif diff --git a/apps/examples/nettest/nettest.h b/apps/examples/nettest/nettest.h index f05038584..37ac470d1 100644 --- a/apps/examples/nettest/nettest.h +++ b/apps/examples/nettest/nettest.h @@ -40,7 +40,7 @@ * Included Files ****************************************************************************/ -#ifdef CONFIG_EXAMPLES_NETTEST_HOST +#ifdef NETTEST_HOST #else # include #endif @@ -49,7 +49,7 @@ * Definitions ****************************************************************************/ -#ifdef CONFIG_EXAMPLES_NETTEST_HOST +#ifdef NETTEST_HOST /* HTONS/L macros are unique to uIP */ # define HTONS(a) htons(a) diff --git a/apps/examples/poll/Kconfig b/apps/examples/poll/Kconfig index c52827496..f35a9200b 100644 --- a/apps/examples/poll/Kconfig +++ b/apps/examples/poll/Kconfig @@ -6,8 +6,26 @@ config EXAMPLES_POLL bool "Poll example" default n + depends on !NSH_BUILTIN_APPS ---help--- Enable the poll example if EXAMPLES_POLL + +config EXAMPLES_POLL_NOMAC + bool "Use Canned MAC Address" + default n + +config EXAMPLES_POLL_IPADDR + hex "Target IP address" + default 0x0a000002 + +config EXAMPLES_POLL_DRIPADDR + hex "Default Router IP address (Gateway)" + default 0x0a000001 + +config EXAMPLES_POLL_NETMASK + hex "Network Mask" + default 0xffffff00 + endif diff --git a/nuttx/drivers/Kconfig b/nuttx/drivers/Kconfig index 3ced01b58..f3d2c871a 100644 --- a/nuttx/drivers/Kconfig +++ b/nuttx/drivers/Kconfig @@ -3,6 +3,14 @@ # see misc/tools/kconfig-language.txt. # +config DISABLE_POLL + bool "Disable driver poll interfaces" + default n + ---help--- + The sizes of drivers can be reduced if the poll() method is not + supported. If you do not use poll() or select(), then you can + select DISABLE_POLL to reduce the code footprint by a small amount. + config DEV_NULL bool "Enable /dev/null" default y diff --git a/nuttx/drivers/loop.c b/nuttx/drivers/loop.c index b5b5d82d8..4744ae0dd 100644 --- a/nuttx/drivers/loop.c +++ b/nuttx/drivers/loop.c @@ -268,7 +268,7 @@ static ssize_t loop_write(FAR struct inode *inode, const unsigned char *buffer, size_t start_sector, unsigned int nsectors) { FAR struct loop_struct_s *dev; - size_t nbyteswritten; + ssize_t nbyteswritten; off_t offset; int ret; diff --git a/nuttx/fs/Kconfig b/nuttx/fs/Kconfig index dfbfda3fa..ab03a2b64 100644 --- a/nuttx/fs/Kconfig +++ b/nuttx/fs/Kconfig @@ -5,6 +5,10 @@ comment "File system configuration" +config DISABLE_MOUNTPOINT + bool "Disable support for mount points" + default n + source fs/mmap/Kconfig source fs/fat/Kconfig source fs/nfs/Kconfig diff --git a/nuttx/sched/Kconfig b/nuttx/sched/Kconfig index fe9a88085..7ea301600 100644 --- a/nuttx/sched/Kconfig +++ b/nuttx/sched/Kconfig @@ -379,21 +379,11 @@ config DISABLE_MQUEUE depends on DISABLE_OS_API default n -config DISABLE_MOUNTPOINT - bool "Disable support for mount points" - depends on DISABLE_OS_API - default n - config DISABLE_ENVIRON bool "Disable environment variable support" depends on DISABLE_OS_API default n -config DISABLE_POLL - bool "Disable driver poll interfaces" - depends on DISABLE_OS_API - default n - if !DISABLE_SIGNALS comment "Signal Numbers" -- cgit v1.2.3 From 888306f7280390e610544289429660d444a637c0 Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 24 Jan 2013 18:39:53 +0000 Subject: Add psock_poll(); Fix some warnings reported by Lorenz Meier; lm4f logic from JP git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5557 42af7a65-404d-4744-a932-0658087f49c3 --- apps/nshlib/nsh_ddcmd.c | 2 +- nuttx/ChangeLog | 1 + nuttx/arch/arm/include/lm/chip.h | 26 +++++++++- nuttx/configs/lm3s6965-ek/tools/oocd.sh | 2 +- nuttx/include/nuttx/net/net.h | 85 ++++++++++++++++++--------------- nuttx/libc/stdio/lib_libfread.c | 4 +- nuttx/net/send.c | 2 +- nuttx/sched/mq_sndinternal.c | 2 +- 8 files changed, 78 insertions(+), 46 deletions(-) (limited to 'nuttx/sched') diff --git a/apps/nshlib/nsh_ddcmd.c b/apps/nshlib/nsh_ddcmd.c index 40a3710b1..e6ef2523c 100644 --- a/apps/nshlib/nsh_ddcmd.c +++ b/apps/nshlib/nsh_ddcmd.c @@ -545,7 +545,7 @@ int cmd_dd(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv) } #endif - if (dd.skip < 0 || dd.skip > dd.nsectors) + if (dd.skip > dd.nsectors) { nsh_output(vtbl, g_fmtarginvalid, g_dd); goto errout_with_paths; diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 36286c77f..ffd1b66ae 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -4020,4 +4020,5 @@ Denis Carikli). * configs/olimex-lpc1766stk/nettest: Configuration converted to use the kconfig-frontends tools. + * net/net_poll.c: Split net_poll() to create psock_poll() too. diff --git a/nuttx/arch/arm/include/lm/chip.h b/nuttx/arch/arm/include/lm/chip.h index 6b49fe2ce..6214a50d0 100644 --- a/nuttx/arch/arm/include/lm/chip.h +++ b/nuttx/arch/arm/include/lm/chip.h @@ -3,6 +3,7 @@ * * Copyright (C) 2009-2010, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt + * Author: Jose Pablo Carballo * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -50,6 +51,7 @@ #if defined(CONFIG_ARCH_CHIP_LM3S6918) # define LM_NTIMERS 4 /* Four general purpose timers */ +# define LM_NWIDETIMERS 0 /* No general purpose wide timers */ # define LM_NETHCONTROLLERS 1 /* One Ethernet controller */ # undef LM_ETHTS /* No timestamp register */ # define LM_NSSI 2 /* Two SSI modules */ @@ -59,8 +61,10 @@ # define LM_NPWM 0 /* No PWM generator modules */ # define LM_NQEI 0 /* No quadrature encoders */ # define LM_NPORTS 8 /* 8 Ports (GPIOA-H) 5-38 GPIOs */ +# define LM_NCANCONTROLLER 0 /* No CAN controllers */ #elif defined(CONFIG_ARCH_CHIP_LM3S6432) # define LM_NTIMERS 3 /* Three general purpose timers */ +# define LM_NWIDETIMERS 0 /* No general purpose wide timers */ # define LM_NETHCONTROLLERS 1 /* One Ethernet controller */ # undef LM_ETHTS /* No timestamp register */ # define LM_NSSI 1 /* One SSI module */ @@ -70,8 +74,10 @@ # define LM_NPWM 1 /* One PWM generator module */ # define LM_NQEI 0 /* No quadrature encoders */ # define LM_NPORTS 7 /* 7 Ports (GPIOA-G), 0-42 GPIOs */ +# define LM_NCANCONTROLLER 0 /* No CAN controllers */ #elif defined(CONFIG_ARCH_CHIP_LM3S6965) # define LM_NTIMERS 4 /* Four general purpose timers */ +# define LM_NWIDETIMERS 0 /* No general purpose wide timers */ # define LM_NETHCONTROLLERS 1 /* One Ethernet controller */ # undef LM_ETHTS /* No timestamp register */ # define LM_NSSI 1 /* One SSI module */ @@ -81,8 +87,10 @@ # define LM_NPWM 3 /* Three PWM generator modules */ # define LM_NQEI 2 /* Two quadrature encoders */ # define LM_NPORTS 7 /* 7 Ports (GPIOA-G), 0-42 GPIOs */ +# define LM_NCANCONTROLLER 0 /* No CAN controllers */ #elif defined(CONFIG_ARCH_CHIP_LM3S9B96) # define LM_NTIMERS 4 /* Four general purpose timers */ +# define LM_NWIDETIMERS 0 /* No general purpose wide timers */ # define LM_NETHCONTROLLERS 1 /* One Ethernet controller */ # undef LM_ETHTS /* No timestamp register */ # define LM_NSSI 2 /* Two SSI modules */ @@ -93,8 +101,10 @@ # define LM_NPWM 4 /* Four PWM generator modules */ # define LM_NQEI 2 /* Two quadrature encoders */ # define LM_NPORTS 9 /* 9 Ports (GPIOA-H,J) 0-65 GPIOs */ +# define LM_NCANCONTROLLER 0 /* No CAN controllers */ #elif defined(CONFIG_ARCH_CHIP_LM3S8962) -# define LM_NTIMERS 4 /* Four general purpose timers */ +# define LM_NTIMERS 6 /* Four general purpose timers */ +# define LM_NWIDETIMERS 0 /* No general purpose wide timers */ # define LM_NETHCONTROLLERS 1 /* One Ethernet controller */ # define LM_NSSI 1 /* One SSI module */ # define LM_NUARTS 3 /* Two UART modules */ @@ -103,7 +113,19 @@ # define LM_NPWM 3 /* Three PWM generator modules */ # define LM_NQEI 2 /* Two quadrature encoders */ # define LM_NPORTS 7 /* 7 Ports (GPIOA-G), 5-42 GPIOs */ -# define LM_CANCONTROLLER 1 /* One CAN controller */ +# define LM_NCANCONTROLLER 1 /* One CAN controller */ +#elif defined(CONFIG_ARCH_CHIP_LM4F120) +# define LM_NTIMERS 6 /* Six general purpose timers */ +# define LM_NWIDETIMERS 6 /* Six general purpose wide timers */ +# define LM_NETHCONTROLLERS 0 /* No Ethernet controller */ +# define LM_NSSI 4 /* Four SSI module */ +# define LM_NUARTS 8 /* Eight UART modules */ +# define LM_NI2C 4 /* Four I2C modules */ +# define LM_NADC 2 /* Two ADC modules */ +# define LM_NPWM 0 /* No PWM generator modules */ +# define LM_NQEI 0 /* No quadrature encoders */ +# define LM_NPORTS 6 /* 6 Ports (GPIOA-F), 0-43 GPIOs */ +# define LM_NCANCONTROLLER 1 /* One CAN controller */ #else # error "Capabilities not specified for this Stellaris chip" #endif diff --git a/nuttx/configs/lm3s6965-ek/tools/oocd.sh b/nuttx/configs/lm3s6965-ek/tools/oocd.sh index 28bcc48a7..758d11450 100755 --- a/nuttx/configs/lm3s6965-ek/tools/oocd.sh +++ b/nuttx/configs/lm3s6965-ek/tools/oocd.sh @@ -22,7 +22,7 @@ TARGET_PATH="/usr/share/openocd/scripts" # like environment #OPENOCD_EXE=openocd.exe OPENOCD_EXE=openocd -OPENOCD_CFG="${TOPDIR}/configs/lm3s6965-ek/tools/ek-lm3s6965.cfg" +OPENOCD_CFG="${TOPDIR}/configs/lm3s6965-ek/tools/lm3s6965-ek.cfg" OPENOCD_ARGS="-f ${OPENOCD_CFG} -s ${TARGET_PATH}" if [ "X$2" = "X-d" ]; then diff --git a/nuttx/include/nuttx/net/net.h b/nuttx/include/nuttx/net/net.h index b79dda755..b625b2fbe 100644 --- a/nuttx/include/nuttx/net/net.h +++ b/nuttx/include/nuttx/net/net.h @@ -117,110 +117,115 @@ struct uip_driver_s; /* Forward reference. See nuttx/net/uip/uip-arch.h */ typedef int (*netdev_callback_t)(FAR struct uip_driver_s *dev, void *arg); /**************************************************************************** - * Public Function Prototypes + * Public Data ****************************************************************************/ #ifdef __cplusplus #define EXTERN extern "C" -extern "C" { +extern "C" +{ #else #define EXTERN extern #endif +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + /* net_checksd.c *************************************************************/ /* Check if the socket descriptor is valid for the provided TCB and if it * supports the requested access. */ -EXTERN int net_checksd(int fd, int oflags); +int net_checksd(int fd, int oflags); /* net_sockets.c *************************************************************/ /* There interfaces are called only from OS scheduling and iniialization logic * under sched/ */ -EXTERN void weak_function net_initialize(void); -EXTERN FAR struct socketlist *net_alloclist(void); -EXTERN int net_addreflist(FAR struct socketlist *list); -EXTERN int net_releaselist(FAR struct socketlist *list); +void weak_function net_initialize(void); +FAR struct socketlist *net_alloclist(void); +int net_addreflist(FAR struct socketlist *list); +int net_releaselist(FAR struct socketlist *list); /* Given a socket descriptor, return the underly NuttX-specific socket * structure. */ -EXTERN FAR struct socket *sockfd_socket(int sockfd); +FAR struct socket *sockfd_socket(int sockfd); /* socket.c ******************************************************************/ /* socket using underlying socket structure */ -EXTERN int psock_socket(int domain, int type, int protocol, - FAR struct socket *psock); +int psock_socket(int domain, int type, int protocol, FAR struct socket *psock); /* net_close.c ***************************************************************/ /* The standard close() operation redirects operations on socket descriptors * to this function. */ -EXTERN int net_close(int sockfd); +int net_close(int sockfd); /* Performs the close operation on a socket instance */ -EXTERN int psock_close(FAR struct socket *psock); +int psock_close(FAR struct socket *psock); /* net_close.c ***************************************************************/ /* Performs the bind() operation on a socket instance */ -EXTERN int psock_bind(FAR struct socket *psock, - FAR const struct sockaddr *addr, socklen_t addrlen); +int psock_bind(FAR struct socket *psock, FAR const struct sockaddr *addr, + socklen_t addrlen); /* connect.c *****************************************************************/ /* Performs the connect() operation on a socket instance */ -EXTERN int psock_connect(FAR struct socket *psock, - FAR const struct sockaddr *addr, socklen_t addrlen); +int psock_connect(FAR struct socket *psock, FAR const struct sockaddr *addr, + socklen_t addrlen); /* send.c ********************************************************************/ /* Send using underlying socket structure */ -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, const void *buf, size_t len, + int flags); /* sendto.c ******************************************************************/ /* Sendto using underlying socket structure */ -EXTERN ssize_t psock_sendto(FAR struct socket *psock, FAR const void *buf, - size_t len, int flags, FAR const struct sockaddr *to, - socklen_t tolen); +ssize_t psock_sendto(FAR struct socket *psock, FAR const void *buf, + size_t len, int flags, FAR const struct sockaddr *to, + socklen_t tolen); /* recvfrom.c ****************************************************************/ /* recvfrom using the underlying socket structure */ -EXTERN ssize_t psock_recvfrom(FAR struct socket *psock, FAR void *buf, - size_t len, int flags,FAR struct sockaddr *from, - FAR socklen_t *fromlen); +ssize_t psock_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len, + int flags,FAR struct sockaddr *from, + FAR socklen_t *fromlen); /* recv using the underlying socket structure */ -#define psock_recv(psock,buf,len,flags) psock_recvfrom(psock,buf,len,flags,NULL,0) +#define psock_recv(psock,buf,len,flags) \ + psock_recvfrom(psock,buf,len,flags,NULL,0) /* getsockopt.c **************************************************************/ /* getsockopt using the underlying socket structure */ -EXTERN int psock_getsockopt(FAR struct socket *psock, int level, int option, - FAR void *value, FAR socklen_t *value_len); +int psock_getsockopt(FAR struct socket *psock, int level, int option, + FAR void *value, FAR socklen_t *value_len); /* setsockopt.c **************************************************************/ /* setsockopt using the underlying socket structure */ -EXTERN int psock_setsockopt(FAR struct socket *psock, int level, int option, - FAR const void *value, socklen_t value_len); +int psock_setsockopt(FAR struct socket *psock, int level, int option, + FAR const void *value, socklen_t value_len); /* net_ioctl.c ***************************************************************/ /* The standard ioctl() operation redirects operations on socket descriptors * to this function. */ -EXTERN int netdev_ioctl(int sockfd, int cmd, unsigned long arg); +int netdev_ioctl(int sockfd, int cmd, unsigned long arg); /* net_poll.c ****************************************************************/ /* The standard poll() operation redirects operations on socket descriptors @@ -229,7 +234,9 @@ EXTERN int netdev_ioctl(int sockfd, int cmd, unsigned long arg); #ifndef CONFIG_DISABLE_POLL struct pollfd; /* Forward reference -- see poll.h */ -EXTERN int net_poll(int sockfd, struct pollfd *fds, bool setup); + +int psock_poll(FAR struct socket *psock, struct pollfd *fds, bool setup); +int net_poll(int sockfd, struct pollfd *fds, bool setup); #endif /* net_dup.c *****************************************************************/ @@ -237,7 +244,7 @@ EXTERN int net_poll(int sockfd, struct pollfd *fds, bool setup); * this function */ -EXTERN int net_dup(int sockfd, int minsd); +int net_dup(int sockfd, int minsd); /* net_dup2.c ****************************************************************/ /* The standard dup2() operation redirects operations on socket descriptors to @@ -245,7 +252,7 @@ EXTERN int net_dup(int sockfd, int minsd); */ #if CONFIG_NFILE_DESCRIPTORS > 0 -EXTERN int net_dup2(int sockfd1, int sockfd2); +int net_dup2(int sockfd1, int sockfd2); #else # define net_dup2(sockfd1, sockfd2) dup2(sockfd1, sockfd2) #endif @@ -253,12 +260,12 @@ EXTERN int net_dup2(int sockfd1, int sockfd2); /* net_clone.c ***************************************************************/ /* Performs the low level, common portion of net_dup() and net_dup2() */ -EXTERN int net_clone(FAR struct socket *psock1, FAR struct socket *psock2); +int net_clone(FAR struct socket *psock1, FAR struct socket *psock2); /* net_vfcntl.c **************************************************************/ /* Performs fcntl operations on socket */ -EXTERN int net_vfcntl(int sockfd, int cmd, va_list ap); +int net_vfcntl(int sockfd, int cmd, va_list ap); /* netdev-register.c *********************************************************/ /* This function is called by network interface device drivers to inform the @@ -267,23 +274,23 @@ EXTERN int net_vfcntl(int sockfd, int cmd, va_list ap); * addresses */ -EXTERN int netdev_register(FAR struct uip_driver_s *dev); +int netdev_register(FAR struct uip_driver_s *dev); /* netdev-unregister.c *********************************************************/ /* Unregister a network device driver. */ -EXTERN int netdev_unregister(FAR struct uip_driver_s *dev); +int netdev_unregister(FAR struct uip_driver_s *dev); /* net_foreach.c ************************************************************/ /* Enumerates all registered network devices */ -EXTERN int netdev_foreach(netdev_callback_t callback, void *arg); +int netdev_foreach(netdev_callback_t callback, void *arg); /* drivers/net/slip.c ******************************************************/ /* Instantiate a SLIP network interface. */ #ifdef CONFIG_NET_SLIP -EXTERN int slip_initialize(int intf, const char *devname); +int slip_initialize(int intf, const char *devname); #endif #undef EXTERN diff --git a/nuttx/libc/stdio/lib_libfread.c b/nuttx/libc/stdio/lib_libfread.c index 3e851bf17..f8cf0f40a 100644 --- a/nuttx/libc/stdio/lib_libfread.c +++ b/nuttx/libc/stdio/lib_libfread.c @@ -1,7 +1,7 @@ /**************************************************************************** * libc/stdio/lib_libfread.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 * * Redistribution and use in source and binary forms, with or without @@ -88,7 +88,9 @@ ssize_t lib_fread(FAR void *ptr, size_t count, FAR FILE *stream) { unsigned char *dest = (unsigned char*)ptr; ssize_t bytes_read; +#if CONFIG_STDIO_BUFFER_SIZE > 0 int ret; +#endif /* Make sure that reading from this stream is allowed */ diff --git a/nuttx/net/send.c b/nuttx/net/send.c index 79dfef4ec..b26a0e5bb 100644 --- a/nuttx/net/send.c +++ b/nuttx/net/send.c @@ -448,7 +448,7 @@ end_wait: * equivalent to sendto(sockfd,buf,len,flags,NULL,0). * * Parameters: - * psock And instance of the internal socket structure. + * psock An instance of the internal socket structure. * buf Data to send * len Length of data to send * flags Send flags diff --git a/nuttx/sched/mq_sndinternal.c b/nuttx/sched/mq_sndinternal.c index 51f898875..f16f7de1a 100644 --- a/nuttx/sched/mq_sndinternal.c +++ b/nuttx/sched/mq_sndinternal.c @@ -124,7 +124,7 @@ int mq_verifysend(mqd_t mqdes, const void *msg, size_t msglen, int prio) return ERROR; } - if (msglen < 0 || msglen > (size_t)mqdes->msgq->maxmsgsize) + if (msglen > (size_t)mqdes->msgq->maxmsgsize) { set_errno(EMSGSIZE); return ERROR; -- cgit v1.2.3 From a2ec48846f786e72a976038c9467b25a61ad5a9f Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 24 Jan 2013 23:18:32 +0000 Subject: Fix some missing logic and inconsistencies in child status logic; Fix a bug introduced into sigaction() git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5560 42af7a65-404d-4744-a932-0658087f49c3 --- apps/examples/ostest/ostest_main.c | 28 ++++++++ nuttx/TODO | 15 +++- nuttx/net/net_poll.c | 4 +- nuttx/sched/Kconfig | 7 ++ nuttx/sched/os_internal.h | 1 + nuttx/sched/sched_waitid.c | 136 +++++++++++++++++++++++++++---------- nuttx/sched/sched_waitpid.c | 132 ++++++++++++++++++++++------------- nuttx/sched/sig_action.c | 22 +++--- nuttx/sched/task_childstatus.c | 36 ++++++++++ nuttx/sched/task_reparent.c | 24 ++++++- nuttx/sched/task_setup.c | 23 ++++--- 11 files changed, 322 insertions(+), 106 deletions(-) (limited to 'nuttx/sched') diff --git a/apps/examples/ostest/ostest_main.c b/apps/examples/ostest/ostest_main.c index aab1ff045..3e4197fdc 100644 --- a/apps/examples/ostest/ostest_main.c +++ b/apps/examples/ostest/ostest_main.c @@ -43,8 +43,11 @@ #include #include #include +#include #include #include +#include + #include #include "ostest.h" @@ -264,6 +267,31 @@ static int user_main(int argc, char *argv[]) } check_test_memory_usage(); + /* If retention of child status is enable, then suppress it for this task. + * This task may produce many, many children (especially if + * CONFIG_EXAMPLES_OSTEST_LOOPS) and it does not harvest their exit status. + * As a result, the test may fail inappropriately unless retention of + * child exit status is disabled. + * + * So basically, this tests that child status can be disabled, but cannot + * verify that status is retained correctly. + */ + +#if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS) + { + struct sigaction sa; + int ret; + + sa.sa_handler = SIG_IGN; + sa.sa_flags = SA_NOCLDWAIT; + ret = sigaction(SIGCHLD, &sa, NULL); + if (ret < 0) + { + printf("user_main: ERROR: sigaction failed: %d\n", errno); + } + } +#endif + /* Check environment variables */ #ifndef CONFIG_DISABLE_ENVIRON show_environment(true, true, true); diff --git a/nuttx/TODO b/nuttx/TODO index ed91515ba..d6bd18d12 100644 --- a/nuttx/TODO +++ b/nuttx/TODO @@ -7,7 +7,7 @@ standards, things that could be improved, and ideas for enhancements. nuttx/ (11) Task/Scheduler (sched/) - (1) Memory Managment (mm/) + (2) Memory Managment (mm/) (3) Signals (sched/, arch/) (2) pthreads (sched/) (2) C++ Support @@ -278,6 +278,19 @@ o Memory Managment (mm/) Priority: Medium/Low, a good feature to prevent memory leaks but would have negative impact on memory usage and code size. + Title: CONTAINER ALLOCATOR + Description: There are several places where the logic requires allocation of + a tiny structure that just contains pointers to other things or + small amounts of data that needs to be bundled together. There + are examples net/net_poll.c and numerous other places. + + I am wondering if it would not be good create a pool of generic + containers (say void *[4]). There re-use these when we need + small containers. The code in sched/task_childstatus.c might + be generalized for this purpose. + Status: Open + Priority: Very low (I am not even sure that this is a good idea yet). + o Signals (sched/, arch/) ^^^^^^^^^^^^^^^^^^^^^^^ diff --git a/nuttx/net/net_poll.c b/nuttx/net/net_poll.c index ea6f54a6b..3021ac35e 100644 --- a/nuttx/net/net_poll.c +++ b/nuttx/net/net_poll.c @@ -367,8 +367,7 @@ int psock_poll(FAR struct socket *psock, FAR struct pollfd *fds, bool setup) if (psock->s_type != SOCK_STREAM) { - ret = -ENOSYS; - goto errout; + return -ENOSYS; } #endif @@ -387,7 +386,6 @@ int psock_poll(FAR struct socket *psock, FAR struct pollfd *fds, bool setup) ret = net_pollteardown(psock, fds); } -errout: return ret; } #endif diff --git a/nuttx/sched/Kconfig b/nuttx/sched/Kconfig index 7ea301600..7745c2c25 100644 --- a/nuttx/sched/Kconfig +++ b/nuttx/sched/Kconfig @@ -124,6 +124,13 @@ config PREALLOC_CHILDSTATUS sa.sa_flags = SA_NOCLDWAIT; int ret = sigaction(SIGCHLD, &sa, NULL); +config DEBUG_CHILDSTATUS + bool "Enable Child Status Debug Output" + default n + depends on SCHED_CHILD_STATUS && DEBUG + ---help--- + Very detailed... I am sure that you do not want this. + config JULIAN_TIME bool "Enables Julian time conversions" default n diff --git a/nuttx/sched/os_internal.h b/nuttx/sched/os_internal.h index 7d5095bad..dc87cb9a4 100644 --- a/nuttx/sched/os_internal.h +++ b/nuttx/sched/os_internal.h @@ -274,6 +274,7 @@ 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_exitchild(FAR _TCB *tcb); 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); diff --git a/nuttx/sched/sched_waitid.c b/nuttx/sched/sched_waitid.c index 37ee26ce0..e73bc223c 100644 --- a/nuttx/sched/sched_waitid.c +++ b/nuttx/sched/sched_waitid.c @@ -53,6 +53,36 @@ * Private Functions *****************************************************************************/ +/***************************************************************************** + * Name: exitted_child + * + * Description: + * Handle the case where a child exitted properlay was we (apparently) lost + * the detch of child signal. + * + *****************************************************************************/ + +#ifdef CONFIG_SCHED_CHILD_STATUS +static void exitted_child(FAR _TCB *rtcb, FAR struct child_status_s *child, + FAR siginfo_t *info) +{ + /* The child has exited. Return the saved exit status (and some fudged + * information. + */ + + info->si_signo = SIGCHLD; + info->si_code = CLD_EXITED; + info->si_value.sival_ptr = NULL; + info->si_pid = child->ch_pid; + info->si_status = child->ch_status; + + /* Discard the child entry */ + + (void)task_removechild(rtcb, child->ch_pid); + task_freechild(child); +} +#endif + /***************************************************************************** * Public Functions *****************************************************************************/ @@ -120,9 +150,14 @@ * *****************************************************************************/ -int waitid(idtype_t idtype, id_t id, siginfo_t *info, int options) +int waitid(idtype_t idtype, id_t id, FAR siginfo_t *info, int options) { FAR _TCB *rtcb = (FAR _TCB *)g_readytorun.head; + FAR _TCB *ctcb; +#ifdef CONFIG_SCHED_CHILD_STATUS + FAR struct child_status_s *child; + bool retains; +#endif sigset_t sigset; int err; int ret; @@ -160,7 +195,11 @@ int waitid(idtype_t idtype, id_t id, siginfo_t *info, int options) */ #ifdef CONFIG_SCHED_CHILD_STATUS - if (rtcb->children == NULL) + /* Does this task retain child status? */ + + retains = ((rtcb->flags && TCB_FLAG_NOCLDWAIT) == 0); + + if (rtcb->children == NULL && retains) { /* There are no children */ @@ -169,13 +208,29 @@ int waitid(idtype_t idtype, id_t id, siginfo_t *info, int options) } else if (idtype == P_PID) { - if (task_findchild(rtcb, (pid_t)id) == NULL) - { - /* This specific pid is not a child */ + /* Get the TCB corresponding to this PID and make sure it is our child. */ + ctcb = sched_gettcb((pid_t)id); + if (!ctcb || ctcb->parent != rtcb->pid) + { err = ECHILD; goto errout_with_errno; } + + /* Does this task retain child status? */ + + if (retains) + { + /* Check if this specific pid has allocated child status? */ + + 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) @@ -189,7 +244,7 @@ int waitid(idtype_t idtype, id_t id, siginfo_t *info, int options) { /* Get the TCB corresponding to this PID and make sure it is our child. */ - FAR _TCB *ctcb = sched_gettcb((pid_t)id); + ctcb = sched_gettcb((pid_t)id); if (!ctcb || ctcb->parent != rtcb->pid) { err = ECHILD; @@ -209,48 +264,61 @@ int waitid(idtype_t idtype, id_t id, siginfo_t *info, int options) * instead). */ - DEBUGASSERT(rtcb->children); - if (rtcb->children == NULL) + DEBUGASSERT(!retains || rtcb->children); + if (idtype == P_ALL) { - /* This should not happen. I am just wasting your FLASH. */ + /* We are waiting for any child to exit */ - err = ECHILD; - goto errout_with_errno; + if (retains && (child = task_exitchild(rtcb)) != NULL) + { + /* A child has exitted. Apparently we missed the signal. + * Return the exit status and break out of the loop. + */ + + exitted_child(rtcb, child, info); + break; + } } - 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. - */ + /* We are waiting for a specific PID. Does this task retain child status? */ + + else if (retains) + { + /* Yes ... 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 */ + /* The child has exited. Return the exit status and break out + * of the loop. + */ - 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; + exitted_child(rtcb, child, info); + break; + } + } + else + { + /* We can use kill() with signal number 0 to determine if that + * task is still alive. + */ - /* Discard the child entry and break out of the loop */ + ret = kill((pid_t)id, 0); + if (ret < 0) + { + /* It is no longer running. We know that the child task + * was running okay when we started, so we must have lost + * the signal. In this case, we know that the task exit'ed, + * but we do not know its exit status. It would be better + * to reported ECHILD than bogus status. + */ - (void)task_removechild(rtcb, (pid_t)id); - task_freechild(child); + err = ECHILD; + goto errout_with_errno; } } #else diff --git a/nuttx/sched/sched_waitpid.c b/nuttx/sched/sched_waitpid.c index fe3f7167d..ecdc60a2c 100644 --- a/nuttx/sched/sched_waitpid.c +++ b/nuttx/sched/sched_waitpid.c @@ -185,7 +185,7 @@ #ifndef CONFIG_SCHED_HAVE_PARENT pid_t waitpid(pid_t pid, int *stat_loc, int options) { - _TCB *tcb; + _TCB *ctcb; bool mystat; int err; int ret; @@ -208,8 +208,8 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options) /* Get the TCB corresponding to this PID */ - tcb = sched_gettcb(pid); - if (!tcb) + ctcb = sched_gettcb(pid); + if (!ctcb) { err = ECHILD; goto errout_with_errno; @@ -221,15 +221,15 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options) * others? */ - if (stat_loc != NULL && tcb->stat_loc == NULL) + if (stat_loc != NULL && ctcb->stat_loc == NULL) { - tcb->stat_loc = stat_loc; - mystat = true; + ctcb->stat_loc = stat_loc; + mystat = true; } /* Then wait for the task to exit */ - ret = sem_wait(&tcb->exitsem); + ret = sem_wait(&ctcb->exitsem); if (ret < 0) { /* Unlock pre-emption and return the ERROR (sem_wait has already set @@ -239,7 +239,7 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options) if (mystat) { - tcb->stat_loc = NULL; + ctcb->stat_loc = NULL; } goto errout; @@ -274,8 +274,10 @@ errout: pid_t waitpid(pid_t pid, int *stat_loc, int options) { FAR _TCB *rtcb = (FAR _TCB *)g_readytorun.head; + FAR _TCB *ctcb; #ifdef CONFIG_SCHED_CHILD_STATUS FAR struct child_status_s *child; + bool retains; #endif FAR struct siginfo info; sigset_t sigset; @@ -303,27 +305,43 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options) sched_lock(); - /* Verify that this task actually has children and that the the request - * TCB is actually a child of this task. + /* Verify that this task actually has children and that the requested PID + * is actually a child of this task. */ #ifdef CONFIG_SCHED_CHILD_STATUS - if (rtcb->children == NULL) - { - /* There are no children */ + /* Does this task retain child status? */ + retains = ((rtcb->flags && TCB_FLAG_NOCLDWAIT) == 0); + + if (rtcb->children == NULL && retains) + { err = ECHILD; goto errout_with_errno; } else if (pid != (pid_t)-1) { - /* This specific pid is not a child */ + /* Get the TCB corresponding to this PID and make sure it is our child. */ - if (task_findchild(rtcb, pid) == NULL) + ctcb = sched_gettcb(pid); + if (!ctcb || ctcb->parent != rtcb->pid) { err = ECHILD; goto errout_with_errno; } + + /* Does this task retain child status? */ + + if (retains) + { + /* Check if this specific pid has allocated child status? */ + + if (task_findchild(rtcb, pid) == NULL) + { + err = ECHILD; + goto errout_with_errno; + } + } } #else if (rtcb->nchildren == 0) @@ -337,7 +355,7 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options) { /* Get the TCB corresponding to this PID and make sure it is our child. */ - FAR _TCB *ctcb = sched_gettcb(pid); + ctcb = sched_gettcb(pid); if (!ctcb || ctcb->parent != rtcb->pid) { err = ECHILD; @@ -350,6 +368,7 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options) 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 @@ -362,39 +381,33 @@ 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 + DEBUGASSERT(!retains || rtcb->children); + if (retains && (child = task_exitchild(rtcb)) != NULL) { - /* There were one or more children when we started so they - * must have exit'ed. There are just no bread crumbs left - * behind to tell us the PID(s) of the existed children. - * Reporting ECHLD is about all we can do in this case. + /* A child has exitted. Apparently we missed the signal. + * Return the saved exit status. */ - err = ECHILD; - goto errout_with_errno; + /* 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, child->ch_pid); + task_freechild(child); + break; } } - else + + /* We are waiting for a specific PID. Does this task retain child status? */ + + else if (retains) { -#ifdef CONFIG_SCHED_CHILD_STATUS - /* We are waiting for a specific PID. Get the current status - * of the child task. - */ + /* 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? */ @@ -408,27 +421,48 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options) (void)task_removechild(rtcb, pid); task_freechild(child); + break; } -#else - /* We are waiting for a specific PID. We can use kill() with - * signal number 0 to determine if that task is still alive. + } + else + { + /* We can use kill() with signal number 0 to determine if that + * task is still alive. */ ret = kill(pid, 0); if (ret < 0) { - /* It is no longer running. We know that the child task was - * running okay when we started, so we must have lost the - * signal. In this case, we know that the task exit'ed, but - * we do not know its exit status. It would be better to - * reported ECHILD that bogus status. + /* It is no longer running. We know that the child task + * was running okay when we started, so we must have lost + * the signal. In this case, we know that the task exit'ed, + * but we do not know its exit status. It would be better + * to reported ECHILD than bogus status. */ err = ECHILD; goto errout_with_errno; } -#endif } +#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 + * instead). + */ + + if (rtcb->nchildren == 0 || + (pid != (pid_t)-1 && (ret = kill((pid_t)id, 0)) < 0)) + { + /* We know that the child task was running okay we stared, + * so we must have lost the signal. What can we do? + * Let's claim we were interrupted by a signal. + */ + + err = EINTR; + goto errout_with_errno; + } +#endif /* Wait for any death-of-child signal */ diff --git a/nuttx/sched/sig_action.c b/nuttx/sched/sig_action.c index 708667993..7d84b6291 100644 --- a/nuttx/sched/sig_action.c +++ b/nuttx/sched/sig_action.c @@ -169,7 +169,6 @@ 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; /* Since sigactions can only be installed from the running thread of * execution, no special precautions should be necessary. @@ -251,24 +250,31 @@ int sigaction(int signo, FAR const struct sigaction *act, FAR struct sigaction * if (act->sa_u._sa_handler == SIG_IGN) { - /* If there is a old sigaction, remove it from sigactionq */ + /* Do we still have a sigaction container from the previous setting? */ - sq_rem((FAR sq_entry_t*)sigact, &rtcb->sigactionq); + if (sigact) + { + /* Yes.. Remove it from sigactionq */ + + sq_rem((FAR sq_entry_t*)sigact, &rtcb->sigactionq); - /* And deallocate it */ + /* And deallocate it */ - sig_releaseaction(sigact); + sig_releaseaction(sigact); + } } /* A sigaction has been supplied */ else { - /* Check if a sigaction was found */ + /* Do we still have a sigaction container from the previous setting? + * If so, then re-use for the new signal action. + */ if (!sigact) { - /* No sigaction was found, but one is needed. Allocate one. */ + /* No.. Then we need to allocate one for the new action. */ sigact = sig_allocateaction(); @@ -294,7 +300,7 @@ int sigaction(int signo, FAR const struct sigaction *act, FAR struct sigaction * COPY_SIGACTION(&sigact->act, act); } - return ret; + return OK; } /**************************************************************************** diff --git a/nuttx/sched/task_childstatus.c b/nuttx/sched/task_childstatus.c index 0f6d36c29..09aa48135 100644 --- a/nuttx/sched/task_childstatus.c +++ b/nuttx/sched/task_childstatus.c @@ -297,6 +297,42 @@ FAR struct child_status_s *task_findchild(FAR _TCB *tcb, pid_t pid) return NULL; } +/***************************************************************************** + * Name: task_exitchild + * + * Description: + * Search for any child that has exitted. + * + * Parameters: + * tcb - The TCB of the parent task to containing the child status. + * + * Return Value: + * On success, a non-NULL pointer to a child status structure for the + * exited child. NULL is returned if not child has exited. + * + * Assumptions: + * Called during SIGCHLD processing in a safe context. No special precautions + * are required here. + * + *****************************************************************************/ + +FAR struct child_status_s *task_exitchild(FAR _TCB *tcb) +{ + 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_flags & CHILD_FLAG_EXITED) != 0) + { + return child; + } + } + + return NULL; +} + /***************************************************************************** * Name: task_removechild * diff --git a/nuttx/sched/task_reparent.c b/nuttx/sched/task_reparent.c index 28d371bf1..3a7ece37d 100644 --- a/nuttx/sched/task_reparent.c +++ b/nuttx/sched/task_reparent.c @@ -138,14 +138,32 @@ int task_reparent(pid_t ppid, pid_t chpid) child = task_removechild(otcb, chpid); if (child) { - /* Add the child status entry to the new parent TCB */ + /* Has the new parent supressed child exit status? */ + + if ((ptcb->flags && TCB_FLAG_NOCLDWAIT) == 0) + { + /* No.. Add the child status entry to the new parent TCB */ + + task_addchild(ptcb, child); + } + else + { + /* Yes.. Discard the child status entry */ + + task_freechild(child); + } + + /* Either case is a success */ - task_addchild(ptcb, child); ret = OK; } else { - ret = -ENOENT; + /* This would not be an error if the original parent has + * suppressed child exit status. + */ + + ret = ((otcb->flags && TCB_FLAG_NOCLDWAIT) == 0) ? -ENOENT : OK; } #else DEBUGASSERT(otcb->nchildren > 0); diff --git a/nuttx/sched/task_setup.c b/nuttx/sched/task_setup.c index 8f54b2e93..66c948cfd 100644 --- a/nuttx/sched/task_setup.c +++ b/nuttx/sched/task_setup.c @@ -150,7 +150,8 @@ static int task_assignpid(FAR _TCB *tcb) * Name: task_saveparent * * Description: - * Save the task ID of the parent task in the child task's TCB. + * Save the task ID of the parent task in the child task's TCB and allocate + * a child status structure to catch the child task's exit status. * * Parameters: * tcb - The TCB of the new, child task. @@ -177,11 +178,15 @@ static inline void task_saveparent(FAR _TCB *tcb, uint8_t ttype) tcb->parent = rtcb->pid; - /* Exit status only needs to be retained for the case of tasks, however */ +#ifdef CONFIG_SCHED_CHILD_STATUS + /* Exit status only needs to be retained for the case of tasks, however. + * Tasks can also suppress retention of their child status by applying + * the SA_NOCLDWAIT flag with sigaction()/ + */ - if (ttype == TCB_FLAG_TTYPE_TASK) + if (ttype == TCB_FLAG_TTYPE_TASK && + (rtcb->flags && TCB_FLAG_NOCLDWAIT) == 0) { -#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 @@ -212,11 +217,11 @@ static inline void task_saveparent(FAR _TCB *tcb, uint8_t ttype) task_addchild(rtcb, child); } + } #else - DEBUGASSERT(rtcb->nchildren < UINT16_MAX); - rtcb->nchildren++; + DEBUGASSERT(rtcb->nchildren < UINT16_MAX); + rtcb->nchildren++; #endif - } } #else # define task_saveparent(tcb,ttype) @@ -318,7 +323,9 @@ int task_schedsetup(FAR _TCB *tcb, int priority, start_t start, main_t main, tcb->flags &= ~TCB_FLAG_TTYPE_MASK; tcb->flags |= ttype; - /* Save the task ID of the parent task in the TCB */ + /* Save the task ID of the parent task in the TCB and allocate + * a child status structure. + */ task_saveparent(tcb, ttype); -- cgit v1.2.3 From b6472b58dcce32d4ab2051f13cef89a6f0296c28 Mon Sep 17 00:00:00 2001 From: patacongo Date: Fri, 25 Jan 2013 00:01:08 +0000 Subject: Fix some compilation errors when child status disabled; new waitpid logic not encoding/decoding status properly git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5561 42af7a65-404d-4744-a932-0658087f49c3 --- apps/ChangeLog.txt | 2 ++ apps/examples/ostest/waitpid.c | 18 +++++++++--------- nuttx/sched/pthread_join.c | 2 +- nuttx/sched/sched_waitid.c | 12 ++++++------ nuttx/sched/sched_waitpid.c | 10 +++++----- nuttx/sched/task_childstatus.c | 4 ++-- nuttx/sched/timer_initialize.c | 2 +- 7 files changed, 26 insertions(+), 24 deletions(-) (limited to 'nuttx/sched') diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt index 5f3440897..494ce34eb 100644 --- a/apps/ChangeLog.txt +++ b/apps/ChangeLog.txt @@ -493,3 +493,5 @@ * apps/netutils/telnetd/telnetd_driver: Was stuck in a loop if recv[from]() ever returned a value <= 0. * apps/examples/nettest and poll: Complete Kconfig files. + * apps/examples/ostest/waitpid.c: Need to use WEXITSTATUS() + to decode the correct exit status. diff --git a/apps/examples/ostest/waitpid.c b/apps/examples/ostest/waitpid.c index e53b49213..d45410265 100644 --- a/apps/examples/ostest/waitpid.c +++ b/apps/examples/ostest/waitpid.c @@ -113,14 +113,14 @@ static void waitpid_last(void) printf("waitpid_last: ERROR: PID %d waitpid failed: %d\n", g_waitpids[NCHILDREN-1], errcode); } - else if (stat_loc != RETURN_STATUS) + else if (WEXITSTATUS(stat_loc) != RETURN_STATUS) { printf("waitpid_last: ERROR: PID %d return status is %d, expected %d\n", - g_waitpids[NCHILDREN-1], stat_loc, RETURN_STATUS); + g_waitpids[NCHILDREN-1], WEXITSTATUS(stat_loc), RETURN_STATUS); } else { - printf("waitpid_last: PID %d waitpid succeeded with stat_loc=%d\n", + printf("waitpid_last: PID %d waitpid succeeded with stat_loc=%04x\n", g_waitpids[NCHILDREN-1], stat_loc); } } @@ -155,14 +155,14 @@ int waitpid_test(void) printf("waitpid_test: ERROR: PID %d wait returned PID %d\n", g_waitpids[0], ret); } - else if (stat_loc != RETURN_STATUS) + else if (WEXITSTATUS(stat_loc) != RETURN_STATUS) { printf("waitpid_test: ERROR: PID %d return status is %d, expected %d\n", - g_waitpids[0], stat_loc, RETURN_STATUS); + g_waitpids[0], WEXITSTATUS(stat_loc), RETURN_STATUS); } else { - printf("waitpid_test: PID %d waitpid succeeded with stat_loc=%d\n", + printf("waitpid_test: PID %d waitpid succeeded with stat_loc=%04x\n", g_waitpids[0], stat_loc); } @@ -246,14 +246,14 @@ int waitpid_test(void) int errcode = errno; printf("waitpid_test: ERROR: wait failed: %d\n", errcode); } - else if (stat_loc != RETURN_STATUS) + else if (WEXITSTATUS(stat_loc) != RETURN_STATUS) { printf("waitpid_test: ERROR: PID %d return status is %d, expected %d\n", - ret, stat_loc, RETURN_STATUS); + ret, WEXITSTATUS(stat_loc), RETURN_STATUS); } else { - printf("waitpid_test: PID %d wait succeeded with stat_loc=%d\n", + printf("waitpid_test: PID %d wait succeeded with stat_loc=%04x\n", ret, stat_loc); } diff --git a/nuttx/sched/pthread_join.c b/nuttx/sched/pthread_join.c index 6a02af352..d3f648dc7 100644 --- a/nuttx/sched/pthread_join.c +++ b/nuttx/sched/pthread_join.c @@ -123,7 +123,7 @@ int pthread_join(pthread_t thread, FAR pthread_addr_t *pexit_value) * This can fail for one of three reasons: (1) There is no * thread associated with 'thread,' (2) the thread is a task * and does not have join information, or (3) the thread - * was detached and has exitted. + * was detached and has exited. */ pjoin = pthread_findjoininfo((pid_t)thread); diff --git a/nuttx/sched/sched_waitid.c b/nuttx/sched/sched_waitid.c index e73bc223c..56bfb36f0 100644 --- a/nuttx/sched/sched_waitid.c +++ b/nuttx/sched/sched_waitid.c @@ -54,16 +54,16 @@ *****************************************************************************/ /***************************************************************************** - * Name: exitted_child + * Name: exited_child * * Description: - * Handle the case where a child exitted properlay was we (apparently) lost + * Handle the case where a child exited properlay was we (apparently) lost * the detch of child signal. * *****************************************************************************/ #ifdef CONFIG_SCHED_CHILD_STATUS -static void exitted_child(FAR _TCB *rtcb, FAR struct child_status_s *child, +static void exited_child(FAR _TCB *rtcb, FAR struct child_status_s *child, FAR siginfo_t *info) { /* The child has exited. Return the saved exit status (and some fudged @@ -271,11 +271,11 @@ int waitid(idtype_t idtype, id_t id, FAR siginfo_t *info, int options) if (retains && (child = task_exitchild(rtcb)) != NULL) { - /* A child has exitted. Apparently we missed the signal. + /* A child has exited. Apparently we missed the signal. * Return the exit status and break out of the loop. */ - exitted_child(rtcb, child, info); + exited_child(rtcb, child, info); break; } } @@ -297,7 +297,7 @@ int waitid(idtype_t idtype, id_t id, FAR siginfo_t *info, int options) * of the loop. */ - exitted_child(rtcb, child, info); + exited_child(rtcb, child, info); break; } } diff --git a/nuttx/sched/sched_waitpid.c b/nuttx/sched/sched_waitpid.c index ecdc60a2c..d7484fca9 100644 --- a/nuttx/sched/sched_waitpid.c +++ b/nuttx/sched/sched_waitpid.c @@ -384,13 +384,13 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options) DEBUGASSERT(!retains || rtcb->children); if (retains && (child = task_exitchild(rtcb)) != NULL) { - /* A child has exitted. Apparently we missed the signal. + /* A child has exited. Apparently we missed the signal. * Return the saved exit status. */ /* The child has exited. Return the saved exit status */ - *stat_loc = child->ch_status; + *stat_loc = child->ch_status << 8; /* Discard the child entry and break out of the loop */ @@ -415,7 +415,7 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options) { /* The child has exited. Return the saved exit status */ - *stat_loc = child->ch_status; + *stat_loc = child->ch_status << 8; /* Discard the child entry and break out of the loop */ @@ -452,7 +452,7 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options) */ if (rtcb->nchildren == 0 || - (pid != (pid_t)-1 && (ret = kill((pid_t)id, 0)) < 0)) + (pid != (pid_t)-1 && (ret = kill(pid, 0)) < 0)) { /* We know that the child task was running okay we stared, * so we must have lost the signal. What can we do? @@ -481,7 +481,7 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options) { /* Yes... return the status and PID (in the event it was -1) */ - *stat_loc = info.si_status; + *stat_loc = info.si_status << 8; pid = info.si_pid; break; } diff --git a/nuttx/sched/task_childstatus.c b/nuttx/sched/task_childstatus.c index 09aa48135..6007f03e5 100644 --- a/nuttx/sched/task_childstatus.c +++ b/nuttx/sched/task_childstatus.c @@ -121,7 +121,7 @@ static void task_dumpchildren(FAR _TCB *tcb, FAR const char *msg) } } #else -# task_dumpchildren(t,m) +# define task_dumpchildren(t,m) #endif /***************************************************************************** @@ -320,7 +320,7 @@ FAR struct child_status_s *task_exitchild(FAR _TCB *tcb) { FAR struct child_status_s *child; - /* Find the status structure with the matching PID */ + /* Find the status structure of any child task that has exitted. */ for (child = tcb->children; child; child = child->flink) { diff --git a/nuttx/sched/timer_initialize.c b/nuttx/sched/timer_initialize.c index 05980bb1a..2651469ef 100644 --- a/nuttx/sched/timer_initialize.c +++ b/nuttx/sched/timer_initialize.c @@ -137,7 +137,7 @@ void weak_function timer_initialize(void) * resources are referenced. * * Parameters: - * pid - the task ID of the thread that exitted + * pid - the task ID of the thread that exited * * Return Value: * None -- cgit v1.2.3 From e95efd5d2a08dcb62c8c635089e4fe146965db45 Mon Sep 17 00:00:00 2001 From: patacongo Date: Fri, 25 Jan 2013 17:23:38 +0000 Subject: Add framework to support task groups git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5562 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/include/nuttx/sched.h | 80 ++++++++++++++++++++++++-- nuttx/net/net_poll.c | 4 +- nuttx/sched/Makefile | 7 ++- nuttx/sched/env_dup.c | 64 ++++++++++----------- nuttx/sched/group_create.c | 111 +++++++++++++++++++++++++++++++++++ nuttx/sched/group_join.c | 107 ++++++++++++++++++++++++++++++++++ nuttx/sched/group_leave.c | 127 +++++++++++++++++++++++++++++++++++++++++ nuttx/sched/os_internal.h | 15 ++++- nuttx/sched/os_start.c | 12 +++- nuttx/sched/pthread_create.c | 43 +++++++++----- nuttx/sched/sched_releasetcb.c | 7 ++- nuttx/sched/sched_waitid.c | 6 +- nuttx/sched/sched_waitpid.c | 6 +- nuttx/sched/sig_action.c | 2 +- nuttx/sched/task_childstatus.c | 27 +++++---- nuttx/sched/task_create.c | 20 ++++++- nuttx/sched/task_exithook.c | 106 ++++++++++++++++++++++------------ nuttx/sched/task_init.c | 54 ++++++++++++++---- nuttx/sched/task_reparent.c | 10 ++-- nuttx/sched/task_setup.c | 10 ++-- 20 files changed, 677 insertions(+), 141 deletions(-) create mode 100644 nuttx/sched/group_create.c create mode 100644 nuttx/sched/group_join.c create mode 100644 nuttx/sched/group_leave.c (limited to 'nuttx/sched') diff --git a/nuttx/include/nuttx/sched.h b/nuttx/include/nuttx/sched.h index 1e75b5020..4a3bae5e4 100644 --- a/nuttx/include/nuttx/sched.h +++ b/nuttx/include/nuttx/sched.h @@ -57,6 +57,14 @@ /******************************************************************************** * Pre-processor Definitions ********************************************************************************/ +/* Configuration ****************************************************************/ +/* Task groups currently only supported for retention of child status */ + +#if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS) +# define HAVE_TASK_GROUP 1 +#else +# undef HAVE_TASK_GROUP +#endif /* Task Management Definitins ***************************************************/ @@ -64,7 +72,7 @@ #define MAX_LOCK_COUNT 127 -/* Values for the _TCB flags flag bits */ +/* Values for the _TCB flags bits */ #define TCB_FLAG_TTYPE_SHIFT (0) /* Bits 0-1: thread type */ #define TCB_FLAG_TTYPE_MASK (3 << TCB_FLAG_TTYPE_SHIFT) @@ -74,7 +82,10 @@ #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 task_group tg_flags */ + +#define GROUP_FLAG_NOCLDWAIT (1 << 0) /* Bit 0: Do not retain child exit status */ /* Values for struct child_status_s ch_flags */ @@ -159,6 +170,7 @@ typedef CODE void (*onexitfunc_t)(int exitcode, FAR void *arg); typedef struct msgq_s msgq_t; +/* struct environ_s **************************************************************/ /* The structure used to maintain environment variables */ #ifndef CONFIG_DISABLE_ENVIRON @@ -173,6 +185,7 @@ typedef struct environ_s environ_t; # define SIZEOF_ENVIRON_T(alloc) (sizeof(environ_t) + alloc - 1) #endif +/* struct child_status_s *********************************************************/ /* This structure is used to maintin information about child tasks. * pthreads work differently, they have join information. This is * only for child tasks. @@ -189,6 +202,7 @@ struct child_status_s }; #endif +/* struct dspace_s ***************************************************************/ /* 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. @@ -214,6 +228,58 @@ struct dspace_s }; #endif +/* struct task_group_s ***********************************************************/ +/* All threads created by pthread_create belong in the same task group (along with + * the thread of the original task). struct task_group_s is a shared, "breakaway" + * structure referenced by each TCB. + * + * This structure should contain *all* resources shared by tasks and threads that + * belong to the same task group: + * + * Child exit status + * Environment varibles + * PIC data space and address environments + * File descriptors + * FILE streams + * Sockets + * + * Currenty, however, this implementation only applies to child exit status. + * + * Each instance of struct task_group_s is reference counted. Each instance is + * created with a reference count of one. The reference incremeneted when each + * thread joins the group and decremented when each thread exits, leaving the + * group. When the refernce count decrements to zero, the struc task_group_s + * is free. + */ + +#ifdef HAVE_TASK_GROUP +struct task_group_s +{ + uint16_t tg_crefs; /* Count of threads sharing this data */ + uint8_t tg_flags; /* See GROUP_FLAG_* definitions */ + + /* Child exit status **********************************************************/ + + FAR struct child_status_s *tg_children; /* Head of a list of child status */ + + /* Environment varibles *******************************************************/ + /* Not yet (see type environ_t) */ + + /* PIC data space and address environments */ + /* Not yet (see struct dspace_s) */ + + /* File descriptors */ + /* Not yet (see struct filelist) */ + + /* FILE streams */ + /* Not yet (see streamlist) */ + + /* Sockets */ + /* Not yet (see struct socketlist) */ +}; +#endif + +/* _TCB **************************************************************************/ /* This is the task control block (TCB). Each task or thread is represented by * a TCB. The TCB is the heart of the NuttX task-control logic. */ @@ -225,14 +291,18 @@ struct _TCB FAR struct _TCB *flink; /* Doubly linked list */ FAR struct _TCB *blink; + /* Task Group *****************************************************************/ + +#ifdef HAVE_TASK_GROUP + FAR struct task_group_s *group; /* Pointer to shared task group data */ +#endif + /* Task Management Fields *****************************************************/ pid_t pid; /* This is the ID of the thread */ #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 +#ifndef CONFIG_SCHED_CHILD_STATUS /* Retain child thread status */ uint16_t nchildren; /* This is the number active children */ #endif #endif diff --git a/nuttx/net/net_poll.c b/nuttx/net/net_poll.c index 3021ac35e..1838f541e 100644 --- a/nuttx/net/net_poll.c +++ b/nuttx/net/net_poll.c @@ -118,11 +118,11 @@ static uint16_t poll_interrupt(FAR struct uip_driver_s *dev, FAR void *conn, nllvdbg("flags: %04x\n", flags); - DEBUGASSERT(info && info->psock && info->fds); + DEBUGASSERT(!info || (info->psock && info->fds)); /* 'priv' might be null in some race conditions (?) */ - if (info->fds) + if (info) { pollevent_t eventset = 0; diff --git a/nuttx/sched/Makefile b/nuttx/sched/Makefile index 1ad244450..6a710ff95 100644 --- a/nuttx/sched/Makefile +++ b/nuttx/sched/Makefile @@ -87,6 +87,8 @@ SCHED_SRCS += sched_waitid.c sched_wait.c endif endif +GRP_SRCS = group_create.c group_join.c group_leave.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 @@ -169,8 +171,9 @@ 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_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) $(GRP_SRCS) $(SCHED_SRCS) $(WDOG_SRCS) +CSRCS += $(TIME_SRCS) $(SEM_SRCS) $(TIMER_SRCS) $(WORK_SRCS) $(PGFILL_SRCS) +CSRCS += $(IRQ_SRCS) ifneq ($(CONFIG_DISABLE_CLOCK),y) CSRCS += $(CLOCK_SRCS) diff --git a/nuttx/sched/env_dup.c b/nuttx/sched/env_dup.c index 033348411..30c0b7773 100644 --- a/nuttx/sched/env_dup.c +++ b/nuttx/sched/env_dup.c @@ -1,7 +1,7 @@ /**************************************************************************** * sched/env_dup.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 * * Redistribution and use in source and binary forms, with or without @@ -68,7 +68,7 @@ * exact duplicate of the parent task's environment. * * Parameters: - * ptcb The tcb to receive the newly allocated copy of the parspecifiedent + * ptcb The tcb to receive the newly allocated copy of the parent * TCB's environment structure with reference count equal to one * * Return Value: @@ -81,48 +81,42 @@ int env_dup(FAR _TCB *ptcb) { + FAR _TCB *parent = (FAR _TCB*)g_readytorun.head; + environ_t *envp = NULL; int ret = OK; - if (!ptcb ) - { - ret = -EINVAL; - } - else - { - FAR _TCB *parent = (FAR _TCB*)g_readytorun.head; - environ_t *envp = NULL; - /* Pre-emption must be disabled throughout the following because the - * environment may be shared. - */ + DEBUGASSERT(ptcb); + + /* Pre-emption must be disabled throughout the following because the + * environment may be shared. + */ + + sched_lock(); - sched_lock(); + /* Does the parent task have an environment? */ - /* Does the parent task have an environment? */ + if (parent->envp) + { + /* Yes..The parent task has an environment, duplicate it */ - if (parent->envp) + size_t envlen = parent->envp->ev_alloc; + envp = (environ_t*)kmalloc(SIZEOF_ENVIRON_T(envlen)); + if (!envp) { - /* Yes..The parent task has an environment, duplicate it */ - - size_t envlen = parent->envp->ev_alloc; - envp = (environ_t*)kmalloc(SIZEOF_ENVIRON_T( envlen )); - if (!envp) - { - ret = -ENOMEM; - } - else - { - envp->ev_crefs = 1; - envp->ev_alloc = envlen; - memcpy( envp->ev_env, parent->envp->ev_env, envlen ); - } + ret = -ENOMEM; } + else + { + envp->ev_crefs = 1; + envp->ev_alloc = envlen; + memcpy(envp->ev_env, parent->envp->ev_env, envlen); + } + } - /* Save the cloned environment in the new TCB */ - - ptcb->envp = envp; - sched_unlock(); - } + /* Save the cloned environment in the new TCB */ + ptcb->envp = envp; + sched_unlock(); return ret; } diff --git a/nuttx/sched/group_create.c b/nuttx/sched/group_create.c new file mode 100644 index 000000000..d036b9084 --- /dev/null +++ b/nuttx/sched/group_create.c @@ -0,0 +1,111 @@ +/***************************************************************************** + * sched/group_create.c + * + * Copyright (C) 2013 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 + +#include +#include +#include +#include + +#include + +#ifdef HAVE_TASK_GROUP + +/***************************************************************************** + * Pre-processor Definitions + *****************************************************************************/ + +/***************************************************************************** + * Private Types + *****************************************************************************/ + +/***************************************************************************** + * Private Data + *****************************************************************************/ + +/***************************************************************************** + * Private Functions + *****************************************************************************/ + +/***************************************************************************** + * Public Functions + *****************************************************************************/ + +/***************************************************************************** + * Name: group_create + * + * Description: + * Create and initialize a new task group structure for the specified TCB. + * This function is called as part of the task creation sequence. + * + * Parameters: + * tcb - The tcb in need of the task group. + * + * Return Value: + * 0 (OK) on success; a negated errno value on failure. + * + * Assumptions: + * Called during task creation in a safe context. No special precautions + * are required here. + * + *****************************************************************************/ + +int group_create(FAR _TCB *tcb) +{ + FAR struct task_group_s *group; + + DEBUGASSERT(tcb && !tcb->group); + + /* Allocate the group structure */ + + group = (FAR struct task_group_s *)kzalloc(sizeof(struct task_group_s)); + if (!group) + { + return -ENOMEM; + } + + /* Initialize the group structure and assign it to the tcb */ + + group->tg_crefs = 1; + tcb->group = group; + return OK; +} + +#endif /* HAVE_TASK_GROUP */ diff --git a/nuttx/sched/group_join.c b/nuttx/sched/group_join.c new file mode 100644 index 000000000..987c1ba87 --- /dev/null +++ b/nuttx/sched/group_join.c @@ -0,0 +1,107 @@ +/***************************************************************************** + * sched/group_join.c + * + * Copyright (C) 2013 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 + +#include +#include +#include + +#include "os_internal.h" + +#ifdef HAVE_TASK_GROUP + +/***************************************************************************** + * Pre-processor Definitions + *****************************************************************************/ + +/***************************************************************************** + * Private Types + *****************************************************************************/ + +/***************************************************************************** + * Private Data + *****************************************************************************/ + +/***************************************************************************** + * Private Functions + *****************************************************************************/ + +/***************************************************************************** + * Public Functions + *****************************************************************************/ + +/***************************************************************************** + * Name: group_join + * + * Description: + * Copy the group structure reference from one TCB to another, incrementing + * the refrence count on the group. This function is called when a pthread + * is produced within the task group so that the pthread can share the + * resources of the task group. + * + * Parameters: + * tcb - The TCB of the new "child" task that need to join the group. + * + * Return Value: + * None + * + * Assumptions: + * - The parent task from which the group will be inherited is the task at + * the thead of the ready to run list. + * - Called during thread creation in a safe context. No special precautions + * are required here. + * + *****************************************************************************/ + +void group_join(FAR _TCB *tcb) +{ + FAR _TCB *ptcb = (FAR _TCB *)g_readytorun.head; + + DEBUGASSERT(ptcb && tcb && ptcb->group && !tcb->group); + + /* Copy the group reference from the parent to the child, incrementing the + * reference count. + */ + + tcb->group = ptcb->group; + ptcb->group->tg_crefs++; +} + +#endif /* HAVE_TASK_GROUP */ diff --git a/nuttx/sched/group_leave.c b/nuttx/sched/group_leave.c new file mode 100644 index 000000000..69a6ea8b2 --- /dev/null +++ b/nuttx/sched/group_leave.c @@ -0,0 +1,127 @@ +/***************************************************************************** + * sched/group_leave.c + * + * Copyright (C) 2013 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 + +#include +#include +#include +#include + +#include "os_internal.h" + +#ifdef HAVE_TASK_GROUP + +/***************************************************************************** + * Pre-processor Definitions + *****************************************************************************/ + +/***************************************************************************** + * Private Types + *****************************************************************************/ + +/***************************************************************************** + * Private Data + *****************************************************************************/ + +/***************************************************************************** + * Private Functions + *****************************************************************************/ + +/***************************************************************************** + * Public Functions + *****************************************************************************/ + +/***************************************************************************** + * Name: group_leave + * + * Description: + * Release a reference on a group. This function is called when a task or + * thread exits. It decrements the reference count on the group. If the + * reference count decrements to zero, then it frees the group and all of + * resources contained in the group. + * + * Parameters: + * tcb - The TCB of the task that is exiting. + * + * Return Value: + * None. + * + * Assumptions: + * Called during task deletion in a safe context. No special precautions + * are required here. + * + *****************************************************************************/ + +void group_leave(FAR _TCB *tcb) +{ + FAR struct task_group_s *group; + + DEBUGASSERT(tcb); + + /* Make sure that we have a group */ + + group = tcb->group; + if (group) + { + /* Would the reference count decrement to zero? */ + + if (group->tg_crefs > 1) + { + /* No.. just decrement the reference count and return */ + + group->tg_crefs--; + } + else + { + /* Yes.. Release all of the resource contained within the group */ + /* Free all un-reaped child exit status */ + + task_removechildren(tcb); + + /* Release the group container itself */ + + sched_free(group); + } + + tcb->group = NULL; + } +} + +#endif /* HAVE_TASK_GROUP */ diff --git a/nuttx/sched/os_internal.h b/nuttx/sched/os_internal.h index dc87cb9a4..ee5ada165 100644 --- a/nuttx/sched/os_internal.h +++ b/nuttx/sched/os_internal.h @@ -268,7 +268,20 @@ int task_schedsetup(FAR _TCB *tcb, int priority, start_t start, 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 +int task_reparent(pid_t ppid, pid_t chpid); + +#ifdef HAVE_TASK_GROUP +int group_create(FAR _TCB *tcb); +void group_join(FAR _TCB *tcb); +void group_leave(FAR _TCB *tcb); +#else +# define group_create(tcb) +# define group_join(tcb) +# define group_leave(tcb) +#endif + #ifdef CONFIG_SCHED_CHILD_STATUS void weak_function task_initialize(void); FAR struct child_status_s *task_allocchild(void); @@ -279,8 +292,8 @@ 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[]); diff --git a/nuttx/sched/os_start.c b/nuttx/sched/os_start.c index a6d4e83b9..244aec967 100644 --- a/nuttx/sched/os_start.c +++ b/nuttx/sched/os_start.c @@ -202,6 +202,9 @@ const tasklist_t g_tasklisttable[NUM_TASK_STATES] = */ static FAR _TCB g_idletcb; +#if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS) +static struct task_group_s g_idlegroup; +#endif /* This is the name of the idle task */ @@ -280,13 +283,20 @@ void os_start(void) g_idletcb.argv[0] = (char*)g_idlename; #endif /* CONFIG_TASK_NAME_SIZE */ + /* Join the IDLE group */ + +#ifdef HAVE_TASK_GROUP + g_idlegroup.tg_crefs = 1; + g_idlegroup.tg_flags = GROUP_FLAG_NOCLDWAIT; + g_idletcb.group = &g_idlegroup; +#endif + /* Then add the idle task's TCB to the head of the ready to run list */ dq_addfirst((FAR dq_entry_t*)&g_idletcb, (FAR dq_queue_t*)&g_readytorun); /* Initialize the processor-specific portion of the TCB */ - 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 diff --git a/nuttx/sched/pthread_create.c b/nuttx/sched/pthread_create.c index f4d0d8fdf..e37c06892 100644 --- a/nuttx/sched/pthread_create.c +++ b/nuttx/sched/pthread_create.c @@ -251,6 +251,7 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr, #if CONFIG_RR_INTERVAL > 0 int policy; #endif + int errcode; pid_t pid; /* If attributes were not supplied, use the default attributes */ @@ -268,6 +269,12 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr, return ENOMEM; } + /* Join the parent's task group */ + +#ifdef HAVE_TASK_GROUP + group_join(ptcb); +#endif + /* Share the address environment of the parent task. NOTE: Only tasks * created throught the nuttx/binfmt loaders may have an address * environment. @@ -277,8 +284,8 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr, ret = up_addrenv_share((FAR const _TCB *)g_readytorun.head, ptcb); if (ret < 0) { - sched_releasetcb(ptcb); - return -ret; + errcode = -ret; + goto errout_with_tcb; } #endif @@ -287,8 +294,8 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr, ret = sched_setuppthreadfiles(ptcb); if (ret != OK) { - sched_releasetcb(ptcb); - return ret; + errcode = ret; + goto errout_with_tcb; } /* Share the parent's envionment */ @@ -300,8 +307,8 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr, pjoin = (FAR join_t*)kzalloc(sizeof(join_t)); if (!pjoin) { - sched_releasetcb(ptcb); - return ENOMEM; + errcode = ENOMEM; + goto errout_with_tcb; } /* Allocate the stack for the TCB */ @@ -309,9 +316,8 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr, ret = up_create_stack(ptcb, attr->stacksize); if (ret != OK) { - sched_releasetcb(ptcb); - sched_free(pjoin); - return ENOMEM; + errcode = ENOMEM; + goto errout_with_join; } /* Should we use the priority and scheduler specified in the @@ -360,9 +366,8 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr, TCB_FLAG_TTYPE_PTHREAD); if (ret != OK) { - sched_releasetcb(ptcb); - sched_free(pjoin); - return EBUSY; + errcode = EBUSY; + goto errout_with_join; } /* Configure the TCB for a pthread receiving on parameter @@ -440,10 +445,18 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr, dq_rem((FAR dq_entry_t*)ptcb, (dq_queue_t*)&g_inactivetasks); (void)sem_destroy(&pjoin->data_sem); (void)sem_destroy(&pjoin->exit_sem); - sched_releasetcb(ptcb); - sched_free(pjoin); - ret = EIO; + + errcode = EIO; + goto errout_with_join; } return ret; + +errout_with_join: + sched_free(pjoin); + ptcb->joininfo = NULL; + +errout_with_tcb: + sched_releasetcb(ptcb); + return errcode; } diff --git a/nuttx/sched/sched_releasetcb.c b/nuttx/sched/sched_releasetcb.c index 0557c829b..50505f579 100644 --- a/nuttx/sched/sched_releasetcb.c +++ b/nuttx/sched/sched_releasetcb.c @@ -1,7 +1,7 @@ /************************************************************************ * sched/sched_releasetcb.c * - * Copyright (C) 2007, 2009, 2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2009, 2012-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -177,6 +177,11 @@ int sched_releasetcb(FAR _TCB *tcb) ret = up_addrenv_release(tcb); #endif + /* Leave the group (if we did not already leady in task_exithook.c) */ + +#ifdef HAVE_TASK_GROUP + group_leave(tcb); +#endif /* And, finally, release the TCB itself */ sched_free(tcb); diff --git a/nuttx/sched/sched_waitid.c b/nuttx/sched/sched_waitid.c index 56bfb36f0..e47e3c38c 100644 --- a/nuttx/sched/sched_waitid.c +++ b/nuttx/sched/sched_waitid.c @@ -197,9 +197,9 @@ int waitid(idtype_t idtype, id_t id, FAR siginfo_t *info, int options) #ifdef CONFIG_SCHED_CHILD_STATUS /* Does this task retain child status? */ - retains = ((rtcb->flags && TCB_FLAG_NOCLDWAIT) == 0); + retains = ((rtcb->group->tg_flags && GROUP_FLAG_NOCLDWAIT) == 0); - if (rtcb->children == NULL && retains) + if (rtcb->group->tg_children == NULL && retains) { /* There are no children */ @@ -264,7 +264,7 @@ int waitid(idtype_t idtype, id_t id, FAR siginfo_t *info, int options) * instead). */ - DEBUGASSERT(!retains || rtcb->children); + DEBUGASSERT(!retains || rtcb->group->tg_children); if (idtype == P_ALL) { /* We are waiting for any child to exit */ diff --git a/nuttx/sched/sched_waitpid.c b/nuttx/sched/sched_waitpid.c index d7484fca9..2d0fe2e48 100644 --- a/nuttx/sched/sched_waitpid.c +++ b/nuttx/sched/sched_waitpid.c @@ -312,9 +312,9 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options) #ifdef CONFIG_SCHED_CHILD_STATUS /* Does this task retain child status? */ - retains = ((rtcb->flags && TCB_FLAG_NOCLDWAIT) == 0); + retains = ((rtcb->group->tg_flags && GROUP_FLAG_NOCLDWAIT) == 0); - if (rtcb->children == NULL && retains) + if (rtcb->group->tg_children == NULL && retains) { err = ECHILD; goto errout_with_errno; @@ -381,7 +381,7 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options) * chilren. */ - DEBUGASSERT(!retains || rtcb->children); + DEBUGASSERT(!retains || rtcb->group->tg_children); if (retains && (child = task_exitchild(rtcb)) != NULL) { /* A child has exited. Apparently we missed the signal. diff --git a/nuttx/sched/sig_action.c b/nuttx/sched/sig_action.c index 7d84b6291..b307c1fb6 100644 --- a/nuttx/sched/sig_action.c +++ b/nuttx/sched/sig_action.c @@ -237,7 +237,7 @@ int sigaction(int signo, FAR const struct sigaction *act, FAR struct sigaction * /* Mark that status should be not be retained */ - rtcb->flags |= TCB_FLAG_NOCLDWAIT; + rtcb->group->tg_flags |= GROUP_FLAG_NOCLDWAIT; /* Free all pending exit status */ diff --git a/nuttx/sched/task_childstatus.c b/nuttx/sched/task_childstatus.c index 6007f03e5..aff2bdf3a 100644 --- a/nuttx/sched/task_childstatus.c +++ b/nuttx/sched/task_childstatus.c @@ -111,10 +111,11 @@ static struct child_pool_s g_child_pool; static void task_dumpchildren(FAR _TCB *tcb, FAR const char *msg) { FAR struct child_status_s *child; + FAR struct task_group_s *group = tcb->group; int i; - dbg("Parent TCB=%p: %s\n", tcb, msg); - for (i = 0, child = tcb->children; child; i++, child = child->flink) + dbg("Parent TCB=%p group=%p: %s\n", tcb, group, msg); + for (i = 0, child = group->tg_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); @@ -250,10 +251,12 @@ void task_freechild(FAR struct child_status_s *child) void task_addchild(FAR _TCB *tcb, FAR struct child_status_s *child) { + FAR struct task_group_s *group = tcb->group; + /* Add the entry into the TCB list of children */ - child->flink = tcb->children; - tcb->children = child; + child->flink = group->tg_children; + group->tg_children = child; task_dumpchildren(tcb, "task_addchild"); } @@ -282,11 +285,12 @@ 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 task_group_s *group = tcb->group; FAR struct child_status_s *child; /* Find the status structure with the matching PID */ - for (child = tcb->children; child; child = child->flink) + for (child = group->tg_children; child; child = child->flink) { if (child->ch_pid == pid) { @@ -318,11 +322,12 @@ FAR struct child_status_s *task_findchild(FAR _TCB *tcb, pid_t pid) FAR struct child_status_s *task_exitchild(FAR _TCB *tcb) { + FAR struct task_group_s *group = tcb->group; FAR struct child_status_s *child; /* Find the status structure of any child task that has exitted. */ - for (child = tcb->children; child; child = child->flink) + for (child = group->tg_children; child; child = child->flink) { if ((child->ch_flags & CHILD_FLAG_EXITED) != 0) { @@ -357,12 +362,13 @@ FAR struct child_status_s *task_exitchild(FAR _TCB *tcb) FAR struct child_status_s *task_removechild(FAR _TCB *tcb, pid_t pid) { + FAR struct task_group_s *group = tcb->group; 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; + for (prev = NULL, curr = group->tg_children; curr; prev = curr, curr = curr->flink) { @@ -384,7 +390,7 @@ FAR struct child_status_s *task_removechild(FAR _TCB *tcb, pid_t pid) } else { - tcb->children = curr->flink; + group->tg_children = curr->flink; } curr->flink = NULL; @@ -414,18 +420,19 @@ FAR struct child_status_s *task_removechild(FAR _TCB *tcb, pid_t pid) void task_removechildren(FAR _TCB *tcb) { + FAR struct task_group_s *group = tcb->group; 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) + for (curr = group->tg_children; curr; curr = next) { next = curr->flink; task_freechild(curr); } - tcb->children = NULL; + group->tg_children = NULL; task_dumpchildren(tcb, "task_removechildren"); } diff --git a/nuttx/sched/task_create.c b/nuttx/sched/task_create.c index 2ed929ab0..f2aeeeec0 100644 --- a/nuttx/sched/task_create.c +++ b/nuttx/sched/task_create.c @@ -108,6 +108,7 @@ static int thread_create(const char *name, uint8_t ttype, int priority, { FAR _TCB *tcb; pid_t pid; + int errcode; int ret; /* Allocate a TCB for the new task. */ @@ -115,15 +116,28 @@ static int thread_create(const char *name, uint8_t ttype, int priority, tcb = (FAR _TCB*)kzalloc(sizeof(_TCB)); if (!tcb) { + errcode = ENOMEM; goto errout; } + /* Create a new task group */ + +#ifdef HAVE_TASK_GROUP + ret = group_create(tcb); + if (ret < 0) + { + errcode = -ret; + goto errout_with_tcb; + } +#endif + /* Associate file descriptors with the new task */ #if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0 ret = sched_setuptaskfiles(tcb); if (ret != OK) { + errcode = -ret; goto errout_with_tcb; } #endif @@ -138,6 +152,7 @@ static int thread_create(const char *name, uint8_t ttype, int priority, ret = up_create_stack(tcb, stack_size); if (ret != OK) { + errcode = -ret; goto errout_with_tcb; } #endif @@ -147,6 +162,7 @@ static int thread_create(const char *name, uint8_t ttype, int priority, ret = task_schedsetup(tcb, priority, task_start, entry, ttype); if (ret != OK) { + errcode = -ret; goto errout_with_tcb; } @@ -163,6 +179,8 @@ static int thread_create(const char *name, uint8_t ttype, int priority, ret = task_activate(tcb); if (ret != OK) { + errcode = get_errno(); + /* The TCB was added to the active task list by task_schedsetup() */ dq_rem((FAR dq_entry_t*)tcb, (dq_queue_t*)&g_inactivetasks); @@ -175,7 +193,7 @@ errout_with_tcb: sched_releasetcb(tcb); errout: - errno = ENOMEM; + set_errno(errcode); return ERROR; } diff --git a/nuttx/sched/task_exithook.c b/nuttx/sched/task_exithook.c index 1813c12ed..30ce41f71 100644 --- a/nuttx/sched/task_exithook.c +++ b/nuttx/sched/task_exithook.c @@ -197,39 +197,28 @@ static inline void task_onexit(FAR _TCB *tcb, int status) ****************************************************************************/ #ifdef CONFIG_SCHED_HAVE_PARENT -static inline void task_sigchild(FAR _TCB *tcb, int status) +static inline void task_sigchild(FAR _TCB *ptcb, FAR _TCB *ctcb, int status) { - FAR _TCB *ptcb; siginfo_t info; - /* Only exiting tasks should generate SIGCHLD. pthreads use other - * mechansims. + /* Only the final exiting thread in a task group should generate SIGCHLD. + * If task groups are not supported then we will report SIGCHLD when the + * task exits. */ - if ((tcb->flags & TCB_FLAG_TTYPE_MASK) == TCB_FLAG_TTYPE_TASK) +#ifdef CONFIG_SCHED_CHILD_STATUS + if (ctcb->group->tg_crefs == 1) +#else + if ((ctcb->flags & TCB_FLAG_TTYPE_MASK) == TCB_FLAG_TTYPE_TASK) +#endif { - /* 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 + /* Check if the parent task group 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) + if ((ptcb->group->tg_flags & GROUP_FLAG_NOCLDWAIT) == 0) { FAR struct child_status_s *child; @@ -255,15 +244,6 @@ static inline void task_sigchild(FAR _TCB *tcb, int status) 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. @@ -272,7 +252,7 @@ static inline void task_sigchild(FAR _TCB *tcb, int status) info.si_signo = SIGCHLD; info.si_code = CLD_EXITED; info.si_value.sival_ptr = NULL; - info.si_pid = tcb->pid; + info.si_pid = ctcb->pid; info.si_status = status; /* Send the signal. We need to use this internal interface so that we @@ -280,11 +260,59 @@ static inline void task_sigchild(FAR _TCB *tcb, int status) */ (void)sig_received(ptcb, &info); + } +} +#else +# define task_sigchild(ptct,ctcb,status) +#endif + +/**************************************************************************** + * Name: task_leavegroup + * + * Description: + * Send the SIGCHILD signal to the parent thread + * + ****************************************************************************/ + +#ifdef CONFIG_SCHED_HAVE_PARENT +static inline void task_leavegroup(FAR _TCB *ctcb, int status) +{ + FAR _TCB *ptcb; + + /* Keep things stationary throughout the following */ + + sched_lock(); + + /* Get the TCB of the receiving, parent task. We do this early to + * handle multiple calls to task_leavegroup. ctcb->parent is set to an + * invalid value below and the following call will fail if we are + * called again. + */ + + ptcb = sched_gettcb(ctcb->parent); + if (!ptcb) + { + /* The parent no longer exists... bail */ + sched_unlock(); + return; } + + /* Send SIGCHLD to all members of the parent's task group */ + + task_sigchild(ptcb, ctcb, status); + + /* 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 and all will be well. + */ + + ctcb->parent = INVALID_PROCESS_ID; + sched_unlock(); } #else -# define task_sigchild(tcb,status) +# define task_leavegroup(ctcb,status) #endif /**************************************************************************** @@ -363,9 +391,9 @@ void task_exithook(FAR _TCB *tcb, int status) task_onexit(tcb, status); - /* Send SIGCHLD to the parent of the exit-ing task */ + /* Leave the task group */ - task_sigchild(tcb, status); + task_leavegroup(tcb, status); /* Wakeup any tasks waiting for this task to exit */ @@ -379,10 +407,12 @@ void task_exithook(FAR _TCB *tcb, int status) (void)lib_flushall(tcb->streams); #endif - /* Discard any un-reaped child status (no zombies here!) */ + /* Leave the task group. Perhaps discarding any un-reaped child + * status (no zombies here!) + */ -#if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS) - task_removechildren(tcb); +#ifdef HAVE_TASK_GROUP + group_leave(tcb); #endif /* Free all file-related resources now. This gets called again diff --git a/nuttx/sched/task_init.c b/nuttx/sched/task_init.c index 0f0fdc68e..5ba6b7e7d 100644 --- a/nuttx/sched/task_init.c +++ b/nuttx/sched/task_init.c @@ -1,7 +1,7 @@ /**************************************************************************** * sched/task_init.c * - * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2009, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -42,6 +42,8 @@ #include #include #include +#include + #include #include "os_internal.h" @@ -102,10 +104,10 @@ * parameters are required, argv may be NULL. * * Return Value: - * OK on success; ERROR on failure. (See task_schedsetup() for possible - * failure conditions). On failure, the caller is responsible for freeing - * the stack memory and for calling sched_releasetcb() to free the TCB - * (which could be in most any state). + * OK on success; ERROR on failure with errno set appropriately. (See + * task_schedsetup() for possible failure conditions). On failure, the + * caller is responsible for freeing the stack memory and for calling + * sched_releasetcb() to free the TCB (which could be in most any state). * ****************************************************************************/ @@ -118,14 +120,28 @@ int task_init(FAR _TCB *tcb, const char *name, int priority, main_t entry, const char *argv[]) #endif { + int errcode; int ret; + /* Create a new task group */ + +#ifdef HAVE_TASK_GROUP + ret = group_create(tcb); + if (ret < 0) + { + errcode = -ret; + goto errout; + } +#endif + /* Associate file descriptors with the new task */ #if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0 - if (sched_setuptaskfiles(tcb) != OK) + ret = sched_setuptaskfiles(tcb); + if (ret < 0) { - return ERROR; + errcode = -ret; + goto errout_with_group; } #endif @@ -143,13 +159,27 @@ int task_init(FAR _TCB *tcb, const char *name, int priority, ret = task_schedsetup(tcb, priority, task_start, entry, TCB_FLAG_TTYPE_TASK); - if (ret == OK) + if (ret < OK) { - /* Setup to pass parameters to the new task */ - - (void)task_argsetup(tcb, name, argv); + errcode = -ret; + goto errout_with_env; } - return ret; + /* Setup to pass parameters to the new task */ + + (void)task_argsetup(tcb, name, argv); + return OK; + +errout_with_env: + env_release(tcb); + +errout_with_group: +#ifdef HAVE_TASK_GROUP + group_leave(tcb); + +errout: +#endif + set_errno(errcode); + return ERROR; } diff --git a/nuttx/sched/task_reparent.c b/nuttx/sched/task_reparent.c index 3a7ece37d..0b502dcce 100644 --- a/nuttx/sched/task_reparent.c +++ b/nuttx/sched/task_reparent.c @@ -138,11 +138,11 @@ int task_reparent(pid_t ppid, pid_t chpid) child = task_removechild(otcb, chpid); if (child) { - /* Has the new parent supressed child exit status? */ + /* Has the new parent's task group supressed child exit status? */ - if ((ptcb->flags && TCB_FLAG_NOCLDWAIT) == 0) + if ((ptcb->group->tg_flags && GROUP_FLAG_NOCLDWAIT) == 0) { - /* No.. Add the child status entry to the new parent TCB */ + /* No.. Add the child status entry to the new parent's task group */ task_addchild(ptcb, child); } @@ -159,11 +159,11 @@ int task_reparent(pid_t ppid, pid_t chpid) } else { - /* This would not be an error if the original parent has + /* This would not be an error if the original parent's task group has * suppressed child exit status. */ - ret = ((otcb->flags && TCB_FLAG_NOCLDWAIT) == 0) ? -ENOENT : OK; + ret = ((otcb->group->tg_flags && GROUP_FLAG_NOCLDWAIT) == 0) ? -ENOENT : OK; } #else DEBUGASSERT(otcb->nchildren > 0); diff --git a/nuttx/sched/task_setup.c b/nuttx/sched/task_setup.c index 66c948cfd..7675c7481 100644 --- a/nuttx/sched/task_setup.c +++ b/nuttx/sched/task_setup.c @@ -1,7 +1,7 @@ /**************************************************************************** * sched/task_setup.c * - * Copyright (C) 2007-2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -179,13 +179,11 @@ static inline void task_saveparent(FAR _TCB *tcb, uint8_t ttype) tcb->parent = rtcb->pid; #ifdef CONFIG_SCHED_CHILD_STATUS - /* Exit status only needs to be retained for the case of tasks, however. - * Tasks can also suppress retention of their child status by applying - * the SA_NOCLDWAIT flag with sigaction()/ + /* Tasks can also suppress retention of their child status by applying + * the SA_NOCLDWAIT flag with sigaction(). */ - if (ttype == TCB_FLAG_TTYPE_TASK && - (rtcb->flags && TCB_FLAG_NOCLDWAIT) == 0) + if ((rtcb->group->tg_flags && GROUP_FLAG_NOCLDWAIT) == 0) { FAR struct child_status_s *child; -- cgit v1.2.3 From 80904539e63681b2dca74e3978effb17f0c071b0 Mon Sep 17 00:00:00 2001 From: patacongo Date: Fri, 25 Jan 2013 19:15:05 +0000 Subject: Add logic to keep track of members of a task group git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5563 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/include/nuttx/sched.h | 24 +++++++--- nuttx/sched/group_create.c | 74 ++++++++++++++++++++++++++----- nuttx/sched/group_join.c | 103 ++++++++++++++++++++++++++++++++++++++----- nuttx/sched/group_leave.c | 68 +++++++++++++++++++++++++--- nuttx/sched/os_internal.h | 10 +++-- nuttx/sched/os_start.c | 19 ++++---- nuttx/sched/pthread_create.c | 24 ++++++++-- nuttx/sched/task_create.c | 17 +++++-- nuttx/sched/task_exithook.c | 2 +- nuttx/sched/task_init.c | 13 +++++- 10 files changed, 298 insertions(+), 56 deletions(-) (limited to 'nuttx/sched') diff --git a/nuttx/include/nuttx/sched.h b/nuttx/include/nuttx/sched.h index 4a3bae5e4..a29f8dfeb 100644 --- a/nuttx/include/nuttx/sched.h +++ b/nuttx/include/nuttx/sched.h @@ -60,10 +60,18 @@ /* Configuration ****************************************************************/ /* Task groups currently only supported for retention of child status */ +#undef HAVE_TASK_GROUP +#undef HAVE_GROUP_MEMBERS + #if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS) -# define HAVE_TASK_GROUP 1 -#else -# undef HAVE_TASK_GROUP +# define HAVE_TASK_GROUP 1 +# define HAVE_GROUP_MEMBERS 1 +#endif + +/* In any event, we don't need group members if support for pthreads is disabled */ + +#ifdef CONFIG_PTHREADS_DISABLE +# undef HAVE_GROUP_MEMBERS #endif /* Task Management Definitins ***************************************************/ @@ -255,12 +263,18 @@ struct dspace_s #ifdef HAVE_TASK_GROUP struct task_group_s { - uint16_t tg_crefs; /* Count of threads sharing this data */ - uint8_t tg_flags; /* See GROUP_FLAG_* definitions */ + uint8_t tg_flags; /* See GROUP_FLAG_* definitions */ + uint8_t tg_nmembers; /* Number of members in the group */ +#ifdef HAVE_GROUP_MEMBERS + uint8_t tg_mxmembers; /* Number of members in allocation */ + FAR pid_t *tg_members; /* Members of the group */ +#endif /* Child exit status **********************************************************/ +#if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS) FAR struct child_status_s *tg_children; /* Head of a list of child status */ +#endif /* Environment varibles *******************************************************/ /* Not yet (see type environ_t) */ diff --git a/nuttx/sched/group_create.c b/nuttx/sched/group_create.c index d036b9084..4612ae8c5 100644 --- a/nuttx/sched/group_create.c +++ b/nuttx/sched/group_create.c @@ -1,5 +1,5 @@ /***************************************************************************** - * sched/group_create.c + * sched/group_allocate.c * * Copyright (C) 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -51,6 +51,9 @@ /***************************************************************************** * Pre-processor Definitions *****************************************************************************/ +/* Is this worth making a configuration option? */ + +#define GROUP_INITIAL_MEMBERS 4 /***************************************************************************** * Private Types @@ -69,11 +72,16 @@ *****************************************************************************/ /***************************************************************************** - * Name: group_create + * Name: group_allocate * * Description: - * Create and initialize a new task group structure for the specified TCB. - * This function is called as part of the task creation sequence. + * Create and a new task group structure for the specified TCB. This + * function is called as part of the task creation sequence. The structure + * allocated and zered, but otherwise uninitialized. The full creation + * of the group of a two step process: (1) First, this function allocates + * group structure early in the task creation sequence in order to provide a + * group container, then (2) group_initialize() is called to set up the + * group membership. * * Parameters: * tcb - The tcb in need of the task group. @@ -87,24 +95,66 @@ * *****************************************************************************/ -int group_create(FAR _TCB *tcb) +int group_allocate(FAR _TCB *tcb) { + DEBUGASSERT(tcb && !tcb->group); + + /* Allocate the group structure and assign it to the TCB */ + + tcb->group = (FAR struct task_group_s *)kzalloc(sizeof(struct task_group_s)); + return tcb->group ? OK : -ENOMEM; +} + +/***************************************************************************** + * Name: group_initialize + * + * Description: + * Add the task as the initial member of the group. The full creation of + * the group of a two step process: (1) First, this group structure is + * allocated by group_allocate() early in the task creation sequence, then + * (2) this function is called to set up the initial group membership. + * + * Parameters: + * tcb - The tcb in need of the task group. + * + * Return Value: + * 0 (OK) on success; a negated errno value on failure. + * + * Assumptions: + * Called during task creation in a safe context. No special precautions + * are required here. + * + *****************************************************************************/ + +int group_initialize(FAR _TCB *tcb) +{ +#ifdef HAVE_GROUP_MEMBERS FAR struct task_group_s *group; - DEBUGASSERT(tcb && !tcb->group); + DEBUGASSERT(tcb && tcb->group); + group = tcb->group; - /* Allocate the group structure */ + /* Allocate space to hold GROUP_INITIAL_MEMBERS members of the group */ - group = (FAR struct task_group_s *)kzalloc(sizeof(struct task_group_s)); - if (!group) + group->tg_members = (FAR pid_t *)kmalloc(GROUP_INITIAL_MEMBERS*sizeof(pid_t)); + if (!group->tg_members) { + free(group); return -ENOMEM; } - /* Initialize the group structure and assign it to the tcb */ + /* Assign the PID of this new task as a member of the group*/ + + group->tg_members[0] = tcb->pid; + + /* Initialize the non-zero elements of group structure and assign it to + * the tcb. + */ + + group->tg_mxmembers = GROUP_INITIAL_MEMBERS; /* Number of members in allocation */ +#endif - group->tg_crefs = 1; - tcb->group = group; + group->tg_nmembers = 1; /* Number of members in the group */ return OK; } diff --git a/nuttx/sched/group_join.c b/nuttx/sched/group_join.c index 987c1ba87..9dcea6599 100644 --- a/nuttx/sched/group_join.c +++ b/nuttx/sched/group_join.c @@ -41,8 +41,11 @@ #include #include +#include #include +#include + #include "os_internal.h" #ifdef HAVE_TASK_GROUP @@ -50,6 +53,9 @@ /***************************************************************************** * Pre-processor Definitions *****************************************************************************/ +/* Is this worth making a configuration option? */ + +#define GROUP_REALLOC_MEMBERS 4 /***************************************************************************** * Private Types @@ -68,19 +74,21 @@ *****************************************************************************/ /***************************************************************************** - * Name: group_join + * Name: group_bind * * Description: - * Copy the group structure reference from one TCB to another, incrementing - * the refrence count on the group. This function is called when a pthread - * is produced within the task group so that the pthread can share the - * resources of the task group. + * A thread joins the group when it is created. This is a two step process, + * first, the group must bound to the new threads TCB. group_bind() does + * this (at the return from group_join, things are a little unstable: The + * group has been bound, but tg_nmembers hs not yet been incremented). + * Then, after the new thread is initialized and has a PID assigned to it, + * group_join() is called, incrementing the tg_nmembers count on the group. * * Parameters: * tcb - The TCB of the new "child" task that need to join the group. * * Return Value: - * None + * 0 (OK) on success; a negated errno value on failure. * * Assumptions: * - The parent task from which the group will be inherited is the task at @@ -90,18 +98,91 @@ * *****************************************************************************/ -void group_join(FAR _TCB *tcb) +int group_bind(FAR _TCB *tcb) { FAR _TCB *ptcb = (FAR _TCB *)g_readytorun.head; DEBUGASSERT(ptcb && tcb && ptcb->group && !tcb->group); - /* Copy the group reference from the parent to the child, incrementing the - * reference count. - */ + /* Copy the group reference from the parent to the child */ tcb->group = ptcb->group; - ptcb->group->tg_crefs++; + return OK; +} + +/***************************************************************************** + * Name: group_join + * + * Description: + * A thread joins the group when it is created. This is a two step process, + * first, the group must bound to the new threads TCB. group_bind() does + * this (at the return from group_join, things are a little unstable: The + * group has been bound, but tg_nmembers hs not yet been incremented). + * Then, after the new thread is initialized and has a PID assigned to it, + * group_join() is called, incrementing the tg_nmembers count on the group. + * + * Parameters: + * tcb - The TCB of the new "child" task that need to join the group. + * + * Return Value: + * 0 (OK) on success; a negated errno value on failure. + * + * Assumptions: + * - The parent task from which the group will be inherited is the task at + * the thead of the ready to run list. + * - Called during thread creation in a safe context. No special precautions + * are required here. + * + *****************************************************************************/ + +int group_join(FAR _TCB *tcb) +{ +#ifdef HAVE_GROUP_MEMBERS + FAR struct task_group_s *group; + + DEBUGASSERT(tcb && tcb->group && + tcb->group->tg_nmembers < UINT8_MAX); + + /* Get the group from the TCB */ + + group = tcb->group; + + /* Will we need to extend the size of the array of groups? */ + + if (group->tg_nmembers >= group->tg_mxmembers) + { + FAR pid_t *newmembers; + unsigned int newmax; + + /* Yes... reallocate the array of members */ + + newmax = group->tg_mxmembers + GROUP_REALLOC_MEMBERS; + if (newmax > UINT8_MAX) + { + newmax = UINT8_MAX; + } + + newmembers = (FAR pid_t *) + krealloc(group->tg_members, sizeof(pid_t) * newmax); + + if (!newmembers) + { + return -ENOMEM; + } + + /* Save the new number of members in the reallocated members array */ + + group->tg_members = newmembers; + group->tg_mxmembers = newmax; + } + + /* Assign this new pid to the group. */ + + group->tg_members[group->tg_nmembers] = tcb->pid; +#endif + + group->tg_nmembers++; + return OK; } #endif /* HAVE_TASK_GROUP */ diff --git a/nuttx/sched/group_leave.c b/nuttx/sched/group_leave.c index 69a6ea8b2..223af1556 100644 --- a/nuttx/sched/group_leave.c +++ b/nuttx/sched/group_leave.c @@ -92,6 +92,7 @@ void group_leave(FAR _TCB *tcb) { FAR struct task_group_s *group; + int i; DEBUGASSERT(tcb); @@ -100,17 +101,69 @@ void group_leave(FAR _TCB *tcb) group = tcb->group; if (group) { - /* Would the reference count decrement to zero? */ +#ifdef HAVE_GROUP_MEMBERS + /* Find the member in the array of members and remove it */ - if (group->tg_crefs > 1) + for (i = 0; i < group->tg_nmembers; i++) { - /* No.. just decrement the reference count and return */ + /* Does this member have the matching pid */ + + if (group->tg_members[i] == tcb->pid) + { + /* Yes.. break out of the loop. We don't do the actual + * removal here, instead we re-test i and do the adjustments + * outside of the loop. We do this because we want the + * DEBUGASSERT to work properly. + */ + + break; + } + } + + /* Now, test if we found the task in the array of members. */ + + DEBUGASSERT(i < group->tg_nmembers); + if (i < group->tg_nmembers) + { + /* Yes..Is this the last member of the group? */ + + if (group->tg_nmembers > 1) + { + /* No.. remove the member from the array of members */ + + group->tg_members[i] = group->tg_members[group->tg_nmembers - 1]; + group->tg_nmembers--; + } + + /* Yes.. that was the last member remaining in the group */ + + else + { + /* Release all of the resource contained within the group */ + /* Free all un-reaped child exit status */ + + task_removechildren(tcb); - group->tg_crefs--; + /* Release the group container itself */ + + sched_free(group); + } + } +#else + /* Yes..Is this the last member of the group? */ + + if (group->tg_nmembers > 1) + { + /* No.. just decrement the number of members in the group */ + + group->tg_nmembers--; } + + /* Yes.. that was the last member remaining in the group */ + else { - /* Yes.. Release all of the resource contained within the group */ + /* Release all of the resource contained within the group */ /* Free all un-reaped child exit status */ task_removechildren(tcb); @@ -119,6 +172,11 @@ void group_leave(FAR _TCB *tcb) sched_free(group); } +#endif + + /* In any event, we can detach the group from the TCB so we won't do + * this again. + */ tcb->group = NULL; } diff --git a/nuttx/sched/os_internal.h b/nuttx/sched/os_internal.h index ee5ada165..8ce99bc44 100644 --- a/nuttx/sched/os_internal.h +++ b/nuttx/sched/os_internal.h @@ -273,12 +273,14 @@ int task_deletecurrent(void); int task_reparent(pid_t ppid, pid_t chpid); #ifdef HAVE_TASK_GROUP -int group_create(FAR _TCB *tcb); -void group_join(FAR _TCB *tcb); +int group_allocate(FAR _TCB *tcb); +int group_initialize(FAR _TCB *tcb); +int group_join(FAR _TCB *tcb); void group_leave(FAR _TCB *tcb); #else -# define group_create(tcb) -# define group_join(tcb) +# define group_allocate(tcb) (0) +# define group_initialize(tcb) (0) +# define group_join(tcb) (0) # define group_leave(tcb) #endif diff --git a/nuttx/sched/os_start.c b/nuttx/sched/os_start.c index 244aec967..3aecc7efb 100644 --- a/nuttx/sched/os_start.c +++ b/nuttx/sched/os_start.c @@ -202,9 +202,6 @@ const tasklist_t g_tasklisttable[NUM_TASK_STATES] = */ static FAR _TCB g_idletcb; -#if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS) -static struct task_group_s g_idlegroup; -#endif /* This is the name of the idle task */ @@ -283,14 +280,6 @@ void os_start(void) g_idletcb.argv[0] = (char*)g_idlename; #endif /* CONFIG_TASK_NAME_SIZE */ - /* Join the IDLE group */ - -#ifdef HAVE_TASK_GROUP - g_idlegroup.tg_crefs = 1; - g_idlegroup.tg_flags = GROUP_FLAG_NOCLDWAIT; - g_idletcb.group = &g_idlegroup; -#endif - /* Then add the idle task's TCB to the head of the ready to run list */ dq_addfirst((FAR dq_entry_t*)&g_idletcb, (FAR dq_queue_t*)&g_readytorun); @@ -447,6 +436,14 @@ void os_start(void) lib_initialize(); } + /* Create the IDLE group and suppress child status */ + +#ifdef HAVE_TASK_GROUP + (void)group_allocate(&g_idletcb); + (void)group_initialize(&g_idletcb); + g_idletcb.group->tg_flags = GROUP_FLAG_NOCLDWAIT; +#endif + /* Create stdout, stderr, stdin on the IDLE task. These will be * inherited by all of the threads created by the IDLE task. */ diff --git a/nuttx/sched/pthread_create.c b/nuttx/sched/pthread_create.c index e37c06892..89a2feb00 100644 --- a/nuttx/sched/pthread_create.c +++ b/nuttx/sched/pthread_create.c @@ -246,13 +246,13 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr, { FAR _TCB *ptcb; FAR join_t *pjoin; - int ret; int priority; #if CONFIG_RR_INTERVAL > 0 int policy; #endif int errcode; pid_t pid; + int ret; /* If attributes were not supplied, use the default attributes */ @@ -269,10 +269,17 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr, return ENOMEM; } - /* Join the parent's task group */ + /* Bind the parent's group to the new TCB (we have not yet joined the + * group). + */ #ifdef HAVE_TASK_GROUP - group_join(ptcb); + ret = group_bind(ptcb); + if (ret < 0) + { + errcode = ENOMEM; + goto errout_with_tcb; + } #endif /* Share the address environment of the parent task. NOTE: Only tasks @@ -376,6 +383,17 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr, pthread_argsetup(ptcb, arg); + /* Join the parent's task group */ + +#ifdef HAVE_TASK_GROUP + ret = group_join(ptcb); + if (ret < 0) + { + errcode = ENOMEM; + goto errout_with_join; + } +#endif + /* Attach the join info to the TCB. */ ptcb->joininfo = (void*)pjoin; diff --git a/nuttx/sched/task_create.c b/nuttx/sched/task_create.c index f2aeeeec0..bb309444b 100644 --- a/nuttx/sched/task_create.c +++ b/nuttx/sched/task_create.c @@ -120,10 +120,10 @@ static int thread_create(const char *name, uint8_t ttype, int priority, goto errout; } - /* Create a new task group */ + /* Allocate a new task group */ #ifdef HAVE_TASK_GROUP - ret = group_create(tcb); + ret = group_allocate(tcb); if (ret < 0) { errcode = -ret; @@ -160,7 +160,7 @@ static int thread_create(const char *name, uint8_t ttype, int priority, /* Initialize the task control block */ ret = task_schedsetup(tcb, priority, task_start, entry, ttype); - if (ret != OK) + if (ret < OK) { errcode = -ret; goto errout_with_tcb; @@ -170,6 +170,17 @@ static int thread_create(const char *name, uint8_t ttype, int priority, (void)task_argsetup(tcb, name, argv); + /* Now we have enough in place that we can join the group */ + +#ifdef HAVE_TASK_GROUP + ret = group_initialize(tcb); + if (ret < 0) + { + errcode = -ret; + goto errout_with_tcb; + } +#endif + /* Get the assigned pid before we start the task */ pid = (int)tcb->pid; diff --git a/nuttx/sched/task_exithook.c b/nuttx/sched/task_exithook.c index 30ce41f71..36836301c 100644 --- a/nuttx/sched/task_exithook.c +++ b/nuttx/sched/task_exithook.c @@ -207,7 +207,7 @@ static inline void task_sigchild(FAR _TCB *ptcb, FAR _TCB *ctcb, int status) */ #ifdef CONFIG_SCHED_CHILD_STATUS - if (ctcb->group->tg_crefs == 1) + if (ctcb->group->tg_nmembers == 1) #else if ((ctcb->flags & TCB_FLAG_TTYPE_MASK) == TCB_FLAG_TTYPE_TASK) #endif diff --git a/nuttx/sched/task_init.c b/nuttx/sched/task_init.c index 5ba6b7e7d..6ae643948 100644 --- a/nuttx/sched/task_init.c +++ b/nuttx/sched/task_init.c @@ -126,7 +126,7 @@ int task_init(FAR _TCB *tcb, const char *name, int priority, /* Create a new task group */ #ifdef HAVE_TASK_GROUP - ret = group_create(tcb); + ret = group_allocate(tcb); if (ret < 0) { errcode = -ret; @@ -168,6 +168,17 @@ int task_init(FAR _TCB *tcb, const char *name, int priority, /* Setup to pass parameters to the new task */ (void)task_argsetup(tcb, name, argv); + + /* Now we have enough in place that we can join the group */ + +#ifdef HAVE_TASK_GROUP + ret = group_initialize(tcb); + if (ret < 0) + { + errcode = -ret; + goto errout_with_env; + } +#endif return OK; errout_with_env: -- cgit v1.2.3 From fdaa22ed2d565e49983e956bc056f1e0797bd9a9 Mon Sep 17 00:00:00 2001 From: patacongo Date: Fri, 25 Jan 2013 20:00:37 +0000 Subject: Add logic to send SIGCHLD to all members of a task group git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5564 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 5 ++ nuttx/include/nuttx/sched.h | 2 +- nuttx/sched/Makefile | 6 +- nuttx/sched/group_signal.c | 135 ++++++++++++++++++++++++++++++++++++++++++++ nuttx/sched/os_internal.h | 14 ++++- nuttx/sched/task_exithook.c | 4 ++ 6 files changed, 161 insertions(+), 5 deletions(-) create mode 100644 nuttx/sched/group_signal.c (limited to 'nuttx/sched') diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 2eaa03b21..f033fc9ba 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -4025,3 +4025,8 @@ poll_interrupt() must cat call net_lostconnection() when a loss of connection is reported. Otherwise, the system will not know that the connection has been lost. + * sched/group_create.c, group_join.c, and group_leave.c: Add + support for task groups. + * sched/group_signal.c and task_exithook.c: Send signal to all + members for the parent task group. + diff --git a/nuttx/include/nuttx/sched.h b/nuttx/include/nuttx/sched.h index a29f8dfeb..2795751ab 100644 --- a/nuttx/include/nuttx/sched.h +++ b/nuttx/include/nuttx/sched.h @@ -70,7 +70,7 @@ /* In any event, we don't need group members if support for pthreads is disabled */ -#ifdef CONFIG_PTHREADS_DISABLE +#ifdef CONFIG_DISABLE_PTHREAD # undef HAVE_GROUP_MEMBERS #endif diff --git a/nuttx/sched/Makefile b/nuttx/sched/Makefile index 6a710ff95..bbf513f34 100644 --- a/nuttx/sched/Makefile +++ b/nuttx/sched/Makefile @@ -87,7 +87,11 @@ SCHED_SRCS += sched_waitid.c sched_wait.c endif endif -GRP_SRCS = group_create.c group_join.c group_leave.c +GRP_SRCS = group_create.c group_join.c group_leave.c + +ifneq ($(CONFIG_DISABLE_SIGNALS),y) +GRP_SRCS += group_signal.c +endif ENV_SRCS = env_getenvironptr.c env_dup.c env_share.c env_release.c ENV_SRCS += env_findvar.c env_removevar.c diff --git a/nuttx/sched/group_signal.c b/nuttx/sched/group_signal.c new file mode 100644 index 000000000..68912fe00 --- /dev/null +++ b/nuttx/sched/group_signal.c @@ -0,0 +1,135 @@ +/***************************************************************************** + * sched/group_signal.c + * + * Copyright (C) 2013 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 + +#include +#include +#include +#include + +#include "sig_internal.h" + +#if defined(HAVE_TASK_GROUP) && !defined(CONFIG_DISABLE_SIGNALS) + +/***************************************************************************** + * Pre-processor Definitions + *****************************************************************************/ + +/***************************************************************************** + * Private Types + *****************************************************************************/ + +/***************************************************************************** + * Private Data + *****************************************************************************/ + +/***************************************************************************** + * Private Functions + *****************************************************************************/ + +/***************************************************************************** + * Public Functions + *****************************************************************************/ + +/***************************************************************************** + * Name: group_signal + * + * Description: + * Send a signal to every member of the group to which task belongs. + * + * Parameters: + * tcb - The tcb of one task in the task group that needs to be signalled. + * + * Return Value: + * 0 (OK) on success; a negated errno value on failure. + * + * Assumptions: + * Called during task terminatino in a safe context. No special precautions + * are required here. + * + *****************************************************************************/ + +int group_signal(FAR _TCB *tcb, FAR siginfo_t *info) +{ +#ifdef HAVE_GROUP_MEMBERS + FAR struct task_group_s *group; + FAR _TCB *gtcb; + int i; + + DEBUGASSERT(tcb && tcb->group && info); + group = tcb->group; + + /* Make sure that pre-emption is disabled to that we signal all of teh + * members of the group before any of them actually run. + */ + + sched_lock(); + + /* Send the signal to each member of the group */ + + for (i = 0; i < group->tg_nmembers; i++) + { + gtcb = sched_gettcb(group->tg_members[i]); + DEBUGASSERT(gtcb); + if (gtcb) + { + /* Use the sig_received interface so that it does not muck with + * the siginfo_t. + */ + +#ifdef CONFIG_DEBUG + int ret = sig_received(gtcb, info); + DEBUGASSERT(ret == 0); +#else + (void)sig_received(gtcb, info); +#endif + } + } + + /* Re-enable pre-emption an return success */ + + sched_unlock(); + return OK; +#else + return sig_received(tcb, info); +#endif +} + +#endif /* HAVE_TASK_GROUP && !CONFIG_DISABLE_SIGNALS */ diff --git a/nuttx/sched/os_internal.h b/nuttx/sched/os_internal.h index 8ce99bc44..599be25bb 100644 --- a/nuttx/sched/os_internal.h +++ b/nuttx/sched/os_internal.h @@ -275,13 +275,21 @@ int task_reparent(pid_t ppid, pid_t chpid); #ifdef HAVE_TASK_GROUP int group_allocate(FAR _TCB *tcb); int group_initialize(FAR _TCB *tcb); +int group_bind(FAR _TCB *tcb); int group_join(FAR _TCB *tcb); void group_leave(FAR _TCB *tcb); +#ifndef CONFIG_DISABLE_SIGNALS +int group_signal(FAR _TCB *tcb, FAR siginfo_t *info); +#else +# define group_signal(tcb,info) (0) +#endif #else -# define group_allocate(tcb) (0) -# define group_initialize(tcb) (0) -# define group_join(tcb) (0) +# define group_allocate(tcb) (0) +# define group_initialize(tcb) (0) +# define group_bind(tcb) (0) +# define group_join(tcb) (0) # define group_leave(tcb) +# define group_signal(tcb,info) (0) #endif #ifdef CONFIG_SCHED_CHILD_STATUS diff --git a/nuttx/sched/task_exithook.c b/nuttx/sched/task_exithook.c index 36836301c..2d596978f 100644 --- a/nuttx/sched/task_exithook.c +++ b/nuttx/sched/task_exithook.c @@ -259,7 +259,11 @@ static inline void task_sigchild(FAR _TCB *ptcb, FAR _TCB *ctcb, int status) * can provide the correct si_code value with the signal. */ +#ifdef HAVE_GROUP_MEMBERS + (void)group_signal(ptcb, &info); +#else (void)sig_received(ptcb, &info); +#endif } } #else -- cgit v1.2.3 From 239e2808cca6ee4c356d087bc83889fc57e64307 Mon Sep 17 00:00:00 2001 From: patacongo Date: Fri, 25 Jan 2013 23:21:27 +0000 Subject: Move environment variables in the task group structure git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5565 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 2 + nuttx/include/nuttx/sched.h | 43 +++++++-------- nuttx/sched/Makefile | 2 +- nuttx/sched/env_clearenv.c | 5 +- nuttx/sched/env_dup.c | 26 +++++---- nuttx/sched/env_dupenv.c | 112 --------------------------------------- nuttx/sched/env_findvar.c | 33 +++++------- nuttx/sched/env_getenv.c | 14 ++--- nuttx/sched/env_internal.h | 32 ++++++----- nuttx/sched/env_release.c | 68 +++++++++--------------- nuttx/sched/env_removevar.c | 56 ++++++++++---------- nuttx/sched/env_setenv.c | 59 ++++++++++----------- nuttx/sched/env_share.c | 117 ----------------------------------------- nuttx/sched/env_unsetenv.c | 62 +++++++++------------- nuttx/sched/group_create.c | 24 ++++++++- nuttx/sched/group_internal.h | 104 ++++++++++++++++++++++++++++++++++++ nuttx/sched/group_join.c | 5 +- nuttx/sched/group_leave.c | 20 +++++-- nuttx/sched/group_signal.c | 2 + nuttx/sched/os_internal.h | 38 ++----------- nuttx/sched/os_start.c | 5 +- nuttx/sched/pthread_create.c | 6 +-- nuttx/sched/sched_releasetcb.c | 6 +-- nuttx/sched/sched_waitid.c | 1 + nuttx/sched/sched_waitpid.c | 1 + nuttx/sched/sig_action.c | 1 + nuttx/sched/task_childstatus.c | 1 + nuttx/sched/task_create.c | 6 +-- nuttx/sched/task_exithook.c | 1 + nuttx/sched/task_init.c | 13 ++--- nuttx/sched/task_posixspawn.c | 1 + nuttx/sched/task_reparent.c | 1 + nuttx/sched/task_setup.c | 1 + nuttx/sched/task_vfork.c | 6 +-- 34 files changed, 347 insertions(+), 527 deletions(-) delete mode 100644 nuttx/sched/env_dupenv.c delete mode 100644 nuttx/sched/env_share.c create mode 100644 nuttx/sched/group_internal.h (limited to 'nuttx/sched') diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index f033fc9ba..f23a3ed73 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -4029,4 +4029,6 @@ support for task groups. * sched/group_signal.c and task_exithook.c: Send signal to all members for the parent task group. + * include/nuttx/sched.h and sched/env_*.c: Move environment + variables into task group structure. diff --git a/nuttx/include/nuttx/sched.h b/nuttx/include/nuttx/sched.h index 2795751ab..dd33b4570 100644 --- a/nuttx/include/nuttx/sched.h +++ b/nuttx/include/nuttx/sched.h @@ -68,6 +68,11 @@ # define HAVE_GROUP_MEMBERS 1 #endif +#if !defined(CONFIG_DISABLE_ENVIRON) +# undef HAVE_TASK_GROUP +# define HAVE_TASK_GROUP 1 +#endif + /* In any event, we don't need group members if support for pthreads is disabled */ #ifdef CONFIG_DISABLE_PTHREAD @@ -178,21 +183,6 @@ typedef CODE void (*onexitfunc_t)(int exitcode, FAR void *arg); typedef struct msgq_s msgq_t; -/* struct environ_s **************************************************************/ -/* The structure used to maintain environment variables */ - -#ifndef CONFIG_DISABLE_ENVIRON -struct environ_s -{ - unsigned int ev_crefs; /* Reference count used when environment - * is shared by threads */ - size_t ev_alloc; /* Number of bytes allocated in environment */ - char ev_env[1]; /* Environment strings */ -}; -typedef struct environ_s environ_t; -# define SIZEOF_ENVIRON_T(alloc) (sizeof(environ_t) + alloc - 1) -#endif - /* struct child_status_s *********************************************************/ /* This structure is used to maintin information about child tasks. * pthreads work differently, they have join information. This is @@ -263,11 +253,14 @@ struct dspace_s #ifdef HAVE_TASK_GROUP struct task_group_s { - uint8_t tg_flags; /* See GROUP_FLAG_* definitions */ - uint8_t tg_nmembers; /* Number of members in the group */ + uint8_t tg_flags; /* See GROUP_FLAG_* definitions */ + + /* Group membership ***********************************************************/ + + uint8_t tg_nmembers; /* Number of members in the group */ #ifdef HAVE_GROUP_MEMBERS - uint8_t tg_mxmembers; /* Number of members in allocation */ - FAR pid_t *tg_members; /* Members of the group */ + uint8_t tg_mxmembers; /* Number of members in allocation */ + FAR pid_t *tg_members; /* Members of the group */ #endif /* Child exit status **********************************************************/ @@ -276,8 +269,12 @@ struct task_group_s FAR struct child_status_s *tg_children; /* Head of a list of child status */ #endif - /* Environment varibles *******************************************************/ - /* Not yet (see type environ_t) */ + /* Environment variables ******************************************************/ + +#ifndef CONFIG_DISABLE_ENVIRON + size_t tg_envsize; /* Size of environment string allocation */ + FAR char *tg_envp; /* Allocated environment strings */ +#endif /* PIC data space and address environments */ /* Not yet (see struct dspace_s) */ @@ -373,10 +370,6 @@ struct _TCB uint8_t init_priority; /* Initial priority of the task */ char *argv[CONFIG_MAX_TASK_ARGS+1]; /* Name+start-up parameters */ -#ifndef CONFIG_DISABLE_ENVIRON - FAR environ_t *envp; /* Environment variables */ -#endif - /* Stack-Related Fields *******************************************************/ #ifndef CONFIG_CUSTOM_STACK diff --git a/nuttx/sched/Makefile b/nuttx/sched/Makefile index bbf513f34..6a0b99144 100644 --- a/nuttx/sched/Makefile +++ b/nuttx/sched/Makefile @@ -93,7 +93,7 @@ ifneq ($(CONFIG_DISABLE_SIGNALS),y) GRP_SRCS += group_signal.c endif -ENV_SRCS = env_getenvironptr.c env_dup.c env_share.c env_release.c +ENV_SRCS = env_getenvironptr.c env_dup.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 diff --git a/nuttx/sched/env_clearenv.c b/nuttx/sched/env_clearenv.c index 75890f3bc..a9e9f5efd 100644 --- a/nuttx/sched/env_clearenv.c +++ b/nuttx/sched/env_clearenv.c @@ -1,7 +1,7 @@ /**************************************************************************** * sched/env_clearenv.c * - * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2009, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -74,7 +74,8 @@ int clearenv(void) { - return env_release((FAR _TCB*)g_readytorun.head); + env_release((FAR _TCB*)g_readytorun.head); + return OK; } #endif /* CONFIG_DISABLE_ENVIRON */ diff --git a/nuttx/sched/env_dup.c b/nuttx/sched/env_dup.c index 30c0b7773..479f7cae7 100644 --- a/nuttx/sched/env_dup.c +++ b/nuttx/sched/env_dup.c @@ -68,7 +68,7 @@ * exact duplicate of the parent task's environment. * * Parameters: - * ptcb The tcb to receive the newly allocated copy of the parent + * ctcb The child tcb to receive the newly allocated copy of the parent * TCB's environment structure with reference count equal to one * * Return Value: @@ -79,13 +79,14 @@ * ****************************************************************************/ -int env_dup(FAR _TCB *ptcb) +int env_dup(FAR _TCB *ctcb) { - FAR _TCB *parent = (FAR _TCB*)g_readytorun.head; - environ_t *envp = NULL; + FAR _TCB *ptcb = (FAR _TCB*)g_readytorun.head; + FAR char *envp = NULL; + size_t envlen; int ret = OK; - DEBUGASSERT(ptcb); + DEBUGASSERT(ctcb && ptcb && ctcb->group && ptcb->group); /* Pre-emption must be disabled throughout the following because the * environment may be shared. @@ -95,27 +96,24 @@ int env_dup(FAR _TCB *ptcb) /* Does the parent task have an environment? */ - if (parent->envp) + if (ptcb->group && ptcb->group->tg_envp) { /* Yes..The parent task has an environment, duplicate it */ - size_t envlen = parent->envp->ev_alloc; - envp = (environ_t*)kmalloc(SIZEOF_ENVIRON_T(envlen)); + envlen = ptcb->group->tg_envsize; + envp = (FAR char *)kmalloc(envlen); if (!envp) { ret = -ENOMEM; } else { - envp->ev_crefs = 1; - envp->ev_alloc = envlen; - memcpy(envp->ev_env, parent->envp->ev_env, envlen); + ctcb->group->tg_envsize = envlen; + ctcb->group->tg_envp = envp; + memcpy(envp, ptcb->group->tg_envp, envlen); } } - /* Save the cloned environment in the new TCB */ - - ptcb->envp = envp; sched_unlock(); return ret; } diff --git a/nuttx/sched/env_dupenv.c b/nuttx/sched/env_dupenv.c deleted file mode 100644 index 32bf6a433..000000000 --- a/nuttx/sched/env_dupenv.c +++ /dev/null @@ -1,112 +0,0 @@ -/**************************************************************************** - * eched/env_dupenv.c - * - * Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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 - -#ifndef CONFIG_DISABLE_ENVIRON - -#include -#include - -#include - -#include "os_internal.h" - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: dupenv - * - * Description: - * Copy the internal environment structure of a task. This is the action - * that is performed when a new task is created: The new task has a private, - * exact duplicate of the parent task's environment. - * - * Parameters: - * None - * - * Return Value: - * A pointer to a newly allocated copy of the specified TCB's environment - * structure with reference count equal to one. - * - * Assumptions: - * Not called from an interrupt handler. - * - ****************************************************************************/ - -FAR environ_t *dupenv(FAR _TCB *ptcb) -{ - environ_t *envp = NULL; - - /* Pre-emption must be disabled throughout the following because the - * environment may be shared. - */ - - sched_lock(); - - /* Does the parent task have an environment? */ - - if (ptcb->envp) - { - /* Yes..The parent task has an environment, duplicate it */ - - size_t envlen = ptcb->envp->ev_alloc - envp = (environ_t*)kmalloc(SIZEOF_ENVIRON_T( envlen )); - if (envp) - { - envp->ev_crefs = 1; - envp->ev_alloc = envlen; - memcmp( envp->ev_env, ptcb->envp->ev_env, envlen ); - } - } - - sched_unlock(); - return envp; -} - -#endif /* CONFIG_DISABLE_ENVIRON */ - - - diff --git a/nuttx/sched/env_findvar.c b/nuttx/sched/env_findvar.c index a8e94180c..a744c6c3a 100644 --- a/nuttx/sched/env_findvar.c +++ b/nuttx/sched/env_findvar.c @@ -1,7 +1,7 @@ /**************************************************************************** * sched/env_findvar.c * - * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2009, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -85,7 +85,7 @@ static bool env_cmpname(const char *pszname, const char *peqname) * specified name. * * Parameters: - * envp The environment structre to be searched. + * group The task group containging environment array to be searched. * pname The variable name to find * * Return Value: @@ -97,32 +97,25 @@ static bool env_cmpname(const char *pszname, const char *peqname) * ****************************************************************************/ -FAR char *env_findvar(environ_t *envp, const char *pname) +FAR char *env_findvar(FAR struct task_group_s *group, const char *pname) { - char *ret = NULL; + char *ptr; + char *end; /* Verify input parameters */ - if (envp && pname) - { - char *ptr; - char *end = &envp->ev_env[envp->ev_alloc]; - - /* Search for a name=value string with matching name */ + DEBUGASSERT(group && pname); - for (ptr = envp->ev_env; - ptr < end && !env_cmpname( pname, ptr); - ptr += (strlen(ptr) + 1)); + /* Search for a name=value string with matching name */ - /* Check for success */ + end = &group->tg_envp[group->tg_envsize]; + for (ptr = group->tg_envp; + ptr < end && !env_cmpname(pname, ptr); + ptr += (strlen(ptr) + 1)); - if (ptr < end) - { - ret = ptr; - } - } + /* Check for success */ - return ret; + return (ptr < end) ? ptr : NULL; } #endif /* CONFIG_DISABLE_ENVIRON */ diff --git a/nuttx/sched/env_getenv.c b/nuttx/sched/env_getenv.c index ee8d798b1..4709bc380 100644 --- a/nuttx/sched/env_getenv.c +++ b/nuttx/sched/env_getenv.c @@ -1,7 +1,7 @@ /**************************************************************************** * env_getenv.c * - * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2008, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -77,10 +77,10 @@ FAR char *getenv(const char *name) { - FAR _TCB *rtcb; - FAR environ_t *envp; - FAR char *pvar; - FAR char *pvalue = NULL; + FAR _TCB *rtcb; + FAR struct task_group_s *group; + FAR char *pvar; + FAR char *pvalue = NULL; int ret = OK; /* Verify that a string was passed */ @@ -95,11 +95,11 @@ FAR char *getenv(const char *name) sched_lock(); rtcb = (FAR _TCB*)g_readytorun.head; - envp = rtcb->envp; + group = rtcb->group; /* Check if the variable exists */ - if ( !envp || (pvar = env_findvar(envp, name)) == NULL) + if ( !group || (pvar = env_findvar(group, name)) == NULL) { ret = ENOENT; goto errout_with_lock; diff --git a/nuttx/sched/env_internal.h b/nuttx/sched/env_internal.h index 5370da059..6f1097c0b 100644 --- a/nuttx/sched/env_internal.h +++ b/nuttx/sched/env_internal.h @@ -1,7 +1,7 @@ /**************************************************************************** * sched/env_internal.h * - * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2009, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -50,9 +50,8 @@ #ifdef CONFIG_DISABLE_ENVIRON # define env_dup(ptcb) (0) -# define env_share(ptcb) (0) # define env_release(ptcb) (0) -#endif +#else /**************************************************************************** * Public Type Declarations @@ -62,34 +61,33 @@ * Public Variables ****************************************************************************/ -/**************************************************************************** - * Public Function Prototypes - ****************************************************************************/ - #ifdef __cplusplus #define EXTERN extern "C" -extern "C" { +extern "C" +{ #else #define EXTERN extern #endif -#ifndef CONFIG_DISABLE_ENVIRON -/* functions used by the task/pthread creation and destruction logic */ +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ -EXTERN int env_dup(FAR _TCB *ptcb); -EXTERN int env_share(FAR _TCB *ptcb); -EXTERN int env_release(FAR _TCB *ptcb); +/* Functions used by the task/pthread creation and destruction logic */ -/* functions used internally by the environment handling logic */ +int env_dup(FAR _TCB *ctcb); +void env_release(FAR _TCB *tcb); -EXTERN FAR char *env_findvar(environ_t *envp, const char *pname); -EXTERN int env_removevar(environ_t *envp, char *pvar); -#endif +/* Functions used internally by the environment handling logic */ + +FAR char *env_findvar(FAR struct task_group_s *group, FAR const char *pname); +int env_removevar(FAR struct task_group_s *group, FAR char *pvar); #undef EXTERN #ifdef __cplusplus } #endif +#endif /* !CONFIG_DISABLE_ENVIRON */ #endif /* __SCHED_ENV_INTERNAL_H */ diff --git a/nuttx/sched/env_release.c b/nuttx/sched/env_release.c index 8bc8d2205..4de55c388 100644 --- a/nuttx/sched/env_release.c +++ b/nuttx/sched/env_release.c @@ -1,7 +1,7 @@ /**************************************************************************** - * sched/env_clearenv.c + * sched/env_release.c * - * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2009, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -58,65 +58,45 @@ * Name: env_release * * Description: - * The env_release() function clears the environment of all name-value - * pairs and sets the value of the external variable environ to NULL. + * env_release() is called only from group_leave() when the last member of + * a task group exits. The env_release() function clears the environment + * of all name-value pairs and sets the value of the external variable + * environ to NULL. * * Parameters: - * ptcb Identifies the TCB containing the environment structure + * tcb Identifies the TCB containing the environment structure to be + * released. * * Return Value: - * zero on success + * None * * Assumptions: * Not called from an interrupt handler * ****************************************************************************/ -int env_release(FAR _TCB *ptcb) +void env_release(FAR _TCB *tcb) { - int ret = OK; + FAR struct task_group_s *group; - if (!ptcb) - { - ret = -EINVAL; - } - else - { - FAR environ_t *envp; - - /* Examine the environ data in the TCB. Preemption is disabled because the - * the environment could be shared among threads. - */ - - sched_lock(); - envp = ptcb->envp; - if (ptcb->envp) - { - /* Check the reference count on the environment structure */ + DEBUGASSERT(tcb && tcb->group); + group = tcb->group; - if (envp->ev_crefs <= 1) - { - /* Decrementing the reference count will destroy the environment */ + /* Free any allocate environment strings */ - sched_free(envp); - } - else - { - /* The environment will persist after decrementing the reference - * count */ - - envp->ev_crefs--; - } - - /* In any case, the environment is no longer accessible on this thread */ - - ptcb->envp = NULL; - } + if (group->tg_envp) + { + /* Free the environment */ - sched_unlock(); + sched_free(group->tg_envp); } - return ret; + /* In any event, make sure that all environment-related varialbles in the + * task group structure are reset to initial values. + */ + + group->tg_envsize = 0; + group->tg_envp = NULL; } #endif /* CONFIG_DISABLE_ENVIRON */ diff --git a/nuttx/sched/env_removevar.c b/nuttx/sched/env_removevar.c index e96aa7a37..811e6079e 100644 --- a/nuttx/sched/env_removevar.c +++ b/nuttx/sched/env_removevar.c @@ -59,7 +59,7 @@ * Remove the referenced name=value pair from the environment * * Parameters: - * envp The environment containing the name=value pair + * group The task group with the environment containing the name=value pair * pvar A pointer to the name=value pair in the restroom * * Return Value: @@ -72,42 +72,44 @@ * ****************************************************************************/ -int env_removevar(environ_t *envp, char *pvar) +int env_removevar(FAR struct task_group_s *group, FAR char *pvar) { + FAR char *end; /* Pointer to the end+1 of the environment */ + int alloc; /* Size of the allocated environment */ int ret = ERROR; - if (envp && pvar) - { - /* Verify that the pointer lies within the environment region */ - int alloc = envp->ev_alloc; /* Size of the allocated environment */ - char *end = &envp->ev_env[alloc]; /* Pointer to the end+1 of the environment */ + DEBUGASSERT(group && pvar); - if (pvar >= envp->ev_env && pvar < end) - { - /* Set up for the removal */ + /* Verify that the pointer lies within the environment region */ - int len = strlen(pvar) + 1; /* Length of name=value string to remove */ - char *src = &pvar[len]; /* Address of name=value string after */ - char *dest = pvar; /* Location to move the next string */ - int count = end - src; /* Number of bytes to move (might be zero) */ + alloc = group->tg_envsize; /* Size of the allocated environment */ + end = &group->tg_envp[alloc]; /* Pointer to the end+1 of the environment */ - /* Move all of the environment strings after the removed one 'down.' - * this is inefficient, but robably not high duty. - */ + if (pvar >= group->tg_envp && pvar < end) + { + /* Set up for the removal */ - while (count-- > 0) - { - *dest++ = *src++; - } + int len = strlen(pvar) + 1; /* Length of name=value string to remove */ + char *src = &pvar[len]; /* Address of name=value string after */ + char *dest = pvar; /* Location to move the next string */ + int count = end - src; /* Number of bytes to move (might be zero) */ - /* Then set to the new allocation size. The caller is expected to - * call realloc at some point but we don't do that here because the - * caller may add more stuff to the environment. - */ + /* Move all of the environment strings after the removed one 'down.' + * this is inefficient, but robably not high duty. + */ - envp->ev_alloc -= len; - ret = OK; + while (count-- > 0) + { + *dest++ = *src++; } + + /* Then set to the new allocation size. The caller is expected to + * call realloc at some point but we don't do that here because the + * caller may add more stuff to the environment. + */ + + group->tg_envsize -= len; + ret = OK; } return ret; diff --git a/nuttx/sched/env_setenv.c b/nuttx/sched/env_setenv.c index c186241ef..cfde71604 100644 --- a/nuttx/sched/env_setenv.c +++ b/nuttx/sched/env_setenv.c @@ -1,7 +1,7 @@ /**************************************************************************** * sched/env_setenv.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 * * Redistribution and use in source and binary forms, with or without @@ -83,12 +83,14 @@ * ****************************************************************************/ -int setenv(const char *name, const char *value, int overwrite) +int setenv(FAR const char *name, FAR const char *value, int overwrite) { - FAR _TCB *rtcb; - FAR environ_t *envp; - FAR char *pvar; - int varlen; + FAR _TCB *rtcb; + FAR struct task_group_s *group; + FAR char *pvar; + FAR char *newenvp; + int newsize; + int varlen; int ret = OK; /* Verify input parameter */ @@ -122,14 +124,15 @@ int setenv(const char *name, const char *value, int overwrite) /* Get a reference to the thread-private environ in the TCB.*/ sched_lock(); - rtcb = (FAR _TCB*)g_readytorun.head; - envp = rtcb->envp; + rtcb = (FAR _TCB*)g_readytorun.head; + group = rtcb->group; + DEBUGASSERT(group); - /* Check if the variable alreay exists */ + /* Check if the variable already exists */ - if ( envp && (pvar = env_findvar(envp, name)) != NULL) + if (group->tg_envp && (pvar = env_findvar(group, name)) != NULL) { - /* It does! Do we have permission to overwrite the existing value? */ + /* It does! Do we have permission to overwrite the existing value? */ if (!overwrite) { @@ -144,7 +147,7 @@ int setenv(const char *name, const char *value, int overwrite) * the environment buffer; this will happen below. */ - (void)env_removevar(envp, pvar); + (void)env_removevar(group, pvar); } /* Get the size of the new name=value string. The +2 is for the '=' and for @@ -155,43 +158,39 @@ int setenv(const char *name, const char *value, int overwrite) /* Then allocate or reallocate the environment buffer */ - if (envp) + if (group->tg_envp) { - int alloc = envp->ev_alloc; - environ_t *tmp = (environ_t*)krealloc(envp, SIZEOF_ENVIRON_T(alloc + varlen)); - if (!tmp) + newsize = group->tg_envsize + varlen; + newenvp = (FAR char *)krealloc(group->tg_envp, newsize); + if (!newenvp) { ret = ENOMEM; goto errout_with_lock; } - envp = tmp; - envp->ev_alloc = alloc + varlen; - pvar = &envp->ev_env[alloc]; + pvar = &newenvp[group->tg_envsize]; } else { - envp = (environ_t*)kmalloc(SIZEOF_ENVIRON_T(varlen)); - if (!envp) + newsize = varlen; + newenvp = (FAR char *)kmalloc(varlen); + if (!newenvp) { ret = ENOMEM; goto errout_with_lock; } - envp->ev_crefs = 1; - envp->ev_alloc = varlen; - pvar = envp->ev_env; + pvar = newenvp; } - /* Now, put the new name=value string into the environment buffer */ + /* Save the new buffer and size */ - sprintf(pvar, "%s=%s", name, value); + group->tg_envp = newenvp; + group->tg_envsize = newsize; - /* Save the new environment pointer (it might have changed due to allocation or - * reallocation. - */ + /* Now, put the new name=value string into the environment buffer */ - rtcb->envp = envp; + sprintf(pvar, "%s=%s", name, value); sched_unlock(); return OK; diff --git a/nuttx/sched/env_share.c b/nuttx/sched/env_share.c deleted file mode 100644 index 5f37a0219..000000000 --- a/nuttx/sched/env_share.c +++ /dev/null @@ -1,117 +0,0 @@ -/**************************************************************************** - * sched/env_share.c - * - * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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 - -#ifndef CONFIG_DISABLE_ENVIRON - -#include -#include - -#include "os_internal.h" -#include "env_internal.h" - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: env_share - * - * Description: - * Increment the reference count on the internal environment structure of - * a task. This is the action that is performed when a new pthread is - * created: The new pthread shares the environment with its parent. - * - * Parameters: - * ptcb The new TCB to receive the shared environment. - * - * Return Value: - * A pointer to a specified TCB's environment structure with an incremented - * reference count. - * - * Assumptions: - * Not called from an interrupt handler. - * - ****************************************************************************/ - -int env_share(FAR _TCB *ptcb) -{ - int ret = OK; - if (!ptcb) - { - ret = -EINVAL; - } - else - { - FAR _TCB *parent = (FAR _TCB*)g_readytorun.head; - environ_t *envp = parent->envp; - - /* Pre-emption must be disabled throughout the following because the - * environment is shared. - */ - - sched_lock(); - - /* Does the parent task have an environment? */ - - if (envp) - { - /* Yes.. increment the reference count on the environment */ - - envp->ev_crefs++; - } - - /* Then share the environment */ - - ptcb->envp = envp; - sched_unlock(); - } - - return ret; -} - -#endif /* CONFIG_DISABLE_ENVIRON */ - - - diff --git a/nuttx/sched/env_unsetenv.c b/nuttx/sched/env_unsetenv.c index 52469fac9..8206a4ece 100644 --- a/nuttx/sched/env_unsetenv.c +++ b/nuttx/sched/env_unsetenv.c @@ -1,7 +1,7 @@ /**************************************************************************** * sched/env_unsetenv.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 * * Redistribution and use in source and binary forms, with or without @@ -75,61 +75,47 @@ * ****************************************************************************/ -int unsetenv(const char *name) +int unsetenv(FAR const char *name) { - FAR _TCB *rtcb; - FAR environ_t *envp; - FAR char *pvar; + FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head; + FAR struct task_group_s *group = rtcb->group; + FAR char *pvar; + FAR char *newenvp; + int newsize; int ret = OK; - /* Verify input parameter */ - - if (!name) - { - ret = EINVAL; - goto errout; - } - - /* Get a reference to the thread-private environ in the TCB.*/ - - sched_lock(); - rtcb = (FAR _TCB*)g_readytorun.head; - envp = rtcb->envp; + DEBUGASSERT(name && group); /* Check if the variable exists */ - if ( envp && (pvar = env_findvar(envp, name)) != NULL) + sched_lock(); + if (group && (pvar = env_findvar(group, name)) != NULL) { - int alloc; - environ_t *tmp; - /* It does! Remove the name=value pair from the environment. */ - (void)env_removevar(envp, pvar); + (void)env_removevar(group, pvar); /* Reallocate the new environment buffer */ - alloc = envp->ev_alloc; - tmp = (environ_t*)krealloc(envp, SIZEOF_ENVIRON_T(alloc)); - if (!tmp) + newsize = group->tg_envsize; + newenvp = (FAR char *)krealloc(group->tg_envp, newsize); + if (!newenvp) { - ret = ENOMEM; - goto errout_with_lock; + set_errno(ENOMEM); + ret = ERROR; } + else + { + /* Save the new environment pointer (it might have changed due to + * reallocation. + */ - /* Save the new environment pointer (it might have changed due to reallocation. */ - - rtcb->envp = tmp; + group->tg_envp = newenvp; + } } sched_unlock(); - return OK; - -errout_with_lock: - sched_unlock(); -errout: - errno = ret; - return ERROR; + return ret; } #endif /* CONFIG_DISABLE_ENVIRON */ diff --git a/nuttx/sched/group_create.c b/nuttx/sched/group_create.c index 4612ae8c5..da91fa065 100644 --- a/nuttx/sched/group_create.c +++ b/nuttx/sched/group_create.c @@ -46,6 +46,9 @@ #include +#include "group_internal.h" +#include "env_internal.h" + #ifdef HAVE_TASK_GROUP /***************************************************************************** @@ -97,12 +100,29 @@ int group_allocate(FAR _TCB *tcb) { + int ret; + DEBUGASSERT(tcb && !tcb->group); /* Allocate the group structure and assign it to the TCB */ tcb->group = (FAR struct task_group_s *)kzalloc(sizeof(struct task_group_s)); - return tcb->group ? OK : -ENOMEM; + if (!tcb->group) + { + return -ENOMEM; + } + + /* Duplicate the parent tasks envionment */ + + ret = env_dup(tcb); + if (ret < 0) + { + kfree(tcb->group); + tcb->group = NULL; + return ret; + } + + return OK; } /***************************************************************************** @@ -128,12 +148,12 @@ int group_allocate(FAR _TCB *tcb) int group_initialize(FAR _TCB *tcb) { -#ifdef HAVE_GROUP_MEMBERS FAR struct task_group_s *group; DEBUGASSERT(tcb && tcb->group); group = tcb->group; +#ifdef HAVE_GROUP_MEMBERS /* Allocate space to hold GROUP_INITIAL_MEMBERS members of the group */ group->tg_members = (FAR pid_t *)kmalloc(GROUP_INITIAL_MEMBERS*sizeof(pid_t)); diff --git a/nuttx/sched/group_internal.h b/nuttx/sched/group_internal.h new file mode 100644 index 000000000..aa8476e3c --- /dev/null +++ b/nuttx/sched/group_internal.h @@ -0,0 +1,104 @@ +/**************************************************************************** + * sched/group_internal.h + * + * Copyright (C) 2007-2013 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 __SCHED_GROUP_INERNAL_H +#define __SCHED_GROUP_INERNAL_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include + +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Public Type Definitions + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ +/* Task group data structure management */ + +#ifdef HAVE_TASK_GROUP +int group_allocate(FAR _TCB *tcb); +int group_initialize(FAR _TCB *tcb); +int group_bind(FAR _TCB *tcb); +int group_join(FAR _TCB *tcb); +void group_leave(FAR _TCB *tcb); +#ifndef CONFIG_DISABLE_SIGNALS +int group_signal(FAR _TCB *tcb, FAR siginfo_t *info); +#else +# define group_signal(tcb,info) (0) +#endif +#else +# define group_allocate(tcb) (0) +# define group_initialize(tcb) (0) +# define group_bind(tcb) (0) +# define group_join(tcb) (0) +# define group_leave(tcb) +# define group_signal(tcb,info) (0) +#endif /* HAVE_TASK_GROUP */ + +/* Parent/child data management */ + +#ifdef CONFIG_SCHED_HAVE_PARENT +int task_reparent(pid_t ppid, pid_t chpid); + +#ifdef CONFIG_SCHED_CHILD_STATUS +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_exitchild(FAR _TCB *tcb); +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 +#endif /* CONFIG_SCHED_HAVE_PARENT */ + +#endif /* __SCHED_GROUP_INERNAL_H */ diff --git a/nuttx/sched/group_join.c b/nuttx/sched/group_join.c index 9dcea6599..077c45763 100644 --- a/nuttx/sched/group_join.c +++ b/nuttx/sched/group_join.c @@ -46,7 +46,8 @@ #include -#include "os_internal.h" +#include "group_internal.h" +#include "env_internal.h" #ifdef HAVE_TASK_GROUP @@ -137,7 +138,6 @@ int group_bind(FAR _TCB *tcb) int group_join(FAR _TCB *tcb) { -#ifdef HAVE_GROUP_MEMBERS FAR struct task_group_s *group; DEBUGASSERT(tcb && tcb->group && @@ -147,6 +147,7 @@ int group_join(FAR _TCB *tcb) group = tcb->group; +#ifdef HAVE_GROUP_MEMBERS /* Will we need to extend the size of the array of groups? */ if (group->tg_nmembers >= group->tg_mxmembers) diff --git a/nuttx/sched/group_leave.c b/nuttx/sched/group_leave.c index 223af1556..d5fa9dbaf 100644 --- a/nuttx/sched/group_leave.c +++ b/nuttx/sched/group_leave.c @@ -44,7 +44,8 @@ #include #include -#include "os_internal.h" +#include "group_internal.h" +#include "env_internal.h" #ifdef HAVE_TASK_GROUP @@ -92,7 +93,6 @@ void group_leave(FAR _TCB *tcb) { FAR struct task_group_s *group; - int i; DEBUGASSERT(tcb); @@ -102,6 +102,8 @@ void group_leave(FAR _TCB *tcb) if (group) { #ifdef HAVE_GROUP_MEMBERS + int i; + /* Find the member in the array of members and remove it */ for (i = 0; i < group->tg_nmembers; i++) @@ -142,8 +144,14 @@ void group_leave(FAR _TCB *tcb) /* Release all of the resource contained within the group */ /* Free all un-reaped child exit status */ - task_removechildren(tcb); +#if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS) + task_removechildren(tcb); +#endif + /* Release all shared environment variables */ +#ifndef CONFIG_DISABLE_ENVIRON + env_release(tcb); +#endif /* Release the group container itself */ sched_free(group); @@ -166,8 +174,14 @@ void group_leave(FAR _TCB *tcb) /* Release all of the resource contained within the group */ /* Free all un-reaped child exit status */ +#if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS) task_removechildren(tcb); +#endif + /* Release all shared environment variables */ +#ifndef CONFIG_DISABLE_ENVIRON + env_release(tcb); +#endif /* Release the group container itself */ sched_free(group); diff --git a/nuttx/sched/group_signal.c b/nuttx/sched/group_signal.c index 68912fe00..5020ec436 100644 --- a/nuttx/sched/group_signal.c +++ b/nuttx/sched/group_signal.c @@ -44,6 +44,8 @@ #include #include +#include "os_internal.h" +#include "group_internal.h" #include "sig_internal.h" #if defined(HAVE_TASK_GROUP) && !defined(CONFIG_DISABLE_SIGNALS) diff --git a/nuttx/sched/os_internal.h b/nuttx/sched/os_internal.h index 599be25bb..e3d0fd48f 100644 --- a/nuttx/sched/os_internal.h +++ b/nuttx/sched/os_internal.h @@ -262,6 +262,9 @@ extern const tasklist_t g_tasklisttable[NUM_TASK_STATES]; ****************************************************************************/ int os_bringup(void); +#ifdef CONFIG_SCHED_CHILD_STATUS +void weak_function task_initialize(void); +#endif void task_start(void); int task_schedsetup(FAR _TCB *tcb, int priority, start_t start, main_t main, uint8_t ttype); @@ -269,41 +272,6 @@ 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 -int task_reparent(pid_t ppid, pid_t chpid); - -#ifdef HAVE_TASK_GROUP -int group_allocate(FAR _TCB *tcb); -int group_initialize(FAR _TCB *tcb); -int group_bind(FAR _TCB *tcb); -int group_join(FAR _TCB *tcb); -void group_leave(FAR _TCB *tcb); -#ifndef CONFIG_DISABLE_SIGNALS -int group_signal(FAR _TCB *tcb, FAR siginfo_t *info); -#else -# define group_signal(tcb,info) (0) -#endif -#else -# define group_allocate(tcb) (0) -# define group_initialize(tcb) (0) -# define group_bind(tcb) (0) -# define group_join(tcb) (0) -# define group_leave(tcb) -# define group_signal(tcb,info) (0) -#endif - -#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_exitchild(FAR _TCB *tcb); -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 -#endif - #ifndef CONFIG_CUSTOM_STACK int kernel_thread(FAR const char *name, int priority, int stack_size, main_t entry, FAR const char *argv[]); diff --git a/nuttx/sched/os_start.c b/nuttx/sched/os_start.c index 3aecc7efb..b2551d2a3 100644 --- a/nuttx/sched/os_start.c +++ b/nuttx/sched/os_start.c @@ -1,7 +1,7 @@ /**************************************************************************** * sched/os_start.c * - * Copyright (C) 2007-2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -63,6 +63,9 @@ #include "clock_internal.h" #include "timer_internal.h" #include "irq_internal.h" +#ifdef HAVE_TASK_GROUP +#include "group_internal.h" +#endif /**************************************************************************** * Pre-processor Definitions diff --git a/nuttx/sched/pthread_create.c b/nuttx/sched/pthread_create.c index 89a2feb00..9fd6a4a61 100644 --- a/nuttx/sched/pthread_create.c +++ b/nuttx/sched/pthread_create.c @@ -53,8 +53,8 @@ #include #include "os_internal.h" +#include "group_internal.h" #include "clock_internal.h" -#include "env_internal.h" #include "pthread_internal.h" /**************************************************************************** @@ -305,10 +305,6 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr, goto errout_with_tcb; } - /* Share the parent's envionment */ - - (void)env_share(ptcb); - /* Allocate a detachable structure to support pthread_join logic */ pjoin = (FAR join_t*)kzalloc(sizeof(join_t)); diff --git a/nuttx/sched/sched_releasetcb.c b/nuttx/sched/sched_releasetcb.c index 50505f579..00d4c2c0c 100644 --- a/nuttx/sched/sched_releasetcb.c +++ b/nuttx/sched/sched_releasetcb.c @@ -45,8 +45,8 @@ #include #include "os_internal.h" +#include "group_internal.h" #include "timer_internal.h" -#include "env_internal.h" /************************************************************************ * Private Functions @@ -167,10 +167,6 @@ int sched_releasetcb(FAR _TCB *tcb) ret = sched_releasefiles(tcb); - /* Release environment variables */ - - (void)env_release(tcb); - /* Release this thread's reference to the address environment */ #ifdef CONFIG_ADDRENV diff --git a/nuttx/sched/sched_waitid.c b/nuttx/sched/sched_waitid.c index e47e3c38c..41e488f90 100644 --- a/nuttx/sched/sched_waitid.c +++ b/nuttx/sched/sched_waitid.c @@ -46,6 +46,7 @@ #include #include "os_internal.h" +#include "group_internal.h" #if defined(CONFIG_SCHED_WAITPID) && defined(CONFIG_SCHED_HAVE_PARENT) diff --git a/nuttx/sched/sched_waitpid.c b/nuttx/sched/sched_waitpid.c index 2d0fe2e48..4af7f7ef3 100644 --- a/nuttx/sched/sched_waitpid.c +++ b/nuttx/sched/sched_waitpid.c @@ -47,6 +47,7 @@ #include #include "os_internal.h" +#include "group_internal.h" #ifdef CONFIG_SCHED_WAITPID diff --git a/nuttx/sched/sig_action.c b/nuttx/sched/sig_action.c index b307c1fb6..fe72cc22d 100644 --- a/nuttx/sched/sig_action.c +++ b/nuttx/sched/sig_action.c @@ -46,6 +46,7 @@ #include #include "os_internal.h" +#include "group_internal.h" #include "sig_internal.h" /**************************************************************************** diff --git a/nuttx/sched/task_childstatus.c b/nuttx/sched/task_childstatus.c index aff2bdf3a..c0df3d534 100644 --- a/nuttx/sched/task_childstatus.c +++ b/nuttx/sched/task_childstatus.c @@ -44,6 +44,7 @@ #include #include "os_internal.h" +#include "group_internal.h" #if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS) diff --git a/nuttx/sched/task_create.c b/nuttx/sched/task_create.c index bb309444b..85c0f5e92 100644 --- a/nuttx/sched/task_create.c +++ b/nuttx/sched/task_create.c @@ -48,7 +48,7 @@ #include #include "os_internal.h" -#include "env_internal.h" +#include "group_internal.h" /**************************************************************************** * Definitions @@ -142,10 +142,6 @@ static int thread_create(const char *name, uint8_t ttype, int priority, } #endif - /* Clone the parent's task environment */ - - (void)env_dup(tcb); - /* Allocate the stack for the TCB */ #ifndef CONFIG_CUSTOM_STACK diff --git a/nuttx/sched/task_exithook.c b/nuttx/sched/task_exithook.c index 2d596978f..cbada851a 100644 --- a/nuttx/sched/task_exithook.c +++ b/nuttx/sched/task_exithook.c @@ -49,6 +49,7 @@ #include #include "os_internal.h" +#include "group_internal.h" #include "sig_internal.h" /**************************************************************************** diff --git a/nuttx/sched/task_init.c b/nuttx/sched/task_init.c index 6ae643948..8dfd8b7f6 100644 --- a/nuttx/sched/task_init.c +++ b/nuttx/sched/task_init.c @@ -47,7 +47,7 @@ #include #include "os_internal.h" -#include "env_internal.h" +#include "group_internal.h" /**************************************************************************** * Definitions @@ -145,10 +145,6 @@ int task_init(FAR _TCB *tcb, const char *name, int priority, } #endif - /* Clone the parent's task environment */ - - (void)env_dup(tcb); - /* Configure the user provided stack region */ #ifndef CONFIG_CUSTOM_STACK @@ -162,7 +158,7 @@ int task_init(FAR _TCB *tcb, const char *name, int priority, if (ret < OK) { errcode = -ret; - goto errout_with_env; + goto errout_with_group; } /* Setup to pass parameters to the new task */ @@ -176,14 +172,11 @@ int task_init(FAR _TCB *tcb, const char *name, int priority, if (ret < 0) { errcode = -ret; - goto errout_with_env; + goto errout_with_group; } #endif return OK; -errout_with_env: - env_release(tcb); - errout_with_group: #ifdef HAVE_TASK_GROUP group_leave(tcb); diff --git a/nuttx/sched/task_posixspawn.c b/nuttx/sched/task_posixspawn.c index 7bb9c9a4d..e9ad1fc45 100644 --- a/nuttx/sched/task_posixspawn.c +++ b/nuttx/sched/task_posixspawn.c @@ -54,6 +54,7 @@ #include #include "os_internal.h" +#include "group_internal.h" /**************************************************************************** * Private Types diff --git a/nuttx/sched/task_reparent.c b/nuttx/sched/task_reparent.c index 0b502dcce..1193c9a7f 100644 --- a/nuttx/sched/task_reparent.c +++ b/nuttx/sched/task_reparent.c @@ -42,6 +42,7 @@ #include #include "os_internal.h" +#include "group_internal.h" #ifdef CONFIG_SCHED_HAVE_PARENT diff --git a/nuttx/sched/task_setup.c b/nuttx/sched/task_setup.c index 7675c7481..b66f3cc7c 100644 --- a/nuttx/sched/task_setup.c +++ b/nuttx/sched/task_setup.c @@ -49,6 +49,7 @@ #include #include "os_internal.h" +#include "group_internal.h" /**************************************************************************** * Definitions diff --git a/nuttx/sched/task_vfork.c b/nuttx/sched/task_vfork.c index fece4c596..3f058bdec 100644 --- a/nuttx/sched/task_vfork.c +++ b/nuttx/sched/task_vfork.c @@ -48,7 +48,7 @@ #include #include "os_internal.h" -#include "env_internal.h" +#include "group_internal.h" /**************************************************************************** * Pre-processor Definitions @@ -132,10 +132,6 @@ FAR _TCB *task_vforksetup(start_t retaddr) } #endif - /* Clone the parent's task environment */ - - (void)env_dup(child); - /* Get the priority of the parent task */ #ifdef CONFIG_PRIORITY_INHERITANCE -- cgit v1.2.3 From a1aa13f62853491f8bd96a3dea0f0427fa83ad05 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 26 Jan 2013 17:28:20 +0000 Subject: Don't keep the parent task's task ID in the child task's TCB. Instead, keep the parent task group IN the child task's task group. git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5566 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 4 +- nuttx/include/nuttx/sched.h | 12 +- nuttx/sched/Makefile | 16 +- nuttx/sched/group_childstatus.c | 441 ++++++++++++++++++++++++++++++++++++++++ nuttx/sched/group_create.c | 99 ++++++++- nuttx/sched/group_find.c | 125 ++++++++++++ nuttx/sched/group_internal.h | 71 +++++-- nuttx/sched/group_join.c | 48 ++++- nuttx/sched/group_leave.c | 212 ++++++++++++++----- nuttx/sched/group_signal.c | 40 +++- nuttx/sched/sched_waitid.c | 22 +- nuttx/sched/sched_waitpid.c | 40 ++-- nuttx/sched/sig_action.c | 2 +- nuttx/sched/task_childstatus.c | 440 --------------------------------------- nuttx/sched/task_exithook.c | 175 ++++++++++++---- nuttx/sched/task_reparent.c | 156 +++++++++++++- nuttx/sched/task_setup.c | 32 ++- 17 files changed, 1322 insertions(+), 613 deletions(-) create mode 100644 nuttx/sched/group_childstatus.c create mode 100644 nuttx/sched/group_find.c delete mode 100644 nuttx/sched/task_childstatus.c (limited to 'nuttx/sched') diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index f23a3ed73..858f82819 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -4031,4 +4031,6 @@ members for the parent task group. * include/nuttx/sched.h and sched/env_*.c: Move environment variables into task group structure. - + * sched/: Lots of file changed. Don't keep the parent task's + task ID in the child task's TCB. Instead, keep the parent + task group IN the child task's task group. diff --git a/nuttx/include/nuttx/sched.h b/nuttx/include/nuttx/sched.h index dd33b4570..8ebb7db4c 100644 --- a/nuttx/include/nuttx/sched.h +++ b/nuttx/include/nuttx/sched.h @@ -95,6 +95,7 @@ #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_EXIT_PROCESSING (1 << 5) /* Bit 5: Exitting */ /* Values for struct task_group tg_flags */ @@ -253,6 +254,11 @@ struct dspace_s #ifdef HAVE_TASK_GROUP struct task_group_s { +#ifdef HAVE_GROUP_MEMBERS + struct task_group_s *flink; /* Supports a singly linked list */ + gid_t tg_gid; /* The ID of this task group */ + gid_t tg_pgid; /* The ID of the parent task group */ +#endif uint8_t tg_flags; /* See GROUP_FLAG_* definitions */ /* Group membership ***********************************************************/ @@ -311,12 +317,16 @@ struct _TCB /* Task Management Fields *****************************************************/ pid_t pid; /* This is the ID of the thread */ + #ifdef CONFIG_SCHED_HAVE_PARENT /* Support parent-child relationship */ - pid_t parent; /* This is the ID of the parent thread */ +#ifndef HAVE_GROUP_MEMBERS /* Don't know pids of group members */ + pid_t ppid; /* This is the ID of the parent thread */ #ifndef CONFIG_SCHED_CHILD_STATUS /* Retain child thread status */ uint16_t nchildren; /* This is the number active children */ #endif #endif +#endif /* CONFIG_SCHED_HAVE_PARENT */ + start_t start; /* Thread start function */ entry_t entry; /* Entry Point into the thread */ diff --git a/nuttx/sched/Makefile b/nuttx/sched/Makefile index 6a0b99144..d059152e0 100644 --- a/nuttx/sched/Makefile +++ b/nuttx/sched/Makefile @@ -73,13 +73,6 @@ ifeq ($(CONFIG_PRIORITY_INHERITANCE),y) 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 ifeq ($(CONFIG_SCHED_HAVE_PARENT),y) @@ -87,7 +80,14 @@ SCHED_SRCS += sched_waitid.c sched_wait.c endif endif -GRP_SRCS = group_create.c group_join.c group_leave.c +GRP_SRCS = group_create.c group_join.c group_leave.c group_find.c + +ifeq ($(CONFIG_SCHED_HAVE_PARENT),y) +GRP_SRCS += task_reparent.c +ifeq ($(CONFIG_SCHED_CHILD_STATUS),y) +GRP_SRCS += group_childstatus.c +endif +endif ifneq ($(CONFIG_DISABLE_SIGNALS),y) GRP_SRCS += group_signal.c diff --git a/nuttx/sched/group_childstatus.c b/nuttx/sched/group_childstatus.c new file mode 100644 index 000000000..ef42b6c34 --- /dev/null +++ b/nuttx/sched/group_childstatus.c @@ -0,0 +1,441 @@ +/***************************************************************************** + * sched/group_childstatus.c + * + * Copyright (C) 2013 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 + +#include +#include +#include + +#include "os_internal.h" +#include "group_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: group_dumpchildren + * + * Description: + * Dump all of the children when the part TCB list is modified. + * + * Parameters: + * group - The task group containing the child status. + * + * Return Value: + * None. + * + * Assumptions: + * Called early in initialization. No special precautions are required. + * + *****************************************************************************/ + +#ifdef CONFIG_DEBUG_CHILDSTATUS +static void group_dumpchildren(FAR struct task_group_s *group, + FAR const char *msg) +{ + FAR struct child_status_s *child; + int i; + + dbg("Task group=%p: %s\n", group, msg); + for (i = 0, child = group->tg_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 +# define group_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: group_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 *group_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: group_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 group_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: group_addchild + * + * Description: + * Add a child status structure in the given TCB. + * + * Parameters: + * group - The task group for 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 group_addchild(FAR struct task_group_s *group, + FAR struct child_status_s *child) +{ + /* Add the entry into the TCB list of children */ + + child->flink = group->tg_children; + group->tg_children = child; + + group_dumpchildren(group, "group_addchild"); +} + +/***************************************************************************** + * Name: group_findchild + * + * Description: + * Find a child status structure in the given task group. A reference to + * the child structure is returned, but the child remains the the group's + * list of children. + * + * Parameters: + * group - The ID of the parent task group 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 *group_findchild(FAR struct task_group_s *group, + pid_t pid) +{ + FAR struct child_status_s *child; + + DEBUGASSERT(group); + + /* Find the status structure with the matching PID */ + + for (child = group->tg_children; child; child = child->flink) + { + if (child->ch_pid == pid) + { + return child; + } + } + + return NULL; +} + +/***************************************************************************** + * Name: group_exitchild + * + * Description: + * Search for any child that has exitted. + * + * Parameters: + * tcb - The TCB of the parent task to containing the child status. + * + * Return Value: + * On success, a non-NULL pointer to a child status structure for the + * exited child. NULL is returned if not child has exited. + * + * Assumptions: + * Called during SIGCHLD processing in a safe context. No special precautions + * are required here. + * + *****************************************************************************/ + +FAR struct child_status_s *group_exitchild(FAR struct task_group_s *group) +{ + FAR struct child_status_s *child; + + /* Find the status structure of any child task that has exitted. */ + + for (child = group->tg_children; child; child = child->flink) + { + if ((child->ch_flags & CHILD_FLAG_EXITED) != 0) + { + return child; + } + } + + return NULL; +} + +/***************************************************************************** + * Name: group_removechild + * + * Description: + * Remove one child structure from a task group. The child is removed, but + * is not yet freed. group_freechild must be called in order to free the + * child status structure. + * + * Parameters: + * group - The task group 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 *group_removechild(FAR struct task_group_s *group, + pid_t pid) +{ + FAR struct child_status_s *curr; + FAR struct child_status_s *prev; + + DEBUGASSERT(group); + + /* Find the status structure with the matching PID */ + + for (prev = NULL, curr = group->tg_children; + curr; + prev = curr, curr = curr->flink) + { + if (curr->ch_pid == pid) + { + break; + } + } + + /* Did we find it? If so, remove it from the group. */ + + if (curr) + { + /* Do we remove it from mid-list? Or from the head of the list? */ + + if (prev) + { + prev->flink = curr->flink; + } + else + { + group->tg_children = curr->flink; + } + + curr->flink = NULL; + group_dumpchildren(group, "group_removechild"); + } + + return curr; +} + +/***************************************************************************** + * Name: group_removechildren + * + * Description: + * Remove and free all child structure from the task group. + * + * Parameters: + * group - The task group containing the child status. + * + * Return Value: + * None. + * + * Assumptions: + * Called during task exit processing in a safe context. No special + * precautions are required here. + * + *****************************************************************************/ + +void group_removechildren(FAR struct task_group_s *group) +{ + 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 = group->tg_children; curr; curr = next) + { + next = curr->flink; + group_freechild(curr); + } + + group->tg_children = NULL; + group_dumpchildren(group, "group_removechildren"); +} + +#endif /* CONFIG_SCHED_HAVE_PARENT && CONFIG_SCHED_CHILD_STATUS */ diff --git a/nuttx/sched/group_create.c b/nuttx/sched/group_create.c index da91fa065..768641be1 100644 --- a/nuttx/sched/group_create.c +++ b/nuttx/sched/group_create.c @@ -1,5 +1,5 @@ /***************************************************************************** - * sched/group_allocate.c + * sched/group_create.c * * Copyright (C) 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -65,11 +65,87 @@ /***************************************************************************** * Private Data *****************************************************************************/ +/* This is counter that is used to generate unique task group IDs */ + +#ifdef HAVE_GROUP_MEMBERS +static gid_t g_gidcounter; +#endif + +/***************************************************************************** + * Public Data + *****************************************************************************/ +/* This is the head of a list of all group members */ + +#ifdef HAVE_GROUP_MEMBERS +FAR struct task_group_s *g_grouphead; +#endif /***************************************************************************** * Private Functions *****************************************************************************/ +/***************************************************************************** + * Name: group_assigngid + * + * Description: + * Create a unique group ID. + * + * Parameters: + * tcb - The tcb in need of the task group. + * + * Return Value: + * None + * + * Assumptions: + * Called during task creation in a safe context. No special precautions + * are required here. + * + *****************************************************************************/ + +#ifdef HAVE_GROUP_MEMBERS +void group_assigngid(FAR struct task_group_s *group) +{ + irqstate_t flags; + gid_t gid; + + /* Pre-emption should already be enabled, but lets be paranoid careful */ + + sched_lock(); + + /* Loop until we create a unique ID */ + + for (;;) + { + /* Increment the ID counter. This is global data so be extra paraoid. */ + + flags = irqsave(); + gid = ++g_gidcounter; + + /* Check for overflow */ + + if (gid <= 0) + { + g_gidcounter = 1; + irqrestore(flags); + } + else + { + /* Does a task group with this ID already exist? */ + + irqrestore(flags); + if (group_find(gid) == NULL) + { + /* Now assign this ID to the group and return */ + + group->tg_gid = gid; + sched_unlock(); + return; + } + } + } +} +#endif /* HAVE_GROUP_MEMBERS */ + /***************************************************************************** * Public Functions *****************************************************************************/ @@ -112,6 +188,14 @@ int group_allocate(FAR _TCB *tcb) return -ENOMEM; } + /* Assign the group a unique ID. If g_gidcounter were to wrap before we + * finish with task creation, that would be a problem. + */ + +#ifdef HAVE_GROUP_MEMBERS + group_assigngid(tcb->group); +#endif + /* Duplicate the parent tasks envionment */ ret = env_dup(tcb); @@ -149,6 +233,9 @@ int group_allocate(FAR _TCB *tcb) int group_initialize(FAR _TCB *tcb) { FAR struct task_group_s *group; +#ifdef HAVE_GROUP_MEMBERS + irqstate_t flags; +#endif DEBUGASSERT(tcb && tcb->group); group = tcb->group; @@ -172,9 +259,17 @@ int group_initialize(FAR _TCB *tcb) */ group->tg_mxmembers = GROUP_INITIAL_MEMBERS; /* Number of members in allocation */ + + /* Add the initialized entry to the list of groups */ + + flags = irqsave(); + group->flink = g_grouphead; + g_grouphead = group; + irqrestore(flags); + #endif - group->tg_nmembers = 1; /* Number of members in the group */ + group->tg_nmembers = 1; /* Number of members in the group */ return OK; } diff --git a/nuttx/sched/group_find.c b/nuttx/sched/group_find.c new file mode 100644 index 000000000..eb3989223 --- /dev/null +++ b/nuttx/sched/group_find.c @@ -0,0 +1,125 @@ +/***************************************************************************** + * sched/group_find.c + * + * Copyright (C) 2013 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 + +#include +#include +#include +#include + +#include + +#include "group_internal.h" +#include "env_internal.h" + +#ifdef HAVE_TASK_GROUP + +/***************************************************************************** + * Pre-processor Definitions + *****************************************************************************/ + +/***************************************************************************** + * Private Types + *****************************************************************************/ + +/***************************************************************************** + * Private Data + *****************************************************************************/ + +/***************************************************************************** + * Public Data + *****************************************************************************/ + +/***************************************************************************** + * Private Functions + *****************************************************************************/ + +/***************************************************************************** + * Public Functions + *****************************************************************************/ + +/***************************************************************************** + * Name: group_find + * + * Description: + * Given a group ID, find the group task structure with that ID. IDs are + * used instead of pointers to group structures. This is done because a + * group can disappear at any time leaving a stale pointer; an ID is cleaner + * because if the group disappears, this function will fail gracefully. + * + * Parameters: + * gid - The group ID to find. + * + * Return Value: + * On success, a pointer to the group task structure is returned. This + * function can fail only if there is no group that corresponds to the + * groupd ID. + * + * Assumptions: + * Called during when signally tasks in a safe context. No special + * precautions should be required here. However, extra care is taken when + * accessing the global g_grouphead list. + * + *****************************************************************************/ + +#ifdef HAVE_GROUP_MEMBERS +FAR struct task_group_s *group_find(gid_t gid) +{ + FAR struct task_group_s *group; + irqstate_t flags; + + /* Find the status structure with the matching PID */ + + flags = irqsave(); + for (group = g_grouphead; group; group = group->flink) + { + if (group->tg_gid == gid) + { + irqrestore(flags); + return group; + } + } + + irqrestore(flags); + return NULL; +} +#endif + +#endif /* HAVE_TASK_GROUP */ diff --git a/nuttx/sched/group_internal.h b/nuttx/sched/group_internal.h index aa8476e3c..b78b38453 100644 --- a/nuttx/sched/group_internal.h +++ b/nuttx/sched/group_internal.h @@ -52,37 +52,62 @@ /**************************************************************************** * Pre-processor Definitions ****************************************************************************/ +/* Any negative GID is invalid. */ + +#define INVALID_GROUP_ID (pid_t)-1 +#define IS_INVALID_GID(gid) ((int)(gid) < 0) /**************************************************************************** * Public Type Definitions ****************************************************************************/ /**************************************************************************** - * Global Variables + * Public Data ****************************************************************************/ +/* This is the head of a list of all group members */ + +#ifdef HAVE_GROUP_MEMBERS +extern FAR struct task_group_s *g_grouphead; +#endif + /**************************************************************************** * Public Function Prototypes ****************************************************************************/ /* Task group data structure management */ #ifdef HAVE_TASK_GROUP -int group_allocate(FAR _TCB *tcb); -int group_initialize(FAR _TCB *tcb); -int group_bind(FAR _TCB *tcb); -int group_join(FAR _TCB *tcb); +int group_allocate(FAR _TCB *tcb); +int group_initialize(FAR _TCB *tcb); +int group_bind(FAR _TCB *tcb); +int group_join(FAR _TCB *tcb); void group_leave(FAR _TCB *tcb); + +#ifdef HAVE_GROUP_MEMBERS +FAR struct task_group_s *group_find(gid_t gid); +int group_addmember(FAR struct task_group_s *group, pid_t pid); +int group_removemember(FAR struct task_group_s *group, pid_t pid); +#else +# define group_find(gid) (NULL) +# define group_addmember(group,pid) (0) +# define group_removemember(group,pid) (1) +#endif + #ifndef CONFIG_DISABLE_SIGNALS -int group_signal(FAR _TCB *tcb, FAR siginfo_t *info); +int group_signal(FAR struct task_group_s *group, FAR siginfo_t *info); #else -# define group_signal(tcb,info) (0) +# define group_signal(tcb,info) (0) #endif + #else -# define group_allocate(tcb) (0) -# define group_initialize(tcb) (0) -# define group_bind(tcb) (0) -# define group_join(tcb) (0) -# define group_leave(tcb) -# define group_signal(tcb,info) (0) +# define group_allocate(tcb) (0) +# define group_initialize(tcb) (0) +# define group_bind(tcb) (0) +# define group_join(tcb) (0) +# define group_leave(tcb) +# define group_find(gid) (NULL) +# define group_addmember(group,pid) (0) +# define group_removemember(group,pid) (1) +# define group_signal(tcb,info) (0) #endif /* HAVE_TASK_GROUP */ /* Parent/child data management */ @@ -91,14 +116,18 @@ int group_signal(FAR _TCB *tcb, FAR siginfo_t *info); int task_reparent(pid_t ppid, pid_t chpid); #ifdef CONFIG_SCHED_CHILD_STATUS -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_exitchild(FAR _TCB *tcb); -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 +FAR struct child_status_s *group_allocchild(void); +void group_freechild(FAR struct child_status_s *status); +void group_addchild(FAR struct task_group_s *group, + FAR struct child_status_s *child); +FAR struct child_status_s *group_exitchild(FAR struct task_group_s *group); +FAR struct child_status_s *group_findchild(FAR struct task_group_s *group, + pid_t pid); +FAR struct child_status_s *group_removechild(FAR struct task_group_s *group, + pid_t pid); +void group_removechildren(FAR struct task_group_s *group); + +#endif /* CONFIG_SCHED_CHILD_STATUS */ #endif /* CONFIG_SCHED_HAVE_PARENT */ #endif /* __SCHED_GROUP_INERNAL_H */ diff --git a/nuttx/sched/group_join.c b/nuttx/sched/group_join.c index 077c45763..70319b3a1 100644 --- a/nuttx/sched/group_join.c +++ b/nuttx/sched/group_join.c @@ -139,6 +139,9 @@ int group_bind(FAR _TCB *tcb) int group_join(FAR _TCB *tcb) { FAR struct task_group_s *group; +#ifdef HAVE_GROUP_MEMBERS + int ret; +#endif DEBUGASSERT(tcb && tcb->group && tcb->group->tg_nmembers < UINT8_MAX); @@ -146,8 +149,45 @@ int group_join(FAR _TCB *tcb) /* Get the group from the TCB */ group = tcb->group; - + #ifdef HAVE_GROUP_MEMBERS + /* Add the member to the group */ + + ret = group_addmember(group, tcb->pid); + if (ret < 0) + { + return ret; + } +#endif + + group->tg_nmembers++; + return OK; +} + +/***************************************************************************** + * Name: group_addmember + * + * Description: + * Add a new member to a group. + * + * Parameters: + * group - The task group to add the new member + * pid - The new member + * + * Return Value: + * 0 (OK) on success; a negated errno value on failure. + * + * Assumptions: + * Called during thread creation and during reparenting in a safe context. + * No special precautions are required here. + * + *****************************************************************************/ + +#ifdef HAVE_GROUP_MEMBERS +int group_addmember(FAR struct task_group_s *group, pid_t pid) +{ + DEBUGASSERT(group && group->tg_nmembers < UINT8_MAX); + /* Will we need to extend the size of the array of groups? */ if (group->tg_nmembers >= group->tg_mxmembers) @@ -179,11 +219,9 @@ int group_join(FAR _TCB *tcb) /* Assign this new pid to the group. */ - group->tg_members[group->tg_nmembers] = tcb->pid; -#endif - - group->tg_nmembers++; + group->tg_members[group->tg_nmembers] = pid; return OK; } +#endif /* HAVE_GROUP_MEMBERS */ #endif /* HAVE_TASK_GROUP */ diff --git a/nuttx/sched/group_leave.c b/nuttx/sched/group_leave.c index d5fa9dbaf..add424185 100644 --- a/nuttx/sched/group_leave.c +++ b/nuttx/sched/group_leave.c @@ -65,6 +65,65 @@ * Private Functions *****************************************************************************/ +/***************************************************************************** + * Name: group_remove + * + * Description: + * Remove a group from the list of groups. + * + * Parameters: + * group - The group to be removed. + * + * Return Value: + * None. + * + * Assumptions: + * Called during task deletion in a safe context. No special precautions + * are required here. + * + *****************************************************************************/ + +#ifdef HAVE_GROUP_MEMBERS +void group_remove(FAR struct task_group_s *group) +{ + FAR struct task_group_s *curr; + FAR struct task_group_s *prev; + irqstate_t flags; + + /* Let's be especially careful while access the global task group list. + * This is probably un-necessary. + */ + + flags = irqsave(); + + /* Find the task group structure */ + + for (prev = NULL, curr = g_grouphead; + curr && curr != group; + prev = curr, curr = curr->flink); + + /* Did we find it? If so, remove it from the list. */ + + if (curr) + { + /* Do we remove it from mid-list? Or from the head of the list? */ + + if (prev) + { + prev->flink = curr->flink; + } + else + { + g_grouphead = curr->flink; + } + + curr->flink = NULL; + } + + irqrestore(flags); +} +#endif + /***************************************************************************** * Public Functions *****************************************************************************/ @@ -90,6 +149,8 @@ * *****************************************************************************/ +#ifdef HAVE_GROUP_MEMBERS + void group_leave(FAR _TCB *tcb) { FAR struct task_group_s *group; @@ -101,64 +162,57 @@ void group_leave(FAR _TCB *tcb) group = tcb->group; if (group) { -#ifdef HAVE_GROUP_MEMBERS - int i; + /* Remove the member from group */ - /* Find the member in the array of members and remove it */ + int ret = group_removemember(group, tcb->pid); + DEBUGASSERT(ret >= 0); - for (i = 0; i < group->tg_nmembers; i++) - { - /* Does this member have the matching pid */ - - if (group->tg_members[i] == tcb->pid) - { - /* Yes.. break out of the loop. We don't do the actual - * removal here, instead we re-test i and do the adjustments - * outside of the loop. We do this because we want the - * DEBUGASSERT to work properly. - */ - - break; - } - } - - /* Now, test if we found the task in the array of members. */ + /* Is the group now empty? */ - DEBUGASSERT(i < group->tg_nmembers); - if (i < group->tg_nmembers) + if (ret == 0) { - /* Yes..Is this the last member of the group? */ - - if (group->tg_nmembers > 1) - { - /* No.. remove the member from the array of members */ - - group->tg_members[i] = group->tg_members[group->tg_nmembers - 1]; - group->tg_nmembers--; - } - - /* Yes.. that was the last member remaining in the group */ - - else - { - /* Release all of the resource contained within the group */ - /* Free all un-reaped child exit status */ + /* Release all of the resource contained within the group */ + /* Free all un-reaped child exit status */ #if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS) - task_removechildren(tcb); + group_removechildren(tcb->group); #endif - /* Release all shared environment variables */ + /* Release all shared environment variables */ #ifndef CONFIG_DISABLE_ENVIRON - env_release(tcb); + env_release(tcb); #endif - /* Release the group container itself */ + /* Remove the group from the list of groups */ + + group_remove(group); + + /* Release the group container itself */ - sched_free(group); - } + sched_free(group); } -#else - /* Yes..Is this the last member of the group? */ + + /* In any event, we can detach the group from the TCB so that we won't + * do this again. + */ + + tcb->group = NULL; + } +} + +#else /* HAVE_GROUP_MEMBERS */ + +void group_leave(FAR _TCB *tcb) +{ + FAR struct task_group_s *group; + + DEBUGASSERT(tcb); + + /* Make sure that we have a group */ + + group = tcb->group; + if (group) + { + /* Yes, we have a group.. Is this the last member of the group? */ if (group->tg_nmembers > 1) { @@ -175,7 +229,7 @@ void group_leave(FAR _TCB *tcb) /* Free all un-reaped child exit status */ #if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS) - task_removechildren(tcb); + group_removechildren(tcb->group); #endif /* Release all shared environment variables */ @@ -186,7 +240,6 @@ void group_leave(FAR _TCB *tcb) sched_free(group); } -#endif /* In any event, we can detach the group from the TCB so we won't do * this again. @@ -196,4 +249,67 @@ void group_leave(FAR _TCB *tcb) } } +#endif /* HAVE_GROUP_MEMBERS */ + +/***************************************************************************** + * Name: group_removemember + * + * Description: + * Remove a member from a group. + * + * Parameters: + * group - The group from which to remove the member. + * pid - The member to be removed. + * + * Return Value: + * On success, returns the number of members remaining in the group (>=0). + * Can fail only if the member is not found in the group. On failure, + * returns -ENOENT + * + * Assumptions: + * Called during task deletion and also from the reparenting logic, both + * in a safe context. No special precautions are required here. + * + *****************************************************************************/ + +#ifdef HAVE_GROUP_MEMBERS +int group_removemember(FAR struct task_group_s *group, pid_t pid) +{ + int i; + + DEBUGASSERT(group); + + /* Find the member in the array of members and remove it */ + + for (i = 0; i < group->tg_nmembers; i++) + { + /* Does this member have the matching pid */ + + if (group->tg_members[i] == pid) + { + /* Yes.. break out of the loop. We don't do the actual + * removal here, instead we re-test i and do the adjustments + * outside of the loop. We do this because we want the + * DEBUGASSERT to work properly. + */ + + break; + } + } + + /* Now, test if we found the task in the array of members. */ + + if (i < group->tg_nmembers) + { + /* Remove the member from the array of members */ + + group->tg_members[i] = group->tg_members[group->tg_nmembers - 1]; + group->tg_nmembers--; + return group->tg_nmembers; + } + + return -ENOENT; +} +#endif /* HAVE_GROUP_MEMBERS */ + #endif /* HAVE_TASK_GROUP */ diff --git a/nuttx/sched/group_signal.c b/nuttx/sched/group_signal.c index 5020ec436..009ab7a55 100644 --- a/nuttx/sched/group_signal.c +++ b/nuttx/sched/group_signal.c @@ -42,6 +42,7 @@ #include #include #include +#include #include #include "os_internal.h" @@ -74,10 +75,10 @@ * Name: group_signal * * Description: - * Send a signal to every member of the group to which task belongs. + * Send a signal to every member of the group. * * Parameters: - * tcb - The tcb of one task in the task group that needs to be signalled. + * group - The task group that needs to be signalled. * * Return Value: * 0 (OK) on success; a negated errno value on failure. @@ -88,15 +89,13 @@ * *****************************************************************************/ -int group_signal(FAR _TCB *tcb, FAR siginfo_t *info) +int group_signal(FAR struct task_group_s *group, FAR siginfo_t *info) { #ifdef HAVE_GROUP_MEMBERS - FAR struct task_group_s *group; FAR _TCB *gtcb; int i; - DEBUGASSERT(tcb && tcb->group && info); - group = tcb->group; + DEBUGASSERT(group && info); /* Make sure that pre-emption is disabled to that we signal all of teh * members of the group before any of them actually run. @@ -130,8 +129,35 @@ int group_signal(FAR _TCB *tcb, FAR siginfo_t *info) sched_unlock(); return OK; #else - return sig_received(tcb, info); + return -ENOSYS; #endif } +/***************************************************************************** + * Name: group_signalmember + * + * Description: + * Send a signal to every member of the group to which task belongs. + * + * Parameters: + * tcb - The tcb of one task in the task group that needs to be signalled. + * + * Return Value: + * 0 (OK) on success; a negated errno value on failure. + * + * Assumptions: + * Called during task terminatino in a safe context. No special precautions + * are required here. + * + *****************************************************************************/ + +int group_signalmember(FAR _TCB *tcb, FAR siginfo_t *info) +{ +#ifdef HAVE_GROUP_MEMBERS + DEBUGASSERT(tcb); + return group_signal(tcb->group, info); +#else + return sig_received(tcb, info); +#endif +} #endif /* HAVE_TASK_GROUP && !CONFIG_DISABLE_SIGNALS */ diff --git a/nuttx/sched/sched_waitid.c b/nuttx/sched/sched_waitid.c index 41e488f90..9c24189c4 100644 --- a/nuttx/sched/sched_waitid.c +++ b/nuttx/sched/sched_waitid.c @@ -79,8 +79,8 @@ static void exited_child(FAR _TCB *rtcb, FAR struct child_status_s *child, /* Discard the child entry */ - (void)task_removechild(rtcb, child->ch_pid); - task_freechild(child); + (void)group_removechild(rtcb->group, child->ch_pid); + group_freechild(child); } #endif @@ -212,7 +212,11 @@ int waitid(idtype_t idtype, id_t id, FAR siginfo_t *info, int options) /* Get the TCB corresponding to this PID and make sure it is our child. */ ctcb = sched_gettcb((pid_t)id); - if (!ctcb || ctcb->parent != rtcb->pid) +#ifdef HAVE_GROUP_MEMBERS + if (!ctcb || ctcb->group->tg_pgid != rtcb->group->tg_gid) +#else + if (!ctcb || ctcb->ppid != rtcb->pid) +#endif { err = ECHILD; goto errout_with_errno; @@ -224,7 +228,7 @@ int waitid(idtype_t idtype, id_t id, FAR siginfo_t *info, int options) { /* Check if this specific pid has allocated child status? */ - if (task_findchild(rtcb, (pid_t)id) == NULL) + if (group_findchild(rtcb->group, (pid_t)id) == NULL) { /* This specific pid is not a child */ @@ -246,7 +250,11 @@ int waitid(idtype_t idtype, id_t id, FAR siginfo_t *info, int options) /* Get the TCB corresponding to this PID and make sure it is our child. */ ctcb = sched_gettcb((pid_t)id); - if (!ctcb || ctcb->parent != rtcb->pid) +#ifdef HAVE_GROUP_MEMBERS + if (!ctcb || ctcb->group->tg_pgid != rtcb->group->tg_gid) +#else + if (!ctcb || ctcb->ppid != rtcb->pid) +#endif { err = ECHILD; goto errout_with_errno; @@ -270,7 +278,7 @@ int waitid(idtype_t idtype, id_t id, FAR siginfo_t *info, int options) { /* We are waiting for any child to exit */ - if (retains && (child = task_exitchild(rtcb)) != NULL) + if (retains && (child = group_exitchild(rtcb->group)) != NULL) { /* A child has exited. Apparently we missed the signal. * Return the exit status and break out of the loop. @@ -287,7 +295,7 @@ int waitid(idtype_t idtype, id_t id, FAR siginfo_t *info, int options) { /* Yes ... Get the current status of the child task. */ - child = task_findchild(rtcb, (pid_t)id); + child = group_findchild(rtcb->group, (pid_t)id); DEBUGASSERT(child); /* Did the child exit? */ diff --git a/nuttx/sched/sched_waitpid.c b/nuttx/sched/sched_waitpid.c index 4af7f7ef3..0285c2673 100644 --- a/nuttx/sched/sched_waitpid.c +++ b/nuttx/sched/sched_waitpid.c @@ -172,16 +172,12 @@ * * Assumptions: * - *****************************************************************************/ - -/*************************************************************************** - * NOTE: This is a partially functional, experimental version of waitpid() + * Compatibility + * If there is no SIGCHLD signal supported (CONFIG_SCHED_HAVE_PARENT not + * defined), then waitpid() is still available, but does not obey the + * restriction that the pid be a child of the caller. * - * If there is no SIGCHLD signal supported (CONFIG_SCHED_HAVE_PARENT not - * defined), then waitpid() is still available, but does not obey the - * restriction that the pid be a child of the caller. - * - ***************************************************************************/ + *****************************************************************************/ #ifndef CONFIG_SCHED_HAVE_PARENT pid_t waitpid(pid_t pid, int *stat_loc, int options) @@ -325,7 +321,11 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options) /* Get the TCB corresponding to this PID and make sure it is our child. */ ctcb = sched_gettcb(pid); - if (!ctcb || ctcb->parent != rtcb->pid) +#ifdef HAVE_GROUP_MEMBERS + if (!ctcb || ctcb->group->tg_pgid != rtcb->group->tg_gid) +#else + if (!ctcb || ctcb->ppid != rtcb->pid) +#endif { err = ECHILD; goto errout_with_errno; @@ -337,7 +337,7 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options) { /* Check if this specific pid has allocated child status? */ - if (task_findchild(rtcb, pid) == NULL) + if (group_findchild(rtcb->group, pid) == NULL) { err = ECHILD; goto errout_with_errno; @@ -357,7 +357,11 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options) /* Get the TCB corresponding to this PID and make sure it is our child. */ ctcb = sched_gettcb(pid); - if (!ctcb || ctcb->parent != rtcb->pid) +#ifdef HAVE_GROUP_MEMBERS + if (!ctcb || ctcb->group->tg_pgid != rtcb->group->tg_gid) +#else + if (!ctcb || ctcb->ppid != rtcb->pid) +#endif { err = ECHILD; goto errout_with_errno; @@ -383,7 +387,7 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options) */ DEBUGASSERT(!retains || rtcb->group->tg_children); - if (retains && (child = task_exitchild(rtcb)) != NULL) + if (retains && (child = group_exitchild(rtcb->group)) != NULL) { /* A child has exited. Apparently we missed the signal. * Return the saved exit status. @@ -395,8 +399,8 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options) /* Discard the child entry and break out of the loop */ - (void)task_removechild(rtcb, child->ch_pid); - task_freechild(child); + (void)group_removechild(rtcb->group, child->ch_pid); + group_freechild(child); break; } } @@ -407,7 +411,7 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options) { /* Get the current status of the child task. */ - child = task_findchild(rtcb, pid); + child = group_findchild(rtcb->group, pid); DEBUGASSERT(child); /* Did the child exit? */ @@ -420,8 +424,8 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options) /* Discard the child entry and break out of the loop */ - (void)task_removechild(rtcb, pid); - task_freechild(child); + (void)group_removechild(rtcb->group, pid); + group_freechild(child); break; } } diff --git a/nuttx/sched/sig_action.c b/nuttx/sched/sig_action.c index fe72cc22d..5c00179dc 100644 --- a/nuttx/sched/sig_action.c +++ b/nuttx/sched/sig_action.c @@ -242,7 +242,7 @@ int sigaction(int signo, FAR const struct sigaction *act, FAR struct sigaction * /* Free all pending exit status */ - task_removechildren(rtcb); + group_removechildren(rtcb->group); irqrestore(flags); } #endif diff --git a/nuttx/sched/task_childstatus.c b/nuttx/sched/task_childstatus.c deleted file mode 100644 index c0df3d534..000000000 --- a/nuttx/sched/task_childstatus.c +++ /dev/null @@ -1,440 +0,0 @@ -/***************************************************************************** - * sched/task_childstatus.c - * - * Copyright (C) 2013 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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 - -#include -#include -#include - -#include "os_internal.h" -#include "group_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; - FAR struct task_group_s *group = tcb->group; - int i; - - dbg("Parent TCB=%p group=%p: %s\n", tcb, group, msg); - for (i = 0, child = group->tg_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 -# define 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) -{ - FAR struct task_group_s *group = tcb->group; - - /* Add the entry into the TCB list of children */ - - child->flink = group->tg_children; - group->tg_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 task_group_s *group = tcb->group; - FAR struct child_status_s *child; - - /* Find the status structure with the matching PID */ - - for (child = group->tg_children; child; child = child->flink) - { - if (child->ch_pid == pid) - { - return child; - } - } - - return NULL; -} - -/***************************************************************************** - * Name: task_exitchild - * - * Description: - * Search for any child that has exitted. - * - * Parameters: - * tcb - The TCB of the parent task to containing the child status. - * - * Return Value: - * On success, a non-NULL pointer to a child status structure for the - * exited child. NULL is returned if not child has exited. - * - * Assumptions: - * Called during SIGCHLD processing in a safe context. No special precautions - * are required here. - * - *****************************************************************************/ - -FAR struct child_status_s *task_exitchild(FAR _TCB *tcb) -{ - FAR struct task_group_s *group = tcb->group; - FAR struct child_status_s *child; - - /* Find the status structure of any child task that has exitted. */ - - for (child = group->tg_children; child; child = child->flink) - { - if ((child->ch_flags & CHILD_FLAG_EXITED) != 0) - { - 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 task_group_s *group = tcb->group; - FAR struct child_status_s *curr; - FAR struct child_status_s *prev; - - /* Find the status structure with the matching PID */ - - for (prev = NULL, curr = group->tg_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 - { - group->tg_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 task_group_s *group = tcb->group; - 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 = group->tg_children; curr; curr = next) - { - next = curr->flink; - task_freechild(curr); - } - - group->tg_children = NULL; - task_dumpchildren(tcb, "task_removechildren"); -} - -#endif /* CONFIG_SCHED_HAVE_PARENT && CONFIG_SCHED_CHILD_STATUS */ diff --git a/nuttx/sched/task_exithook.c b/nuttx/sched/task_exithook.c index cbada851a..3fdf08bf7 100644 --- a/nuttx/sched/task_exithook.c +++ b/nuttx/sched/task_exithook.c @@ -104,10 +104,7 @@ static inline void task_atexit(FAR _TCB *tcb) (*tcb->atexitfunc[index])(); - /* Nullify the atexit function. task_exithook may be called more then - * once in most task exit scenarios. Nullifying the atext function - * pointer will assure that the callback is performed only once. - */ + /* Nullify the atexit function to prevent its reuse. */ tcb->atexitfunc[index] = NULL; } @@ -120,10 +117,7 @@ static inline void task_atexit(FAR _TCB *tcb) (*tcb->atexitfunc)(); - /* Nullify the atexit function. task_exithook may be called more then - * once in most task exit scenarios. Nullifying the atext function - * pointer will assure that the callback is performed only once. - */ + /* Nullify the atexit function to prevent its reuse. */ tcb->atexitfunc = NULL; } @@ -161,10 +155,7 @@ static inline void task_onexit(FAR _TCB *tcb, int status) (*tcb->onexitfunc[index])(status, tcb->onexitarg[index]); - /* Nullify the on_exit function. task_exithook may be called more then - * once in most task exit scenarios. Nullifying the atext function - * pointer will assure that the callback is performed only once. - */ + /* Nullify the on_exit function to prevent its reuse. */ tcb->onexitfunc[index] = NULL; } @@ -176,10 +167,7 @@ static inline void task_onexit(FAR _TCB *tcb, int status) (*tcb->onexitfunc)(status, tcb->onexitarg); - /* Nullify the on_exit function. task_exithook may be called more then - * once in most task exit scenarios. Nullifying the on_exit function - * pointer will assure that the callback is performed only once. - */ + /* Nullify the on_exit function to prevent its reuse. */ tcb->onexitfunc = NULL; } @@ -198,20 +186,96 @@ static inline void task_onexit(FAR _TCB *tcb, int status) ****************************************************************************/ #ifdef CONFIG_SCHED_HAVE_PARENT +#ifdef HAVE_GROUP_MEMBERS +static inline void task_sigchild(gid_t pgid, FAR _TCB *ctcb, int status) +{ + FAR struct task_group_s *chgrp = ctcb->group; + FAR struct task_group_s *pgrp; + siginfo_t info; + + DEBUGASSERT(chgrp); + + /* Only the final exiting thread in a task group should generate SIGCHLD. */ + + if (chgrp->tg_nmembers == 1) + { + /* Get the parent task group */ + + pgrp = group_find(chgrp->tg_pgid); + + /* It is possible that all of the members of the parent task group + * have exited. This would not be an error. In this case, the + * child task group has been orphaned. + */ + + if (!pgrp) + { + /* Set the task group ID to an invalid group ID. The dead parent + * task group ID could get reused some time in the future. + */ + + chgrp->tg_pgid = INVALID_GROUP_ID; + return; + } + +#ifdef CONFIG_SCHED_CHILD_STATUS + /* Check if the parent task group has suppressed retention of child exit + * status information. Only 'tasks' report exit status, not pthreads. + * pthreads have a different mechanism. + */ + + if ((pgrp->tg_flags & GROUP_FLAG_NOCLDWAIT) == 0) + { + FAR struct child_status_s *child; + + /* No.. Find the exit status entry for this task in the parent TCB */ + + child = group_findchild(pgrp, 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; + } + } +#endif /* CONFIG_SCHED_CHILD_STATUS */ + + /* 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 = ctcb->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)group_signal(pgrp, &info); + } +} + +#else /* HAVE_GROUP_MEMBERS */ + static inline void task_sigchild(FAR _TCB *ptcb, FAR _TCB *ctcb, int status) { siginfo_t info; - /* Only the final exiting thread in a task group should generate SIGCHLD. - * If task groups are not supported then we will report SIGCHLD when the - * task exits. + /* If task groups are not supported then we will report SIGCHLD when the + * task exits. Unfortunately, there could still be threads in the group + * that are still running. */ -#ifdef CONFIG_SCHED_CHILD_STATUS - if (ctcb->group->tg_nmembers == 1) -#else if ((ctcb->flags & TCB_FLAG_TTYPE_MASK) == TCB_FLAG_TTYPE_TASK) -#endif { #ifdef CONFIG_SCHED_CHILD_STATUS /* Check if the parent task group has suppressed retention of child exit @@ -225,7 +289,7 @@ static inline void task_sigchild(FAR _TCB *ptcb, FAR _TCB *ctcb, int status) /* No.. Find the exit status entry for this task in the parent TCB */ - child = task_findchild(ptcb, getpid()); + child = group_findchild(ptcb->group, getpid()); DEBUGASSERT(child); if (child) { @@ -238,12 +302,15 @@ static inline void task_sigchild(FAR _TCB *ptcb, FAR _TCB *ctcb, int status) child->ch_status = status; } } -#else + +#else /* CONFIG_SCHED_CHILD_STATUS */ + /* Decrement the number of children from this parent */ DEBUGASSERT(ptcb->nchildren > 0); ptcb->nchildren--; -#endif + +#endif /* CONFIG_SCHED_CHILD_STATUS */ /* 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 @@ -260,16 +327,16 @@ static inline void task_sigchild(FAR _TCB *ptcb, FAR _TCB *ctcb, int status) * can provide the correct si_code value with the signal. */ -#ifdef HAVE_GROUP_MEMBERS - (void)group_signal(ptcb, &info); -#else (void)sig_received(ptcb, &info); -#endif } } -#else -# define task_sigchild(ptct,ctcb,status) -#endif + +#endif /* HAVE_GROUP_MEMBERS */ +#else /* CONFIG_SCHED_HAVE_PARENT */ + +# define task_sigchild(x,ctcb,status) + +#endif /* CONFIG_SCHED_HAVE_PARENT */ /**************************************************************************** * Name: task_leavegroup @@ -282,6 +349,18 @@ static inline void task_sigchild(FAR _TCB *ptcb, FAR _TCB *ctcb, int status) #ifdef CONFIG_SCHED_HAVE_PARENT static inline void task_leavegroup(FAR _TCB *ctcb, int status) { +#ifdef HAVE_GROUP_MEMBERS + DEBUGASSERT(ctcb && ctcb->group); + + /* Keep things stationary throughout the following */ + + sched_lock(); + + /* Send SIGCHLD to all members of the parent's task group */ + + task_sigchild(ctcb->group->tg_pgid, ctcb, status); + sched_unlock(); +#else FAR _TCB *ptcb; /* Keep things stationary throughout the following */ @@ -289,12 +368,12 @@ static inline void task_leavegroup(FAR _TCB *ctcb, int status) sched_lock(); /* Get the TCB of the receiving, parent task. We do this early to - * handle multiple calls to task_leavegroup. ctcb->parent is set to an + * handle multiple calls to task_leavegroup. ctcb->ppid is set to an * invalid value below and the following call will fail if we are * called again. */ - ptcb = sched_gettcb(ctcb->parent); + ptcb = sched_gettcb(ctcb->ppid); if (!ptcb) { /* The parent no longer exists... bail */ @@ -307,14 +386,11 @@ static inline void task_leavegroup(FAR _TCB *ctcb, int status) task_sigchild(ptcb, ctcb, status); - /* 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 and all will be well. - */ + /* Forget who our parent was */ - ctcb->parent = INVALID_PROCESS_ID; + ctcb->ppid = INVALID_PROCESS_ID; sched_unlock(); +#endif } #else # define task_leavegroup(ctcb,status) @@ -385,6 +461,16 @@ static inline void task_exitwakeup(FAR _TCB *tcb, int status) void task_exithook(FAR _TCB *tcb, int status) { + /* Under certain conditions, task_exithook() can be called multiple times. + * A bit in the TCB was set the first time this function was called. If + * that bit is set, then just ext doing nothing more.. + */ + + if ((tcb->flags & TCB_FLAG_EXIT_PROCESSING) != 0) + { + return; + } + /* If exit function(s) were registered, call them now before we do any un- * initialization. NOTE: In the case of task_delete(), the exit function * will *not* be called on the thread execution of the task being deleted! @@ -433,4 +519,11 @@ void task_exithook(FAR _TCB *tcb, int status) #ifndef CONFIG_DISABLE_SIGNALS sig_cleanup(tcb); /* Deallocate Signal lists */ #endif + + /* This function can be re-entered in certain cases. Set a flag + * bit in the TCB to not that we have already completed this exit + * processing. + */ + + tcb->flags |= TCB_FLAG_EXIT_PROCESSING; } diff --git a/nuttx/sched/task_reparent.c b/nuttx/sched/task_reparent.c index 1193c9a7f..5bb62893f 100644 --- a/nuttx/sched/task_reparent.c +++ b/nuttx/sched/task_reparent.c @@ -70,6 +70,141 @@ * *****************************************************************************/ +#ifdef HAVE_GROUP_MEMBERS +int task_reparent(pid_t ppid, pid_t chpid) +{ +#ifdef CONFIG_SCHED_CHILD_STATUS + FAR struct child_status_s *child; +#endif + FAR struct task_group_s *chgrp; + FAR struct task_group_s *ogrp; + FAR struct task_group_s *pgrp; + _TCB *tcb; + gid_t ogid; + gid_t pgid; + 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 task group */ + + tcb = sched_gettcb(chpid); + if (!tcb) + { + ret = -ECHILD; + goto errout_with_ints; + } + + DEBUGASSERT(tcb->group); + chgrp = tcb->group; + + /* Get the GID of the old parent task's task group (ogid) */ + + ogid = chgrp->tg_pgid; + + /* Get the old parent task's task group (ogrp) */ + + ogrp = group_find(ogid); + if (!ogrp) + { + 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) + { + /* Get the grandparent task's task group (pgrp) */ + + pgid = ogrp->tg_pgid; + pgrp = group_find(pgid); + } + else + { + /* Get the new parent task's task group (pgrp) */ + + tcb = sched_gettcb(ppid); + if (!tcb) + { + ret = -ESRCH; + goto errout_with_ints; + } + + pgrp = tcb->group; + pgid = pgrp->tg_gid; + } + + if (!pgrp) + { + ret = -ESRCH; + goto errout_with_ints; + } + + /* Then reparent the child. Notice that we don't actually change the + * parent of the task. Rather, we change the parent task group for + * all members of the child's task group. + */ + + chgrp->tg_pgid = pgid; + +#ifdef CONFIG_SCHED_CHILD_STATUS + /* Remove the child status entry from old parent task group */ + + child = group_removechild(ogrp, chpid); + if (child) + { + /* Has the new parent's task group supressed child exit status? */ + + if ((pgrp->tg_flags && GROUP_FLAG_NOCLDWAIT) == 0) + { + /* No.. Add the child status entry to the new parent's task group */ + + group_addchild(pgrp, child); + } + else + { + /* Yes.. Discard the child status entry */ + + group_freechild(child); + } + + /* Either case is a success */ + + ret = OK; + } + else + { + /* This would not be an error if the original parent's task group has + * suppressed child exit status. + */ + + ret = ((ogrp->tg_flags && GROUP_FLAG_NOCLDWAIT) == 0) ? -ENOENT : OK; + } + +#else /* CONFIG_SCHED_CHILD_STATUS */ + + 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 /* CONFIG_SCHED_CHILD_STATUS */ + +errout_with_ints: + irqrestore(flags); + return ret; +} +#else int task_reparent(pid_t ppid, pid_t chpid) { #ifdef CONFIG_SCHED_CHILD_STATUS @@ -99,7 +234,7 @@ int task_reparent(pid_t ppid, pid_t chpid) /* Get the PID of the child task's parent (opid) */ - opid = chtcb->parent; + opid = chtcb->ppid; /* Get the TCB of the child task's parent (otcb) */ @@ -117,7 +252,7 @@ int task_reparent(pid_t ppid, pid_t chpid) if (ppid == 0) { - ppid = otcb->parent; + ppid = otcb->ppid; } /* Get the new parent task's TCB (ptcb) */ @@ -131,12 +266,12 @@ int task_reparent(pid_t ppid, pid_t chpid) /* Then reparent the child */ - chtcb->parent = ppid; /* The task specified by ppid is the new parent */ + chtcb->ppid = 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); + child = group_removechild(otcb->group, chpid); if (child) { /* Has the new parent's task group supressed child exit status? */ @@ -145,13 +280,13 @@ int task_reparent(pid_t ppid, pid_t chpid) { /* No.. Add the child status entry to the new parent's task group */ - task_addchild(ptcb, child); + group_addchild(ptcb->group, child); } else { /* Yes.. Discard the child status entry */ - task_freechild(child); + group_freechild(child); } /* Either case is a success */ @@ -166,17 +301,20 @@ int task_reparent(pid_t ppid, pid_t chpid) ret = ((otcb->group->tg_flags && GROUP_FLAG_NOCLDWAIT) == 0) ? -ENOENT : OK; } -#else + +#else /* CONFIG_SCHED_CHILD_STATUS */ + 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 + +#endif /* CONFIG_SCHED_CHILD_STATUS */ errout_with_ints: irqrestore(flags); return ret; } - +#endif #endif /* CONFIG_SCHED_HAVE_PARENT */ diff --git a/nuttx/sched/task_setup.c b/nuttx/sched/task_setup.c index b66f3cc7c..b770d46e6 100644 --- a/nuttx/sched/task_setup.c +++ b/nuttx/sched/task_setup.c @@ -172,12 +172,36 @@ static inline void task_saveparent(FAR _TCB *tcb, uint8_t ttype) { FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head; +#if defined(HAVE_GROUP_MEMBERS) || defined(CONFIG_SCHED_CHILD_STATUS) + DEBUGASSERT(tcb && tcb->group && rtcb->group); +#else +#endif + +#ifdef HAVE_GROUP_MEMBERS + /* Save the ID of the parent tasks' task group in the child's task group. + * Do nothing for pthreads. The parent and the child are both members of + * the same task group. + */ + + if ((tcb->flags & TCB_FLAG_TTYPE_MASK) != TCB_FLAG_TTYPE_PTHREAD) + { + /* This is a new task in a new task group, we have to copy the ID from + * the parent's task group structure to child's task group. + */ + + tcb->group->tg_pgid = rtcb->group->tg_gid; + } + +#else + DEBUGASSERT(tcb); + /* 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; + tcb->ppid = rtcb->pid; +#endif #ifdef CONFIG_SCHED_CHILD_STATUS /* Tasks can also suppress retention of their child status by applying @@ -192,13 +216,13 @@ static inline void task_saveparent(FAR _TCB *tcb, uint8_t ttype) * parent TCB. There should not be. */ - child = task_findchild(rtcb, tcb->pid); + child = group_findchild(rtcb->group, tcb->pid); DEBUGASSERT(!child); if (!child) { /* Allocate a new status structure */ - child = task_allocchild(); + child = group_allocchild(); } /* Did we successfully find/allocate the child status structure? */ @@ -214,7 +238,7 @@ static inline void task_saveparent(FAR _TCB *tcb, uint8_t ttype) /* Add the entry into the TCB list of children */ - task_addchild(rtcb, child); + group_addchild(rtcb->group, child); } } #else -- cgit v1.2.3 From 5b6482a22bb8b656e3d70a6efc5ae2c77ed2a58b Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 26 Jan 2013 20:17:29 +0000 Subject: Move file data from TCB to task group git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5567 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 2 + nuttx/TODO | 23 +---- nuttx/arch/arm/src/common/up_exit.c | 8 +- nuttx/arch/avr/src/common/up_exit.c | 8 +- nuttx/arch/hc/src/common/up_exit.c | 8 +- nuttx/arch/mips/src/common/up_exit.c | 8 +- nuttx/arch/sh/src/common/up_exit.c | 9 +- nuttx/arch/x86/src/common/up_exit.c | 6 +- nuttx/arch/z16/src/common/up_exit.c | 11 +- nuttx/arch/z80/src/common/up_exit.c | 9 +- nuttx/fs/fs_fdopen.c | 8 +- nuttx/fs/fs_files.c | 101 ++++--------------- nuttx/include/nuttx/fs/fs.h | 89 +++++++---------- nuttx/include/nuttx/sched.h | 42 +++++--- nuttx/sched/group_leave.c | 16 ++- nuttx/sched/sched_getfiles.c | 5 +- nuttx/sched/sched_releasefiles.c | 13 ++- nuttx/sched/sched_releasetcb.c | 4 - nuttx/sched/sched_setupidlefiles.c | 15 +-- nuttx/sched/sched_setuppthreadfiles.c | 8 -- nuttx/sched/sched_setuptaskfiles.c | 49 +++++---- nuttx/sched/task_exithook.c | 182 +++++++++++++++++++++------------- 22 files changed, 288 insertions(+), 336 deletions(-) (limited to 'nuttx/sched') diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 858f82819..ae7105b89 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -4034,3 +4034,5 @@ * sched/: Lots of file changed. Don't keep the parent task's task ID in the child task's TCB. Instead, keep the parent task group IN the child task's task group. + * fs/, sched/, include/nuttx/sched.h, and include/nutts/fs/fs.h: + Move file data from TCB to task group structure. diff --git a/nuttx/TODO b/nuttx/TODO index d6bd18d12..cb99f1bf7 100644 --- a/nuttx/TODO +++ b/nuttx/TODO @@ -1,4 +1,4 @@ -NuttX TODO List (Last updated January 24, 2013) +NuttX TODO List (Last updated January 26, 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/ - (11) Task/Scheduler (sched/) + (10) Task/Scheduler (sched/) (2) Memory Managment (mm/) (3) Signals (sched/, arch/) (2) pthreads (sched/) @@ -161,25 +161,6 @@ o Task/Scheduler (sched/) Status: Open Priority: Medium Low for now - Title: IMPROVED TASK CONTROL BLOCK STRUCTURE - 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). - It would be more efficent to have one reference counted - structure that holds all of the shared resources. - - These are the current shared structures: - - Environment varaibles (struct environ_s) - - PIC data space and address environments (struct dspace_s) - - File descriptors (struct filelist) - - FILE streams (struct streamlist) - - Sockets (struct socketlist) - 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: diff --git a/nuttx/arch/arm/src/common/up_exit.c b/nuttx/arch/arm/src/common/up_exit.c index 6f6d54f76..5b469fd03 100644 --- a/nuttx/arch/arm/src/common/up_exit.c +++ b/nuttx/arch/arm/src/common/up_exit.c @@ -1,7 +1,7 @@ /**************************************************************************** * common/up_exit.c * - * Copyright (C) 2007-2009, 2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2009, 201-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -85,12 +85,10 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) #if CONFIG_NFILE_DESCRIPTORS > 0 if (tcb->filelist) { - sdbg(" filelist refcount=%d\n", - tcb->filelist->fl_crefs); - + FAR struct filelist *list = tcb->group->tg_filelist; for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - struct inode *inode = tcb->filelist->fl_files[i].f_inode; + struct inode *inode = list->fl_files[i].f_inode; if (inode) { sdbg(" fd=%d refcount=%d\n", diff --git a/nuttx/arch/avr/src/common/up_exit.c b/nuttx/arch/avr/src/common/up_exit.c index 0a8cc0d18..0813754a0 100644 --- a/nuttx/arch/avr/src/common/up_exit.c +++ b/nuttx/arch/avr/src/common/up_exit.c @@ -1,7 +1,7 @@ /**************************************************************************** * arch/avr/src/common/up_exit.c * - * Copyright (C) 2010 Gregory Nutt. All rights reserved. + * Copyright (C) 2010, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -85,12 +85,10 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) #if CONFIG_NFILE_DESCRIPTORS > 0 if (tcb->filelist) { - sdbg(" filelist refcount=%d\n", - tcb->filelist->fl_crefs); - + FAR struct filelist *list = tcb->group->tg_filelist; for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - struct inode *inode = tcb->filelist->fl_files[i].f_inode; + struct inode *inode = list->fl_files[i].f_inode; if (inode) { sdbg(" fd=%d refcount=%d\n", diff --git a/nuttx/arch/hc/src/common/up_exit.c b/nuttx/arch/hc/src/common/up_exit.c index 7cd16b438..5313a1172 100644 --- a/nuttx/arch/hc/src/common/up_exit.c +++ b/nuttx/arch/hc/src/common/up_exit.c @@ -1,7 +1,7 @@ /**************************************************************************** * arch/hc/src/common/up_exit.c * - * Copyright (C) 2011 Gregory Nutt. All rights reserved. + * Copyright (C) 2011, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -85,12 +85,10 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) #if CONFIG_NFILE_DESCRIPTORS > 0 if (tcb->filelist) { - sdbg(" filelist refcount=%d\n", - tcb->filelist->fl_crefs); - + FAR struct filelist *list = tcb->group->tg_filelist; for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - struct inode *inode = tcb->filelist->fl_files[i].f_inode; + struct inode *inode = list->fl_files[i].f_inode; if (inode) { sdbg(" fd=%d refcount=%d\n", diff --git a/nuttx/arch/mips/src/common/up_exit.c b/nuttx/arch/mips/src/common/up_exit.c index 876b486b6..5a7b68a99 100644 --- a/nuttx/arch/mips/src/common/up_exit.c +++ b/nuttx/arch/mips/src/common/up_exit.c @@ -1,7 +1,7 @@ /**************************************************************************** * arch/mips/src/common/up_exit.c * - * Copyright (C) 2011 Gregory Nutt. All rights reserved. + * Copyright (C) 2011, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -87,12 +87,10 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) #if CONFIG_NFILE_DESCRIPTORS > 0 if (tcb->filelist) { - sdbg(" filelist refcount=%d\n", - tcb->filelist->fl_crefs); - + FAR struct filelist *list = tcb->group->tg_filelist; for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - struct inode *inode = tcb->filelist->fl_files[i].f_inode; + struct inode *inode = list->fl_files[i].f_inode; if (inode) { sdbg(" fd=%d refcount=%d\n", diff --git a/nuttx/arch/sh/src/common/up_exit.c b/nuttx/arch/sh/src/common/up_exit.c index 84a44a705..af270b335 100644 --- a/nuttx/arch/sh/src/common/up_exit.c +++ b/nuttx/arch/sh/src/common/up_exit.c @@ -1,7 +1,7 @@ /**************************************************************************** * common/up_exit.c * - * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved. + * Copyright (C) 2008-2009, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -81,16 +81,15 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) #endif sdbg(" TCB=%p name=%s\n", tcb, tcb->argv[0]); + sdbg(" priority=%d state=%d\n", tcb->sched_priority, tcb->task_state); #if CONFIG_NFILE_DESCRIPTORS > 0 if (tcb->filelist) { - sdbg(" filelist refcount=%d\n", - tcb->filelist->fl_crefs); - + FAR struct filelist *list = tcb->group->tg_filelist; for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - struct inode *inode = tcb->filelist->fl_files[i].f_inode; + struct inode *inode = list->fl_files[i].f_inode; if (inode) { sdbg(" fd=%d refcount=%d\n", diff --git a/nuttx/arch/x86/src/common/up_exit.c b/nuttx/arch/x86/src/common/up_exit.c index e3d27b0af..6a98c7dd0 100644 --- a/nuttx/arch/x86/src/common/up_exit.c +++ b/nuttx/arch/x86/src/common/up_exit.c @@ -85,12 +85,10 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) #if CONFIG_NFILE_DESCRIPTORS > 0 if (tcb->filelist) { - sdbg(" filelist refcount=%d\n", - tcb->filelist->fl_crefs); - + FAR struct filelist *list = tcb->group->tg_filelist; for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - struct inode *inode = tcb->filelist->fl_files[i].f_inode; + struct inode *inode = list->fl_files[i].f_inode; if (inode) { sdbg(" fd=%d refcount=%d\n", diff --git a/nuttx/arch/z16/src/common/up_exit.c b/nuttx/arch/z16/src/common/up_exit.c index 41f058347..ad0c55eed 100644 --- a/nuttx/arch/z16/src/common/up_exit.c +++ b/nuttx/arch/z16/src/common/up_exit.c @@ -1,7 +1,7 @@ /**************************************************************************** * common/up_exit.c * - * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved. + * Copyright (C) 2008-2009, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -81,17 +81,16 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) int i; #endif - dbg(" TCB=%p name=%s\n", tcb, tcb->argv[0]); + lldbg(" TCB=%p name=%s\n", tcb, tcb->argv[0]); + lldbg(" priority=%d state=%d\n", tcb->sched_priority, tcb->task_state); #if CONFIG_NFILE_DESCRIPTORS > 0 if (tcb->filelist) { - lldbg(" filelist refcount=%d\n", - tcb->filelist->fl_crefs); - + FAR struct filelist *list = tcb->group->tg_filelist; for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - struct inode *inode = tcb->filelist->fl_files[i].f_inode; + struct inode *inode = list->fl_files[i].f_inode; if (inode) { lldbg(" fd=%d refcount=%d\n", diff --git a/nuttx/arch/z80/src/common/up_exit.c b/nuttx/arch/z80/src/common/up_exit.c index 85ddd841e..50289f52b 100644 --- a/nuttx/arch/z80/src/common/up_exit.c +++ b/nuttx/arch/z80/src/common/up_exit.c @@ -82,17 +82,16 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) int i; #endif - dbg(" TCB=%p name=%s\n", tcb, tcb->argv[0]); + lldbg(" TCB=%p name=%s\n", tcb, tcb->argv[0]); + lldbg(" priority=%d state=%d\n", tcb->sched_priority, tcb->task_state); #if CONFIG_NFILE_DESCRIPTORS > 0 if (tcb->filelist) { - lldbg(" filelist refcount=%d\n", - tcb->filelist->fl_crefs); - + FAR struct filelist *list = tcb->group->tg_filelist; for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - struct inode *inode = tcb->filelist->fl_files[i].f_inode; + struct inode *inode = list->fl_files[i].f_inode; if (inode) { lldbg(" fd=%d refcount=%d\n", diff --git a/nuttx/fs/fs_fdopen.c b/nuttx/fs/fs_fdopen.c index fd6aa88a8..629083c77 100644 --- a/nuttx/fs/fs_fdopen.c +++ b/nuttx/fs/fs_fdopen.c @@ -1,7 +1,7 @@ /**************************************************************************** * fs/fs_fdopen.c * - * Copyright (C) 2007-2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -68,9 +68,11 @@ static inline int fs_checkfd(FAR _TCB *tcb, int fd, int oflags) FAR struct filelist *flist; FAR struct inode *inode; - /* Get the file list from the TCB */ + DEBUGASSERT(tcb && tcb->group); - flist = tcb->filelist; + /* Get the file list from the task group */ + + flist = &tcb->group->tg_filelist; /* Get the inode associated with the file descriptor. This should * normally be the case if fd >= 0. But not in the case where the diff --git a/nuttx/fs/fs_files.c b/nuttx/fs/fs_files.c index 06addb1ef..c68ec7e73 100644 --- a/nuttx/fs/fs_files.c +++ b/nuttx/fs/fs_files.c @@ -155,56 +155,19 @@ void files_initialize(void) } /**************************************************************************** - * Name: files_alloclist + * Name: files_initlist * - * Description: Allocate a list of files for a new task + * Description: Initializes the list of files for a new task * ****************************************************************************/ -FAR struct filelist *files_alloclist(void) +void files_initlist(FAR struct filelist *list) { - FAR struct filelist *list; - list = (FAR struct filelist*)kzalloc(sizeof(struct filelist)); - if (list) - { - /* Start with a reference count of one */ - - list->fl_crefs = 1; - - /* Initialize the list access mutex */ + DEBUGASSERT(list); - (void)sem_init(&list->fl_sem, 0, 1); - } + /* Initialize the list access mutex */ - return list; -} - -/**************************************************************************** - * Name: files_addreflist - * - * Description: - * Increase the reference count on a file list - * - ****************************************************************************/ - -int files_addreflist(FAR struct filelist *list) -{ - if (list) - { - /* Increment the reference count on the list. - * NOTE: that we disable interrupts to do this - * (vs. taking the list semaphore). We do this - * because file cleanup operations often must be - * done from the IDLE task which cannot wait - * on semaphores. - */ - - register irqstate_t flags = irqsave(); - list->fl_crefs++; - irqrestore(flags); - } - - return OK; + (void)sem_init(&list->fl_sem, 0, 1); } /**************************************************************************** @@ -215,51 +178,25 @@ int files_addreflist(FAR struct filelist *list) * ****************************************************************************/ -int files_releaselist(FAR struct filelist *list) +void files_releaselist(FAR struct filelist *list) { - int crefs; - if (list) - { - /* Decrement the reference count on the list. - * NOTE: that we disable interrupts to do this - * (vs. taking the list semaphore). We do this - * because file cleanup operations often must be - * done from the IDLE task which cannot wait - * on semaphores. - */ - - register irqstate_t flags = irqsave(); - crefs = --(list->fl_crefs); - irqrestore(flags); - - /* If the count decrements to zero, then there is no reference - * to the structure and it should be deallocated. Since there - * are references, it would be an error if any task still held - * a reference to the list's semaphore. - */ - - if (crefs <= 0) - { - int i; + int i; - /* Close each file descriptor .. Normally, you would need - * take the list semaphore, but it is safe to ignore the - * semaphore in this context because there are no references - */ + DEBUGASSERT(list); - for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) - { - (void)_files_close(&list->fl_files[i]); - } - - /* Destroy the semaphore and release the filelist */ + /* Close each file descriptor .. Normally, you would need take the list + * semaphore, but it is safe to ignore the semaphore in this context because + * there should not be any references in this context. + */ - (void)sem_destroy(&list->fl_sem); - sched_free(list); - } + for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) + { + (void)_files_close(&list->fl_files[i]); } - return OK; + /* Destroy the semaphore */ + + (void)sem_destroy(&list->fl_sem); } /**************************************************************************** diff --git a/nuttx/include/nuttx/fs/fs.h b/nuttx/include/nuttx/fs/fs.h index 327bf37ca..02855460c 100644 --- a/nuttx/include/nuttx/fs/fs.h +++ b/nuttx/include/nuttx/fs/fs.h @@ -240,7 +240,6 @@ struct file struct filelist { sem_t fl_sem; /* Manage access to the file list */ - int16_t fl_crefs; /* Reference count */ struct file fl_files[CONFIG_NFILE_DESCRIPTORS]; }; #endif @@ -318,7 +317,8 @@ typedef int (*foreach_mountpoint_t)(FAR const char *mountpoint, #undef EXTERN #if defined(__cplusplus) #define EXTERN extern "C" -extern "C" { +extern "C" +{ #else #define EXTERN extern #endif @@ -333,7 +333,7 @@ extern "C" { * ****************************************************************************/ -EXTERN void weak_function fs_initialize(void); +void weak_function fs_initialize(void); /* fs_foreachmountpoint.c ***************************************************/ /**************************************************************************** @@ -357,7 +357,7 @@ EXTERN void weak_function fs_initialize(void); ****************************************************************************/ #ifndef CONFIG_DISABLE_MOUNTPOUNT -EXTERN int foreach_mountpoint(foreach_mountpoint_t handler, FAR void *arg); +int foreach_mountpoint(foreach_mountpoint_t handler, FAR void *arg); #endif /* fs_registerdriver.c ******************************************************/ @@ -384,9 +384,8 @@ EXTERN int foreach_mountpoint(foreach_mountpoint_t handler, FAR void *arg); * ****************************************************************************/ -EXTERN int register_driver(const char *path, - const struct file_operations *fops, - mode_t mode, void *priv); +int register_driver(FAR const char *path, FAR const struct file_operations *fops, + mode_t mode, FAR void *priv); /* fs_registerblockdriver.c *************************************************/ /**************************************************************************** @@ -412,9 +411,9 @@ EXTERN int register_driver(const char *path, * ****************************************************************************/ -EXTERN int register_blockdriver(const char *path, - const struct block_operations *bops, - mode_t mode, void *priv); +int register_blockdriver(FAR const char *path, + FAR const struct block_operations *bops, mode_t mode, + FAR void *priv); /* fs_unregisterdriver.c ****************************************************/ /**************************************************************************** @@ -425,7 +424,7 @@ EXTERN int register_blockdriver(const char *path, * ****************************************************************************/ -EXTERN int unregister_driver(const char *path); +int unregister_driver(const char *path); /* fs_unregisterblockdriver.c ***********************************************/ /**************************************************************************** @@ -436,7 +435,7 @@ EXTERN int unregister_driver(const char *path); * ****************************************************************************/ -EXTERN int unregister_blockdriver(const char *path); +int unregister_blockdriver(const char *path); /* fs_open.c ****************************************************************/ /**************************************************************************** @@ -447,30 +446,19 @@ EXTERN int unregister_blockdriver(const char *path); * ****************************************************************************/ -EXTERN int inode_checkflags(FAR struct inode *inode, int oflags); +int inode_checkflags(FAR struct inode *inode, int oflags); /* fs_files.c ***************************************************************/ /**************************************************************************** - * Name: files_alloclist - * - * Description: Allocate a list of files for a new task - * - ****************************************************************************/ - -#if CONFIG_NFILE_DESCRIPTORS > 0 -EXTERN FAR struct filelist *files_alloclist(void); -#endif - -/**************************************************************************** - * Name: files_addreflist + * Name: files_initlist * * Description: - * Increase the reference count on a file list + * Initializes the list of files for a new task * ****************************************************************************/ #if CONFIG_NFILE_DESCRIPTORS > 0 -EXTERN int files_addreflist(FAR struct filelist *list); +void files_initlist(FAR struct filelist *list); #endif /**************************************************************************** @@ -482,7 +470,7 @@ EXTERN int files_addreflist(FAR struct filelist *list); ****************************************************************************/ #if CONFIG_NFILE_DESCRIPTORS > 0 -EXTERN int files_releaselist(FAR struct filelist *list); +void files_releaselist(FAR struct filelist *list); #endif /**************************************************************************** @@ -495,7 +483,7 @@ EXTERN int files_releaselist(FAR struct filelist *list); ****************************************************************************/ #if CONFIG_NFILE_DESCRIPTORS > 0 -EXTERN int files_dup(FAR struct file *filep1, FAR struct file *filep2); +int files_dup(FAR struct file *filep1, FAR struct file *filep2); #endif /* fs_filedup.c *************************************************************/ @@ -515,7 +503,7 @@ EXTERN int files_dup(FAR struct file *filep1, FAR struct file *filep2); ****************************************************************************/ #if CONFIG_NFILE_DESCRIPTORS > 0 -EXTERN int file_dup(int fd, int minfd); +int file_dup(int fd, int minfd); #endif /* fs_filedup2.c ************************************************************/ @@ -535,7 +523,7 @@ EXTERN int file_dup(int fd, int minfd); #if CONFIG_NFILE_DESCRIPTORS > 0 #if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0 -EXTERN int file_dup2(int fd1, int fd2); +int file_dup2(int fd1, int fd2); #else # define file_dup2(fd1, fd2) dup2(fd1, fd2) #endif @@ -566,8 +554,8 @@ EXTERN int file_dup2(int fd1, int fd2); ****************************************************************************/ #if CONFIG_NFILE_DESCRIPTORS > 0 -EXTERN int open_blockdriver(FAR const char *pathname, int mountflags, - FAR struct inode **ppinode); +int open_blockdriver(FAR const char *pathname, int mountflags, + FAR struct inode **ppinode); #endif /* fs_closeblockdriver.c ****************************************************/ @@ -589,7 +577,7 @@ EXTERN int open_blockdriver(FAR const char *pathname, int mountflags, ****************************************************************************/ #if CONFIG_NFILE_DESCRIPTORS > 0 -EXTERN int close_blockdriver(FAR struct inode *inode); +int close_blockdriver(FAR struct inode *inode); #endif /* fs_fdopen.c **************************************************************/ @@ -609,7 +597,7 @@ typedef struct _TCB _TCB; #define __TCB_DEFINED__ #endif -EXTERN FAR struct file_struct *fs_fdopen(int fd, int oflags, FAR _TCB *tcb); +FAR struct file_struct *fs_fdopen(int fd, int oflags, FAR _TCB *tcb); #endif /* lib/stdio/lib_fflush.c **************************************************/ @@ -623,7 +611,7 @@ EXTERN FAR struct file_struct *fs_fdopen(int fd, int oflags, FAR _TCB *tcb); ****************************************************************************/ #if CONFIG_NFILE_STREAMS > 0 -EXTERN int lib_flushall(FAR struct streamlist *list); +int lib_flushall(FAR struct streamlist *list); #endif /* drivers/dev_null.c *******************************************************/ @@ -635,7 +623,7 @@ EXTERN int lib_flushall(FAR struct streamlist *list); * ****************************************************************************/ -EXTERN void devnull_register(void); +void devnull_register(void); /* drivers/dev_zero.c *******************************************************/ /**************************************************************************** @@ -646,7 +634,7 @@ EXTERN void devnull_register(void); * ****************************************************************************/ -EXTERN void devzero_register(void); +void devzero_register(void); /* drivers/loop.c ***********************************************************/ /**************************************************************************** @@ -658,8 +646,8 @@ EXTERN void devzero_register(void); * ****************************************************************************/ -EXTERN int losetup(FAR const char *devname, FAR const char *filename, - uint16_t sectsize, off_t offset, bool readonly); +int losetup(FAR const char *devname, FAR const char *filename, + uint16_t sectsize, off_t offset, bool readonly); /**************************************************************************** * Name: loteardown @@ -669,7 +657,7 @@ EXTERN int losetup(FAR const char *devname, FAR const char *filename, * ****************************************************************************/ -EXTERN int loteardown(FAR const char *devname); +int loteardown(FAR const char *devname); /* drivers/bch/bchdev_register.c ********************************************/ /**************************************************************************** @@ -681,8 +669,8 @@ EXTERN int loteardown(FAR const char *devname); * ****************************************************************************/ -EXTERN int bchdev_register(FAR const char *blkdev, FAR const char *chardev, - bool readonly); +int bchdev_register(FAR const char *blkdev, FAR const char *chardev, + bool readonly); /* drivers/bch/bchdev_unregister.c ******************************************/ /**************************************************************************** @@ -694,7 +682,7 @@ EXTERN int bchdev_register(FAR const char *blkdev, FAR const char *chardev, * ****************************************************************************/ -EXTERN int bchdev_unregister(FAR const char *chardev); +int bchdev_unregister(FAR const char *chardev); /* Low level, direct access. NOTE: low-level access and character driver access * are incompatible. One and only one access method should be implemented. @@ -710,8 +698,7 @@ EXTERN int bchdev_unregister(FAR const char *chardev); * ****************************************************************************/ -EXTERN int bchlib_setup(FAR const char *blkdev, bool readonly, - FAR void **handle); +int bchlib_setup(FAR const char *blkdev, bool readonly, FAR void **handle); /* drivers/bch/bchlib_teardown.c ********************************************/ /**************************************************************************** @@ -723,7 +710,7 @@ EXTERN int bchlib_setup(FAR const char *blkdev, bool readonly, * ****************************************************************************/ -EXTERN int bchlib_teardown(FAR void *handle); +int bchlib_teardown(FAR void *handle); /* drivers/bch/bchlib_read.c ************************************************/ /**************************************************************************** @@ -735,8 +722,8 @@ EXTERN int bchlib_teardown(FAR void *handle); * ****************************************************************************/ -EXTERN ssize_t bchlib_read(FAR void *handle, FAR char *buffer, size_t offset, - size_t len); +ssize_t bchlib_read(FAR void *handle, FAR char *buffer, size_t offset, + size_t len); /* drivers/bch/bchlib_write.c ***********************************************/ /**************************************************************************** @@ -748,8 +735,8 @@ EXTERN ssize_t bchlib_read(FAR void *handle, FAR char *buffer, size_t offset, * ****************************************************************************/ -EXTERN ssize_t bchlib_write(FAR void *handle, FAR const char *buffer, - size_t offset, size_t len); +ssize_t bchlib_write(FAR void *handle, FAR const char *buffer, size_t offset, + size_t len); #undef EXTERN #if defined(__cplusplus) diff --git a/nuttx/include/nuttx/sched.h b/nuttx/include/nuttx/sched.h index 8ebb7db4c..1580a80d3 100644 --- a/nuttx/include/nuttx/sched.h +++ b/nuttx/include/nuttx/sched.h @@ -52,6 +52,7 @@ #include #include +#include #include /******************************************************************************** @@ -63,14 +64,24 @@ #undef HAVE_TASK_GROUP #undef HAVE_GROUP_MEMBERS +/* We need a group an group members if we are supportint the parent/child + * relationship. + */ + #if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS) -# define HAVE_TASK_GROUP 1 -# define HAVE_GROUP_MEMBERS 1 -#endif +# define HAVE_TASK_GROUP 1 +# define HAVE_GROUP_MEMBERS 1 -#if !defined(CONFIG_DISABLE_ENVIRON) -# undef HAVE_TASK_GROUP -# define HAVE_TASK_GROUP 1 +/* We need a group (but not members) if any other resources are shared within + * a task group. + */ + +#else +# if !defined(CONFIG_DISABLE_ENVIRON) +# define HAVE_TASK_GROUP 1 +# elif CONFIG_NFILE_DESCRIPTORS > 0 +# define HAVE_TASK_GROUP 1 +# endif #endif /* In any event, we don't need group members if support for pthreads is disabled */ @@ -79,7 +90,7 @@ # undef HAVE_GROUP_MEMBERS #endif -/* Task Management Definitins ***************************************************/ +/* Task Management Definitions **************************************************/ /* This is the maximum number of times that a lock can be set */ @@ -282,16 +293,19 @@ struct task_group_s FAR char *tg_envp; /* Allocated environment strings */ #endif - /* PIC data space and address environments */ + /* PIC data space and address environments ************************************/ /* Not yet (see struct dspace_s) */ - /* File descriptors */ - /* Not yet (see struct filelist) */ + /* File descriptors ***********************************************************/ - /* FILE streams */ +#if CONFIG_NFILE_DESCRIPTORS > 0 + struct filelist tg_filelist; /* Maps file descriptor to file */ +#endif + + /* FILE streams ***************************************************************/ /* Not yet (see streamlist) */ - /* Sockets */ + /* Sockets ********************************************************************/ /* Not yet (see struct socketlist) */ }; #endif @@ -433,10 +447,6 @@ struct _TCB /* File system support ********************************************************/ -#if CONFIG_NFILE_DESCRIPTORS > 0 - FAR struct filelist *filelist; /* Maps file descriptor to file */ -#endif - #if CONFIG_NFILE_STREAMS > 0 FAR struct streamlist *streams; /* Holds C buffered I/O info */ #endif diff --git a/nuttx/sched/group_leave.c b/nuttx/sched/group_leave.c index add424185..f5dca1829 100644 --- a/nuttx/sched/group_leave.c +++ b/nuttx/sched/group_leave.c @@ -176,6 +176,13 @@ void group_leave(FAR _TCB *tcb) #if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS) group_removechildren(tcb->group); +#endif + /* Free all file-related resources now. We really need to close + * files as soon as possible while we still have a functioning task. + */ + +#if CONFIG_NFILE_DESCRIPTORS > 0 + (void)sched_releasefiles(tcb); #endif /* Release all shared environment variables */ @@ -231,7 +238,14 @@ void group_leave(FAR _TCB *tcb) #if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS) group_removechildren(tcb->group); #endif - /* Release all shared environment variables */ + /* Free all file-related resources now. We really need to close + * files as soon as possible while we still have a functioning task. + */ + +#if CONFIG_NFILE_DESCRIPTORS > 0 + (void)sched_releasefiles(tcb); +#endif + /* Release all shared environment variables */ #ifndef CONFIG_DISABLE_ENVIRON env_release(tcb); diff --git a/nuttx/sched/sched_getfiles.c b/nuttx/sched/sched_getfiles.c index 256b4cb6b..eca4ba3ff 100644 --- a/nuttx/sched/sched_getfiles.c +++ b/nuttx/sched/sched_getfiles.c @@ -70,7 +70,10 @@ FAR struct filelist *sched_getfiles(void) { FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head; - return rtcb->filelist; + FAR struct task_group_s *group = rtcb->group; + + DEBUGASSERT(group); + return &group->tg_filelist; } #endif /* CONFIG_NFILE_DESCRIPTORS */ diff --git a/nuttx/sched/sched_releasefiles.c b/nuttx/sched/sched_releasefiles.c index a3ef71af4..4be92f4eb 100644 --- a/nuttx/sched/sched_releasefiles.c +++ b/nuttx/sched/sched_releasefiles.c @@ -1,7 +1,7 @@ /**************************************************************************** * sched/sched_releasefiles.c * - * Copyright (C) 2007, 2008, 2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2008, 2012-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -78,13 +78,12 @@ int sched_releasefiles(_TCB *tcb) if (tcb) { #if CONFIG_NFILE_DESCRIPTORS > 0 - /* Free the file descriptor list */ + FAR struct task_group_s *group = tcb->group; + DEBUGASSERT(group); - if (tcb->filelist) - { - files_releaselist(tcb->filelist); - tcb->filelist = NULL; - } + /* Free resources used by the file descriptor list */ + + files_releaselist(&group->tg_filelist); #if CONFIG_NFILE_STREAMS > 0 /* Free the stream list */ diff --git a/nuttx/sched/sched_releasetcb.c b/nuttx/sched/sched_releasetcb.c index 00d4c2c0c..02f7170c2 100644 --- a/nuttx/sched/sched_releasetcb.c +++ b/nuttx/sched/sched_releasetcb.c @@ -163,10 +163,6 @@ int sched_releasetcb(FAR _TCB *tcb) } } - /* Release any allocated file structures */ - - ret = sched_releasefiles(tcb); - /* Release this thread's reference to the address environment */ #ifdef CONFIG_ADDRENV diff --git a/nuttx/sched/sched_setupidlefiles.c b/nuttx/sched/sched_setupidlefiles.c index ae814e1a6..4bbd4d3b7 100644 --- a/nuttx/sched/sched_setupidlefiles.c +++ b/nuttx/sched/sched_setupidlefiles.c @@ -79,18 +79,21 @@ int sched_setupidlefiles(FAR _TCB *tcb) { +#if CONFIG_NFILE_DESCRIPTORS > 0 + FAR struct task_group_s *group = tcb->group; +#endif #if CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_DEV_CONSOLE) int fd; #endif - /* Allocate file descriptors for the TCB */ +#if CONFIG_NFILE_DESCRIPTORS > 0 + DEBUGASSERT(group); +#endif + + /* Initialize file descriptors for the TCB */ #if CONFIG_NFILE_DESCRIPTORS > 0 - tcb->filelist = files_alloclist(); - if (!tcb->filelist) - { - return -ENOMEM; - } + files_initlist(&group->tg_filelist); #endif /* Allocate socket descriptors for the TCB */ diff --git a/nuttx/sched/sched_setuppthreadfiles.c b/nuttx/sched/sched_setuppthreadfiles.c index 648d9273e..78d6cbfec 100644 --- a/nuttx/sched/sched_setuppthreadfiles.c +++ b/nuttx/sched/sched_setuppthreadfiles.c @@ -79,14 +79,6 @@ int sched_setuppthreadfiles(FAR _TCB *tcb) { FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head; -#if CONFIG_NFILE_DESCRIPTORS > 0 - /* The child thread inherits the parent file descriptors */ - - tcb->filelist = rtcb->filelist; - files_addreflist(tcb->filelist); - -#endif /* CONFIG_NFILE_DESCRIPTORS */ - #if CONFIG_NSOCKET_DESCRIPTORS > 0 /* The child thread inherits the parent socket descriptors */ diff --git a/nuttx/sched/sched_setuptaskfiles.c b/nuttx/sched/sched_setuptaskfiles.c index d01b8d4cd..9e44147e9 100644 --- a/nuttx/sched/sched_setuptaskfiles.c +++ b/nuttx/sched/sched_setuptaskfiles.c @@ -1,7 +1,7 @@ /**************************************************************************** * sched/sched_setuptaskfiles.c * - * Copyright (C) 2007-2008, 2010, 2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2008, 2010, 2012-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -93,34 +93,33 @@ static inline void sched_dupfiles(FAR _TCB *tcb) FAR struct file *child; int i; + DEBUGASSERT(tcb && tcb->group && rtcb->group); + /* Duplicate the file descriptors. This will be either all of the * file descriptors or just the first three (stdin, stdout, and stderr) * if CONFIG_FDCLONE_STDIO is defined. NFSDS_TOCLONE is set * accordingly above. */ - if (rtcb->filelist) - { - /* Get pointers to the parent and child task file lists */ + /* Get pointers to the parent and child task file lists */ - parent = rtcb->filelist->fl_files; - child = tcb->filelist->fl_files; + parent = rtcb->group->tg_filelist.fl_files; + child = tcb->group->tg_filelist.fl_files; - /* Check each file in the parent file list */ + /* Check each file in the parent file list */ - for (i = 0; i < NFDS_TOCLONE; i++) - { - /* Check if this file is opened by the parent. We can tell if - * if the file is open because it contain a reference to a non-NULL - * i-node structure. - */ + for (i = 0; i < NFDS_TOCLONE; i++) + { + /* Check if this file is opened by the parent. We can tell if + * if the file is open because it contain a reference to a non-NULL + * i-node structure. + */ - if (parent[i].f_inode) - { - /* Yes... duplicate it for the child */ + if (parent[i].f_inode) + { + /* Yes... duplicate it for the child */ - (void)files_dup(&parent[i], &child[i]); - } + (void)files_dup(&parent[i], &child[i]); } } } @@ -209,14 +208,14 @@ static inline void sched_dupsockets(FAR _TCB *tcb) int sched_setuptaskfiles(FAR _TCB *tcb) { - /* Allocate file descriptors for the TCB */ - #if CONFIG_NFILE_DESCRIPTORS > 0 - tcb->filelist = files_alloclist(); - if (!tcb->filelist) - { - return -ENOMEM; - } + FAR struct task_group_s *group = tcb->group; + + DEBUGASSERT(group); + + /* Initialize file descriptors for the TCB */ + + files_initlist(&group->tg_filelist); #endif /* Allocate socket descriptors for the TCB */ diff --git a/nuttx/sched/task_exithook.c b/nuttx/sched/task_exithook.c index 3fdf08bf7..5a2b9e57e 100644 --- a/nuttx/sched/task_exithook.c +++ b/nuttx/sched/task_exithook.c @@ -177,6 +177,89 @@ static inline void task_onexit(FAR _TCB *tcb, int status) # define task_onexit(tcb,status) #endif +/**************************************************************************** + * Name: task_exitstatus + * + * Description: + * Report exit status when main task of a task group exits + * + ****************************************************************************/ + +#ifdef CONFIG_SCHED_CHILD_STATUS +static inline void task_exitstatus(FAR struct task_group_s *group, int status) +{ + FAR struct child_status_s *child; + + /* Check if the parent task group has suppressed retention of + * child exit status information. + */ + + if ((group->tg_flags & GROUP_FLAG_NOCLDWAIT) == 0) + { + /* No.. Find the exit status entry for this task in the parent TCB */ + + child = group_findchild(group, getpid()); + DEBUGASSERT(child); + if (child) + { +#ifndef HAVE_GROUP_MEMBERS + /* No group members? Save the exit status */ + + child->ch_status = status; +#endif + /* Save the exit status.. For the case of HAVE_GROUP_MEMBERS, + * the child status will be as exited until the last member + * of the task group exits. + */ + + child->ch_status = status; + } + } +} +#else + +# define task_exitstatus(group,status) + +#endif /* CONFIG_SCHED_CHILD_STATUS */ + +/**************************************************************************** + * Name: task_groupexit + * + * Description: + * Mark that the final thread of a child task group as exited. + * + ****************************************************************************/ + +#ifdef CONFIG_SCHED_CHILD_STATUS +static inline void task_groupexit(FAR struct task_group_s *group) +{ + FAR struct child_status_s *child; + + /* Check if the parent task group has suppressed retention of child exit + * status information. + */ + + if ((group->tg_flags & GROUP_FLAG_NOCLDWAIT) == 0) + { + /* No.. Find the exit status entry for this task in the parent TCB */ + + child = group_findchild(group, getpid()); + DEBUGASSERT(child); + if (child) + { + /* Mark that all members of the child task group has exit'ed */ + + child->ch_flags |= CHILD_FLAG_EXITED; + } + } +} + +#else + +# define task_groupexit(group) + +#endif /* CONFIG_SCHED_CHILD_STATUS */ + /**************************************************************************** * Name: task_sigchild * @@ -195,55 +278,41 @@ static inline void task_sigchild(gid_t pgid, FAR _TCB *ctcb, int status) DEBUGASSERT(chgrp); - /* Only the final exiting thread in a task group should generate SIGCHLD. */ + /* Get the parent task group. It is possible that all of the members of + * the parent task group have exited. This would not be an error. In + * this case, the child task group has been orphaned. + */ - if (chgrp->tg_nmembers == 1) + pgrp = group_find(chgrp->tg_pgid); + if (!pgrp) { - /* Get the parent task group */ - - pgrp = group_find(chgrp->tg_pgid); - - /* It is possible that all of the members of the parent task group - * have exited. This would not be an error. In this case, the - * child task group has been orphaned. + /* Set the task group ID to an invalid group ID. The dead parent + * task group ID could get reused some time in the future. */ - if (!pgrp) - { - /* Set the task group ID to an invalid group ID. The dead parent - * task group ID could get reused some time in the future. - */ - - chgrp->tg_pgid = INVALID_GROUP_ID; - return; - } - -#ifdef CONFIG_SCHED_CHILD_STATUS - /* Check if the parent task group has suppressed retention of child exit - * status information. Only 'tasks' report exit status, not pthreads. - * pthreads have a different mechanism. - */ - - if ((pgrp->tg_flags & GROUP_FLAG_NOCLDWAIT) == 0) - { - FAR struct child_status_s *child; + chgrp->tg_pgid = INVALID_GROUP_ID; + return; + } - /* No.. Find the exit status entry for this task in the parent TCB */ + /* Save the exit status now if this is the main thread of the task group + * that is exiting. Only the exiting main task of a task group carries + * interpretable exit Check if this is the main task that is exiting. + */ - child = group_findchild(pgrp, getpid()); - DEBUGASSERT(child); - if (child) - { - /* Mark that the child has exit'ed */ + if ((ctcb->flags & TCB_FLAG_TTYPE_MASK) == TCB_FLAG_TTYPE_TASK) + { + task_exitstatus(pgrp, status); + } - child->ch_flags |= CHILD_FLAG_EXITED; + /* But only the final exiting thread in a task group, whatever it is, + * should generate SIGCHLD. + */ - /* Save the exit status */ + if (chgrp->tg_nmembers == 1) + { + /* Mark that all of the threads in the task group have exited */ - child->ch_status = status; - } - } -#endif /* CONFIG_SCHED_CHILD_STATUS */ + task_groupexit(pgrp); /* 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 @@ -278,30 +347,9 @@ static inline void task_sigchild(FAR _TCB *ptcb, FAR _TCB *ctcb, int status) if ((ctcb->flags & TCB_FLAG_TTYPE_MASK) == TCB_FLAG_TTYPE_TASK) { #ifdef CONFIG_SCHED_CHILD_STATUS - /* Check if the parent task group has suppressed retention of child exit - * status information. Only 'tasks' report exit status, not pthreads. - * pthreads have a different mechanism. - */ + /* Save the exit status now of the main thread */ - if ((ptcb->group->tg_flags & GROUP_FLAG_NOCLDWAIT) == 0) - { - FAR struct child_status_s *child; - - /* No.. Find the exit status entry for this task in the parent TCB */ - - child = group_findchild(ptcb->group, 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; - } - } + task_exitstatus(ptcb->group, status); #else /* CONFIG_SCHED_CHILD_STATUS */ @@ -506,14 +554,6 @@ void task_exithook(FAR _TCB *tcb, int status) group_leave(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 - * have a functioning task. - */ - - (void)sched_releasefiles(tcb); - /* Deallocate anything left in the TCB's queues */ #ifndef CONFIG_DISABLE_SIGNALS -- cgit v1.2.3 From 3bec164b3ae1cd7f9b5dcec532e7d073be96d45d Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 26 Jan 2013 21:01:19 +0000 Subject: Fix a recently introduced memory leak git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5568 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/sched/Makefile | 3 +- nuttx/sched/group_internal.h | 8 +++ nuttx/sched/group_leave.c | 107 ++++++++++++++++++++---------------- nuttx/sched/group_releasefiles.c | 113 +++++++++++++++++++++++++++++++++++++++ nuttx/sched/os_internal.h | 2 - nuttx/sched/sched_releasefiles.c | 113 --------------------------------------- 6 files changed, 185 insertions(+), 161 deletions(-) create mode 100644 nuttx/sched/group_releasefiles.c delete mode 100644 nuttx/sched/sched_releasefiles.c (limited to 'nuttx/sched') diff --git a/nuttx/sched/Makefile b/nuttx/sched/Makefile index d059152e0..c8fe7cf69 100644 --- a/nuttx/sched/Makefile +++ b/nuttx/sched/Makefile @@ -41,7 +41,7 @@ AOBJS = $(ASRCS:.S=$(OBJEXT)) 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 +MISC_SRCS += sched_setuppthreadfiles.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 @@ -81,6 +81,7 @@ endif endif GRP_SRCS = group_create.c group_join.c group_leave.c group_find.c +GRP_SRCS += group_releasefiles.c ifeq ($(CONFIG_SCHED_HAVE_PARENT),y) GRP_SRCS += task_reparent.c diff --git a/nuttx/sched/group_internal.h b/nuttx/sched/group_internal.h index b78b38453..39d0a2b7c 100644 --- a/nuttx/sched/group_internal.h +++ b/nuttx/sched/group_internal.h @@ -127,6 +127,14 @@ FAR struct child_status_s *group_removechild(FAR struct task_group_s *group, pid_t pid); void group_removechildren(FAR struct task_group_s *group); +/* File/network resources */ + +#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0 +int group_releasefiles(FAR _TCB *tcb); +#else +# define group_releasefiles(t) (OK) +#endif + #endif /* CONFIG_SCHED_CHILD_STATUS */ #endif /* CONFIG_SCHED_HAVE_PARENT */ diff --git a/nuttx/sched/group_leave.c b/nuttx/sched/group_leave.c index f5dca1829..158ba30b5 100644 --- a/nuttx/sched/group_leave.c +++ b/nuttx/sched/group_leave.c @@ -124,6 +124,64 @@ void group_remove(FAR struct task_group_s *group) } #endif +/***************************************************************************** + * Name: group_release + * + * Description: + * Release group resources after the last member has left the group. + * + * Parameters: + * group - The group to be removed. + * + * Return Value: + * None. + * + * Assumptions: + * Called during task deletion in a safe context. No special precautions + * are required here. + * + *****************************************************************************/ + +static inline void group_release(FAR _TCB *tcb, + FAR struct task_group_s *group) +{ + /* Free all un-reaped child exit status */ + +#if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS) + group_removechildren(group); +#endif + + /* Free all file-related resources now. We really need to close files as + * soon as possible while we still have a functioning task. + */ + +#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0 + (void)group_releasefiles(tcb); +#endif + + /* Release all shared environment variables */ + +#ifndef CONFIG_DISABLE_ENVIRON + env_release(tcb); +#endif + + /* Remove the group from the list of groups */ + + group_remove(group); + + /* Release the members array */ + + if (group->tg_members) + { + sched_free(group->tg_members); + group->tg_members = NULL; + } + + /* Release the group container itself */ + + sched_free(group); +} + /***************************************************************************** * Public Functions *****************************************************************************/ @@ -150,7 +208,6 @@ void group_remove(FAR struct task_group_s *group) *****************************************************************************/ #ifdef HAVE_GROUP_MEMBERS - void group_leave(FAR _TCB *tcb) { FAR struct task_group_s *group; @@ -171,31 +228,9 @@ void group_leave(FAR _TCB *tcb) if (ret == 0) { - /* Release all of the resource contained within the group */ - /* Free all un-reaped child exit status */ - -#if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS) - group_removechildren(tcb->group); -#endif - /* Free all file-related resources now. We really need to close - * files as soon as possible while we still have a functioning task. - */ - -#if CONFIG_NFILE_DESCRIPTORS > 0 - (void)sched_releasefiles(tcb); -#endif - /* Release all shared environment variables */ + /* Release all of the resource held by the task group */ -#ifndef CONFIG_DISABLE_ENVIRON - env_release(tcb); -#endif - /* Remove the group from the list of groups */ - - group_remove(group); - - /* Release the group container itself */ - - sched_free(group); + group_release(tcb, group); } /* In any event, we can detach the group from the TCB so that we won't @@ -232,27 +267,9 @@ void group_leave(FAR _TCB *tcb) else { - /* Release all of the resource contained within the group */ - /* Free all un-reaped child exit status */ - -#if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS) - group_removechildren(tcb->group); -#endif - /* Free all file-related resources now. We really need to close - * files as soon as possible while we still have a functioning task. - */ - -#if CONFIG_NFILE_DESCRIPTORS > 0 - (void)sched_releasefiles(tcb); -#endif - /* Release all shared environment variables */ - -#ifndef CONFIG_DISABLE_ENVIRON - env_release(tcb); -#endif - /* Release the group container itself */ + /* Release all of the resource held by the task group */ - sched_free(group); + group_release(tcb, group); } /* In any event, we can detach the group from the TCB so we won't do diff --git a/nuttx/sched/group_releasefiles.c b/nuttx/sched/group_releasefiles.c new file mode 100644 index 000000000..40bf373b4 --- /dev/null +++ b/nuttx/sched/group_releasefiles.c @@ -0,0 +1,113 @@ +/**************************************************************************** + * sched/group_releasefiles.c + * + * Copyright (C) 2007, 2008, 2012-2013 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 + +#include +#include +#include +#include + +#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0 + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: group_releasefiles + * + * Description: + * Release file resources attached to a TCB. This file may be called + * multiple times as a task exists. It will be called as early as possible + * to support proper closing of complex drivers that may need to wait + * on external events. + * + * Parameters: + * tcb - tcb of the new task. + * + * Return Value: + * None + * + * Assumptions: + * + ****************************************************************************/ + +int group_releasefiles(_TCB *tcb) +{ + if (tcb) + { +#if CONFIG_NFILE_DESCRIPTORS > 0 + FAR struct task_group_s *group = tcb->group; + DEBUGASSERT(group); + + /* Free resources used by the file descriptor list */ + + files_releaselist(&group->tg_filelist); + +#if CONFIG_NFILE_STREAMS > 0 + /* Free the stream list */ + + if (tcb->streams) + { + lib_releaselist(tcb->streams); + tcb->streams = NULL; + } +#endif /* CONFIG_NFILE_STREAMS */ +#endif /* CONFIG_NFILE_DESCRIPTORS */ + +#if CONFIG_NSOCKET_DESCRIPTORS > 0 + /* Free the file descriptor list */ + + if (tcb->sockets) + { + net_releaselist(tcb->sockets); + tcb->sockets = NULL; + } +#endif /* CONFIG_NSOCKET_DESCRIPTORS */ + } + + return OK; +} + +#endif /* CONFIG_NFILE_DESCRIPTORS || CONFIG_NSOCKET_DESCRIPTORS */ diff --git a/nuttx/sched/os_internal.h b/nuttx/sched/os_internal.h index e3d0fd48f..5aa6487d0 100644 --- a/nuttx/sched/os_internal.h +++ b/nuttx/sched/os_internal.h @@ -105,7 +105,6 @@ enum os_crash_codes_e # define sched_setupidlefiles(t) (OK) # define sched_setuptaskfiles(t) (OK) # define sched_setuppthreadfiles(t) (OK) -# define sched_releasefiles(t) (OK) #endif /* One processor family supported by NuttX has a single, fixed hardware stack. @@ -301,7 +300,6 @@ int sched_setuppthreadfiles(FAR _TCB *tcb); #if CONFIG_NFILE_STREAMS > 0 int sched_setupstreams(FAR _TCB *tcb); #endif -int sched_releasefiles(FAR _TCB *tcb); #endif int sched_releasetcb(FAR _TCB *tcb); diff --git a/nuttx/sched/sched_releasefiles.c b/nuttx/sched/sched_releasefiles.c deleted file mode 100644 index 4be92f4eb..000000000 --- a/nuttx/sched/sched_releasefiles.c +++ /dev/null @@ -1,113 +0,0 @@ -/**************************************************************************** - * sched/sched_releasefiles.c - * - * Copyright (C) 2007, 2008, 2012-2013 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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 - -#include -#include -#include -#include - -#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0 - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: sched_releasefiles - * - * Description: - * Release file resources attached to a TCB. This file may be called - * multiple times as a task exists. It will be called as early as possible - * to support proper closing of complex drivers that may need to wait - * on external events. - * - * Parameters: - * tcb - tcb of the new task. - * - * Return Value: - * None - * - * Assumptions: - * - ****************************************************************************/ - -int sched_releasefiles(_TCB *tcb) -{ - if (tcb) - { -#if CONFIG_NFILE_DESCRIPTORS > 0 - FAR struct task_group_s *group = tcb->group; - DEBUGASSERT(group); - - /* Free resources used by the file descriptor list */ - - files_releaselist(&group->tg_filelist); - -#if CONFIG_NFILE_STREAMS > 0 - /* Free the stream list */ - - if (tcb->streams) - { - lib_releaselist(tcb->streams); - tcb->streams = NULL; - } -#endif /* CONFIG_NFILE_STREAMS */ -#endif /* CONFIG_NFILE_DESCRIPTORS */ - -#if CONFIG_NSOCKET_DESCRIPTORS > 0 - /* Free the file descriptor list */ - - if (tcb->sockets) - { - net_releaselist(tcb->sockets); - tcb->sockets = NULL; - } -#endif /* CONFIG_NSOCKET_DESCRIPTORS */ - } - - return OK; -} - -#endif /* CONFIG_NFILE_DESCRIPTORS || CONFIG_NSOCKET_DESCRIPTORS */ -- cgit v1.2.3 From b82c36961aa730fc39a9fc8eac17e2518128cb67 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 26 Jan 2013 22:25:21 +0000 Subject: Move stream data from TCB to task group structure. git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5569 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 2 + nuttx/arch/arm/src/common/up_exit.c | 42 +++++------ nuttx/arch/avr/src/common/up_exit.c | 42 +++++------ nuttx/arch/hc/src/common/up_exit.c | 42 +++++------ nuttx/arch/mips/src/common/up_exit.c | 42 +++++------ nuttx/arch/sh/src/common/up_exit.c | 42 +++++------ nuttx/arch/x86/src/common/up_exit.c | 44 +++++------ nuttx/arch/z16/src/common/up_exit.c | 42 +++++------ nuttx/arch/z80/src/common/up_exit.c | 44 +++++------ nuttx/fs/fs_fdopen.c | 5 +- nuttx/include/nuttx/fs/fs.h | 1 - nuttx/include/nuttx/lib.h | 9 +-- nuttx/include/nuttx/sched.h | 13 ++-- nuttx/libc/misc/lib_init.c | 134 ++++++++++------------------------ nuttx/libc/stdio/lib_libflushall.c | 2 +- nuttx/sched/group_internal.h | 27 +------ nuttx/sched/group_leave.c | 2 + nuttx/sched/group_releasefiles.c | 9 +-- nuttx/sched/sched_getfiles.c | 2 +- nuttx/sched/sched_getstreams.c | 7 +- nuttx/sched/sched_setuppthreadfiles.c | 9 --- nuttx/sched/sched_setupstreams.c | 35 +++++---- nuttx/sched/task_exithook.c | 2 +- 23 files changed, 242 insertions(+), 357 deletions(-) (limited to 'nuttx/sched') diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index ae7105b89..b5933f620 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -4036,3 +4036,5 @@ task group IN the child task's task group. * fs/, sched/, include/nuttx/sched.h, and include/nutts/fs/fs.h: Move file data from TCB to task group structure. + * libc/stdio/, sched/, include/nuttx/lib.h, and include/nutts/fs/fs.h: + Move stream data from TCB to task group structure. diff --git a/nuttx/arch/arm/src/common/up_exit.c b/nuttx/arch/arm/src/common/up_exit.c index 5b469fd03..16f5c4442 100644 --- a/nuttx/arch/arm/src/common/up_exit.c +++ b/nuttx/arch/arm/src/common/up_exit.c @@ -75,7 +75,11 @@ #if defined(CONFIG_DUMP_ON_EXIT) && defined(CONFIG_DEBUG) static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) { -#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NFILE_STREAMS > 0 +#if CONFIG_NFILE_DESCRIPTORS > 0 + FAR struct filelist *filelist; +#if CONFIG_NFILE_STREAMS > 0 + FAR struct streamlist *streamlist; +#endif int i; #endif @@ -83,40 +87,32 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) sdbg(" priority=%d state=%d\n", tcb->sched_priority, tcb->task_state); #if CONFIG_NFILE_DESCRIPTORS > 0 - if (tcb->filelist) + filelist = tcb->group->tg_filelist; + for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - FAR struct filelist *list = tcb->group->tg_filelist; - for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) + struct inode *inode = filelist->fl_files[i].f_inode; + if (inode) { - struct inode *inode = list->fl_files[i].f_inode; - if (inode) - { - sdbg(" fd=%d refcount=%d\n", - i, inode->i_crefs); - } + sdbg(" fd=%d refcount=%d\n", + i, inode->i_crefs); } } #endif #if CONFIG_NFILE_STREAMS > 0 - if (tcb->streams) + streamlist = tcb->group->tg_streamlist; + for (i = 0; i < CONFIG_NFILE_STREAMS; i++) { - sdbg(" streamlist refcount=%d\n", - tcb->streams->sl_crefs); - - for (i = 0; i < CONFIG_NFILE_STREAMS; i++) + struct file_struct *filep = &streamlist->sl_streams[i]; + if (filep->fs_filedes >= 0) { - struct file_struct *filep = &tcb->streams->sl_streams[i]; - if (filep->fs_filedes >= 0) - { #if CONFIG_STDIO_BUFFER_SIZE > 0 - sdbg(" fd=%d nbytes=%d\n", - filep->fs_filedes, - filep->fs_bufpos - filep->fs_bufstart); + sdbg(" fd=%d nbytes=%d\n", + filep->fs_filedes, + filep->fs_bufpos - filep->fs_bufstart); #else - sdbg(" fd=%d\n", filep->fs_filedes); + sdbg(" fd=%d\n", filep->fs_filedes); #endif - } } } #endif diff --git a/nuttx/arch/avr/src/common/up_exit.c b/nuttx/arch/avr/src/common/up_exit.c index 0813754a0..68e33fde7 100644 --- a/nuttx/arch/avr/src/common/up_exit.c +++ b/nuttx/arch/avr/src/common/up_exit.c @@ -75,7 +75,11 @@ #if defined(CONFIG_DUMP_ON_EXIT) && defined(CONFIG_DEBUG) static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) { -#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NFILE_STREAMS > 0 +#if CONFIG_NFILE_DESCRIPTORS > 0 + FAR struct filelist *filelist; +#if CONFIG_NFILE_STREAMS > 0 + FAR struct streamlist *streamlist; +#endif int i; #endif @@ -83,40 +87,32 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) sdbg(" priority=%d state=%d\n", tcb->sched_priority, tcb->task_state); #if CONFIG_NFILE_DESCRIPTORS > 0 - if (tcb->filelist) + filelist = tcb->group->tg_filelist; + for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - FAR struct filelist *list = tcb->group->tg_filelist; - for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) + struct inode *inode = filelist->fl_files[i].f_inode; + if (inode) { - struct inode *inode = list->fl_files[i].f_inode; - if (inode) - { - sdbg(" fd=%d refcount=%d\n", - i, inode->i_crefs); - } + sdbg(" fd=%d refcount=%d\n", + i, inode->i_crefs); } } #endif #if CONFIG_NFILE_STREAMS > 0 - if (tcb->streams) + streamlist = tcb->group->tg_streamlist; + for (i = 0; i < CONFIG_NFILE_STREAMS; i++) { - sdbg(" streamlist refcount=%d\n", - tcb->streams->sl_crefs); - - for (i = 0; i < CONFIG_NFILE_STREAMS; i++) + struct file_struct *filep = &streamlist->sl_streams[i]; + if (filep->fs_filedes >= 0) { - struct file_struct *filep = &tcb->streams->sl_streams[i]; - if (filep->fs_filedes >= 0) - { #if CONFIG_STDIO_BUFFER_SIZE > 0 - sdbg(" fd=%d nbytes=%d\n", - filep->fs_filedes, - filep->fs_bufpos - filep->fs_bufstart); + sdbg(" fd=%d nbytes=%d\n", + filep->fs_filedes, + filep->fs_bufpos - filep->fs_bufstart); #else - sdbg(" fd=%d\n", filep->fs_filedes); + sdbg(" fd=%d\n", filep->fs_filedes); #endif - } } } #endif diff --git a/nuttx/arch/hc/src/common/up_exit.c b/nuttx/arch/hc/src/common/up_exit.c index 5313a1172..1c46875f8 100644 --- a/nuttx/arch/hc/src/common/up_exit.c +++ b/nuttx/arch/hc/src/common/up_exit.c @@ -75,7 +75,11 @@ #if defined(CONFIG_DUMP_ON_EXIT) && defined(CONFIG_DEBUG) static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) { -#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NFILE_STREAMS > 0 +#if CONFIG_NFILE_DESCRIPTORS > 0 + FAR struct filelist *filelist; +#if CONFIG_NFILE_STREAMS > 0 + FAR struct streamlist *streamlist; +#endif int i; #endif @@ -83,40 +87,32 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) sdbg(" priority=%d state=%d\n", tcb->sched_priority, tcb->task_state); #if CONFIG_NFILE_DESCRIPTORS > 0 - if (tcb->filelist) + filelist = tcb->group->tg_filelist; + for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - FAR struct filelist *list = tcb->group->tg_filelist; - for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) + struct inode *inode = filelist->fl_files[i].f_inode; + if (inode) { - struct inode *inode = list->fl_files[i].f_inode; - if (inode) - { - sdbg(" fd=%d refcount=%d\n", - i, inode->i_crefs); - } + sdbg(" fd=%d refcount=%d\n", + i, inode->i_crefs); } } #endif #if CONFIG_NFILE_STREAMS > 0 - if (tcb->streams) + streamlist = tcb->group->tg_streamlist; + for (i = 0; i < CONFIG_NFILE_STREAMS; i++) { - sdbg(" streamlist refcount=%d\n", - tcb->streams->sl_crefs); - - for (i = 0; i < CONFIG_NFILE_STREAMS; i++) + struct file_struct *filep = &streamlist->sl_streams[i]; + if (filep->fs_filedes >= 0) { - struct file_struct *filep = &tcb->streams->sl_streams[i]; - if (filep->fs_filedes >= 0) - { #if CONFIG_STDIO_BUFFER_SIZE > 0 - sdbg(" fd=%d nbytes=%d\n", - filep->fs_filedes, - filep->fs_bufpos - filep->fs_bufstart); + sdbg(" fd=%d nbytes=%d\n", + filep->fs_filedes, + filep->fs_bufpos - filep->fs_bufstart); #else - sdbg(" fd=%d\n", filep->fs_filedes); + sdbg(" fd=%d\n", filep->fs_filedes); #endif - } } } #endif diff --git a/nuttx/arch/mips/src/common/up_exit.c b/nuttx/arch/mips/src/common/up_exit.c index 5a7b68a99..e112364b4 100644 --- a/nuttx/arch/mips/src/common/up_exit.c +++ b/nuttx/arch/mips/src/common/up_exit.c @@ -77,7 +77,11 @@ #if defined(CONFIG_DUMP_ON_EXIT) && defined(CONFIG_DEBUG) static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) { -#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NFILE_STREAMS > 0 +#if CONFIG_NFILE_DESCRIPTORS > 0 + FAR struct filelist *filelist; +#if CONFIG_NFILE_STREAMS > 0 + FAR struct streamlist *streamlist; +#endif int i; #endif @@ -85,40 +89,32 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) sdbg(" priority=%d state=%d\n", tcb->sched_priority, tcb->task_state); #if CONFIG_NFILE_DESCRIPTORS > 0 - if (tcb->filelist) + filelist = tcb->group->tg_filelist; + for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - FAR struct filelist *list = tcb->group->tg_filelist; - for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) + struct inode *inode = filelist->fl_files[i].f_inode; + if (inode) { - struct inode *inode = list->fl_files[i].f_inode; - if (inode) - { - sdbg(" fd=%d refcount=%d\n", - i, inode->i_crefs); - } + sdbg(" fd=%d refcount=%d\n", + i, inode->i_crefs); } } #endif #if CONFIG_NFILE_STREAMS > 0 - if (tcb->streams) + streamlist = tcb->group->tg_streamlist; + for (i = 0; i < CONFIG_NFILE_STREAMS; i++) { - sdbg(" streamlist refcount=%d\n", - tcb->streams->sl_crefs); - - for (i = 0; i < CONFIG_NFILE_STREAMS; i++) + struct file_struct *filep = &streamlist->sl_streams[i]; + if (filep->fs_filedes >= 0) { - struct file_struct *filep = &tcb->streams->sl_streams[i]; - if (filep->fs_filedes >= 0) - { #if CONFIG_STDIO_BUFFER_SIZE > 0 - sdbg(" fd=%d nbytes=%d\n", - filep->fs_filedes, - filep->fs_bufpos - filep->fs_bufstart); + sdbg(" fd=%d nbytes=%d\n", + filep->fs_filedes, + filep->fs_bufpos - filep->fs_bufstart); #else - sdbg(" fd=%d\n", filep->fs_filedes); + sdbg(" fd=%d\n", filep->fs_filedes); #endif - } } } #endif diff --git a/nuttx/arch/sh/src/common/up_exit.c b/nuttx/arch/sh/src/common/up_exit.c index af270b335..705f49852 100644 --- a/nuttx/arch/sh/src/common/up_exit.c +++ b/nuttx/arch/sh/src/common/up_exit.c @@ -76,7 +76,11 @@ #if defined(CONFIG_DUMP_ON_EXIT) && defined(CONFIG_DEBUG) static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) { -#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NFILE_STREAMS > 0 +#if CONFIG_NFILE_DESCRIPTORS > 0 + FAR struct filelist *filelist; +#if CONFIG_NFILE_STREAMS > 0 + FAR struct streamlist *streamlist; +#endif int i; #endif @@ -84,40 +88,32 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) sdbg(" priority=%d state=%d\n", tcb->sched_priority, tcb->task_state); #if CONFIG_NFILE_DESCRIPTORS > 0 - if (tcb->filelist) + filelist = tcb->group->tg_filelist; + for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - FAR struct filelist *list = tcb->group->tg_filelist; - for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) + struct inode *inode = filelist->fl_files[i].f_inode; + if (inode) { - struct inode *inode = list->fl_files[i].f_inode; - if (inode) - { - sdbg(" fd=%d refcount=%d\n", - i, inode->i_crefs); - } + sdbg(" fd=%d refcount=%d\n", + i, inode->i_crefs); } } #endif #if CONFIG_NFILE_STREAMS > 0 - if (tcb->streams) + streamlist = tcb->group->tg_streamlist; + for (i = 0; i < CONFIG_NFILE_STREAMS; i++) { - sdbg(" streamlist refcount=%d\n", - tcb->streams->sl_crefs); - - for (i = 0; i < CONFIG_NFILE_STREAMS; i++) + struct file_struct *filep = &streamlist->sl_streams[i]; + if (filep->fs_filedes >= 0) { - struct file_struct *filep = &tcb->streams->sl_streams[i]; - if (filep->fs_filedes >= 0) - { #if CONFIG_STDIO_BUFFER_SIZE > 0 - sdbg(" fd=%d nbytes=%d\n", - filep->fs_filedes, - filep->fs_bufpos - filep->fs_bufstart); + sdbg(" fd=%d nbytes=%d\n", + filep->fs_filedes, + filep->fs_bufpos - filep->fs_bufstart); #else - sdbg(" fd=%d\n", filep->fs_filedes); + sdbg(" fd=%d\n", filep->fs_filedes); #endif - } } } #endif diff --git a/nuttx/arch/x86/src/common/up_exit.c b/nuttx/arch/x86/src/common/up_exit.c index 6a98c7dd0..dee6f7d49 100644 --- a/nuttx/arch/x86/src/common/up_exit.c +++ b/nuttx/arch/x86/src/common/up_exit.c @@ -1,7 +1,7 @@ /**************************************************************************** * common/up_exit.c * - * Copyright (C) 2011 Gregory Nutt. All rights reserved. + * Copyright (C) 2011, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -75,7 +75,11 @@ #if defined(CONFIG_DUMP_ON_EXIT) && defined(CONFIG_DEBUG) static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) { -#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NFILE_STREAMS > 0 +#if CONFIG_NFILE_DESCRIPTORS > 0 + FAR struct filelist *filelist; +#if CONFIG_NFILE_STREAMS > 0 + FAR struct streamlist *streamlist; +#endif int i; #endif @@ -83,40 +87,32 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) sdbg(" priority=%d state=%d\n", tcb->sched_priority, tcb->task_state); #if CONFIG_NFILE_DESCRIPTORS > 0 - if (tcb->filelist) + filelist = tcb->group->tg_filelist; + for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - FAR struct filelist *list = tcb->group->tg_filelist; - for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) + struct inode *inode = filelist->fl_files[i].f_inode; + if (inode) { - struct inode *inode = list->fl_files[i].f_inode; - if (inode) - { - sdbg(" fd=%d refcount=%d\n", - i, inode->i_crefs); - } + sdbg(" fd=%d refcount=%d\n", + i, inode->i_crefs); } } #endif #if CONFIG_NFILE_STREAMS > 0 - if (tcb->streams) + streamlist = tcb->group->tg_streamlist; + for (i = 0; i < CONFIG_NFILE_STREAMS; i++) { - sdbg(" streamlist refcount=%d\n", - tcb->streams->sl_crefs); - - for (i = 0; i < CONFIG_NFILE_STREAMS; i++) + struct file_struct *filep = &streamlist->sl_streams[i]; + if (filep->fs_filedes >= 0) { - struct file_struct *filep = &tcb->streams->sl_streams[i]; - if (filep->fs_filedes >= 0) - { #if CONFIG_STDIO_BUFFER_SIZE > 0 - sdbg(" fd=%d nbytes=%d\n", - filep->fs_filedes, - filep->fs_bufpos - filep->fs_bufstart); + sdbg(" fd=%d nbytes=%d\n", + filep->fs_filedes, + filep->fs_bufpos - filep->fs_bufstart); #else - sdbg(" fd=%d\n", filep->fs_filedes); + sdbg(" fd=%d\n", filep->fs_filedes); #endif - } } } #endif diff --git a/nuttx/arch/z16/src/common/up_exit.c b/nuttx/arch/z16/src/common/up_exit.c index ad0c55eed..20b808360 100644 --- a/nuttx/arch/z16/src/common/up_exit.c +++ b/nuttx/arch/z16/src/common/up_exit.c @@ -77,7 +77,11 @@ #if defined(CONFIG_DUMP_ON_EXIT) && defined(CONFIG_DEBUG) static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) { -#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NFILE_STREAMS > 0 +#if CONFIG_NFILE_DESCRIPTORS > 0 + FAR struct filelist *filelist; +#if CONFIG_NFILE_STREAMS > 0 + FAR struct streamlist *streamlist; +#endif int i; #endif @@ -85,40 +89,32 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) lldbg(" priority=%d state=%d\n", tcb->sched_priority, tcb->task_state); #if CONFIG_NFILE_DESCRIPTORS > 0 - if (tcb->filelist) + filelist = tcb->group->tg_filelist; + for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - FAR struct filelist *list = tcb->group->tg_filelist; - for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) + struct inode *inode = filelist->fl_files[i].f_inode; + if (inode) { - struct inode *inode = list->fl_files[i].f_inode; - if (inode) - { - lldbg(" fd=%d refcount=%d\n", - i, inode->i_crefs); - } + lldbg(" fd=%d refcount=%d\n", + i, inode->i_crefs); } } #endif #if CONFIG_NFILE_STREAMS > 0 - if (tcb->streams) + streamlist = tcb->group->tg_streamlist; + for (i = 0; i < CONFIG_NFILE_STREAMS; i++) { - lldbg(" streamlist refcount=%d\n", - tcb->streams->sl_crefs); - - for (i = 0; i < CONFIG_NFILE_STREAMS; i++) + struct file_struct *filep = &streamlist->sl_streams[i]; + if (filep->fs_filedes >= 0) { - struct file_struct *filep = &tcb->streams->sl_streams[i]; - if (filep->fs_filedes >= 0) - { #if CONFIG_STDIO_BUFFER_SIZE > 0 - lldbg(" fd=%d nbytes=%d\n", - filep->fs_filedes, - filep->fs_bufpos - filep->fs_bufstart); + lldbg(" fd=%d nbytes=%d\n", + filep->fs_filedes, + filep->fs_bufpos - filep->fs_bufstart); #else - lldbg(" fd=%d\n", filep->fs_filedes); + lldbg(" fd=%d\n", filep->fs_filedes); #endif - } } } #endif diff --git a/nuttx/arch/z80/src/common/up_exit.c b/nuttx/arch/z80/src/common/up_exit.c index 50289f52b..603a0bfbe 100644 --- a/nuttx/arch/z80/src/common/up_exit.c +++ b/nuttx/arch/z80/src/common/up_exit.c @@ -1,7 +1,7 @@ /**************************************************************************** * common/up_exit.c * - * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2009, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -78,7 +78,11 @@ #if defined(CONFIG_DUMP_ON_EXIT) && defined(CONFIG_DEBUG) static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) { -#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NFILE_STREAMS > 0 +#if CONFIG_NFILE_DESCRIPTORS > 0 + FAR struct filelist *filelist; +#if CONFIG_NFILE_STREAMS > 0 + FAR struct streamlist *streamlist; +#endif int i; #endif @@ -86,40 +90,32 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg) lldbg(" priority=%d state=%d\n", tcb->sched_priority, tcb->task_state); #if CONFIG_NFILE_DESCRIPTORS > 0 - if (tcb->filelist) + filelist = tcb->group->tg_filelist; + for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) { - FAR struct filelist *list = tcb->group->tg_filelist; - for (i = 0; i < CONFIG_NFILE_DESCRIPTORS; i++) + struct inode *inode = filelist->fl_files[i].f_inode; + if (inode) { - struct inode *inode = list->fl_files[i].f_inode; - if (inode) - { - lldbg(" fd=%d refcount=%d\n", - i, inode->i_crefs); - } + lldbg(" fd=%d refcount=%d\n", + i, inode->i_crefs); } } #endif #if CONFIG_NFILE_STREAMS > 0 - if (tcb->streams) + streamlist = tcb->group->tg_streamlist; + for (i = 0; i < CONFIG_NFILE_STREAMS; i++) { - lldbg(" streamlist refcount=%d\n", - tcb->streams->sl_crefs); - - for (i = 0; i < CONFIG_NFILE_STREAMS; i++) + struct file_struct *filep = &streamlist->sl_streams[i]; + if (filep->fs_filedes >= 0) { - struct file_struct *filep = &tcb->streams->sl_streams[i]; - if (filep->fs_filedes >= 0) - { #if CONFIG_STDIO_BUFFER_SIZE > 0 - lldbg(" fd=%d nbytes=%d\n", - filep->fs_filedes, - filep->fs_bufpos - filep->fs_bufstart); + lldbg(" fd=%d nbytes=%d\n", + filep->fs_filedes, + filep->fs_bufpos - filep->fs_bufstart); #else - lldbg(" fd=%d\n", filep->fs_filedes); + lldbg(" fd=%d\n", filep->fs_filedes); #endif - } } } #endif diff --git a/nuttx/fs/fs_fdopen.c b/nuttx/fs/fs_fdopen.c index 629083c77..d8a370482 100644 --- a/nuttx/fs/fs_fdopen.c +++ b/nuttx/fs/fs_fdopen.c @@ -144,6 +144,7 @@ FAR struct file_struct *fs_fdopen(int fd, int oflags, FAR _TCB *tcb) { tcb = sched_self(); } + DEBUGASSERT(tcb && tcb->group); /* Verify that this is a valid file/socket descriptor and that the * requested access can be support. @@ -191,9 +192,9 @@ FAR struct file_struct *fs_fdopen(int fd, int oflags, FAR _TCB *tcb) /* Get the stream list from the TCB */ - slist = tcb->streams; + slist = &tcb->group->tg_streamlist; - /* Find an unallocated FILE structure in the stream list */ + /* Find an unallocated FILE structure in the stream list */ ret = sem_wait(&slist->sl_sem); if (ret != OK) diff --git a/nuttx/include/nuttx/fs/fs.h b/nuttx/include/nuttx/fs/fs.h index 02855460c..93ca2a334 100644 --- a/nuttx/include/nuttx/fs/fs.h +++ b/nuttx/include/nuttx/fs/fs.h @@ -293,7 +293,6 @@ struct file_struct struct streamlist { - int sl_crefs; /* Reference count */ sem_t sl_sem; /* For thread safety */ struct file_struct sl_streams[CONFIG_NFILE_STREAMS]; }; diff --git a/nuttx/include/nuttx/lib.h b/nuttx/include/nuttx/lib.h index 220af2030..3bc581e18 100644 --- a/nuttx/include/nuttx/lib.h +++ b/nuttx/include/nuttx/lib.h @@ -2,7 +2,7 @@ * include/nuttx/lib.h * Non-standard, internal APIs available in lib/. * - * Copyright (C) 2007-2009, 2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2009, 2012-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -67,11 +67,10 @@ extern "C" { /* Functions contained in lib_init.c ****************************************/ -EXTERN void weak_function lib_initialize(void); +void weak_function lib_initialize(void); #if CONFIG_NFILE_STREAMS > 0 -EXTERN FAR struct streamlist *lib_alloclist(void); -EXTERN void lib_addreflist(FAR struct streamlist *list); -EXTERN void lib_releaselist(FAR struct streamlist *list); +void lib_streaminit(FAR struct streamlist *list); +void lib_releaselist(FAR struct streamlist *list); #endif #undef EXTERN diff --git a/nuttx/include/nuttx/sched.h b/nuttx/include/nuttx/sched.h index 1580a80d3..a084d50ba 100644 --- a/nuttx/include/nuttx/sched.h +++ b/nuttx/include/nuttx/sched.h @@ -81,6 +81,8 @@ # define HAVE_TASK_GROUP 1 # elif CONFIG_NFILE_DESCRIPTORS > 0 # define HAVE_TASK_GROUP 1 +# elif CONFIG_NFILE_STREAMS > 0 +# define HAVE_TASK_GROUP 1 # endif #endif @@ -303,7 +305,10 @@ struct task_group_s #endif /* FILE streams ***************************************************************/ - /* Not yet (see streamlist) */ + +#if CONFIG_NFILE_STREAMS > 0 + struct streamlist tg_streamlist; /* Holds C buffered I/O info */ +#endif /* CONFIG_NFILE_STREAMS */ /* Sockets ********************************************************************/ /* Not yet (see struct socketlist) */ @@ -445,12 +450,6 @@ struct _TCB int pterrno; /* Current per-thread errno */ - /* File system support ********************************************************/ - -#if CONFIG_NFILE_STREAMS > 0 - FAR struct streamlist *streams; /* Holds C buffered I/O info */ -#endif - /* Network socket *************************************************************/ #if CONFIG_NSOCKET_DESCRIPTORS > 0 diff --git a/nuttx/libc/misc/lib_init.c b/nuttx/libc/misc/lib_init.c index 6a120f7b1..434c46505 100644 --- a/nuttx/libc/misc/lib_init.c +++ b/nuttx/libc/misc/lib_init.c @@ -1,7 +1,7 @@ /************************************************************ * libc/misc/lib_init.c * - * Copyright (C) 2007, 2011 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2011, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -76,69 +76,35 @@ void weak_const_function lib_initialize(void) } #if CONFIG_NFILE_STREAMS > 0 -/* The following function is called when a new TCB is allocated. It - * creates the streamlist instance that is stored in the TCB. +/* The following function is called when a new task is allocated. It + * intializes the streamlist instance that is stored in the task group. */ -FAR struct streamlist *lib_alloclist(void) +void lib_streaminit(FAR struct streamlist *list) { - FAR struct streamlist *list; - list = (FAR struct streamlist*)lib_zalloc(sizeof(struct streamlist)); - if (list) - { - int i; - - /* Start with a reference count of one */ - - list->sl_crefs = 1; + int i; - /* Initialize the list access mutex */ + /* Initialize the list access mutex */ - (void)sem_init(&list->sl_sem, 0, 1); + (void)sem_init(&list->sl_sem, 0, 1); - /* Initialize each FILE structure */ + /* Initialize each FILE structure */ - for (i = 0; i < CONFIG_NFILE_STREAMS; i++) - { - /* Clear the IOB */ + for (i = 0; i < CONFIG_NFILE_STREAMS; i++) + { + /* Clear the IOB */ - memset(&list->sl_streams[i], 0, sizeof(FILE)); + memset(&list->sl_streams[i], 0, sizeof(FILE)); - /* Indicate not opened */ + /* Indicate not opened */ - list->sl_streams[i].fs_filedes = -1; + list->sl_streams[i].fs_filedes = -1; - /* Initialize the stream semaphore to one to support one-at- - * a-time access to private data sets. - */ - - lib_sem_initialize(&list->sl_streams[i]); - } - } - return list; + /* Initialize the stream semaphore to one to support one-at- + * a-time access to private data sets. + */ -} - -/* This function is called when a TCB is closed (such as with - * pthread_create(). It increases the reference count on the stream - * list. - */ - -void lib_addreflist(FAR struct streamlist *list) -{ - if (list) - { - /* Increment the reference count on the list. - * NOTE: that we disable interrupts to do this - * (vs. taking the list semaphore). We do this - * because file cleanup operations often must be - * done from the IDLE task which cannot wait - * on semaphores. - */ - - register irqstate_t flags = irqsave(); - list->sl_crefs++; - irqrestore(flags); + lib_sem_initialize(&list->sl_streams[i]); } } @@ -149,57 +115,33 @@ void lib_addreflist(FAR struct streamlist *list) void lib_releaselist(FAR struct streamlist *list) { - int crefs; - if (list) - { - /* Decrement the reference count on the list. - * NOTE: that we disable interrupts to do this - * (vs. taking the list semaphore). We do this - * because file cleanup operations often must be - * done from the IDLE task which cannot wait - * on semaphores. - */ - - register irqstate_t flags = irqsave(); - crefs = --(list->sl_crefs); - irqrestore(flags); - - /* If the count decrements to zero, then there is no reference - * to the structure and it should be deallocated. Since there - * are references, it would be an error if any task still held - * a reference to the list's semaphore. - */ - - if (crefs <= 0) - { #if CONFIG_STDIO_BUFFER_SIZE > 0 - int i; + int i; #endif - /* Destroy the semaphore and release the filelist */ - (void)sem_destroy(&list->sl_sem); + DEBUGASSERT(list); + + /* Destroy the semaphore and release the filelist */ - /* Release each stream in the list */ + (void)sem_destroy(&list->sl_sem); + + /* Release each stream in the list */ #if CONFIG_STDIO_BUFFER_SIZE > 0 - for (i = 0; i < CONFIG_NFILE_STREAMS; i++) - { - /* Destroy the semaphore that protects the IO buffer */ - - (void)sem_destroy(&list->sl_streams[i].fs_sem); - - /* Release the IO buffer */ - if (list->sl_streams[i].fs_bufstart) - { - sched_free(list->sl_streams[i].fs_bufstart); - } - } -#endif - /* Finally, release the list itself */ + for (i = 0; i < CONFIG_NFILE_STREAMS; i++) + { + /* Destroy the semaphore that protects the IO buffer */ - sched_free(list); - } - } + (void)sem_destroy(&list->sl_streams[i].fs_sem); + + /* Release the IO buffer */ + + if (list->sl_streams[i].fs_bufstart) + { + sched_free(list->sl_streams[i].fs_bufstart); + } + } +#endif } #endif /* CONFIG_NFILE_STREAMS */ diff --git a/nuttx/libc/stdio/lib_libflushall.c b/nuttx/libc/stdio/lib_libflushall.c index 7ac3da7e0..22baed968 100644 --- a/nuttx/libc/stdio/lib_libflushall.c +++ b/nuttx/libc/stdio/lib_libflushall.c @@ -1,7 +1,7 @@ /**************************************************************************** * libc/stdio/lib_libflushall.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 * * Redistribution and use in source and binary forms, with or without diff --git a/nuttx/sched/group_internal.h b/nuttx/sched/group_internal.h index 39d0a2b7c..e6e0dfd16 100644 --- a/nuttx/sched/group_internal.h +++ b/nuttx/sched/group_internal.h @@ -86,28 +86,11 @@ void group_leave(FAR _TCB *tcb); FAR struct task_group_s *group_find(gid_t gid); int group_addmember(FAR struct task_group_s *group, pid_t pid); int group_removemember(FAR struct task_group_s *group, pid_t pid); -#else -# define group_find(gid) (NULL) -# define group_addmember(group,pid) (0) -# define group_removemember(group,pid) (1) #endif #ifndef CONFIG_DISABLE_SIGNALS int group_signal(FAR struct task_group_s *group, FAR siginfo_t *info); -#else -# define group_signal(tcb,info) (0) #endif - -#else -# define group_allocate(tcb) (0) -# define group_initialize(tcb) (0) -# define group_bind(tcb) (0) -# define group_join(tcb) (0) -# define group_leave(tcb) -# define group_find(gid) (NULL) -# define group_addmember(group,pid) (0) -# define group_removemember(group,pid) (1) -# define group_signal(tcb,info) (0) #endif /* HAVE_TASK_GROUP */ /* Parent/child data management */ @@ -127,15 +110,13 @@ FAR struct child_status_s *group_removechild(FAR struct task_group_s *group, pid_t pid); void group_removechildren(FAR struct task_group_s *group); +#endif /* CONFIG_SCHED_CHILD_STATUS */ +#endif /* CONFIG_SCHED_HAVE_PARENT */ + /* File/network resources */ #if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0 -int group_releasefiles(FAR _TCB *tcb); -#else -# define group_releasefiles(t) (OK) +int group_releasefiles(FAR _TCB *tcb); #endif -#endif /* CONFIG_SCHED_CHILD_STATUS */ -#endif /* CONFIG_SCHED_HAVE_PARENT */ - #endif /* __SCHED_GROUP_INERNAL_H */ diff --git a/nuttx/sched/group_leave.c b/nuttx/sched/group_leave.c index 158ba30b5..70ef93666 100644 --- a/nuttx/sched/group_leave.c +++ b/nuttx/sched/group_leave.c @@ -165,6 +165,7 @@ static inline void group_release(FAR _TCB *tcb, env_release(tcb); #endif +#ifdef HAVE_GROUP_MEMBERS /* Remove the group from the list of groups */ group_remove(group); @@ -176,6 +177,7 @@ static inline void group_release(FAR _TCB *tcb, sched_free(group->tg_members); group->tg_members = NULL; } +#endif /* Release the group container itself */ diff --git a/nuttx/sched/group_releasefiles.c b/nuttx/sched/group_releasefiles.c index 40bf373b4..b33415c76 100644 --- a/nuttx/sched/group_releasefiles.c +++ b/nuttx/sched/group_releasefiles.c @@ -80,7 +80,9 @@ int group_releasefiles(_TCB *tcb) #if CONFIG_NFILE_DESCRIPTORS > 0 FAR struct task_group_s *group = tcb->group; DEBUGASSERT(group); +#endif +#if CONFIG_NFILE_DESCRIPTORS > 0 /* Free resources used by the file descriptor list */ files_releaselist(&group->tg_filelist); @@ -88,11 +90,8 @@ int group_releasefiles(_TCB *tcb) #if CONFIG_NFILE_STREAMS > 0 /* Free the stream list */ - if (tcb->streams) - { - lib_releaselist(tcb->streams); - tcb->streams = NULL; - } + lib_releaselist(&group->tg_streamlist); + #endif /* CONFIG_NFILE_STREAMS */ #endif /* CONFIG_NFILE_DESCRIPTORS */ diff --git a/nuttx/sched/sched_getfiles.c b/nuttx/sched/sched_getfiles.c index eca4ba3ff..17ca2bbf6 100644 --- a/nuttx/sched/sched_getfiles.c +++ b/nuttx/sched/sched_getfiles.c @@ -1,7 +1,7 @@ /************************************************************************ * sched/sched_getfiles.c * - * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2009, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without diff --git a/nuttx/sched/sched_getstreams.c b/nuttx/sched/sched_getstreams.c index f7c21ab4c..dab406e66 100644 --- a/nuttx/sched/sched_getstreams.c +++ b/nuttx/sched/sched_getstreams.c @@ -1,7 +1,7 @@ /**************************************************************************** * sched/sched_getstreams.c * - * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2008, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -70,7 +70,10 @@ FAR struct streamlist *sched_getstreams(void) { FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head; - return rtcb->streams; + FAR struct task_group_s *group = rtcb->group; + + DEBUGASSERT(group); + return &group->tg_streamlist; } #endif /* CONFIG_NFILE_DESCRIPTORS && CONFIG_NFILE_STREAMS */ diff --git a/nuttx/sched/sched_setuppthreadfiles.c b/nuttx/sched/sched_setuppthreadfiles.c index 78d6cbfec..91d72fa7f 100644 --- a/nuttx/sched/sched_setuppthreadfiles.c +++ b/nuttx/sched/sched_setuppthreadfiles.c @@ -77,8 +77,6 @@ int sched_setuppthreadfiles(FAR _TCB *tcb) { - FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head; - #if CONFIG_NSOCKET_DESCRIPTORS > 0 /* The child thread inherits the parent socket descriptors */ @@ -87,13 +85,6 @@ int sched_setuppthreadfiles(FAR _TCB *tcb) #endif /* CONFIG_NSOCKET_DESCRIPTORS */ -#if CONFIG_NFILE_STREAMS > 0 - /* The child thread inherits the parent streams */ - - tcb->streams = rtcb->streams; - lib_addreflist(tcb->streams); - -#endif /* CONFIG_NFILE_STREAMS */ return OK; } diff --git a/nuttx/sched/sched_setupstreams.c b/nuttx/sched/sched_setupstreams.c index 22895b047..fb2e4d0be 100644 --- a/nuttx/sched/sched_setupstreams.c +++ b/nuttx/sched/sched_setupstreams.c @@ -72,24 +72,23 @@ int sched_setupstreams(FAR _TCB *tcb) { - /* Allocate file streams for the TCB */ - - tcb->streams = lib_alloclist(); - if (tcb->streams) - { - /* fdopen to get the stdin, stdout and stderr streams. - * The following logic depends on the fact that the library - * layer will allocate FILEs in order. - * - * fd = 0 is stdin (read-only) - * fd = 1 is stdout (write-only, append) - * fd = 2 is stderr (write-only, append) - */ - - (void)fs_fdopen(0, O_RDONLY, tcb); - (void)fs_fdopen(1, O_WROK|O_CREAT, tcb); - (void)fs_fdopen(2, O_WROK|O_CREAT, tcb); - } + DEBUGASSERT(tcb && tcb->group); + + /* Initialize file streams for the task group */ + + lib_streaminit(&tcb->group->tg_streamlist); + + /* fdopen to get the stdin, stdout and stderr streams. The following logic + * depends on the fact that the library layer will allocate FILEs in order. + * + * fd = 0 is stdin (read-only) + * fd = 1 is stdout (write-only, append) + * fd = 2 is stderr (write-only, append) + */ + + (void)fs_fdopen(0, O_RDONLY, tcb); + (void)fs_fdopen(1, O_WROK|O_CREAT, tcb); + (void)fs_fdopen(2, O_WROK|O_CREAT, tcb); return OK; } diff --git a/nuttx/sched/task_exithook.c b/nuttx/sched/task_exithook.c index 5a2b9e57e..889df25e0 100644 --- a/nuttx/sched/task_exithook.c +++ b/nuttx/sched/task_exithook.c @@ -543,7 +543,7 @@ void task_exithook(FAR _TCB *tcb, int status) */ #if CONFIG_NFILE_STREAMS > 0 - (void)lib_flushall(tcb->streams); + (void)lib_flushall(&tcb->group->tg_streamlist); #endif /* Leave the task group. Perhaps discarding any un-reaped child -- cgit v1.2.3 From 47b94bafa5045532f239ea57a3610873b1a71368 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 26 Jan 2013 23:49:02 +0000 Subject: Move socket data from TCB to task group structure. git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5570 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 6 +- nuttx/include/nuttx/net/net.h | 8 +- nuttx/include/nuttx/sched.h | 13 +- nuttx/net/net_sockets.c | 100 +++----------- nuttx/sched/Makefile | 6 +- nuttx/sched/env_clearenv.c | 5 +- nuttx/sched/env_dup.c | 12 +- nuttx/sched/env_internal.h | 8 +- nuttx/sched/env_release.c | 11 +- nuttx/sched/group_create.c | 2 +- nuttx/sched/group_internal.h | 8 +- nuttx/sched/group_leave.c | 34 +++-- nuttx/sched/group_releasefiles.c | 112 --------------- nuttx/sched/group_setupidlefiles.c | 147 ++++++++++++++++++++ nuttx/sched/group_setupstreams.c | 97 +++++++++++++ nuttx/sched/group_setuptaskfiles.c | 245 +++++++++++++++++++++++++++++++++ nuttx/sched/os_internal.h | 17 --- nuttx/sched/os_start.c | 2 +- nuttx/sched/pthread_create.c | 9 -- nuttx/sched/sched_getsockets.c | 7 +- nuttx/sched/sched_setupidlefiles.c | 151 --------------------- nuttx/sched/sched_setuppthreadfiles.c | 91 ------------- nuttx/sched/sched_setupstreams.c | 97 ------------- nuttx/sched/sched_setuptaskfiles.c | 248 ---------------------------------- nuttx/sched/task_create.c | 2 +- nuttx/sched/task_init.c | 2 +- nuttx/sched/task_vfork.c | 2 +- 27 files changed, 583 insertions(+), 859 deletions(-) delete mode 100644 nuttx/sched/group_releasefiles.c create mode 100644 nuttx/sched/group_setupidlefiles.c create mode 100644 nuttx/sched/group_setupstreams.c create mode 100644 nuttx/sched/group_setuptaskfiles.c delete mode 100644 nuttx/sched/sched_setupidlefiles.c delete mode 100644 nuttx/sched/sched_setuppthreadfiles.c delete mode 100644 nuttx/sched/sched_setupstreams.c delete mode 100644 nuttx/sched/sched_setuptaskfiles.c (limited to 'nuttx/sched') diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index b5933f620..255d69a3d 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -4035,6 +4035,8 @@ task ID in the child task's TCB. Instead, keep the parent task group IN the child task's task group. * fs/, sched/, include/nuttx/sched.h, and include/nutts/fs/fs.h: - Move file data from TCB to task group structure. + Move file data from the TCB to the task group structure. * libc/stdio/, sched/, include/nuttx/lib.h, and include/nutts/fs/fs.h: - Move stream data from TCB to task group structure. + Move stream data from the TCB to the task group structure. + * net/, sched/, and include/nuttx/net/net.h: Move socket data + from the TCB to the task group structure. diff --git a/nuttx/include/nuttx/net/net.h b/nuttx/include/nuttx/net/net.h index b625b2fbe..d23fb8796 100644 --- a/nuttx/include/nuttx/net/net.h +++ b/nuttx/include/nuttx/net/net.h @@ -1,7 +1,7 @@ /**************************************************************************** * include/nuttx/net/net.h * - * Copyright (C) 2007, 2009-2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2009-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -106,7 +106,6 @@ struct socket struct socketlist { sem_t sl_sem; /* Manage access to the socket list */ - int16_t sl_crefs; /* Reference count */ struct socket sl_sockets[CONFIG_NSOCKET_DESCRIPTORS]; }; #endif @@ -145,9 +144,8 @@ int net_checksd(int fd, int oflags); */ void weak_function net_initialize(void); -FAR struct socketlist *net_alloclist(void); -int net_addreflist(FAR struct socketlist *list); -int net_releaselist(FAR struct socketlist *list); +void net_initlist(FAR struct socketlist *list); +void net_releaselist(FAR struct socketlist *list); /* Given a socket descriptor, return the underly NuttX-specific socket * structure. diff --git a/nuttx/include/nuttx/sched.h b/nuttx/include/nuttx/sched.h index a084d50ba..244455cd4 100644 --- a/nuttx/include/nuttx/sched.h +++ b/nuttx/include/nuttx/sched.h @@ -83,6 +83,8 @@ # define HAVE_TASK_GROUP 1 # elif CONFIG_NFILE_STREAMS > 0 # define HAVE_TASK_GROUP 1 +# elif CONFIG_NSOCKET_DESCRIPTORS > 0 +# define HAVE_TASK_GROUP 1 # endif #endif @@ -311,7 +313,10 @@ struct task_group_s #endif /* CONFIG_NFILE_STREAMS */ /* Sockets ********************************************************************/ - /* Not yet (see struct socketlist) */ + +#if CONFIG_NSOCKET_DESCRIPTORS > 0 + struct socketlist tg_socketlist; /* Maps socket descriptor to socket */ +#endif }; #endif @@ -450,12 +455,6 @@ struct _TCB int pterrno; /* Current per-thread errno */ - /* Network socket *************************************************************/ - -#if CONFIG_NSOCKET_DESCRIPTORS > 0 - FAR struct socketlist *sockets; /* Maps file descriptor to file */ -#endif - /* State save areas ***********************************************************/ /* The form and content of these fields are processor-specific. */ diff --git a/nuttx/net/net_sockets.c b/nuttx/net/net_sockets.c index 81e48c121..ddb54c98c 100644 --- a/nuttx/net/net_sockets.c +++ b/nuttx/net/net_sockets.c @@ -116,99 +116,37 @@ void net_initialize(void) #if CONFIG_NSOCKET_DESCRIPTORS > 0 -/* Allocate a list of files for a new task */ +/* Initialize a list of sockets for a new task */ -FAR struct socketlist *net_alloclist(void) +void net_initlist(FAR struct socketlist *list) { - FAR struct socketlist *list; - list = (FAR struct socketlist*)kzalloc(sizeof(struct socketlist)); - if (list) - { - /* Start with a reference count of one */ - - list->sl_crefs = 1; - - /* Initialize the list access mutex */ + /* Initialize the list access mutex */ - (void)sem_init(&list->sl_sem, 0, 1); - } - return list; + (void)sem_init(&list->sl_sem, 0, 1); } -/* Increase the reference count on a file list */ +/* Release release resources held by the socket list */ -int net_addreflist(FAR struct socketlist *list) +void net_releaselist(FAR struct socketlist *list) { - if (list) - { - /* Increment the reference count on the list. - * NOTE: that we disable interrupts to do this - * (vs. taking the list semaphore). We do this - * because file cleanup operations often must be - * done from the IDLE task which cannot wait - * on semaphores. - */ - - register uip_lock_t flags = uip_lock(); - list->sl_crefs++; - uip_unlock(flags); - } - return OK; -} + int ndx; -/* Release a reference to the file list */ + DEBUGASSERT(list); -int net_releaselist(FAR struct socketlist *list) -{ - int crefs; - int ndx; + /* Close each open socket in the list. */ - if (list) + for (ndx = 0; ndx < CONFIG_NSOCKET_DESCRIPTORS; ndx++) { - /* Decrement the reference count on the list. - * NOTE: that we disable interrupts to do this - * (vs. taking the list semaphore). We do this - * because file cleanup operations often must be - * done from the IDLE task which cannot wait - * on semaphores. - */ - - uip_lock_t flags = uip_lock(); - crefs = --(list->sl_crefs); - uip_unlock(flags); - - /* If the count decrements to zero, then there is no reference - * to the structure and it should be deallocated. Since there - * are references, it would be an error if any task still held - * a reference to the list's semaphore. - */ - - if (crefs <= 0) - { - /* Close each open socket in the list - * REVISIT: psock_close() will attempt to use semaphores. - * If we actually are in the IDLE thread, then could this cause - * problems? Probably not, if the task has exited and crefs is - * zero, then there probably could not be a contender for the - * semaphore. - */ - - for (ndx = 0; ndx < CONFIG_NSOCKET_DESCRIPTORS; ndx++) - { - FAR struct socket *psock = &list->sl_sockets[ndx]; - if (psock->s_crefs > 0) - { - (void)psock_close(psock); - } - } - - /* Destroy the semaphore and release the filelist */ - - (void)sem_destroy(&list->sl_sem); - sched_free(list); - } + FAR struct socket *psock = &list->sl_sockets[ndx]; + if (psock->s_crefs > 0) + { + (void)psock_close(psock); + } } - return OK; + + /* Destroy the semaphore */ + + (void)sem_destroy(&list->sl_sem); } int sockfd_allocate(int minsd) diff --git a/nuttx/sched/Makefile b/nuttx/sched/Makefile index c8fe7cf69..7710ae058 100644 --- a/nuttx/sched/Makefile +++ b/nuttx/sched/Makefile @@ -39,9 +39,7 @@ ASRCS = AOBJS = $(ASRCS:.S=$(OBJEXT)) 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 +MISC_SRCS += sched_garbage.c sched_getfiles.c sched_getsockets.c sched_getstreams.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 @@ -81,7 +79,7 @@ endif endif GRP_SRCS = group_create.c group_join.c group_leave.c group_find.c -GRP_SRCS += group_releasefiles.c +GRP_SRCS += group_setupstreams.c group_setupidlefiles.c group_setuptaskfiles.c ifeq ($(CONFIG_SCHED_HAVE_PARENT),y) GRP_SRCS += task_reparent.c diff --git a/nuttx/sched/env_clearenv.c b/nuttx/sched/env_clearenv.c index a9e9f5efd..062fd60ed 100644 --- a/nuttx/sched/env_clearenv.c +++ b/nuttx/sched/env_clearenv.c @@ -74,7 +74,10 @@ int clearenv(void) { - env_release((FAR _TCB*)g_readytorun.head); + FAR _TCB *tcb = (FAR _TCB*)g_readytorun.head; + DEBUGASSERT(tcb->group); + + env_release(tcb->group); return OK; } diff --git a/nuttx/sched/env_dup.c b/nuttx/sched/env_dup.c index 479f7cae7..3b653b010 100644 --- a/nuttx/sched/env_dup.c +++ b/nuttx/sched/env_dup.c @@ -68,8 +68,8 @@ * exact duplicate of the parent task's environment. * * Parameters: - * ctcb The child tcb to receive the newly allocated copy of the parent - * TCB's environment structure with reference count equal to one + * group The child task group to receive the newly allocated copy of the + * parent task groups environment structure. * * Return Value: * zero on success @@ -79,14 +79,14 @@ * ****************************************************************************/ -int env_dup(FAR _TCB *ctcb) +int env_dup(FAR struct task_group_s *group) { FAR _TCB *ptcb = (FAR _TCB*)g_readytorun.head; FAR char *envp = NULL; size_t envlen; int ret = OK; - DEBUGASSERT(ctcb && ptcb && ctcb->group && ptcb->group); + DEBUGASSERT(group && ptcb && ptcb->group); /* Pre-emption must be disabled throughout the following because the * environment may be shared. @@ -108,8 +108,8 @@ int env_dup(FAR _TCB *ctcb) } else { - ctcb->group->tg_envsize = envlen; - ctcb->group->tg_envp = envp; + group->tg_envsize = envlen; + group->tg_envp = envp; memcpy(envp, ptcb->group->tg_envp, envlen); } } diff --git a/nuttx/sched/env_internal.h b/nuttx/sched/env_internal.h index 6f1097c0b..e02bf289d 100644 --- a/nuttx/sched/env_internal.h +++ b/nuttx/sched/env_internal.h @@ -49,8 +49,8 @@ ****************************************************************************/ #ifdef CONFIG_DISABLE_ENVIRON -# define env_dup(ptcb) (0) -# define env_release(ptcb) (0) +# define env_dup(group) (0) +# define env_release(group) (0) #else /**************************************************************************** @@ -75,8 +75,8 @@ extern "C" /* Functions used by the task/pthread creation and destruction logic */ -int env_dup(FAR _TCB *ctcb); -void env_release(FAR _TCB *tcb); +int env_dup(FAR struct task_group_s *group); +void env_release(FAR struct task_group_s *group); /* Functions used internally by the environment handling logic */ diff --git a/nuttx/sched/env_release.c b/nuttx/sched/env_release.c index 4de55c388..aebb1f7e8 100644 --- a/nuttx/sched/env_release.c +++ b/nuttx/sched/env_release.c @@ -64,8 +64,8 @@ * environ to NULL. * * Parameters: - * tcb Identifies the TCB containing the environment structure to be - * released. + * group Identifies the task group containing the environment structure + * to be released. * * Return Value: * None @@ -75,12 +75,9 @@ * ****************************************************************************/ -void env_release(FAR _TCB *tcb) +void env_release(FAR struct task_group_s *group) { - FAR struct task_group_s *group; - - DEBUGASSERT(tcb && tcb->group); - group = tcb->group; + DEBUGASSERT(group); /* Free any allocate environment strings */ diff --git a/nuttx/sched/group_create.c b/nuttx/sched/group_create.c index 768641be1..24f6923aa 100644 --- a/nuttx/sched/group_create.c +++ b/nuttx/sched/group_create.c @@ -198,7 +198,7 @@ int group_allocate(FAR _TCB *tcb) /* Duplicate the parent tasks envionment */ - ret = env_dup(tcb); + ret = env_dup(tcb->group); if (ret < 0) { kfree(tcb->group); diff --git a/nuttx/sched/group_internal.h b/nuttx/sched/group_internal.h index e6e0dfd16..ca6aacff7 100644 --- a/nuttx/sched/group_internal.h +++ b/nuttx/sched/group_internal.h @@ -113,10 +113,14 @@ void group_removechildren(FAR struct task_group_s *group); #endif /* CONFIG_SCHED_CHILD_STATUS */ #endif /* CONFIG_SCHED_HAVE_PARENT */ -/* File/network resources */ +/* Group data resource configuration */ #if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0 -int group_releasefiles(FAR _TCB *tcb); +int group_setupidlefiles(FAR _TCB *tcb); +int group_setuptaskfiles(FAR _TCB *tcb); +#if CONFIG_NFILE_STREAMS > 0 +int group_setupstreams(FAR _TCB *tcb); +#endif #endif #endif /* __SCHED_GROUP_INERNAL_H */ diff --git a/nuttx/sched/group_leave.c b/nuttx/sched/group_leave.c index 70ef93666..4dec30633 100644 --- a/nuttx/sched/group_leave.c +++ b/nuttx/sched/group_leave.c @@ -44,6 +44,10 @@ #include #include +#include +#include +#include + #include "group_internal.h" #include "env_internal.h" @@ -142,8 +146,7 @@ void group_remove(FAR struct task_group_s *group) * *****************************************************************************/ -static inline void group_release(FAR _TCB *tcb, - FAR struct task_group_s *group) +static inline void group_release(FAR struct task_group_s *group) { /* Free all un-reaped child exit status */ @@ -155,14 +158,29 @@ static inline void group_release(FAR _TCB *tcb, * soon as possible while we still have a functioning task. */ -#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0 - (void)group_releasefiles(tcb); -#endif +#if CONFIG_NFILE_DESCRIPTORS > 0 + /* Free resources held by the file descriptor list */ + + files_releaselist(&group->tg_filelist); + +#if CONFIG_NFILE_STREAMS > 0 + /* Free resource held by the stream list */ + + lib_releaselist(&group->tg_streamlist); + +#endif /* CONFIG_NFILE_STREAMS */ +#endif /* CONFIG_NFILE_DESCRIPTORS */ + +#if CONFIG_NSOCKET_DESCRIPTORS > 0 + /* Free resource held by the socket list */ + + net_releaselist(&group->tg_socketlist); +#endif /* CONFIG_NSOCKET_DESCRIPTORS */ /* Release all shared environment variables */ #ifndef CONFIG_DISABLE_ENVIRON - env_release(tcb); + env_release(group); #endif #ifdef HAVE_GROUP_MEMBERS @@ -232,7 +250,7 @@ void group_leave(FAR _TCB *tcb) { /* Release all of the resource held by the task group */ - group_release(tcb, group); + group_release(group); } /* In any event, we can detach the group from the TCB so that we won't @@ -271,7 +289,7 @@ void group_leave(FAR _TCB *tcb) { /* Release all of the resource held by the task group */ - group_release(tcb, group); + group_release(group); } /* In any event, we can detach the group from the TCB so we won't do diff --git a/nuttx/sched/group_releasefiles.c b/nuttx/sched/group_releasefiles.c deleted file mode 100644 index b33415c76..000000000 --- a/nuttx/sched/group_releasefiles.c +++ /dev/null @@ -1,112 +0,0 @@ -/**************************************************************************** - * sched/group_releasefiles.c - * - * Copyright (C) 2007, 2008, 2012-2013 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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 - -#include -#include -#include -#include - -#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0 - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: group_releasefiles - * - * Description: - * Release file resources attached to a TCB. This file may be called - * multiple times as a task exists. It will be called as early as possible - * to support proper closing of complex drivers that may need to wait - * on external events. - * - * Parameters: - * tcb - tcb of the new task. - * - * Return Value: - * None - * - * Assumptions: - * - ****************************************************************************/ - -int group_releasefiles(_TCB *tcb) -{ - if (tcb) - { -#if CONFIG_NFILE_DESCRIPTORS > 0 - FAR struct task_group_s *group = tcb->group; - DEBUGASSERT(group); -#endif - -#if CONFIG_NFILE_DESCRIPTORS > 0 - /* Free resources used by the file descriptor list */ - - files_releaselist(&group->tg_filelist); - -#if CONFIG_NFILE_STREAMS > 0 - /* Free the stream list */ - - lib_releaselist(&group->tg_streamlist); - -#endif /* CONFIG_NFILE_STREAMS */ -#endif /* CONFIG_NFILE_DESCRIPTORS */ - -#if CONFIG_NSOCKET_DESCRIPTORS > 0 - /* Free the file descriptor list */ - - if (tcb->sockets) - { - net_releaselist(tcb->sockets); - tcb->sockets = NULL; - } -#endif /* CONFIG_NSOCKET_DESCRIPTORS */ - } - - return OK; -} - -#endif /* CONFIG_NFILE_DESCRIPTORS || CONFIG_NSOCKET_DESCRIPTORS */ diff --git a/nuttx/sched/group_setupidlefiles.c b/nuttx/sched/group_setupidlefiles.c new file mode 100644 index 000000000..98cc7885e --- /dev/null +++ b/nuttx/sched/group_setupidlefiles.c @@ -0,0 +1,147 @@ +/**************************************************************************** + * sched/group_setupidlefiles.c + * + * Copyright (C) 2007-2010, 2012-2013 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 + +#include +#include +#include +#include +#include +#include + +#include +#include + +#include "os_internal.h" + +#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0 + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: group_setupidlefiles + * + * Description: + * Configure the idle thread's TCB. + * + * Parameters: + * tcb - tcb of the idle task. + * + * Return Value: + * None + * + * Assumptions: + * + ****************************************************************************/ + +int group_setupidlefiles(FAR _TCB *tcb) +{ +#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NFILE_DESCRIPTORS > 0 + FAR struct task_group_s *group = tcb->group; +#endif +#if CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_DEV_CONSOLE) + int fd; +#endif + +#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NFILE_DESCRIPTORS > 0 + DEBUGASSERT(group); +#endif + +#if CONFIG_NFILE_DESCRIPTORS > 0 + /* Initialize file descriptors for the TCB */ + + files_initlist(&group->tg_filelist); +#endif + +#if CONFIG_NSOCKET_DESCRIPTORS > 0 + /* Allocate socket descriptors for the TCB */ + + net_initlist(&group->tg_socketlist); +#endif + + /* Open stdin, dup to get stdout and stderr. This should always + * be the first file opened and, hence, should always get file + * descriptor 0. + */ + +#if CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_DEV_CONSOLE) + fd = open("/dev/console", O_RDWR); + if (fd == 0) + { + /* Successfully opened /dev/console as stdin (fd == 0) */ + + (void)file_dup2(0, 1); + (void)file_dup2(0, 2); + } + else + { + /* We failed to open /dev/console OR for some reason, we opened + * it and got some file descriptor other than 0. + */ + + if (fd > 0) + { + slldbg("Open /dev/console fd: %d\n", fd); + (void)close(fd); + } + else + { + slldbg("Failed to open /dev/console: %d\n", errno); + } + return -ENFILE; + } +#endif + + /* Allocate file/socket streams for the TCB */ + +#if CONFIG_NFILE_STREAMS > 0 + return group_setupstreams(tcb); +#else + return OK; +#endif +} + +#endif /* CONFIG_NFILE_DESCRIPTORS || CONFIG_NSOCKET_DESCRIPTORS */ diff --git a/nuttx/sched/group_setupstreams.c b/nuttx/sched/group_setupstreams.c new file mode 100644 index 000000000..88e266280 --- /dev/null +++ b/nuttx/sched/group_setupstreams.c @@ -0,0 +1,97 @@ +/**************************************************************************** + * group_setupstreams.c + * + * Copyright (C) 2007-2008, 2010-2013 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 + +#include +#include + +#include +#include +#include + +/* Make sure that there are file or socket descriptors in the system and + * that some number of streams have been configured. + */ + +#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0 +#if CONFIG_NFILE_STREAMS > 0 + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: group_setupstreams + * + * Description: + * Setup streams data structures that may be used for standard C buffered + * I/O with underlying socket or file desciptors + * + ****************************************************************************/ + +int group_setupstreams(FAR _TCB *tcb) +{ + DEBUGASSERT(tcb && tcb->group); + + /* Initialize file streams for the task group */ + + lib_streaminit(&tcb->group->tg_streamlist); + + /* fdopen to get the stdin, stdout and stderr streams. The following logic + * depends on the fact that the library layer will allocate FILEs in order. + * + * fd = 0 is stdin (read-only) + * fd = 1 is stdout (write-only, append) + * fd = 2 is stderr (write-only, append) + */ + + (void)fs_fdopen(0, O_RDONLY, tcb); + (void)fs_fdopen(1, O_WROK|O_CREAT, tcb); + (void)fs_fdopen(2, O_WROK|O_CREAT, tcb); + + return OK; +} + +#endif /* CONFIG_NFILE_STREAMS > 0 */ +#endif /* CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0*/ diff --git a/nuttx/sched/group_setuptaskfiles.c b/nuttx/sched/group_setuptaskfiles.c new file mode 100644 index 000000000..d52adcfee --- /dev/null +++ b/nuttx/sched/group_setuptaskfiles.c @@ -0,0 +1,245 @@ +/**************************************************************************** + * sched/group_setuptaskfiles.c + * + * Copyright (C) 2007-2008, 2010, 2012-2013 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 + +#include +#include + +#include +#include + +#include "os_internal.h" + +#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0 + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Determine how many file descriptors to clone. If CONFIG_FDCLONE_DISABLE + * is set, no file descriptors will be cloned. If CONFIG_FDCLONE_STDIO is + * set, only the first three descriptors (stdin, stdout, and stderr) will + * be cloned. Otherwise all file descriptors will be cloned. + */ + +#if defined(CONFIG_FDCLONE_STDIO) && CONFIG_NFILE_DESCRIPTORS > 3 +# define NFDS_TOCLONE 3 +#else +# define NFDS_TOCLONE CONFIG_NFILE_DESCRIPTORS +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: sched_dupfiles + * + * Description: + * Duplicate parent task's file descriptors. + * + * Input Parameters: + * tcb - tcb of the new task. + * + * Return Value: + * None + * + ****************************************************************************/ + +#if CONFIG_NFILE_DESCRIPTORS > 0 && !defined(CONFIG_FDCLONE_DISABLE) +static inline void sched_dupfiles(FAR _TCB *tcb) +{ + /* The parent task is the one at the head of the ready-to-run list */ + + FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head; + FAR struct file *parent; + FAR struct file *child; + int i; + + DEBUGASSERT(tcb && tcb->group && rtcb->group); + + /* Duplicate the file descriptors. This will be either all of the + * file descriptors or just the first three (stdin, stdout, and stderr) + * if CONFIG_FDCLONE_STDIO is defined. NFSDS_TOCLONE is set + * accordingly above. + */ + + /* Get pointers to the parent and child task file lists */ + + parent = rtcb->group->tg_filelist.fl_files; + child = tcb->group->tg_filelist.fl_files; + + /* Check each file in the parent file list */ + + for (i = 0; i < NFDS_TOCLONE; i++) + { + /* Check if this file is opened by the parent. We can tell if + * if the file is open because it contain a reference to a non-NULL + * i-node structure. + */ + + if (parent[i].f_inode) + { + /* Yes... duplicate it for the child */ + + (void)files_dup(&parent[i], &child[i]); + } + } +} +#else /* CONFIG_NFILE_DESCRIPTORS && !CONFIG_FDCLONE_DISABLE */ +# define sched_dupfiles(tcb) +#endif /* CONFIG_NFILE_DESCRIPTORS && !CONFIG_FDCLONE_DISABLE */ + +/**************************************************************************** + * Name: sched_dupsockets + * + * Description: + * Duplicate the parent task's socket descriptors. + * + * Input Parameters: + * tcb - tcb of the new task. + * + * Return Value: + * None + * + ****************************************************************************/ + +#if CONFIG_NSOCKET_DESCRIPTORS > 0 && !defined(CONFIG_SDCLONE_DISABLE) +static inline void sched_dupsockets(FAR _TCB *tcb) +{ + /* The parent task is the one at the head of the ready-to-run list */ + + FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head; + FAR struct socket *parent; + FAR struct socket *child; + int i; + + /* Duplicate the socket descriptors of all sockets opened by the parent + * task. + */ + + DEBUGASSERT(tcb && tcb->group && rtcb->group); + + /* Get pointers to the parent and child task socket lists */ + + parent = rtcb->group->tg_sockets->sl_sockets; + child = tcb->group->tg_sockets->sl_sockets; + + /* Check each socket in the parent socket list */ + + for (i = 0; i < CONFIG_NSOCKET_DESCRIPTORS; i++) + { + /* Check if this parent socket is allocated. We can tell if the + * socket is allocated because it will have a positive, non-zero + * reference count. + */ + + if (parent[i].s_crefs > 0) + { + /* Yes... duplicate it for the child */ + + (void)net_clone(&parent[i], &child[i]); + } + } +} +#else /* CONFIG_NSOCKET_DESCRIPTORS && !CONFIG_SDCLONE_DISABLE */ +# define sched_dupsockets(tcb) +#endif /* CONFIG_NSOCKET_DESCRIPTORS && !CONFIG_SDCLONE_DISABLE */ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: group_setuptaskfiles + * + * Description: + * Configure a newly allocated TCB so that it will inherit + * file descriptors and streams from the parent task. + * + * Parameters: + * tcb - tcb of the new task. + * + * Return Value: + * Zero (OK) is returned on success; A negated errno value is returned on + * failure. + * + * Assumptions: + * + ****************************************************************************/ + +int group_setuptaskfiles(FAR _TCB *tcb) +{ +#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0 + FAR struct task_group_s *group = tcb->group; + + DEBUGASSERT(group); +#endif + +#if CONFIG_NFILE_DESCRIPTORS > 0 + /* Initialize file descriptors for the TCB */ + + files_initlist(&group->tg_filelist); +#endif + +#if CONFIG_NSOCKET_DESCRIPTORS > 0 + /* Allocate socket descriptors for the TCB */ + + net_initlist(&group->tg_socketlist); +#endif + + /* Duplicate the parent task's file descriptors */ + + sched_dupfiles(tcb); + + /* Duplicate the parent task's socket descriptors */ + + sched_dupsockets(tcb); + + /* Allocate file/socket streams for the new TCB */ + +#if CONFIG_NFILE_STREAMS > 0 + return group_setupstreams(tcb); +#else + return OK; +#endif +} + +#endif /* CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0*/ diff --git a/nuttx/sched/os_internal.h b/nuttx/sched/os_internal.h index 5aa6487d0..262a40ccc 100644 --- a/nuttx/sched/os_internal.h +++ b/nuttx/sched/os_internal.h @@ -99,14 +99,6 @@ enum os_crash_codes_e #define MAX_TASKS_MASK (CONFIG_MAX_TASKS-1) #define PIDHASH(pid) ((pid) & MAX_TASKS_MASK) -/* Stubs used when there are no file descriptors */ - -#if CONFIG_NFILE_DESCRIPTORS <= 0 && CONFIG_NSOCKET_DESCRIPTORS <= 0 -# define sched_setupidlefiles(t) (OK) -# define sched_setuptaskfiles(t) (OK) -# define sched_setuppthreadfiles(t) (OK) -#endif - /* One processor family supported by NuttX has a single, fixed hardware stack. * That is the 8051 family. So for that family only, there is a variant form * of kernel_thread() that does not take a stack size parameter. The following @@ -293,15 +285,6 @@ int sched_reprioritize(FAR _TCB *tcb, int sched_priority); FAR _TCB *sched_gettcb(pid_t pid); bool sched_verifytcb(FAR _TCB *tcb); -#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0 -int sched_setupidlefiles(FAR _TCB *tcb); -int sched_setuptaskfiles(FAR _TCB *tcb); -int sched_setuppthreadfiles(FAR _TCB *tcb); -#if CONFIG_NFILE_STREAMS > 0 -int sched_setupstreams(FAR _TCB *tcb); -#endif -#endif - int sched_releasetcb(FAR _TCB *tcb); void sched_garbagecollection(void); diff --git a/nuttx/sched/os_start.c b/nuttx/sched/os_start.c index b2551d2a3..5e6eaa858 100644 --- a/nuttx/sched/os_start.c +++ b/nuttx/sched/os_start.c @@ -451,7 +451,7 @@ void os_start(void) * inherited by all of the threads created by the IDLE task. */ - (void)sched_setupidlefiles(&g_idletcb); + (void)group_setupidlefiles(&g_idletcb); /* Create initial tasks and bring-up the system */ diff --git a/nuttx/sched/pthread_create.c b/nuttx/sched/pthread_create.c index 9fd6a4a61..48a0788a6 100644 --- a/nuttx/sched/pthread_create.c +++ b/nuttx/sched/pthread_create.c @@ -296,15 +296,6 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr, } #endif - /* Associate file descriptors with the new task */ - - ret = sched_setuppthreadfiles(ptcb); - if (ret != OK) - { - errcode = ret; - goto errout_with_tcb; - } - /* Allocate a detachable structure to support pthread_join logic */ pjoin = (FAR join_t*)kzalloc(sizeof(join_t)); diff --git a/nuttx/sched/sched_getsockets.c b/nuttx/sched/sched_getsockets.c index cd499420f..ea988d6ff 100644 --- a/nuttx/sched/sched_getsockets.c +++ b/nuttx/sched/sched_getsockets.c @@ -1,7 +1,7 @@ /************************************************************************ * sched/sched_getsockets.c * - * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2009, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -71,7 +71,10 @@ FAR struct socketlist *sched_getsockets(void) { FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head; - return rtcb->sockets; + FAR struct task_group_s *group = rtcb->group; + + DEBUGASSERT(group); + return &group->tg_socketlist; } #endif /* CONFIG_NSOCKET_DESCRIPTORS */ diff --git a/nuttx/sched/sched_setupidlefiles.c b/nuttx/sched/sched_setupidlefiles.c deleted file mode 100644 index 4bbd4d3b7..000000000 --- a/nuttx/sched/sched_setupidlefiles.c +++ /dev/null @@ -1,151 +0,0 @@ -/**************************************************************************** - * sched/sched_setupidlefiles.c - * - * Copyright (C) 2007-2010, 2012 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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 - -#include -#include -#include -#include -#include -#include - -#include -#include - -#include "os_internal.h" - -#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0 - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: sched_setupidlefiles - * - * Description: - * Configure the idle thread's TCB. - * - * Parameters: - * tcb - tcb of the idle task. - * - * Return Value: - * None - * - * Assumptions: - * - ****************************************************************************/ - -int sched_setupidlefiles(FAR _TCB *tcb) -{ -#if CONFIG_NFILE_DESCRIPTORS > 0 - FAR struct task_group_s *group = tcb->group; -#endif -#if CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_DEV_CONSOLE) - int fd; -#endif - -#if CONFIG_NFILE_DESCRIPTORS > 0 - DEBUGASSERT(group); -#endif - - /* Initialize file descriptors for the TCB */ - -#if CONFIG_NFILE_DESCRIPTORS > 0 - files_initlist(&group->tg_filelist); -#endif - - /* Allocate socket descriptors for the TCB */ - -#if CONFIG_NSOCKET_DESCRIPTORS > 0 - tcb->sockets = net_alloclist(); - if (!tcb->sockets) - { - return -ENOMEM; - } -#endif - - /* Open stdin, dup to get stdout and stderr. This should always - * be the first file opened and, hence, should always get file - * descriptor 0. - */ - -#if CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_DEV_CONSOLE) - fd = open("/dev/console", O_RDWR); - if (fd == 0) - { - /* Successfully opened /dev/console as stdin (fd == 0) */ - - (void)file_dup2(0, 1); - (void)file_dup2(0, 2); - } - else - { - /* We failed to open /dev/console OR for some reason, we opened - * it and got some file descriptor other than 0. - */ - - if (fd > 0) - { - slldbg("Open /dev/console fd: %d\n", fd); - (void)close(fd); - } - else - { - slldbg("Failed to open /dev/console: %d\n", errno); - } - return -ENFILE; - } -#endif - - /* Allocate file/socket streams for the TCB */ - -#if CONFIG_NFILE_STREAMS > 0 - return sched_setupstreams(tcb); -#else - return OK; -#endif -} - -#endif /* CONFIG_NFILE_DESCRIPTORS || CONFIG_NSOCKET_DESCRIPTORS */ diff --git a/nuttx/sched/sched_setuppthreadfiles.c b/nuttx/sched/sched_setuppthreadfiles.c deleted file mode 100644 index 91d72fa7f..000000000 --- a/nuttx/sched/sched_setuppthreadfiles.c +++ /dev/null @@ -1,91 +0,0 @@ -/**************************************************************************** - * sched_setuppthreadfiles.c - * - * Copyright (C) 2007, 2009, 2012 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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 - -#include - -#include -#include -#include - -#include "os_internal.h" - -#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0 - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: sched_setuppthreadfiles - * - * Description: - * Configure a newly allocated TCB so that it will inherit file - * descriptors and streams from the parent pthread. - * - * Parameters: - * tcb - tcb of the new task. - * - * Return Value: - * OK (if an error were returned, it would need to be a non-negated - * errno value). - * - * Assumptions: - * - ****************************************************************************/ - -int sched_setuppthreadfiles(FAR _TCB *tcb) -{ -#if CONFIG_NSOCKET_DESCRIPTORS > 0 - /* The child thread inherits the parent socket descriptors */ - - tcb->sockets = rtcb->sockets; - net_addreflist(tcb->sockets); - -#endif /* CONFIG_NSOCKET_DESCRIPTORS */ - - return OK; -} - -#endif /* CONFIG_NFILE_DESCRIPTORS || CONFIG_NSOCKET_DESCRIPTORS */ diff --git a/nuttx/sched/sched_setupstreams.c b/nuttx/sched/sched_setupstreams.c deleted file mode 100644 index fb2e4d0be..000000000 --- a/nuttx/sched/sched_setupstreams.c +++ /dev/null @@ -1,97 +0,0 @@ -/**************************************************************************** - * sched_setupstreams.c - * - * Copyright (C) 2007-2008, 2010-2012 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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 - -#include -#include - -#include -#include -#include - -/* Make sure that there are file or socket descriptors in the system and - * that some number of streams have been configured. - */ - -#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0 -#if CONFIG_NFILE_STREAMS > 0 - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: sched_setupstreams - * - * Description: - * Setup streams data structures that may be used for standard C buffered - * I/O with underlying socket or file desciptors - * - ****************************************************************************/ - -int sched_setupstreams(FAR _TCB *tcb) -{ - DEBUGASSERT(tcb && tcb->group); - - /* Initialize file streams for the task group */ - - lib_streaminit(&tcb->group->tg_streamlist); - - /* fdopen to get the stdin, stdout and stderr streams. The following logic - * depends on the fact that the library layer will allocate FILEs in order. - * - * fd = 0 is stdin (read-only) - * fd = 1 is stdout (write-only, append) - * fd = 2 is stderr (write-only, append) - */ - - (void)fs_fdopen(0, O_RDONLY, tcb); - (void)fs_fdopen(1, O_WROK|O_CREAT, tcb); - (void)fs_fdopen(2, O_WROK|O_CREAT, tcb); - - return OK; -} - -#endif /* CONFIG_NFILE_STREAMS > 0 */ -#endif /* CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0*/ diff --git a/nuttx/sched/sched_setuptaskfiles.c b/nuttx/sched/sched_setuptaskfiles.c deleted file mode 100644 index 9e44147e9..000000000 --- a/nuttx/sched/sched_setuptaskfiles.c +++ /dev/null @@ -1,248 +0,0 @@ -/**************************************************************************** - * sched/sched_setuptaskfiles.c - * - * Copyright (C) 2007-2008, 2010, 2012-2013 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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 - -#include -#include - -#include -#include - -#include "os_internal.h" - -#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0 - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/* Determine how many file descriptors to clone. If CONFIG_FDCLONE_DISABLE - * is set, no file descriptors will be cloned. If CONFIG_FDCLONE_STDIO is - * set, only the first three descriptors (stdin, stdout, and stderr) will - * be cloned. Otherwise all file descriptors will be cloned. - */ - -#if defined(CONFIG_FDCLONE_STDIO) && CONFIG_NFILE_DESCRIPTORS > 3 -# define NFDS_TOCLONE 3 -#else -# define NFDS_TOCLONE CONFIG_NFILE_DESCRIPTORS -#endif - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: sched_dupfiles - * - * Description: - * Duplicate parent task's file descriptors. - * - * Input Parameters: - * tcb - tcb of the new task. - * - * Return Value: - * None - * - ****************************************************************************/ - -#if CONFIG_NFILE_DESCRIPTORS > 0 && !defined(CONFIG_FDCLONE_DISABLE) -static inline void sched_dupfiles(FAR _TCB *tcb) -{ - /* The parent task is the one at the head of the ready-to-run list */ - - FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head; - FAR struct file *parent; - FAR struct file *child; - int i; - - DEBUGASSERT(tcb && tcb->group && rtcb->group); - - /* Duplicate the file descriptors. This will be either all of the - * file descriptors or just the first three (stdin, stdout, and stderr) - * if CONFIG_FDCLONE_STDIO is defined. NFSDS_TOCLONE is set - * accordingly above. - */ - - /* Get pointers to the parent and child task file lists */ - - parent = rtcb->group->tg_filelist.fl_files; - child = tcb->group->tg_filelist.fl_files; - - /* Check each file in the parent file list */ - - for (i = 0; i < NFDS_TOCLONE; i++) - { - /* Check if this file is opened by the parent. We can tell if - * if the file is open because it contain a reference to a non-NULL - * i-node structure. - */ - - if (parent[i].f_inode) - { - /* Yes... duplicate it for the child */ - - (void)files_dup(&parent[i], &child[i]); - } - } -} -#else /* CONFIG_NFILE_DESCRIPTORS && !CONFIG_FDCLONE_DISABLE */ -# define sched_dupfiles(tcb) -#endif /* CONFIG_NFILE_DESCRIPTORS && !CONFIG_FDCLONE_DISABLE */ - -/**************************************************************************** - * Name: sched_dupsockets - * - * Description: - * Duplicate the parent task's socket descriptors. - * - * Input Parameters: - * tcb - tcb of the new task. - * - * Return Value: - * None - * - ****************************************************************************/ - -#if CONFIG_NSOCKET_DESCRIPTORS > 0 && !defined(CONFIG_SDCLONE_DISABLE) -static inline void sched_dupsockets(FAR _TCB *tcb) -{ - /* The parent task is the one at the head of the ready-to-run list */ - - FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head; - FAR struct socket *parent; - FAR struct socket *child; - int i; - - /* Duplicate the socket descriptors of all sockets opened by the parent - * task. - */ - - if (rtcb->sockets) - { - /* Get pointers to the parent and child task socket lists */ - - parent = rtcb->sockets->sl_sockets; - child = tcb->sockets->sl_sockets; - - /* Check each socket in the parent socket list */ - - for (i = 0; i < CONFIG_NSOCKET_DESCRIPTORS; i++) - { - /* Check if this parent socket is allocated. We can tell if the - * socket is allocated because it will have a positive, non-zero - * reference count. - */ - - if (parent[i].s_crefs > 0) - { - /* Yes... duplicate it for the child */ - - (void)net_clone(&parent[i], &child[i]); - } - } - } -} -#else /* CONFIG_NSOCKET_DESCRIPTORS && !CONFIG_SDCLONE_DISABLE */ -# define sched_dupsockets(tcb) -#endif /* CONFIG_NSOCKET_DESCRIPTORS && !CONFIG_SDCLONE_DISABLE */ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: sched_setuptaskfiles - * - * Description: - * Configure a newly allocated TCB so that it will inherit - * file descriptors and streams from the parent task. - * - * Parameters: - * tcb - tcb of the new task. - * - * Return Value: - * Zero (OK) is returned on success; A negated errno value is returned on - * failure. - * - * Assumptions: - * - ****************************************************************************/ - -int sched_setuptaskfiles(FAR _TCB *tcb) -{ -#if CONFIG_NFILE_DESCRIPTORS > 0 - FAR struct task_group_s *group = tcb->group; - - DEBUGASSERT(group); - - /* Initialize file descriptors for the TCB */ - - files_initlist(&group->tg_filelist); -#endif - - /* Allocate socket descriptors for the TCB */ - -#if CONFIG_NSOCKET_DESCRIPTORS > 0 - tcb->sockets = net_alloclist(); - if (!tcb->sockets) - { - return -ENOMEM; - } -#endif - - /* Duplicate the parent task's file descriptors */ - - sched_dupfiles(tcb); - - /* Duplicate the parent task's socket descriptors */ - - sched_dupsockets(tcb); - - /* Allocate file/socket streams for the new TCB */ - -#if CONFIG_NFILE_STREAMS > 0 - return sched_setupstreams(tcb); -#else - return OK; -#endif -} - -#endif /* CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0*/ diff --git a/nuttx/sched/task_create.c b/nuttx/sched/task_create.c index 85c0f5e92..944743200 100644 --- a/nuttx/sched/task_create.c +++ b/nuttx/sched/task_create.c @@ -134,7 +134,7 @@ static int thread_create(const char *name, uint8_t ttype, int priority, /* Associate file descriptors with the new task */ #if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0 - ret = sched_setuptaskfiles(tcb); + ret = group_setuptaskfiles(tcb); if (ret != OK) { errcode = -ret; diff --git a/nuttx/sched/task_init.c b/nuttx/sched/task_init.c index 8dfd8b7f6..78f35bc2a 100644 --- a/nuttx/sched/task_init.c +++ b/nuttx/sched/task_init.c @@ -137,7 +137,7 @@ int task_init(FAR _TCB *tcb, const char *name, int priority, /* Associate file descriptors with the new task */ #if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0 - ret = sched_setuptaskfiles(tcb); + ret = group_setuptaskfiles(tcb); if (ret < 0) { errcode = -ret; diff --git a/nuttx/sched/task_vfork.c b/nuttx/sched/task_vfork.c index 3f058bdec..5b42a1e55 100644 --- a/nuttx/sched/task_vfork.c +++ b/nuttx/sched/task_vfork.c @@ -125,7 +125,7 @@ FAR _TCB *task_vforksetup(start_t retaddr) /* Associate file descriptors with the new task */ #if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0 - ret = sched_setuptaskfiles(child); + ret = group_setuptaskfiles(child); if (ret != OK) { goto errout_with_tcb; -- cgit v1.2.3 From e96d8f046b6bce6c4e810b302c1cc1cc578bdae3 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sun, 27 Jan 2013 15:52:58 +0000 Subject: Add a start hook that can be setup to call a function in the context of a new thread before the new threads main() has been called. git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5571 42af7a65-404d-4744-a932-0658087f49c3 --- apps/examples/elf/tests/signal/signal.c | 2 +- apps/examples/nxflat/tests/signal/signal.c | 2 +- nuttx/ChangeLog | 6 ++ nuttx/TODO | 17 +++- nuttx/binfmt/Kconfig | 5 +- nuttx/binfmt/binfmt_execmodule.c | 61 +++++-------- nuttx/binfmt/binfmt_internal.h | 2 +- nuttx/configs/stm32f4discovery/elf/defconfig | 45 ++++++++-- .../configs/stm32f4discovery/posix_spawn/defconfig | 1 + nuttx/include/nuttx/sched.h | 24 ++++- nuttx/sched/Kconfig | 10 +++ nuttx/sched/Makefile | 4 + nuttx/sched/group_setupidlefiles.c | 1 + nuttx/sched/group_setupstreams.c | 2 + nuttx/sched/group_setuptaskfiles.c | 5 +- nuttx/sched/task_start.c | 9 ++ nuttx/sched/task_starthook.c | 100 +++++++++++++++++++++ 17 files changed, 239 insertions(+), 57 deletions(-) create mode 100644 nuttx/sched/task_starthook.c (limited to 'nuttx/sched') diff --git a/apps/examples/elf/tests/signal/signal.c b/apps/examples/elf/tests/signal/signal.c index b40da7a86..d43f012cb 100644 --- a/apps/examples/elf/tests/signal/signal.c +++ b/apps/examples/elf/tests/signal/signal.c @@ -161,7 +161,7 @@ int main(int argc, char **argv) /* Send SIGUSR1 to ourselves via kill() */ printf("Kill-ing SIGUSR1 from pid=%d\n", mypid); - status = kill(0, SIGUSR1); + status = kill(mypid, SIGUSR1); if (status != 0) { fprintf(stderr, "Failed to kill SIGUSR1, errno=%d\n", errno); diff --git a/apps/examples/nxflat/tests/signal/signal.c b/apps/examples/nxflat/tests/signal/signal.c index c5ea6bdcc..ac03f6d33 100644 --- a/apps/examples/nxflat/tests/signal/signal.c +++ b/apps/examples/nxflat/tests/signal/signal.c @@ -161,7 +161,7 @@ int main(int argc, char **argv) /* Send SIGUSR1 to ourselves via kill() */ printf("Kill-ing SIGUSR1 from pid=%d\n", mypid); - status = kill(0, SIGUSR1); + status = kill(mypid, SIGUSR1); if (status != 0) { fprintf(stderr, "Failed to kill SIGUSR1, errno=%d\n", errno); diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 255d69a3d..32112f358 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -4040,3 +4040,9 @@ Move stream data from the TCB to the task group structure. * net/, sched/, and include/nuttx/net/net.h: Move socket data from the TCB to the task group structure. + * sched/task_starthook.c, sched/task_start.c, and include/nuttx/sched.h: + Add a task start hook that will be called before the task main + is started. This can be used to schedule C++ constructors to run + automatically in the context of the new task. + * binfmt/binfmt_execmodule: Execute constructors as a start hook. + diff --git a/nuttx/TODO b/nuttx/TODO index cb99f1bf7..05e0fa99b 100644 --- a/nuttx/TODO +++ b/nuttx/TODO @@ -1,4 +1,4 @@ -NuttX TODO List (Last updated January 26, 2013) +NuttX TODO List (Last updated January 27, 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/) (2) Memory Managment (mm/) (3) Signals (sched/, arch/) (2) pthreads (sched/) @@ -193,6 +193,16 @@ o Task/Scheduler (sched/) Status: Open Priority: Low (it might as well be low since it isn't going to be fixed). + Title: errno IS NOT SHARED AMONG THREADS + Description: In NuttX, the errno value is unique for each thread. But for + bug-for-bug compatibility, the same errno should be shared by + the task and each thread that it creates. It is *very* easy + to make this change: Just move the pterrno field from + _TCB to struct task_group_s. However, I am still not sure + if this should be done or not. + Status: Open + Priority: Low + o Memory Managment (mm/) ^^^^^^^^^^^^^^^^^^^^^^ @@ -407,6 +417,9 @@ o Binary loaders (binfmt/) Description: Not all of the NXFLAT test under apps/examples/nxflat are working. Most simply do not compile yet. tests/mutex runs okay but outputs garbage on completion. + + Update: 13-27-1, tests/mutex crashed with a memory corruption + problem the last time that I ran it. Status: Open Priority: High diff --git a/nuttx/binfmt/Kconfig b/nuttx/binfmt/Kconfig index 8d6c0bb18..6e5f7c251 100644 --- a/nuttx/binfmt/Kconfig +++ b/nuttx/binfmt/Kconfig @@ -72,9 +72,10 @@ config PIC config BINFMT_CONSTRUCTORS bool "C++ Static Constructor Support" default n - depends on HAVE_CXX && ELF # FIX ME: Currently only supported for ELF + depends on HAVE_CXX && SCHED_STARTHOOK && ELF ---help--- - Build in support for C++ constructors in loaded modules. + Build in support for C++ constructors in loaded modules. Currently + only support for ELF binary formats. config SYMTAB_ORDEREDBYNAME bool "Symbol Tables Ordered by Name" diff --git a/nuttx/binfmt/binfmt_execmodule.c b/nuttx/binfmt/binfmt_execmodule.c index afa445abb..10068b482 100644 --- a/nuttx/binfmt/binfmt_execmodule.c +++ b/nuttx/binfmt/binfmt_execmodule.c @@ -58,6 +58,14 @@ /**************************************************************************** * Pre-processor Definitions ****************************************************************************/ +/* If C++ constructors are used, then CONFIG_SCHED_STARTHOOK must also be + * selected be the start hook is used to schedule execution of the + * constructors. + */ + +#if defined(CONFIG_BINFMT_CONSTRUCTORS) && !defined(CONFIG_SCHED_STARTHOOK) +# errror "CONFIG_SCHED_STARTHOOK must be defined to use constructors" +#endif /**************************************************************************** * Private Function Prototypes @@ -75,7 +83,9 @@ * Name: exec_ctors * * Description: - * Execute C++ static constructors. + * Execute C++ static constructors. This function is registered as a + * start hook and runs on the thread of the newly created task before + * the new task's main function is called. * * Input Parameters: * loadinfo - Load state information @@ -87,26 +97,12 @@ ****************************************************************************/ #ifdef CONFIG_BINFMT_CONSTRUCTORS -static inline int exec_ctors(FAR const struct binary_s *binp) +static void exec_ctors(FAR void *arg) { + FAR const struct binary_s *binp = (FAR const struct binary_s *)arg; binfmt_ctor_t *ctor = binp->ctors; -#ifdef CONFIG_ADDRENV - hw_addrenv_t oldenv; - int ret; -#endif int i; - /* Instantiate the address enviroment containing the constructors */ - -#ifdef CONFIG_ADDRENV - ret = up_addrenv_select(binp->addrenv, &oldenv); - if (ret < 0) - { - bdbg("up_addrenv_select() failed: %d\n", ret); - return ret; - } -#endif - /* Execute each constructor */ for (i = 0; i < binp->nctors; i++) @@ -116,14 +112,6 @@ static inline int exec_ctors(FAR const struct binary_s *binp) (*ctor)(); ctor++; } - - /* Restore the address enviroment */ - -#ifdef CONFIG_ADDRENV - return up_addrenv_restore(oldenv); -#else - return OK; -#endif } #endif @@ -139,7 +127,7 @@ static inline int exec_ctors(FAR const struct binary_s *binp) * * 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. * ****************************************************************************/ @@ -229,22 +217,19 @@ int exec_module(FAR const struct binary_s *binp) } #endif - /* Get the assigned pid before we start the task */ - - pid = tcb->pid; - - /* Execute all of the C++ static constructors */ + /* Setup a start hook that will execute all of the C++ static constructors + * on the newly created thread. The struct binary_s must persist at least + * until the new task has been started. + */ #ifdef CONFIG_BINFMT_CONSTRUCTORS - ret = exec_ctors(binp); - if (ret < 0) - { - err = -ret; - bdbg("exec_ctors() failed: %d\n", ret); - goto errout_with_stack; - } + task_starthook(tcb, exec_ctors, (FAR void *)binp); #endif + /* Get the assigned pid before we start the task */ + + pid = tcb->pid; + /* Then activate the task at the provided priority */ ret = task_activate(tcb); diff --git a/nuttx/binfmt/binfmt_internal.h b/nuttx/binfmt/binfmt_internal.h index 4fab9724d..fa750543a 100644 --- a/nuttx/binfmt/binfmt_internal.h +++ b/nuttx/binfmt/binfmt_internal.h @@ -71,7 +71,7 @@ EXTERN FAR struct binfmt_s *g_binfmts; * Public Function Prototypes ***********************************************************************/ -/* Dump the contents of strtuc binary_s */ +/* Dump the contents of struct binary_s */ #if defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_BINFMT) EXTERN int dump_module(FAR const struct binary_s *bin); diff --git a/nuttx/configs/stm32f4discovery/elf/defconfig b/nuttx/configs/stm32f4discovery/elf/defconfig index 3f5a5d0fc..f7e0dc5f2 100644 --- a/nuttx/configs/stm32f4discovery/elf/defconfig +++ b/nuttx/configs/stm32f4discovery/elf/defconfig @@ -69,7 +69,7 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_DM320 is not set # CONFIG_ARCH_CHIP_IMX is not set # CONFIG_ARCH_CHIP_KINETIS is not set -# CONFIG_ARCH_CHIP_LM3S is not set +# CONFIG_ARCH_CHIP_LM is not set # CONFIG_ARCH_CHIP_LPC17XX is not set # CONFIG_ARCH_CHIP_LPC214X is not set # CONFIG_ARCH_CHIP_LPC2378 is not set @@ -81,6 +81,7 @@ CONFIG_ARCH_CHIP_STM32=y CONFIG_ARCH_CORTEXM4=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" +CONFIG_ARMV7M_USEBASEPRI=y CONFIG_ARCH_HAVE_CMNVECTOR=y # CONFIG_ARMV7M_CMNVECTOR is not set # CONFIG_ARCH_FPU is not set @@ -201,26 +202,35 @@ CONFIG_STM32_JTAG_SW_ENABLE=y # CONFIG_STM32_FORCEPOWER is not set # CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set CONFIG_STM32_CCMEXCLUDE=y +CONFIG_STM32_USART=y # # U[S]ART Configuration # # CONFIG_USART2_RS485 is not set +# CONFIG_STM32_USART_SINGLEWIRE is not set # # USB Host Configuration # +# +# External Memory Configuration +# + # # Architecture Options # # CONFIG_ARCH_NOINTC is not set +# CONFIG_ARCH_VECNOTIRQ is not set # CONFIG_ARCH_DMA is not set CONFIG_ARCH_IRQPRIO=y # CONFIG_CUSTOM_STACK is not set # CONFIG_ADDRENV is not set +CONFIG_ARCH_HAVE_VFORK=y CONFIG_ARCH_STACKDUMP=y # CONFIG_ENDIAN_BIG is not set +# CONFIG_ARCH_HAVE_RAMFUNCS is not set # # Board Settings @@ -266,6 +276,7 @@ CONFIG_MSEC_PER_TICK=10 CONFIG_RR_INTERVAL=200 # CONFIG_SCHED_INSTRUMENTATION is not set CONFIG_TASK_NAME_SIZE=0 +# CONFIG_SCHED_HAVE_PARENT is not set # CONFIG_JULIAN_TIME is not set CONFIG_START_YEAR=2012 CONFIG_START_MONTH=10 @@ -278,6 +289,7 @@ CONFIG_DEV_CONSOLE=y CONFIG_SDCLONE_DISABLE=y # CONFIG_SCHED_WORKQUEUE is not set # CONFIG_SCHED_WAITPID is not set +CONFIG_SCHED_STARTHOOK=y # CONFIG_SCHED_ATEXIT is not set # CONFIG_SCHED_ONEXIT is not set CONFIG_USER_ENTRYPOINT="elf_main" @@ -287,9 +299,15 @@ CONFIG_DISABLE_OS_API=y # CONFIG_DISABLE_PTHREAD is not set # CONFIG_DISABLE_SIGNALS is not set # CONFIG_DISABLE_MQUEUE is not set -# CONFIG_DISABLE_MOUNTPOINT is not set # CONFIG_DISABLE_ENVIRON is not set -# CONFIG_DISABLE_POLL is not set + +# +# Signal Numbers +# +CONFIG_SIG_SIGUSR1=1 +CONFIG_SIG_SIGUSR2=2 +CONFIG_SIG_SIGALARM=3 +CONFIG_SIG_SIGCONDTIMEDOUT=16 # # Sizes of configurable things (0 disables) @@ -317,6 +335,7 @@ CONFIG_PTHREAD_STACK_DEFAULT=2048 # # Device Drivers # +# CONFIG_DISABLE_POLL is not set CONFIG_DEV_NULL=y # CONFIG_DEV_ZERO is not set # CONFIG_LOOP is not set @@ -381,8 +400,9 @@ CONFIG_USART2_2STOP=0 # # File system configuration # -# CONFIG_FS_FAT is not set +# CONFIG_DISABLE_MOUNTPOINT is not set # CONFIG_FS_RAMMAP is not set +# CONFIG_FS_FAT is not set # CONFIG_FS_NXFFS is not set CONFIG_FS_ROMFS=y @@ -415,6 +435,7 @@ CONFIG_ELF_ALIGN_LOG2=2 CONFIG_ELF_STACKSIZE=2048 CONFIG_ELF_BUFFERSIZE=128 CONFIG_ELF_BUFFERINCR=32 +# CONFIG_BUILTIN is not set # CONFIG_PIC is not set CONFIG_BINFMT_CONSTRUCTORS=y CONFIG_SYMTAB_ORDEREDBYNAME=y @@ -422,6 +443,10 @@ CONFIG_SYMTAB_ORDEREDBYNAME=y # # Library Routines # + +# +# Standard C Library Options +# CONFIG_STDIO_BUFFER_SIZE=256 CONFIG_STDIO_LINEBUFFER=y CONFIG_NUNGET_CHARS=2 @@ -433,6 +458,7 @@ CONFIG_LIB_HOMEDIR="/" # CONFIG_EOL_IS_LF is not set # CONFIG_EOL_IS_BOTH_CRLF is not set CONFIG_EOL_IS_EITHER_CRLF=y +# CONFIG_LIBC_EXECFUNCS is not set # CONFIG_LIBC_STRERROR is not set # CONFIG_LIBC_PERROR_STDOUT is not set CONFIG_ARCH_LOWPUTC=y @@ -440,6 +466,11 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512 # CONFIG_ARCH_ROMGETC is not set # CONFIG_ARCH_OPTIMIZED_FUNCTIONS is not set +# +# Non-standard Helper Functions +# +# CONFIG_LIB_KBDCODEC is not set + # # Basic CXX Support # @@ -458,9 +489,8 @@ CONFIG_HAVE_CXX=y # # -# Named Applications +# Built-In Applications # -# CONFIG_BUILTIN is not set # # Examples @@ -486,7 +516,6 @@ CONFIG_EXAMPLES_ELF_DEVPATH="/dev/ram0" # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MOUNT is not set # CONFIG_EXAMPLES_MODBUS is not set -# CONFIG_EXAMPLES_NETTEST is not set # CONFIG_EXAMPLES_NSH is not set # CONFIG_EXAMPLES_NULL is not set # CONFIG_EXAMPLES_NX is not set @@ -501,6 +530,7 @@ CONFIG_EXAMPLES_ELF_DEVPATH="/dev/ram0" # CONFIG_EXAMPLES_PASHELLO is not set # CONFIG_EXAMPLES_PIPE is not set # CONFIG_EXAMPLES_POLL is not set +# CONFIG_EXAMPLES_POSIXSPAWN is not set # CONFIG_EXAMPLES_QENCODER is not set # CONFIG_EXAMPLES_RGMP is not set # CONFIG_EXAMPLES_ROMFS is not set @@ -516,7 +546,6 @@ CONFIG_EXAMPLES_ELF_DEVPATH="/dev/ram0" # CONFIG_EXAMPLES_USBMSC is not set # CONFIG_EXAMPLES_USBTERM is not set # CONFIG_EXAMPLES_WATCHDOG is not set -# CONFIG_EXAMPLES_WLAN is not set # # Interpreters diff --git a/nuttx/configs/stm32f4discovery/posix_spawn/defconfig b/nuttx/configs/stm32f4discovery/posix_spawn/defconfig index 9e30ada8a..97cf84ab4 100644 --- a/nuttx/configs/stm32f4discovery/posix_spawn/defconfig +++ b/nuttx/configs/stm32f4discovery/posix_spawn/defconfig @@ -279,6 +279,7 @@ CONFIG_DEV_CONSOLE=y CONFIG_SDCLONE_DISABLE=y # CONFIG_SCHED_WORKQUEUE is not set # CONFIG_SCHED_WAITPID is not set +CONFIG_SCHED_STARTHOOK=y # CONFIG_SCHED_ATEXIT is not set # CONFIG_SCHED_ONEXIT is not set CONFIG_USER_ENTRYPOINT="spawn_main" diff --git a/nuttx/include/nuttx/sched.h b/nuttx/include/nuttx/sched.h index 244455cd4..f8b4eb0dc 100644 --- a/nuttx/include/nuttx/sched.h +++ b/nuttx/include/nuttx/sched.h @@ -183,7 +183,13 @@ union entry_u }; typedef union entry_u entry_t; -/* These is the types of the functions that are executed with exit() is called +/* This is the type of the function called at task startup */ + +#ifdef CONFIG_SCHED_STARTHOOK +typedef CODE void (*starthook_t)(FAR void *arg); +#endif + +/* These are the types of the functions that are executed with exit() is called * (if registered via atexit() on on_exit()). */ @@ -298,7 +304,10 @@ struct task_group_s #endif /* PIC data space and address environments ************************************/ - /* Not yet (see struct dspace_s) */ + /* Logically the PIC data space belongs here (see struct dspace_s). The + * current logic needs review: There are differences in the away that the + * life of the PIC data is managed. + */ /* File descriptors ***********************************************************/ @@ -354,6 +363,11 @@ struct _TCB start_t start; /* Thread start function */ entry_t entry; /* Entry Point into the thread */ +#ifdef CONFIG_SCHED_STARTHOOK + starthook_t starthook; /* Task startup function */ + FAR void *starthookarg; /* The argument passed to the function */ +#endif + #if defined(CONFIG_SCHED_ATEXIT) && !defined(CONFIG_SCHED_ONEXIT) # if defined(CONFIG_SCHED_ATEXIT_MAX) && CONFIG_SCHED_ATEXIT_MAX > 1 atexitfunc_t atexitfunc[CONFIG_SCHED_ATEXIT_MAX]; @@ -516,6 +530,12 @@ FAR struct streamlist *sched_getstreams(void); FAR struct socketlist *sched_getsockets(void); #endif /* CONFIG_NSOCKET_DESCRIPTORS */ +/* Setup up a start hook */ + +#ifdef CONFIG_SCHED_STARTHOOK +void task_starthook(FAR _TCB *tcb, starthook_t starthook, FAR void *arg); +#endif + /* Internal vfork support.The overall sequence is: * * 1) User code calls vfork(). vfork() is provided in architecture-specific diff --git a/nuttx/sched/Kconfig b/nuttx/sched/Kconfig index 7745c2c25..097dd1993 100644 --- a/nuttx/sched/Kconfig +++ b/nuttx/sched/Kconfig @@ -296,6 +296,16 @@ config SCHED_WAITPID compliant) and will enable the waitid() and wait() interfaces as well. +config SCHED_STARTHOOK + bool "Enable startup hook" + default n + ---help--- + Enable a non-standard, internal OS API call task_starthook(). + task_starthook() registers a function that will be called on task + startup before that actual task entry point is called. The + starthook is useful, for example, for setting up automatic + configuration of C++ constructors. + config SCHED_ATEXIT bool "Enable atexit() API" default n diff --git a/nuttx/sched/Makefile b/nuttx/sched/Makefile index 7710ae058..961560176 100644 --- a/nuttx/sched/Makefile +++ b/nuttx/sched/Makefile @@ -54,6 +54,10 @@ TSK_SRCS += task_posixspawn.c endif endif +ifeq ($(CONFIG_SCHED_STARTHOOK),y) +TSK_SRCS += task_starthook.c +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 diff --git a/nuttx/sched/group_setupidlefiles.c b/nuttx/sched/group_setupidlefiles.c index 98cc7885e..ceb9f3e2c 100644 --- a/nuttx/sched/group_setupidlefiles.c +++ b/nuttx/sched/group_setupidlefiles.c @@ -50,6 +50,7 @@ #include #include "os_internal.h" +#include "group_internal.h" #if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0 diff --git a/nuttx/sched/group_setupstreams.c b/nuttx/sched/group_setupstreams.c index 88e266280..08399ae41 100644 --- a/nuttx/sched/group_setupstreams.c +++ b/nuttx/sched/group_setupstreams.c @@ -46,6 +46,8 @@ #include #include +#include "group_internal.h" + /* Make sure that there are file or socket descriptors in the system and * that some number of streams have been configured. */ diff --git a/nuttx/sched/group_setuptaskfiles.c b/nuttx/sched/group_setuptaskfiles.c index d52adcfee..e2e7d4634 100644 --- a/nuttx/sched/group_setuptaskfiles.c +++ b/nuttx/sched/group_setuptaskfiles.c @@ -46,6 +46,7 @@ #include #include "os_internal.h" +#include "group_internal.h" #if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0 @@ -159,8 +160,8 @@ static inline void sched_dupsockets(FAR _TCB *tcb) /* Get pointers to the parent and child task socket lists */ - parent = rtcb->group->tg_sockets->sl_sockets; - child = tcb->group->tg_sockets->sl_sockets; + parent = rtcb->group->tg_socketlist.sl_sockets; + child = tcb->group->tg_socketlist.sl_sockets; /* Check each socket in the parent socket list */ diff --git a/nuttx/sched/task_start.c b/nuttx/sched/task_start.c index a9cc38dfc..5a32a5dd8 100644 --- a/nuttx/sched/task_start.c +++ b/nuttx/sched/task_start.c @@ -94,6 +94,15 @@ void task_start(void) FAR _TCB *tcb = (FAR _TCB*)g_readytorun.head; int argc; + /* Execute the start hook if one has been registered */ + +#ifdef CONFIG_SCHED_STARTHOOK + if (tcb->starthook) + { + tcb->starthook(tcb->starthookarg); + } +#endif + /* Count how many non-null arguments we are passing */ for (argc = 1; argc <= CONFIG_MAX_TASK_ARGS; argc++) diff --git a/nuttx/sched/task_starthook.c b/nuttx/sched/task_starthook.c new file mode 100644 index 000000000..1cb29349f --- /dev/null +++ b/nuttx/sched/task_starthook.c @@ -0,0 +1,100 @@ +/**************************************************************************** + * sched/task_start.c + * + * Copyright (C) 2007-2010 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 + +#include + +#ifdef CONFIG_SCHED_STARTHOOK + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Type Declarations + ****************************************************************************/ + +/**************************************************************************** + * Global Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: task_starthook + * + * Description: + * Configure a start hook... a function that will be called on the thread + * of the new task before the new task's main entry point is called. + * The start hook is useful, for example, for setting up automatic + * configuration of C++ constructors. + * + * Inputs: + * tcb - The new, unstarted task task that needs the start hook + * starthook - The pointer to the start hook function + * arg - The argument to pass to the start hook function. + * + * Return: + * None + * + ****************************************************************************/ + +void task_starthook(FAR _TCB *tcb, starthook_t starthook, FAR void *arg) +{ + DEBUGASSERT(tcb); + tcb->starthook = starthook; + tcb->starthookarg = arg; +} + +#endif /* CONFIG_SCHED_STARTHOOK */ -- cgit v1.2.3 From b4db7635d85361c3cb8a718d5f460000b7123fb3 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sun, 27 Jan 2013 19:17:56 +0000 Subject: Add configs/stm32f4discovery/usbnsh git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5572 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 3 + nuttx/configs/stm32f4discovery/README.txt | 50 ++ nuttx/configs/stm32f4discovery/usbnsh/Make.defs | 111 ++++ nuttx/configs/stm32f4discovery/usbnsh/defconfig | 738 ++++++++++++++++++++++++ nuttx/configs/stm32f4discovery/usbnsh/setenv.sh | 75 +++ nuttx/drivers/usbdev/Kconfig | 18 +- nuttx/fs/Kconfig | 23 +- nuttx/fs/fs_syslog.c | 2 +- nuttx/libc/stdio/lib_lowprintf.c | 2 + nuttx/libc/stdio/lib_rawprintf.c | 3 + nuttx/sched/os_start.c | 23 +- nuttx/sched/task_vfork.c | 1 + 12 files changed, 1029 insertions(+), 20 deletions(-) create mode 100644 nuttx/configs/stm32f4discovery/usbnsh/Make.defs create mode 100644 nuttx/configs/stm32f4discovery/usbnsh/defconfig create mode 100755 nuttx/configs/stm32f4discovery/usbnsh/setenv.sh (limited to 'nuttx/sched') diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 32112f358..76ed2b603 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -4045,4 +4045,7 @@ is started. This can be used to schedule C++ constructors to run automatically in the context of the new task. * binfmt/binfmt_execmodule: Execute constructors as a start hook. + * sched/os_start.c: Fix ordering of group initialization. + * configs/stm32f4discovery/usbnsh: Add an NSH STM32F4Discovery + configuration that uses USB CDC/ACM for the NSH console. diff --git a/nuttx/configs/stm32f4discovery/README.txt b/nuttx/configs/stm32f4discovery/README.txt index 39fb41d78..0e295c429 100644 --- a/nuttx/configs/stm32f4discovery/README.txt +++ b/nuttx/configs/stm32f4discovery/README.txt @@ -1473,6 +1473,56 @@ Where is one of the following: 3. By default, this project assumes that you are *NOT* using the DFU bootloader. + usbnsh: + ------- + + This is another NSH example. If differs from other 'nsh' configurations + in that this configurations uses a USB serial device for console I/O. + Such a configuration is useful on the stm32f4discovery which has no + builtin RS-232 drivers. + + NOTES: + + 1. This configuration uses the mconf-based configuration tool. To + change this configuration using that tool, you should: + + a. Build and install the kconfig-mconf tool. See nuttx/README.txt + and misc/tools/ + + b. Execute 'make menuconfig' in nuttx/ in order to start the + reconfiguration process. + + 2. By default, this configuration uses the CodeSourcery toolchain + for Windows and builds under Cygwin (or probably MSYS). That + can easily be reconfigured, of course. + + CONFIG_HOST_WINDOWS=y : Builds under Windows + CONFIG_WINDOWS_CYGWIN=y : Using Cygwin + CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYW=y : CodeSourcery for Windows + + 3. This configuration does have UART2 output enabled and set up as + the system logging device: + + CONFIG_SYSLOG=y : Enable output to syslog, not console + CONFIG_SYSLOG_CHAR=y : Use a character device for system logging + CONFIG_SYSLOG_DEVPATH="/dev/ttyS0" : UART2 will be /dev/ttyS0 + + Debug, however, is not enable so in the default configuration nothing + should appear on UART2 unless you enable some debug output. + + 4. By default, this project assumes that you are *NOT* using the DFU + bootloader. + + Using the Prolifics PL2303 Emulation + ------------------------------------ + You could also use the non-standard PL2303 serial device instead of + the standard CDC/ACM serial device by changing: + + CONFIG_CDCACM=y : Disable the CDC/ACM serial device class + CONFIG_CDCACM_CONSOLE=y : The CDC/ACM serial device is NOT the console + CONFIG_PL2303=y : The Prolifics PL2303 emulation is enabled + CONFIG_PL2303_CONSOLE=y : The PL2303 serial device is the console + winbuild: -------- diff --git a/nuttx/configs/stm32f4discovery/usbnsh/Make.defs b/nuttx/configs/stm32f4discovery/usbnsh/Make.defs new file mode 100644 index 000000000..0bea20b8a --- /dev/null +++ b/nuttx/configs/stm32f4discovery/usbnsh/Make.defs @@ -0,0 +1,111 @@ +############################################################################ +# configs/stm32f4discovery/usbnsh/Make.defs +# +# Copyright (C) 2013 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# +# 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. +# +############################################################################ + +include ${TOPDIR}/.config +include ${TOPDIR}/tools/Config.mk +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs + +LDSCRIPT = ld.script + +ifeq ($(WINTOOL),y) + # Windows-native toolchains + DIRLINK = $(TOPDIR)/tools/copydir.sh + DIRUNLINK = $(TOPDIR)/tools/unlink.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh + ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" + ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}" + MAXOPTIMIZATION = -O2 +else + # Linux/Cygwin-native toolchain + MKDEP = $(TOPDIR)/tools/mkdeps.sh + ARCHINCLUDES = -I. -isystem $(TOPDIR)/include + ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT) +endif + +CC = $(CROSSDEV)gcc +CXX = $(CROSSDEV)g++ +CPP = $(CROSSDEV)gcc -E +LD = $(CROSSDEV)ld +AR = $(ARCROSSDEV)ar rcs +NM = $(ARCROSSDEV)nm +OBJCOPY = $(CROSSDEV)objcopy +OBJDUMP = $(CROSSDEV)objdump + +ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'} +ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1} + +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + ARCHOPTIMIZATION = -g +else + ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer +endif + +ARCHCFLAGS = -fno-builtin +ARCHCXXFLAGS = -fno-builtin -fno-exceptions -fno-rtti +ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow +ARCHWARNINGSXX = -Wall -Wshadow +ARCHDEFINES = +ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10 + +CFLAGS = $(ARCHCFLAGS) $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS) +CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS) +CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) +AFLAGS = $(CFLAGS) -D__ASSEMBLY__ + +NXFLATLDFLAGS1 = -r -d -warn-common +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections +LDNXFLATFLAGS = -e main -s 2048 + +OBJEXT = .o +LIBEXT = .a +EXEEXT = + +ifneq ($(CROSSDEV),arm-nuttx-elf-) + LDFLAGS += -nostartfiles -nodefaultlibs +endif +ifeq ($(CONFIG_DEBUG_SYMBOLS),y) + LDFLAGS += -g +endif + + +HOSTCC = gcc +HOSTINCLUDES = -I. +HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe +HOSTLDFLAGS = + diff --git a/nuttx/configs/stm32f4discovery/usbnsh/defconfig b/nuttx/configs/stm32f4discovery/usbnsh/defconfig new file mode 100644 index 000000000..3ddcab424 --- /dev/null +++ b/nuttx/configs/stm32f4discovery/usbnsh/defconfig @@ -0,0 +1,738 @@ +# +# Automatically generated file; DO NOT EDIT. +# Nuttx/ Configuration +# +CONFIG_NUTTX_NEWCONFIG=y + +# +# Build Setup +# +# CONFIG_EXPERIMENTAL is not set +# CONFIG_HOST_LINUX is not set +# CONFIG_HOST_OSX is not set +CONFIG_HOST_WINDOWS=y +# CONFIG_HOST_OTHER is not set +# CONFIG_WINDOWS_NATIVE is not set +CONFIG_WINDOWS_CYGWIN=y +# CONFIG_WINDOWS_MSYS is not set +# CONFIG_WINDOWS_OTHER is not set + +# +# Build Configuration +# +# CONFIG_APPS_DIR="../apps" +# CONFIG_BUILD_2PASS is not set + +# +# Binary Output Formats +# +# CONFIG_RRLOAD_BINARY is not set +CONFIG_INTELHEX_BINARY=y +# CONFIG_MOTOROLA_SREC is not set +CONFIG_RAW_BINARY=y + +# +# Customize Header Files +# +# CONFIG_ARCH_STDBOOL_H is not set +# CONFIG_ARCH_MATH_H is not set +# CONFIG_ARCH_FLOAT_H is not set +# CONFIG_ARCH_STDARG_H is not set + +# +# Debug Options +# +# CONFIG_DEBUG is not set +# CONFIG_DEBUG_SYMBOLS is not set + +# +# System Type +# +# CONFIG_ARCH_8051 is not set +CONFIG_ARCH_ARM=y +# CONFIG_ARCH_AVR is not set +# CONFIG_ARCH_HC is not set +# CONFIG_ARCH_MIPS is not set +# CONFIG_ARCH_RGMP is not set +# CONFIG_ARCH_SH is not set +# CONFIG_ARCH_SIM is not set +# CONFIG_ARCH_X86 is not set +# CONFIG_ARCH_Z16 is not set +# CONFIG_ARCH_Z80 is not set +CONFIG_ARCH="arm" + +# +# ARM Options +# +# CONFIG_ARCH_CHIP_C5471 is not set +# CONFIG_ARCH_CHIP_CALYPSO is not set +# CONFIG_ARCH_CHIP_DM320 is not set +# CONFIG_ARCH_CHIP_IMX is not set +# CONFIG_ARCH_CHIP_KINETIS is not set +# CONFIG_ARCH_CHIP_LM is not set +# CONFIG_ARCH_CHIP_LPC17XX is not set +# CONFIG_ARCH_CHIP_LPC214X is not set +# CONFIG_ARCH_CHIP_LPC2378 is not set +# CONFIG_ARCH_CHIP_LPC31XX is not set +# CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_SAM3U is not set +CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STR71X is not set +CONFIG_ARCH_CORTEXM4=y +CONFIG_ARCH_FAMILY="armv7-m" +CONFIG_ARCH_CHIP="stm32" +# CONFIG_ARMV7M_USEBASEPRI is not set +CONFIG_ARCH_HAVE_CMNVECTOR=y +# CONFIG_ARMV7M_CMNVECTOR is not set +# CONFIG_ARCH_FPU is not set +CONFIG_ARCH_HAVE_MPU=y +# CONFIG_ARMV7M_MPU is not set +CONFIG_BOARD_LOOPSPERMSEC=16717 +# CONFIG_ARCH_CALIBRATION is not set + +# +# ARMV7M Configuration Options +# +# CONFIG_ARMV7M_TOOLCHAIN_ATOLLIC is not set +# CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT is not set +# CONFIG_ARMV7M_TOOLCHAIN_CODEREDL is not set +# CONFIG_ARMV7M_TOOLCHAIN_CODEREDW is not set +# CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYL is not set +CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYW=y +# CONFIG_ARMV7M_TOOLCHAIN_DEVKITARM is not set +# CONFIG_ARMV7M_TOOLCHAIN_GNU_EABI is not set +# CONFIG_ARMV7M_TOOLCHAIN_RAISONANCE is not set +# CONFIG_SERIAL_TERMIOS is not set + +# +# STM32 Configuration Options +# +# CONFIG_ARCH_CHIP_STM32F100C8 is not set +# CONFIG_ARCH_CHIP_STM32F100CB is not set +# CONFIG_ARCH_CHIP_STM32F100R8 is not set +# CONFIG_ARCH_CHIP_STM32F100RB is not set +# CONFIG_ARCH_CHIP_STM32F100RC is not set +# CONFIG_ARCH_CHIP_STM32F100RD is not set +# CONFIG_ARCH_CHIP_STM32F100RE is not set +# CONFIG_ARCH_CHIP_STM32F100V8 is not set +# CONFIG_ARCH_CHIP_STM32F100VB is not set +# CONFIG_ARCH_CHIP_STM32F100VC is not set +# CONFIG_ARCH_CHIP_STM32F100VD is not set +# CONFIG_ARCH_CHIP_STM32F100VE is not set +# CONFIG_ARCH_CHIP_STM32F103RET6 is not set +# CONFIG_ARCH_CHIP_STM32F103VCT6 is not set +# CONFIG_ARCH_CHIP_STM32F103VET6 is not set +# CONFIG_ARCH_CHIP_STM32F103ZET6 is not set +# CONFIG_ARCH_CHIP_STM32F105VBT7 is not set +# CONFIG_ARCH_CHIP_STM32F107VC is not set +# CONFIG_ARCH_CHIP_STM32F207IG is not set +# CONFIG_ARCH_CHIP_STM32F405RG is not set +# CONFIG_ARCH_CHIP_STM32F405VG is not set +# CONFIG_ARCH_CHIP_STM32F405ZG is not set +# CONFIG_ARCH_CHIP_STM32F407VE is not set +CONFIG_ARCH_CHIP_STM32F407VG=y +# CONFIG_ARCH_CHIP_STM32F407ZE is not set +# CONFIG_ARCH_CHIP_STM32F407ZG is not set +# CONFIG_ARCH_CHIP_STM32F407IE is not set +# CONFIG_ARCH_CHIP_STM32F407IG is not set +CONFIG_STM32_STM32F40XX=y +# CONFIG_STM32_DFU is not set + +# +# STM32 Peripheral Support +# +# CONFIG_STM32_ADC1 is not set +# CONFIG_STM32_ADC2 is not set +# CONFIG_STM32_ADC3 is not set +# CONFIG_STM32_BKPSRAM is not set +# CONFIG_STM32_CAN1 is not set +# CONFIG_STM32_CAN2 is not set +# CONFIG_STM32_CCMDATARAM is not set +# CONFIG_STM32_CRC is not set +# CONFIG_STM32_CRYP is not set +# CONFIG_STM32_DMA1 is not set +# CONFIG_STM32_DMA2 is not set +# CONFIG_STM32_DAC1 is not set +# CONFIG_STM32_DAC2 is not set +# CONFIG_STM32_DCMI is not set +# CONFIG_STM32_ETHMAC is not set +# CONFIG_STM32_FSMC is not set +# CONFIG_STM32_HASH is not set +# CONFIG_STM32_I2C1 is not set +# CONFIG_STM32_I2C2 is not set +# CONFIG_STM32_I2C3 is not set +# CONFIG_STM32_IWDG is not set +CONFIG_STM32_OTGFS=y +# CONFIG_STM32_OTGHS is not set +CONFIG_STM32_PWR=y +# CONFIG_STM32_RNG is not set +# CONFIG_STM32_SDIO is not set +CONFIG_STM32_SPI1=y +# CONFIG_STM32_SPI2 is not set +# CONFIG_STM32_SPI3 is not set +CONFIG_STM32_SYSCFG=y +# CONFIG_STM32_TIM1 is not set +# CONFIG_STM32_TIM2 is not set +# CONFIG_STM32_TIM3 is not set +# CONFIG_STM32_TIM4 is not set +# CONFIG_STM32_TIM5 is not set +# CONFIG_STM32_TIM6 is not set +# CONFIG_STM32_TIM7 is not set +# CONFIG_STM32_TIM8 is not set +# CONFIG_STM32_TIM9 is not set +# CONFIG_STM32_TIM10 is not set +# CONFIG_STM32_TIM11 is not set +# CONFIG_STM32_TIM12 is not set +# CONFIG_STM32_TIM13 is not set +# CONFIG_STM32_TIM14 is not set +# CONFIG_STM32_USART1 is not set +CONFIG_STM32_USART2=y +# CONFIG_STM32_USART3 is not set +# CONFIG_STM32_UART4 is not set +# CONFIG_STM32_UART5 is not set +# CONFIG_STM32_USART6 is not set +# CONFIG_STM32_WWDG is not set +CONFIG_STM32_SPI=y + +# +# Alternate Pin Mapping +# +# CONFIG_STM32_FLASH_PREFETCH is not set +# CONFIG_STM32_JTAG_DISABLE is not set +# CONFIG_STM32_JTAG_FULL_ENABLE is not set +# CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set +CONFIG_STM32_JTAG_SW_ENABLE=y +# CONFIG_STM32_FORCEPOWER is not set +# CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set +# CONFIG_STM32_CCMEXCLUDE is not set +CONFIG_STM32_USART=y + +# +# U[S]ART Configuration +# +# CONFIG_USART2_RS485 is not set +# CONFIG_STM32_USART_SINGLEWIRE is not set + +# +# SPI Configuration +# +# CONFIG_STM32_SPI_INTERRUPTS is not set +# CONFIG_STM32_SPI_DMA is not set + +# +# USB Host Configuration +# + +# +# External Memory Configuration +# + +# +# Architecture Options +# +# CONFIG_ARCH_NOINTC is not set +# CONFIG_ARCH_VECNOTIRQ is not set +# CONFIG_ARCH_DMA is not set +CONFIG_ARCH_IRQPRIO=y +# CONFIG_CUSTOM_STACK is not set +# CONFIG_ADDRENV is not set +CONFIG_ARCH_HAVE_VFORK=y +CONFIG_ARCH_STACKDUMP=y +# CONFIG_ENDIAN_BIG is not set +# CONFIG_ARCH_HAVE_RAMFUNCS is not set + +# +# Board Settings +# +CONFIG_DRAM_START=0x20000000 +CONFIG_DRAM_SIZE=114688 +CONFIG_ARCH_HAVE_INTERRUPTSTACK=y +CONFIG_ARCH_INTERRUPTSTACK=0 + +# +# Boot options +# +# CONFIG_BOOT_RUNFROMEXTSRAM is not set +CONFIG_BOOT_RUNFROMFLASH=y +# CONFIG_BOOT_RUNFROMISRAM is not set +# CONFIG_BOOT_RUNFROMSDRAM is not set +# CONFIG_BOOT_COPYTORAM is not set + +# +# Board Selection +# +CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y +# CONFIG_ARCH_BOARD_CUSTOM is not set +CONFIG_ARCH_BOARD="stm32f4discovery" + +# +# Common Board Options +# +CONFIG_ARCH_HAVE_LEDS=y +CONFIG_ARCH_LEDS=y +CONFIG_ARCH_HAVE_BUTTONS=y +CONFIG_ARCH_BUTTONS=y +CONFIG_ARCH_HAVE_IRQBUTTONS=y +# CONFIG_ARCH_IRQBUTTONS is not set +CONFIG_NSH_MMCSDMINOR=0 + +# +# Board-Specific Options +# + +# +# RTOS Features +# +CONFIG_MSEC_PER_TICK=10 +CONFIG_RR_INTERVAL=200 +# CONFIG_SCHED_INSTRUMENTATION is not set +CONFIG_TASK_NAME_SIZE=0 +# CONFIG_SCHED_HAVE_PARENT is not set +# CONFIG_JULIAN_TIME is not set +CONFIG_START_YEAR=2013 +CONFIG_START_MONTH=1 +CONFIG_START_DAY=27 +CONFIG_DEV_CONSOLE=y +# CONFIG_MUTEX_TYPES is not set +# CONFIG_PRIORITY_INHERITANCE is not set +# CONFIG_FDCLONE_DISABLE is not set +# CONFIG_FDCLONE_STDIO is not set +CONFIG_SDCLONE_DISABLE=y +# CONFIG_SCHED_WORKQUEUE is not set +CONFIG_SCHED_WAITPID=y +# CONFIG_SCHED_STARTHOOK is not set +# CONFIG_SCHED_ATEXIT is not set +# CONFIG_SCHED_ONEXIT is not set +CONFIG_USER_ENTRYPOINT="nsh_main" +CONFIG_DISABLE_OS_API=y +# CONFIG_DISABLE_CLOCK is not set +# CONFIG_DISABLE_POSIX_TIMERS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_DISABLE_SIGNALS is not set +# CONFIG_DISABLE_MQUEUE is not set +# CONFIG_DISABLE_ENVIRON is not set + +# +# Signal Numbers +# +CONFIG_SIG_SIGUSR1=1 +CONFIG_SIG_SIGUSR2=2 +CONFIG_SIG_SIGALARM=3 +CONFIG_SIG_SIGCONDTIMEDOUT=16 + +# +# Sizes of configurable things (0 disables) +# +CONFIG_MAX_TASKS=16 +CONFIG_MAX_TASK_ARGS=4 +CONFIG_NPTHREAD_KEYS=4 +CONFIG_NFILE_DESCRIPTORS=8 +CONFIG_NFILE_STREAMS=8 +CONFIG_NAME_MAX=32 +CONFIG_PREALLOC_MQ_MSGS=4 +CONFIG_MQ_MAXMSGSIZE=32 +CONFIG_MAX_WDOGPARMS=2 +CONFIG_PREALLOC_WDOGS=4 +CONFIG_PREALLOC_TIMERS=4 + +# +# Stack and heap information +# +CONFIG_IDLETHREAD_STACKSIZE=2048 +CONFIG_USERMAIN_STACKSIZE=2048 +CONFIG_PTHREAD_STACK_MIN=256 +CONFIG_PTHREAD_STACK_DEFAULT=2048 + +# +# Device Drivers +# +CONFIG_DISABLE_POLL=y +CONFIG_DEV_NULL=y +# CONFIG_DEV_ZERO is not set +# CONFIG_LOOP is not set +# CONFIG_RAMDISK is not set +# CONFIG_CAN is not set +# CONFIG_PWM is not set +# CONFIG_I2C is not set +CONFIG_ARCH_HAVE_I2CRESET=y +CONFIG_SPI=y +# CONFIG_SPI_OWNBUS is not set +CONFIG_SPI_EXCHANGE=y +# CONFIG_SPI_CMDDATA is not set +# CONFIG_RTC is not set +# CONFIG_WATCHDOG is not set +# CONFIG_ANALOG is not set +# CONFIG_BCH is not set +# CONFIG_INPUT is not set +# CONFIG_LCD is not set +# CONFIG_MMCSD is not set +# CONFIG_MTD is not set +# CONFIG_PIPES is not set +# CONFIG_PM is not set +# CONFIG_POWER is not set +# CONFIG_SENSORS is not set +# CONFIG_SERCOMM_CONSOLE is not set +CONFIG_SERIAL=y +# CONFIG_DEV_LOWCONSOLE is not set +# CONFIG_16550_UART is not set +CONFIG_ARCH_HAVE_USART2=y +CONFIG_MCU_SERIAL=y +CONFIG_STANDARD_SERIAL=y +# CONFIG_USART2_SERIAL_CONSOLE is not set +CONFIG_NO_SERIAL_CONSOLE=y + +# +# USART2 Configuration +# +CONFIG_USART2_RXBUFSIZE=256 +CONFIG_USART2_TXBUFSIZE=256 +CONFIG_USART2_BAUD=115200 +CONFIG_USART2_BITS=8 +CONFIG_USART2_PARITY=0 +CONFIG_USART2_2STOP=0 +CONFIG_USBDEV=y + +# +# Device Controller Driver Options +# +# CONFIG_USBDEV_ISOCHRONOUS is not set +# CONFIG_USBDEV_DUALSPEED is not set +CONFIG_USBDEV_SELFPOWERED=y +# CONFIG_USBDEV_BUSPOWERED is not set +# CONFIG_USBDEV_DMA is not set +# CONFIG_USBDEV_TRACE is not set +# CONFIG_USBDEV_COMPOSITE is not set +# CONFIG_PL2303 is not set +CONFIG_CDCACM=y +CONFIG_CDCACM_CONSOLE=y +CONFIG_CDCACM_EP0MAXPACKET=64 +CONFIG_CDCACM_EPINTIN=2 +CONFIG_CDCACM_EPINTIN_FSSIZE=64 +CONFIG_CDCACM_EPINTIN_HSSIZE=64 +CONFIG_CDCACM_EPBULKOUT=0 +CONFIG_CDCACM_EPBULKOUT_FSSIZE=64 +CONFIG_CDCACM_EPBULKOUT_HSSIZE=512 +CONFIG_CDCACM_EPBULKIN=0 +CONFIG_CDCACM_EPBULKIN_FSSIZE=64 +CONFIG_CDCACM_EPBULKIN_HSSIZE=512 +CONFIG_CDCACM_NWRREQS=4 +CONFIG_CDCACM_NRDREQS=4 +CONFIG_CDCACM_RXBUFSIZE=256 +# CONFIG_CDCACM_TXBUFSIZE is not set +CONFIG_CDCACM_VENDORID=0x0525 +CONFIG_CDCACM_PRODUCTID=0xa4a7 +CONFIG_CDCACM_VENDORSTR="NuttX" +CONFIG_CDCACM_PRODUCTSTR="USBdev Serial" +# CONFIG_USBMSC is not set +# CONFIG_USBHOST is not set +# CONFIG_WIRELESS is not set + +# +# System Logging Device Options +# + +# +# System Logging +# +# CONFIG_RAMLOG is not set + +# +# Networking Support +# +# CONFIG_NET is not set + +# +# File Systems +# + +# +# File system configuration +# +# CONFIG_DISABLE_MOUNTPOINT is not set +# CONFIG_FS_RAMMAP is not set +# CONFIG_FS_FAT is not set +# CONFIG_FS_NXFFS is not set +# CONFIG_FS_ROMFS is not set +# CONFIG_FS_BINFS is not set + +# +# System Logging +# +CONFIG_SYSLOG=y +CONFIG_SYSLOG_CHAR=y +CONFIG_SYSLOG_DEVPATH="/dev/ttyS0" + +# +# Graphics Support +# +# CONFIG_NX is not set + +# +# Memory Management +# +# CONFIG_MM_SMALL is not set +CONFIG_MM_REGIONS=2 +# CONFIG_GRAN is not set + +# +# Binary Formats +# +# CONFIG_BINFMT_DISABLE is not set +# CONFIG_BINFMT_EXEPATH is not set +# CONFIG_NXFLAT is not set +# CONFIG_ELF is not set +CONFIG_BUILTIN=y +# CONFIG_PIC is not set +# CONFIG_SYMTAB_ORDEREDBYNAME is not set + +# +# Library Routines +# + +# +# Standard C Library Options +# +CONFIG_STDIO_BUFFER_SIZE=64 +CONFIG_STDIO_LINEBUFFER=y +CONFIG_NUNGET_CHARS=2 +CONFIG_LIB_HOMEDIR="/" +# CONFIG_LIBM is not set +# CONFIG_NOPRINTF_FIELDWIDTH is not set +# CONFIG_LIBC_FLOATINGPOINT is not set +# CONFIG_EOL_IS_CR is not set +# CONFIG_EOL_IS_LF is not set +# CONFIG_EOL_IS_BOTH_CRLF is not set +CONFIG_EOL_IS_EITHER_CRLF=y +# CONFIG_LIBC_EXECFUNCS is not set +# CONFIG_LIBC_STRERROR is not set +# CONFIG_LIBC_PERROR_STDOUT is not set +CONFIG_ARCH_LOWPUTC=y +CONFIG_LIB_SENDFILE_BUFSIZE=512 +# CONFIG_ARCH_ROMGETC is not set +# CONFIG_ARCH_OPTIMIZED_FUNCTIONS is not set + +# +# Non-standard Helper Functions +# +# CONFIG_LIB_KBDCODEC is not set + +# +# Basic CXX Support +# +# CONFIG_C99_BOOL8 is not set +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +# CONFIG_CXX_NEWLONG is not set + +# +# uClibc++ Standard C++ Library +# +# CONFIG_UCLIBCXX is not set + +# +# Application Configuration +# + +# +# Built-In Applications +# +CONFIG_BUILTIN_PROXY_STACKSIZE=1024 + +# +# Examples +# +# CONFIG_EXAMPLES_BUTTONS is not set +# CONFIG_EXAMPLES_CAN is not set +# CONFIG_EXAMPLES_CDCACM is not set +# CONFIG_EXAMPLES_COMPOSITE is not set +# CONFIG_EXAMPLES_CXXTEST is not set +# CONFIG_EXAMPLES_DHCPD is not set +# CONFIG_EXAMPLES_ELF is not set +# CONFIG_EXAMPLES_FTPC is not set +# CONFIG_EXAMPLES_FTPD is not set +# CONFIG_EXAMPLES_HELLO is not set +# CONFIG_EXAMPLES_HELLOXX is not set +# CONFIG_EXAMPLES_JSON is not set +# CONFIG_EXAMPLES_HIDKBD is not set +# CONFIG_EXAMPLES_KEYPADTEST is not set +# CONFIG_EXAMPLES_IGMP is not set +# CONFIG_EXAMPLES_LCDRW is not set +# CONFIG_EXAMPLES_MM is not set +# CONFIG_EXAMPLES_MOUNT is not set +# CONFIG_EXAMPLES_MODBUS is not set +CONFIG_EXAMPLES_NSH=y +# CONFIG_EXAMPLES_NULL is not set +# CONFIG_EXAMPLES_NX is not set +# CONFIG_EXAMPLES_NXCONSOLE is not set +# CONFIG_EXAMPLES_NXFFS is not set +# CONFIG_EXAMPLES_NXFLAT is not set +# CONFIG_EXAMPLES_NXHELLO is not set +# CONFIG_EXAMPLES_NXIMAGE is not set +# CONFIG_EXAMPLES_NXLINES is not set +# CONFIG_EXAMPLES_NXTEXT is not set +# CONFIG_EXAMPLES_OSTEST is not set +# CONFIG_EXAMPLES_PASHELLO is not set +# CONFIG_EXAMPLES_PIPE is not set +# CONFIG_EXAMPLES_POSIXSPAWN is not set +# CONFIG_EXAMPLES_QENCODER is not set +# CONFIG_EXAMPLES_RGMP is not set +# CONFIG_EXAMPLES_ROMFS is not set +# CONFIG_EXAMPLES_SENDMAIL is not set +# CONFIG_EXAMPLES_SERLOOP is not set +# CONFIG_EXAMPLES_TELNETD is not set +# CONFIG_EXAMPLES_THTTPD is not set +# CONFIG_EXAMPLES_TIFF is not set +# CONFIG_EXAMPLES_TOUCHSCREEN is not set +# CONFIG_EXAMPLES_UDP is not set +# CONFIG_EXAMPLES_UIP is not set +# CONFIG_EXAMPLES_USBSERIAL is not set +# CONFIG_EXAMPLES_USBMSC is not set +# CONFIG_EXAMPLES_USBTERM is not set +# CONFIG_EXAMPLES_WATCHDOG is not set + +# +# Interpreters +# + +# +# Interpreters +# +# CONFIG_INTERPRETERS_FICL is not set +# CONFIG_INTERPRETERS_PCODE is not set + +# +# Network Utilities +# + +# +# Networking Utilities +# +# CONFIG_NETUTILS_CODECS is not set +# CONFIG_NETUTILS_DHCPC is not set +# CONFIG_NETUTILS_DHCPD is not set +# CONFIG_NETUTILS_FTPC is not set +# CONFIG_NETUTILS_FTPD is not set +# CONFIG_NETUTILS_JSON is not set +# CONFIG_NETUTILS_RESOLV is not set +# CONFIG_NETUTILS_SMTP is not set +# CONFIG_NETUTILS_TELNETD is not set +# CONFIG_NETUTILS_TFTPC is not set +# CONFIG_NETUTILS_THTTPD is not set +# CONFIG_NETUTILS_UIPLIB is not set +# CONFIG_NETUTILS_WEBCLIENT is not set + +# +# ModBus +# + +# +# FreeModbus +# +# CONFIG_MODBUS is not set + +# +# NSH Library +# +CONFIG_NSH_LIBRARY=y +CONFIG_NSH_BUILTIN_APPS=y + +# +# Disable Individual commands +# +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +# CONFIG_NSH_DISABLE_DD is not set +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXIT is not set +# CONFIG_NSH_DISABLE_FREE is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_HEXDUMP is not set +# CONFIG_NSH_DISABLE_IFCONFIG is not set +# CONFIG_NSH_DISABLE_KILL is not set +# CONFIG_NSH_DISABLE_LOSETUP is not set +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MB is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +# CONFIG_NSH_DISABLE_MKFATFS is not set +# CONFIG_NSH_DISABLE_MKFIFO is not set +# CONFIG_NSH_DISABLE_MKRD is not set +# CONFIG_NSH_DISABLE_MH is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MW is not set +# CONFIG_NSH_DISABLE_NSFMOUNT is not set +# CONFIG_NSH_DISABLE_PS is not set +# CONFIG_NSH_DISABLE_PING is not set +# CONFIG_NSH_DISABLE_PUT is not set +# CONFIG_NSH_DISABLE_PWD is not set +# CONFIG_NSH_DISABLE_RM is not set +# CONFIG_NSH_DISABLE_RMDIR is not set +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SH is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +# CONFIG_NSH_DISABLE_TEST is not set +# CONFIG_NSH_DISABLE_UMOUNT is not set +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +# CONFIG_NSH_DISABLE_WGET is not set +# CONFIG_NSH_DISABLE_XD is not set +CONFIG_NSH_CODECS_BUFSIZE=128 +CONFIG_NSH_FILEIOSIZE=512 +CONFIG_NSH_LINELEN=64 +CONFIG_NSH_NESTDEPTH=3 +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLEBG is not set +CONFIG_NSH_CONSOLE=y +# CONFIG_NSH_USBCONSOLE is not set +# CONFIG_NSH_CONDEV is not set +CONFIG_NSH_ARCHINIT=y + +# +# NxWidgets/NxWM +# + +# +# System NSH Add-Ons +# + +# +# Custom Free Memory Command +# +# CONFIG_SYSTEM_FREE is not set + +# +# I2C tool +# + +# +# FLASH Program Installation +# +# CONFIG_SYSTEM_INSTALL is not set + +# +# readline() +# +CONFIG_SYSTEM_READLINE=y +CONFIG_READLINE_ECHO=y + +# +# Power Off +# +# CONFIG_SYSTEM_POWEROFF is not set + +# +# RAMTRON +# +# CONFIG_SYSTEM_RAMTRON is not set + +# +# SD Card +# +# CONFIG_SYSTEM_SDCARD is not set + +# +# Sysinfo +# +# CONFIG_SYSTEM_SYSINFO is not set diff --git a/nuttx/configs/stm32f4discovery/usbnsh/setenv.sh b/nuttx/configs/stm32f4discovery/usbnsh/setenv.sh new file mode 100755 index 000000000..a56f85d35 --- /dev/null +++ b/nuttx/configs/stm32f4discovery/usbnsh/setenv.sh @@ -0,0 +1,75 @@ +#!/bin/bash +# configs/stm32f4discovery/usbnsh/setenv.sh +# +# Copyright (C) 2013 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# +# 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. +# + +if [ "$_" = "$0" ] ; then + echo "You must source this script, not run it!" 1>&2 + exit 1 +fi + +WD=`pwd` +if [ ! -x "setenv.sh" ]; then + echo "This script must be executed from the top-level NuttX build directory" + exit 1 +fi + +if [ -z "${PATH_ORIG}" ]; then + export PATH_ORIG="${PATH}" +fi + +# This is the Cygwin path to the location where I installed the RIDE +# toolchain under windows. You will also have to edit this if you install +# the RIDE toolchain in any other location +#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" + +# This is the Cygwin path to the location where I installed the CodeSourcery +# toolchain under windows. You will also have to edit this if you install +# the CodeSourcery toolchain in any other location +export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" + +# These are the Cygwin paths to the locations where I installed the Atollic +# toolchain under windows. You will also have to edit this if you install +# the Atollic toolchain in any other location. /usr/bin is added before +# the Atollic bin path because there is are binaries named gcc.exe and g++.exe +# at those locations as well. +#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" +#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin" + +# This is the Cygwin path to the location where I build the buildroot +# toolchain. +#export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" + +# Add the path to the toolchain to the PATH varialble +export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" + +echo "PATH : ${PATH}" diff --git a/nuttx/drivers/usbdev/Kconfig b/nuttx/drivers/usbdev/Kconfig index 70c7a04f0..6fa4124be 100644 --- a/nuttx/drivers/usbdev/Kconfig +++ b/nuttx/drivers/usbdev/Kconfig @@ -154,6 +154,14 @@ menuconfig PL2303 This logic emulates the Prolific PL2303 serial/USB converter if PL2303 + +config PL2303_CONSOLE + bool "PL2303 console device" + default n + ---help--- + Register the USB device as /dev/console so that is will be used + as the console device. + config PL2303_EPINTIN int "Logical endpoint numbers" default 1 @@ -218,8 +226,16 @@ menuconfig CDCACM Enables USB Modem (CDC ACM) support if CDCACM + +config CDCACM_CONSOLE + bool "CDC/ACM console device" + default n + ---help--- + Register the USB device as /dev/console so that is will be used + as the console device. + config CDCACM_COMPOSITE - bool "CDCACM composite support" + bool "CDC/ACM composite support" default n depends on USBDEV_COMPOSITE ---help--- diff --git a/nuttx/fs/Kconfig b/nuttx/fs/Kconfig index ab03a2b64..e6647f516 100644 --- a/nuttx/fs/Kconfig +++ b/nuttx/fs/Kconfig @@ -24,23 +24,26 @@ config SYSLOG ---help--- Enables generic system logging features. -config SYSLOG_DEVPATH - string "System log device" - default "/dev/syslog" - depends on SYSLOG - ---help--- - The full path to the system logging device. For the RAMLOG SYSLOG device, - this is normally "/dev/ramlog". For character SYSLOG devices, it should be - some other existing character device (or file) supported by the configuration - (such as "/dev/ttyS1")/ +if SYSLOG config SYSLOG_CHAR bool "System log character device support" default y - depends on SYSLOG ---help--- Enable the generic character device for the SYSLOG. The full path to the SYSLOG device is provided by SYSLOG_DEVPATH. A valid character device (or file) must exist at this path. It will by opened by syslog_initialize. Do not enable more than one SYSLOG device. + +config SYSLOG_DEVPATH + string "System log device" + default "/dev/syslog" + depends on SYSLOG_CHAR + ---help--- + The full path to the system logging device. For the RAMLOG SYSLOG device, + this is normally "/dev/ramlog". For character SYSLOG devices, it should be + some other existing character device (or file) supported by the configuration + (such as "/dev/ttyS1")/ + +endif diff --git a/nuttx/fs/fs_syslog.c b/nuttx/fs/fs_syslog.c index 1d569082a..f348bdb03 100644 --- a/nuttx/fs/fs_syslog.c +++ b/nuttx/fs/fs_syslog.c @@ -265,7 +265,7 @@ int syslog_initialize(void) { /* The inode was not found. In this case, we will attempt to re-open * the device repeatedly. The assumption is that the device path is - * value but that the driver has not yet been registered. + * valid but that the driver has not yet been registered. */ g_sysdev.sl_state = SYSLOG_REOPEN; diff --git a/nuttx/libc/stdio/lib_lowprintf.c b/nuttx/libc/stdio/lib_lowprintf.c index f7d4ffe2f..667fad7be 100644 --- a/nuttx/libc/stdio/lib_lowprintf.c +++ b/nuttx/libc/stdio/lib_lowprintf.c @@ -38,8 +38,10 @@ ****************************************************************************/ #include + #include #include + #include "lib_internal.h" /* This interface can only be used from within the kernel */ diff --git a/nuttx/libc/stdio/lib_rawprintf.c b/nuttx/libc/stdio/lib_rawprintf.c index 98bbbea05..d8deba12d 100644 --- a/nuttx/libc/stdio/lib_rawprintf.c +++ b/nuttx/libc/stdio/lib_rawprintf.c @@ -37,8 +37,11 @@ * Included Files ****************************************************************************/ +#include + #include #include + #include "lib_internal.h" /**************************************************************************** diff --git a/nuttx/sched/os_start.c b/nuttx/sched/os_start.c index 5e6eaa858..c60edc495 100644 --- a/nuttx/sched/os_start.c +++ b/nuttx/sched/os_start.c @@ -327,6 +327,12 @@ void os_start(void) } #endif + /* Allocate the IDLE group and suppress child status. */ + +#ifdef HAVE_TASK_GROUP + (void)group_allocate(&g_idletcb); +#endif + /* Initialize the interrupt handling subsystem (if included) */ #ifdef CONFIG_HAVE_WEAKFUNCTIONS @@ -439,20 +445,21 @@ void os_start(void) lib_initialize(); } - /* Create the IDLE group and suppress child status */ - -#ifdef HAVE_TASK_GROUP - (void)group_allocate(&g_idletcb); - (void)group_initialize(&g_idletcb); - g_idletcb.group->tg_flags = GROUP_FLAG_NOCLDWAIT; -#endif - /* Create stdout, stderr, stdin on the IDLE task. These will be * inherited by all of the threads created by the IDLE task. */ (void)group_setupidlefiles(&g_idletcb); + /* Complete initialization of the IDLE group. Suppress retention + * of child status in the IDLE group. + */ + +#ifdef HAVE_TASK_GROUP + (void)group_initialize(&g_idletcb); + g_idletcb.group->tg_flags = GROUP_FLAG_NOCLDWAIT; +#endif + /* Create initial tasks and bring-up the system */ (void)os_bringup(); diff --git a/nuttx/sched/task_vfork.c b/nuttx/sched/task_vfork.c index 5b42a1e55..ac86ddc56 100644 --- a/nuttx/sched/task_vfork.c +++ b/nuttx/sched/task_vfork.c @@ -39,6 +39,7 @@ #include +#include #include #include #include -- cgit v1.2.3