summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-03-07 17:59:21 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-03-07 17:59:21 +0000
commit76494a2d103c88d1c3888a6f0348a6b7e31b564d (patch)
tree14e5b1ce78a004bf1154cb1091782f32f19fb8b5 /nuttx
parent24151ccd83ce2d0d75bb9c45b137215c24c821c3 (diff)
downloadpx4-nuttx-76494a2d103c88d1c3888a6f0348a6b7e31b564d.tar.gz
px4-nuttx-76494a2d103c88d1c3888a6f0348a6b7e31b564d.tar.bz2
px4-nuttx-76494a2d103c88d1c3888a6f0348a6b7e31b564d.zip
Fix network poll() issue: don't interrupt poll if socket not connected. Listen sockets are not connected and the poll() is waiting for connection events.
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5717 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/arch/arm/src/lm/lm_gpio.c2
-rwxr-xr-xnuttx/configs/lm3s6965-ek/nsh/setenv.sh25
-rwxr-xr-xnuttx/configs/lm3s6965-ek/nx/setenv.sh25
-rwxr-xr-xnuttx/configs/lm3s6965-ek/ostest/setenv.sh25
-rwxr-xr-xnuttx/configs/lm3s6965-ek/tools/oocd.sh18
-rw-r--r--nuttx/fs/fs_select.c57
-rw-r--r--nuttx/include/nuttx/kmalloc.h14
-rw-r--r--nuttx/net/net_poll.c19
8 files changed, 147 insertions, 38 deletions
diff --git a/nuttx/arch/arm/src/lm/lm_gpio.c b/nuttx/arch/arm/src/lm/lm_gpio.c
index a33d229c9..6607966a2 100644
--- a/nuttx/arch/arm/src/lm/lm_gpio.c
+++ b/nuttx/arch/arm/src/lm/lm_gpio.c
@@ -764,7 +764,7 @@ static inline void lm_portcontrol(uint32_t base, uint32_t pinno,
putreg32(regval, base + LM_GPIO_PCTL_OFFSET);
}
#else
-# define lm_portcontrol(b,p,f)
+# define lm_portcontrol(b,p,c,f)
#endif
/****************************************************************************
diff --git a/nuttx/configs/lm3s6965-ek/nsh/setenv.sh b/nuttx/configs/lm3s6965-ek/nsh/setenv.sh
index 0636f2fed..98ea7e573 100755
--- a/nuttx/configs/lm3s6965-ek/nsh/setenv.sh
+++ b/nuttx/configs/lm3s6965-ek/nsh/setenv.sh
@@ -32,15 +32,32 @@
# POSSIBILITY OF SUCH DAMAGE.
#
-if [ "$(basename $0)" = "setenv.sh" ] ; then
+if [ "$_" = "$0" ] ; then
echo "You must source this script, not run it!" 1>&2
exit 1
fi
-if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; 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 build the buildroot
+# toolchain.
+
export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin"
-export PATH="${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
+
+# This is the path to the LM3S6995-EK tools directory
+
+export TOOL_BIN="${WD}/configs/lm3s6965-ek/tools"
+
+# Update the PATH variable
+
+export PATH="${BUILDROOT_BIN}:${TOOL_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
echo "PATH : ${PATH}"
diff --git a/nuttx/configs/lm3s6965-ek/nx/setenv.sh b/nuttx/configs/lm3s6965-ek/nx/setenv.sh
index 3edb2710e..43bbeada9 100755
--- a/nuttx/configs/lm3s6965-ek/nx/setenv.sh
+++ b/nuttx/configs/lm3s6965-ek/nx/setenv.sh
@@ -32,15 +32,32 @@
# POSSIBILITY OF SUCH DAMAGE.
#
-if [ "$(basename $0)" = "setenv.sh" ] ; then
+if [ "$_" = "$0" ] ; then
echo "You must source this script, not run it!" 1>&2
exit 1
fi
-if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; 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 build the buildroot
+# toolchain.
+
export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin"
-export PATH="${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
+
+# This is the path to the LM3S6995-EK tools directory
+
+export TOOL_BIN="${WD}/configs/lm3s6965-ek/tools"
+
+# Update the PATH variable
+
+export PATH="${BUILDROOT_BIN}:${TOOL_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
echo "PATH : ${PATH}"
diff --git a/nuttx/configs/lm3s6965-ek/ostest/setenv.sh b/nuttx/configs/lm3s6965-ek/ostest/setenv.sh
index 686a61701..1ac3ec5e3 100755
--- a/nuttx/configs/lm3s6965-ek/ostest/setenv.sh
+++ b/nuttx/configs/lm3s6965-ek/ostest/setenv.sh
@@ -32,15 +32,32 @@
# POSSIBILITY OF SUCH DAMAGE.
#
-if [ "$(basename $0)" = "setenv.sh" ] ; then
+if [ "$_" = "$0" ] ; then
echo "You must source this script, not run it!" 1>&2
exit 1
fi
-if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; 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 build the buildroot
+# toolchain.
+
export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin"
-export PATH="${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
+
+# This is the path to the LM3S6995-EK tools directory
+
+export TOOL_BIN="${WD}/configs/lm3s6965-ek/tools"
+
+# Update the PATH variable
+
+export PATH="${BUILDROOT_BIN}:${TOOL_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
echo "PATH : ${PATH}"
diff --git a/nuttx/configs/lm3s6965-ek/tools/oocd.sh b/nuttx/configs/lm3s6965-ek/tools/oocd.sh
index 758d11450..86eab3992 100755
--- a/nuttx/configs/lm3s6965-ek/tools/oocd.sh
+++ b/nuttx/configs/lm3s6965-ek/tools/oocd.sh
@@ -13,15 +13,21 @@ fi
# Assume that OpenOCD was installed and at /usr/local/bin. Uncomment
# the following to run directly from the build directory
-#OPENOCD_PATH="/home/OpenOCD/openocd/src"
-#TARGET_PATH="/home/OpenOCD/openocd/tcl"
-OPENOCD_PATH="/usr/bin"
-TARGET_PATH="/usr/share/openocd/scripts"
+
+# OPENOCD_PATH="/home/OpenOCD/openocd/src"
+# OPENOCD_PATH="/usr/bin"
+OPENOCD_PATH="/usr/local/bin"
+
+# TARGET_PATH="/home/OpenOCD/openocd/tcl"
+# TARGET_PATH="/usr/share/openocd/scripts"
+TARGET_PATH="/usr/local/share/openocd/scripts"
# Assume a Unix development environment. Uncomment to use a Windows
# like environment
-#OPENOCD_EXE=openocd.exe
-OPENOCD_EXE=openocd
+
+OPENOCD_EXE=openocd.exe
+# OPENOCD_EXE=openocd
+
OPENOCD_CFG="${TOPDIR}/configs/lm3s6965-ek/tools/lm3s6965-ek.cfg"
OPENOCD_ARGS="-f ${OPENOCD_CFG} -s ${TARGET_PATH}"
diff --git a/nuttx/fs/fs_select.c b/nuttx/fs/fs_select.c
index e40c5bc13..206e73be0 100644
--- a/nuttx/fs/fs_select.c
+++ b/nuttx/fs/fs_select.c
@@ -1,7 +1,7 @@
/****************************************************************************
* fs/fs_select.c
*
- * Copyright (C) 2008-2009, 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2008-2009, 2012-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -109,9 +109,27 @@ int select(int nfds, FAR fd_set *readfds, FAR fd_set *writefds,
int ndx;
int ret;
+ /* How many pollfd structures do we need to allocate? */
+
+ /* Initialize the descriptor list for poll() */
+
+ for (fd = 0, npfds = 0; fd < nfds; fd++)
+ {
+ /* Check if any monitor operation is requested on this fd */
+
+ if (readfds && FD_ISSET(fd, readfds) ||
+ writefds && FD_ISSET(fd, writefds) ||
+ exceptfds && FD_ISSET(fd, exceptfds))
+ {
+ /* Yes.. increment the count of pollfds structures needed */
+
+ npfds++;
+ }
+ }
+
/* Allocate the descriptor list for poll() */
- pollset = (struct pollfd *)kzalloc(nfds * sizeof(struct pollfd));
+ pollset = (struct pollfd *)kzalloc(npfds * sizeof(struct pollfd));
if (!pollset)
{
set_errno(ENOMEM);
@@ -120,7 +138,7 @@ int select(int nfds, FAR fd_set *readfds, FAR fd_set *writefds,
/* Initialize the descriptor list for poll() */
- for (fd = 0, npfds = 0; fd < nfds; fd++)
+ for (fd = 0, ndx = 0; fd < nfds; fd++)
{
int incr = 0;
@@ -133,9 +151,9 @@ int select(int nfds, FAR fd_set *readfds, FAR fd_set *writefds,
if (readfds && FD_ISSET(fd, readfds))
{
- pollset[npfds].fd = fd;
- pollset[npfds].events |= POLLIN;
- incr = 1;
+ pollset[ndx].fd = fd;
+ pollset[ndx].events |= POLLIN;
+ incr = 1;
}
/* The writefds set holds the set of FDs that the caller can be assured
@@ -144,25 +162,38 @@ int select(int nfds, FAR fd_set *readfds, FAR fd_set *writefds,
if (writefds && FD_ISSET(fd, writefds))
{
- pollset[npfds].fd = fd;
- pollset[npfds].events |= POLLOUT;
- incr = 1;
+ pollset[ndx].fd = fd;
+ pollset[ndx].events |= POLLOUT;
+ incr = 1;
}
/* The exceptfds set holds the set of FDs that are watched for exceptions */
if (exceptfds && FD_ISSET(fd, exceptfds))
{
- pollset[npfds].fd = fd;
- incr = 1;
+ pollset[ndx].fd = fd;
+ incr = 1;
}
- npfds += incr;
+ ndx += incr;
}
+ DEBUGASSERT(ndx == npfds);
+
/* Convert the timeout to milliseconds */
- msec = timeout->tv_sec * 1000 + timeout->tv_usec / 1000;
+ if (timeout)
+ {
+ /* Calculate the timeout in milliseconds */
+
+ msec = timeout->tv_sec * 1000 + timeout->tv_usec / 1000;
+ }
+ else
+ {
+ /* Any negative value of msec means no timeout */
+
+ msec = -1;
+ }
/* Then let poll do all of the real work. */
diff --git a/nuttx/include/nuttx/kmalloc.h b/nuttx/include/nuttx/kmalloc.h
index 75f7cd67a..de0246370 100644
--- a/nuttx/include/nuttx/kmalloc.h
+++ b/nuttx/include/nuttx/kmalloc.h
@@ -100,16 +100,22 @@ void kfree(FAR void*);
#endif
-/* Functions defined in os_list.c *******************************************/
+/* Functions defined in sched/sched_free.c **********************************/
-/* Handles memory freed from an interrupt handler */
+/* Handles memory freed from an interrupt handler. In that context, kfree()
+ * cannot be called. Instead, the allocations are saved in a list of
+ * delayed allocations that will be periodically cleaned up by
+ * sched_garbagecollection().
+ */
void sched_free(FAR void *address);
-/* Functions defined in os_list.c *******************************************/
+/* Functions defined in sched/sched_garbage *********************************/
/* Must be called periodically to clean up deallocations delayed by
- * sched_free()
+ * sched_free(). This may be done from either the IDLE thread or from a
+ * worker thread. The IDLE thread has very low priority and could starve
+ * the system for memory in some context.
*/
void sched_garbagecollection(void);
diff --git a/nuttx/net/net_poll.c b/nuttx/net/net_poll.c
index 1838f541e..583d469a7 100644
--- a/nuttx/net/net_poll.c
+++ b/nuttx/net/net_poll.c
@@ -253,9 +253,24 @@ static inline int net_pollsetup(FAR struct socket *psock,
fds->revents |= (POLLOUT & fds->events);
}
- /* Check for a loss of connection events */
+ /* Check for a loss of connection events. We need to be careful here.
+ * There are four possibilities:
+ *
+ * 1) The socket is connected and we are waiting for data availability
+ * events.
+ * 2) This is a listener socket that was never connected and we are
+ * waiting for connection events.
+ * 3) This socket was previously connected, but the peer has gracefully
+ * closed the connection.
+ * 4) This socket was previously connected, but we lost the connection
+ * due to some exceptional event.
+ *
+ * We can detect 1) and 3), but 2) and 4) appear the same. So we
+ * do the best we can for now: We will report POLLHUP if the socket
+ * has been gracefully closed.
+ */
- if (!_SS_ISCONNECTED(psock->s_flags))
+ if (_SS_ISCLOSED(psock->s_flags))
{
fds->revents |= (POLLERR | POLLHUP);
}