From 25e9b8d0846b68a18014c63146234193bfe539e8 Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 24 Jan 2013 19:19:38 +0000 Subject: Fix poll/select issue reported by Qiang git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5559 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 5 +- nuttx/TODO | 19 +-- nuttx/arch/8051/src/up_reprioritizertr.c | 13 +- nuttx/arch/arm/src/armv7-m/up_reprioritizertr.c | 13 +- nuttx/arch/arm/src/lm/chip/lm4f_memorymap.h | 85 +++++++++++++ nuttx/arch/avr/src/avr/up_reprioritizertr.c | 13 +- nuttx/arch/avr/src/avr32/up_reprioritizertr.c | 13 +- nuttx/arch/hc/src/common/up_reprioritizertr.c | 2 +- nuttx/arch/mips/src/mips32/up_reprioritizertr.c | 13 +- nuttx/arch/sh/src/common/up_reprioritizertr.c | 13 +- nuttx/arch/sim/src/up_reprioritizertr.c | 6 +- nuttx/arch/x86/src/common/up_reprioritizertr.c | 2 +- nuttx/arch/z16/src/common/up_reprioritizertr.c | 13 +- nuttx/arch/z80/src/common/up_reprioritizertr.c | 13 +- nuttx/net/net_poll.c | 156 +++++++++++++++++------- 15 files changed, 279 insertions(+), 100 deletions(-) create mode 100644 nuttx/arch/arm/src/lm/chip/lm4f_memorymap.h diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index ffd1b66ae..2eaa03b21 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -4021,4 +4021,7 @@ * configs/olimex-lpc1766stk/nettest: Configuration converted to use the kconfig-frontends tools. * net/net_poll.c: Split net_poll() to create psock_poll() too. - + * net/net_poll.c: Fix poll/select issure reported by Qiang: + 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. diff --git a/nuttx/TODO b/nuttx/TODO index c302760ab..ed91515ba 100644 --- a/nuttx/TODO +++ b/nuttx/TODO @@ -1,4 +1,4 @@ -NuttX TODO List (Last updated January 23, 2013) +NuttX TODO List (Last updated January 24, 2013) ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ This file summarizes known NuttX bugs, limitations, inconsistencies with @@ -12,7 +12,7 @@ nuttx/ (2) pthreads (sched/) (2) C++ Support (6) Binary loaders (binfmt/) - (17) Network (net/, drivers/net) + (16) Network (net/, drivers/net) (4) USB (drivers/usbdev, drivers/usbhost) (12) Libraries (libc/, ) (9) File system/Generic drivers (fs/, drivers/) @@ -667,21 +667,6 @@ o Network (net/, drivers/net) Status: Open Priority: Low... fix defconfig files as necessary. - Title: net_poll() DOES NOT HANDLE LOSS-OF-CONNECTION CORRECTLY - Description: When a loss of connection is detected by any logic waiting on the - networking events, the function net_lostconnection() must be called. - That function just sets some bits in the socket structure so that - it remembers that the connection is lost. - - That is currently done in recvfrom(), send(), and net_monitor.c. But - it is not done in the net_poll() logic; that logic correctly sets - the POLLHUP status, but it does not call net_lostconnection(). As a - result, if recv() is called after the poll() or select(), the system - will hang because the recv() does not know that the connection has - been lost. - Status: Open - Priority: High - o USB (drivers/usbdev, drivers/usbhost) ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ diff --git a/nuttx/arch/8051/src/up_reprioritizertr.c b/nuttx/arch/8051/src/up_reprioritizertr.c index 6d4a72487..0d1941f66 100644 --- a/nuttx/arch/8051/src/up_reprioritizertr.c +++ b/nuttx/arch/8051/src/up_reprioritizertr.c @@ -1,7 +1,7 @@ /**************************************************************************** * up_reprioritizertr.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 @@ -90,9 +90,14 @@ void up_reprioritize_rtr(FAR _TCB *tcb, uint8_t priority) /* Verify that the caller is sane */ if (tcb->task_state < FIRST_READY_TO_RUN_STATE || - tcb->task_state > LAST_READY_TO_RUN_STATE || - priority < SCHED_PRIORITY_MIN || - priority > SCHED_PRIORITY_MAX) + tcb->task_state > LAST_READY_TO_RUN_STATE +#if SCHED_PRIORITY_MIN > 0 + || priority < SCHED_PRIORITY_MIN +#endif +#if SCHED_PRIORITY_MAX < UINT8_MAX + || priority > SCHED_PRIORITY_MAX +#endif + ) { PANIC(OSERR_BADREPRIORITIZESTATE); } diff --git a/nuttx/arch/arm/src/armv7-m/up_reprioritizertr.c b/nuttx/arch/arm/src/armv7-m/up_reprioritizertr.c index f1c961b15..9a971f064 100644 --- a/nuttx/arch/arm/src/armv7-m/up_reprioritizertr.c +++ b/nuttx/arch/arm/src/armv7-m/up_reprioritizertr.c @@ -1,7 +1,7 @@ /**************************************************************************** * arch/arm/src/armv7-m/up_reprioritizertr.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 @@ -89,9 +89,14 @@ void up_reprioritize_rtr(_TCB *tcb, uint8_t priority) /* Verify that the caller is sane */ if (tcb->task_state < FIRST_READY_TO_RUN_STATE || - tcb->task_state > LAST_READY_TO_RUN_STATE || - priority < SCHED_PRIORITY_MIN || - priority > SCHED_PRIORITY_MAX) + tcb->task_state > LAST_READY_TO_RUN_STATE +#if SCHED_PRIORITY_MIN > 0 + || priority < SCHED_PRIORITY_MIN +#endif +#if SCHED_PRIORITY_MAX < UINT8_MAX + || priority > SCHED_PRIORITY_MAX +#endif + ) { PANIC(OSERR_BADREPRIORITIZESTATE); } diff --git a/nuttx/arch/arm/src/lm/chip/lm4f_memorymap.h b/nuttx/arch/arm/src/lm/chip/lm4f_memorymap.h new file mode 100644 index 000000000..6963545fe --- /dev/null +++ b/nuttx/arch/arm/src/lm/chip/lm4f_memorymap.h @@ -0,0 +1,85 @@ +/************************************************************************************ + * arch/arm/src/lm/chip/lm3s_memorymap.h + * + * Copyright (C) 2013 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * Jose Pablo Carballo + * + * 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 __ARCH_ARM_SRC_LM_CHIP_LM4F_MEMORYMAP_H +#define __ARCH_ARM_SRC_LM_CHIP_LM4F_MEMORYMAP_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Memory map ***********************************************************************/ + +#if defined(CONFIG_ARCH_CHIP_LM4F120) +# define LM_FLASH_BASE 0x00000000 /* -0x0003ffff: On-chip FLASH */ + /* -0x00ffffff: Reserved */ +# define LM_ROM_BASE 0x01000000 /* -0x1fffffff: Reserved for ROM */ +# define LM_SRAM_BASE 0x20000000 /* -0x20007fff: Bit-banded on-chip SRAM */ + /* -0x21ffffff: Reserved */ +/* @TODO */ +#endif + +#else +# error "Memory map not specified for this LM4F chip" +#endif + +/* Peripheral base addresses ********************************************************/ + +#if defined(CONFIG_ARCH_CHIP_LM4F120) +/* @TODO */ +#else +# error "Peripheral base addresses not specified for this Stellaris chip" +#endif + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +/************************************************************************************ + * Public Function Prototypes + ************************************************************************************/ + +#endif /* __ARCH_ARM_SRC_LM_CHIP_LM4F_MEMORYMAP_H */ diff --git a/nuttx/arch/avr/src/avr/up_reprioritizertr.c b/nuttx/arch/avr/src/avr/up_reprioritizertr.c index 14033a3bd..af329c13f 100644 --- a/nuttx/arch/avr/src/avr/up_reprioritizertr.c +++ b/nuttx/arch/avr/src/avr/up_reprioritizertr.c @@ -1,7 +1,7 @@ /**************************************************************************** * arch/avr/src/avr/up_reprioritizertr.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 @@ -89,9 +89,14 @@ void up_reprioritize_rtr(_TCB *tcb, uint8_t priority) /* Verify that the caller is sane */ if (tcb->task_state < FIRST_READY_TO_RUN_STATE || - tcb->task_state > LAST_READY_TO_RUN_STATE || - priority < SCHED_PRIORITY_MIN || - priority > SCHED_PRIORITY_MAX) + tcb->task_state > LAST_READY_TO_RUN_STATE +#if SCHED_PRIORITY_MIN > 0 + || priority < SCHED_PRIORITY_MIN +#endif +#if SCHED_PRIORITY_MAX < UINT8_MAX + || priority > SCHED_PRIORITY_MAX +#endif + ) { PANIC(OSERR_BADREPRIORITIZESTATE); } diff --git a/nuttx/arch/avr/src/avr32/up_reprioritizertr.c b/nuttx/arch/avr/src/avr32/up_reprioritizertr.c index e1712fed0..0aad214e8 100644 --- a/nuttx/arch/avr/src/avr32/up_reprioritizertr.c +++ b/nuttx/arch/avr/src/avr32/up_reprioritizertr.c @@ -1,7 +1,7 @@ /**************************************************************************** * arch/avr/src/avr32/up_reprioritizertr.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 @@ -89,9 +89,14 @@ void up_reprioritize_rtr(_TCB *tcb, uint8_t priority) /* Verify that the caller is sane */ if (tcb->task_state < FIRST_READY_TO_RUN_STATE || - tcb->task_state > LAST_READY_TO_RUN_STATE || - priority < SCHED_PRIORITY_MIN || - priority > SCHED_PRIORITY_MAX) + tcb->task_state > LAST_READY_TO_RUN_STATE +#if SCHED_PRIORITY_MIN > 0 + || priority < SCHED_PRIORITY_MIN +#endif +#if SCHED_PRIORITY_MAX < UINT8_MAX + || priority > SCHED_PRIORITY_MAX +#endif + ) { PANIC(OSERR_BADREPRIORITIZESTATE); } diff --git a/nuttx/arch/hc/src/common/up_reprioritizertr.c b/nuttx/arch/hc/src/common/up_reprioritizertr.c index ffd90bf1f..31c76a9f5 100644 --- a/nuttx/arch/hc/src/common/up_reprioritizertr.c +++ b/nuttx/arch/hc/src/common/up_reprioritizertr.c @@ -1,7 +1,7 @@ /**************************************************************************** * arch/hc/src/common/up_reprioritizertr.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 diff --git a/nuttx/arch/mips/src/mips32/up_reprioritizertr.c b/nuttx/arch/mips/src/mips32/up_reprioritizertr.c index 66ce687e0..2e5f41d68 100644 --- a/nuttx/arch/mips/src/mips32/up_reprioritizertr.c +++ b/nuttx/arch/mips/src/mips32/up_reprioritizertr.c @@ -1,7 +1,7 @@ /**************************************************************************** * arch/mips/src/mips32/up_reprioritizertr.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 @@ -91,9 +91,14 @@ void up_reprioritize_rtr(_TCB *tcb, uint8_t priority) /* Verify that the caller is sane */ if (tcb->task_state < FIRST_READY_TO_RUN_STATE || - tcb->task_state > LAST_READY_TO_RUN_STATE || - priority < SCHED_PRIORITY_MIN || - priority > SCHED_PRIORITY_MAX) + tcb->task_state > LAST_READY_TO_RUN_STATE +#if SCHED_PRIORITY_MIN > 0 + || priority < SCHED_PRIORITY_MIN +#endif +#if SCHED_PRIORITY_MAX < UINT8_MAX + || priority > SCHED_PRIORITY_MAX +#endif + ) { PANIC(OSERR_BADREPRIORITIZESTATE); } diff --git a/nuttx/arch/sh/src/common/up_reprioritizertr.c b/nuttx/arch/sh/src/common/up_reprioritizertr.c index 728cafdf3..99d350b29 100644 --- a/nuttx/arch/sh/src/common/up_reprioritizertr.c +++ b/nuttx/arch/sh/src/common/up_reprioritizertr.c @@ -1,7 +1,7 @@ /**************************************************************************** * arch/sh/src/common/up_reprioritizertr.c * - * Copyright (C) 2008-2009, 2011 Gregory Nutt. All rights reserved. + * Copyright (C) 2008-2009, 2011, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -89,9 +89,14 @@ void up_reprioritize_rtr(_TCB *tcb, uint8_t priority) /* Verify that the caller is sane */ if (tcb->task_state < FIRST_READY_TO_RUN_STATE || - tcb->task_state > LAST_READY_TO_RUN_STATE || - priority < SCHED_PRIORITY_MIN || - priority > SCHED_PRIORITY_MAX) + tcb->task_state > LAST_READY_TO_RUN_STATE +#if SCHED_PRIORITY_MIN > 0 + || priority < SCHED_PRIORITY_MIN +#endif +#if SCHED_PRIORITY_MAX < UINT8_MAX + || priority > SCHED_PRIORITY_MAX +#endif + ) { PANIC(OSERR_BADREPRIORITIZESTATE); } diff --git a/nuttx/arch/sim/src/up_reprioritizertr.c b/nuttx/arch/sim/src/up_reprioritizertr.c index 913d8d5f5..15c1b26d5 100644 --- a/nuttx/arch/sim/src/up_reprioritizertr.c +++ b/nuttx/arch/sim/src/up_reprioritizertr.c @@ -1,7 +1,7 @@ /**************************************************************************** * up_reprioritizertr.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 @@ -91,13 +91,13 @@ void up_reprioritize_rtr(_TCB *tcb, uint8_t priority) if (tcb->task_state < FIRST_READY_TO_RUN_STATE || tcb->task_state > LAST_READY_TO_RUN_STATE -#if SCHED_PRIORITY_MIN > UINT8_MIN +#if SCHED_PRIORITY_MIN > 0 || priority < SCHED_PRIORITY_MIN #endif #if SCHED_PRIORITY_MAX < UINT8_MAX || priority > SCHED_PRIORITY_MAX #endif - ) + ) { PANIC(OSERR_BADREPRIORITIZESTATE); } diff --git a/nuttx/arch/x86/src/common/up_reprioritizertr.c b/nuttx/arch/x86/src/common/up_reprioritizertr.c index ad8a748a8..53a0e4315 100644 --- a/nuttx/arch/x86/src/common/up_reprioritizertr.c +++ b/nuttx/arch/x86/src/common/up_reprioritizertr.c @@ -1,7 +1,7 @@ /**************************************************************************** * arch/arm/src/arm/up_reprioritizertr.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 diff --git a/nuttx/arch/z16/src/common/up_reprioritizertr.c b/nuttx/arch/z16/src/common/up_reprioritizertr.c index 0363184cd..6e76d6ce1 100644 --- a/nuttx/arch/z16/src/common/up_reprioritizertr.c +++ b/nuttx/arch/z16/src/common/up_reprioritizertr.c @@ -1,7 +1,7 @@ /**************************************************************************** * common/up_reprioritizertr.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 @@ -91,9 +91,14 @@ void up_reprioritize_rtr(FAR _TCB *tcb, uint8_t priority) /* Verify that the caller is sane */ if (tcb->task_state < FIRST_READY_TO_RUN_STATE || - tcb->task_state > LAST_READY_TO_RUN_STATE || - priority < SCHED_PRIORITY_MIN || - priority > SCHED_PRIORITY_MAX) + tcb->task_state > LAST_READY_TO_RUN_STATE +#if SCHED_PRIORITY_MIN > 0 + || priority < SCHED_PRIORITY_MIN +#endif +#if SCHED_PRIORITY_MAX < UINT8_MAX + || priority > SCHED_PRIORITY_MAX +#endif + ) { PANIC(OSERR_BADREPRIORITIZESTATE); } diff --git a/nuttx/arch/z80/src/common/up_reprioritizertr.c b/nuttx/arch/z80/src/common/up_reprioritizertr.c index 84cd3e1e1..b8102c99f 100644 --- a/nuttx/arch/z80/src/common/up_reprioritizertr.c +++ b/nuttx/arch/z80/src/common/up_reprioritizertr.c @@ -1,7 +1,7 @@ /**************************************************************************** * arch/z80/src/common/up_reprioritizertr.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 @@ -92,9 +92,14 @@ void up_reprioritize_rtr(FAR _TCB *tcb, uint8_t priority) /* Verify that the caller is sane */ if (tcb->task_state < FIRST_READY_TO_RUN_STATE || - tcb->task_state > LAST_READY_TO_RUN_STATE || - priority < SCHED_PRIORITY_MIN || - priority > SCHED_PRIORITY_MAX) + tcb->task_state > LAST_READY_TO_RUN_STATE +#if SCHED_PRIORITY_MIN > 0 + || priority < SCHED_PRIORITY_MIN +#endif +#if SCHED_PRIORITY_MAX < UINT8_MAX + || priority > SCHED_PRIORITY_MAX +#endif + ) { PANIC(OSERR_BADREPRIORITIZESTATE); } diff --git a/nuttx/net/net_poll.c b/nuttx/net/net_poll.c index 2e73bd73c..ea6f54a6b 100644 --- a/nuttx/net/net_poll.c +++ b/nuttx/net/net_poll.c @@ -1,7 +1,7 @@ /**************************************************************************** * net/net_poll.c * - * Copyright (C) 2008-2009, 2011-2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2008-2009, 2011-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -46,11 +46,13 @@ #include #include #include +#include #include +#include +#include #include #include -#include #include @@ -75,6 +77,14 @@ /**************************************************************************** * Private Types ****************************************************************************/ +/* This is an allocated container that holds the poll-related information */ + +struct net_poll_s +{ + FAR struct socket *psock; /* Needed to handle loss of connection */ + struct pollfd *fds; /* Needed to handle poll events */ + FAR struct uip_callback_s *cb; /* Needed to teardown the poll */ +}; /**************************************************************************** * Private Functions @@ -101,16 +111,18 @@ ****************************************************************************/ #ifdef HAVE_NETPOLL -static uint16_t poll_interrupt(struct uip_driver_s *dev, FAR void *conn, +static uint16_t poll_interrupt(FAR struct uip_driver_s *dev, FAR void *conn, FAR void *pvpriv, uint16_t flags) { - FAR struct pollfd *fds = (FAR struct pollfd *)pvpriv; + FAR struct net_poll_s *info = (FAR struct net_poll_s *)pvpriv; nllvdbg("flags: %04x\n", flags); + DEBUGASSERT(info && info->psock && info->fds); + /* 'priv' might be null in some race conditions (?) */ - if (fds) + if (info->fds) { pollevent_t eventset = 0; @@ -118,24 +130,23 @@ static uint16_t poll_interrupt(struct uip_driver_s *dev, FAR void *conn, if ((flags & (UIP_NEWDATA|UIP_BACKLOG)) != 0) { - eventset |= POLLIN & fds->events; + eventset |= POLLIN & info->fds->events; } /* A poll is a sign that we are free to send data. */ if ((flags & UIP_POLL) != 0) { - eventset |= (POLLOUT & fds->events); + eventset |= (POLLOUT & info->fds->events); } - /* Check for a loss of connection events. - * - * REVISIT: Need to call net_lostconnection() here, but don't have - * the psock instance. What should we do? - */ + /* Check for a loss of connection events. */ if ((flags & (UIP_CLOSE|UIP_ABORT|UIP_TIMEDOUT)) != 0) { + /* Make the the connection has been lost */ + + net_lostconnection(info->psock, flags); eventset |= (POLLERR | POLLHUP); } @@ -143,8 +154,8 @@ static uint16_t poll_interrupt(struct uip_driver_s *dev, FAR void *conn, if (eventset) { - fds->revents |= eventset; - sem_post(fds->sem); + info->fds->revents |= eventset; + sem_post(info->fds->sem); } } @@ -169,9 +180,11 @@ static uint16_t poll_interrupt(struct uip_driver_s *dev, FAR void *conn, ****************************************************************************/ #ifdef HAVE_NETPOLL -static inline int net_pollsetup(FAR struct socket *psock, struct pollfd *fds) +static inline int net_pollsetup(FAR struct socket *psock, + FAR struct pollfd *fds) { FAR struct uip_conn *conn = psock->s_conn; + FAR struct net_poll_s *info; FAR struct uip_callback_s *cb; uip_lock_t flags; int ret; @@ -185,6 +198,14 @@ static inline int net_pollsetup(FAR struct socket *psock, struct pollfd *fds) } #endif + /* Allocate a container to hold the poll information */ + + info = (FAR struct net_poll_s *)kmalloc(sizeof(struct net_poll_s)); + if (!info) + { + return -ENOMEM; + } + /* Some of the following must be atomic */ flags = uip_lock(); @@ -195,18 +216,29 @@ static inline int net_pollsetup(FAR struct socket *psock, struct pollfd *fds) if (!cb) { ret = -EBUSY; - goto errout_with_irq; + goto errout_with_lock; } - /* Initialize the callback structure */ + /* Initialize the poll info container */ + + info->psock = psock; + info->fds = fds; + info->cb = cb; + + /* Initialize the callback structure. Save the reference to the info + * structure as callback private data so that it will be available during + * callback processing. + */ cb->flags = (UIP_NEWDATA|UIP_BACKLOG|UIP_POLL|UIP_CLOSE|UIP_ABORT|UIP_TIMEDOUT); - cb->priv = (FAR void *)fds; + cb->priv = (FAR void *)info; cb->event = poll_interrupt; - /* Save the nps reference in the poll structure for use at teardown as well */ + /* Save the reference in the poll info structure as fds private as well + * for use durring poll teardown as well. + */ - fds->priv = (FAR void *)cb; + fds->priv = (FAR void *)info; #ifdef CONFIG_NET_TCPBACKLOG /* Check for read data or backlogged connection availability now */ @@ -240,7 +272,8 @@ static inline int net_pollsetup(FAR struct socket *psock, struct pollfd *fds) uip_unlock(flags); return OK; -errout_with_irq: +errout_with_lock: + kfree(info); uip_unlock(flags); return ret; } @@ -261,10 +294,11 @@ errout_with_irq: ****************************************************************************/ #ifdef HAVE_NETPOLL -static inline int net_pollteardown(FAR struct socket *psock, struct pollfd *fds) +static inline int net_pollteardown(FAR struct socket *psock, + FAR struct pollfd *fds) { FAR struct uip_conn *conn = psock->s_conn; - FAR struct uip_callback_s *cb; + FAR struct net_poll_s *info; uip_lock_t flags; /* Sanity check */ @@ -278,18 +312,23 @@ static inline int net_pollteardown(FAR struct socket *psock, struct pollfd *fds) /* Recover the socket descriptor poll state info from the poll structure */ - cb = (FAR struct uip_callback_s *)fds->priv; - if (cb) + info = (FAR struct net_poll_s *)fds->priv; + DEBUGASSERT(info && info->fds && info->cb); + if (info) { /* Release the callback */ flags = uip_lock(); - uip_tcpcallbackfree(conn, cb); + uip_tcpcallbackfree(conn, info->cb); uip_unlock(flags); /* Release the poll/select data slot */ - fds->priv = NULL; + info->fds->priv = NULL; + + /* Then free the poll info container */ + + kfree(info); } return OK; @@ -308,7 +347,7 @@ static inline int net_pollteardown(FAR struct socket *psock, struct pollfd *fds) * to this function. * * Input Parameters: - * fd - The socket descriptor of interest + * psock - An instance of the internal socket structure. * fds - The structure describing the events to be monitored, OR NULL if * this is a request to stop monitoring events. * setup - true: Setup up the poll; false: Teardown the poll @@ -318,26 +357,11 @@ static inline int net_pollteardown(FAR struct socket *psock, struct pollfd *fds) * ****************************************************************************/ -#ifndef CONFIG_DISABLE_POLL -int net_poll(int sockfd, struct pollfd *fds, bool setup) +#if !defined(CONFIG_DISABLE_POLL) && defined(HAVE_NETPOLL) +int psock_poll(FAR struct socket *psock, FAR struct pollfd *fds, bool setup) { -#ifndef HAVE_NETPOLL - return -ENOSYS; -#else - FAR struct socket *psock; int ret; - /* Get the underlying socket structure and verify that the sockfd - * corresponds to valid, allocated socket - */ - - psock = sockfd_socket(sockfd); - if (!psock || psock->s_crefs <= 0) - { - ret = -EBADF; - goto errout; - } - #ifdef CONFIG_NET_UDP /* poll() not supported for UDP */ @@ -365,6 +389,48 @@ int net_poll(int sockfd, struct pollfd *fds, bool setup) errout: return ret; +} +#endif + +/**************************************************************************** + * Function: net_poll + * + * Description: + * The standard poll() operation redirects operations on socket descriptors + * to this function. + * + * Input Parameters: + * fd - The socket descriptor of interest + * fds - The structure describing the events to be monitored, OR NULL if + * this is a request to stop monitoring events. + * setup - true: Setup up the poll; false: Teardown the poll + * + * Returned Value: + * 0: Success; Negated errno on failure + * + ****************************************************************************/ + +#ifndef CONFIG_DISABLE_POLL +int net_poll(int sockfd, struct pollfd *fds, bool setup) +{ +#ifndef HAVE_NETPOLL + return -ENOSYS; +#else + FAR struct socket *psock; + + /* Get the underlying socket structure and verify that the sockfd + * corresponds to valid, allocated socket + */ + + psock = sockfd_socket(sockfd); + if (!psock || psock->s_crefs <= 0) + { + return -EBADF; + } + + /* Then let psock_poll() do the heavy lifting */ + + return psock_poll(psock, fds, setup); #endif /* HAVE_NETPOLL */ } #endif /* !CONFIG_DISABLE_POLL */ -- cgit v1.2.3