summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-02-24 18:24:35 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-02-24 18:24:35 +0000
commit1b4c92672cfd43d05dbee2db143af08ec84d90af (patch)
tree334ac14c141647e11b2ca6f79d362f15dfd727fa
parent200fa47c3ca70ddbb91057823425c252f3985942 (diff)
downloadpx4-nuttx-1b4c92672cfd43d05dbee2db143af08ec84d90af.tar.gz
px4-nuttx-1b4c92672cfd43d05dbee2db143af08ec84d90af.tar.bz2
px4-nuttx-1b4c92672cfd43d05dbee2db143af08ec84d90af.zip
select() fix to handl POLLHUP; STM32 FPU saving in context switches seems to be functional
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4420 42af7a65-404d-4744-a932-0658087f49c3
-rw-r--r--nuttx/ChangeLog11
-rw-r--r--nuttx/arch/arm/src/armv7-m/up_fpu.S29
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_qencoder.c2
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_vectors.S82
-rwxr-xr-xnuttx/configs/stm3240g-eval/README.txt34
-rwxr-xr-xnuttx/configs/stm32f4discovery/README.txt36
-rw-r--r--nuttx/fs/fs_select.c35
7 files changed, 170 insertions, 59 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index dde876459..fa85503ef 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -2477,6 +2477,9 @@
* arch/arm/src/stm32_sdio.c: STM32 F4 SDIO DMA is now supported
* configs/stm3240g-eval/nsh/defconfig: This configuration now supports SDIO
with DMA (see configs/stm3240g-eval/README.txt for some issues).
+ * arch/arm/src/armv7-m/up_vectors.S and arch/arm/src/armv7-m/up_vectors.S: New,
+ streamlined Cortex-M exception handling (with FPU supported). Contributed byh
+ Mike Smith
* net/accept.c, connect.c,and net_monitor.c: Correct an error in the accept
logic. After a new connection is made via accept(), monitoring for losses
of TCP connection must be set up (just as with connect()). The new file
@@ -2495,3 +2498,11 @@
accepted.
* configs/stm3240g-eval, configs/stm32f40discovery, and arch/*/src/Makefile:
Add changes to support building with the Atollic "Lite" toolchain.
+ * fs/fs_select.c: Correct select(), in the case of loss of network
+ connection (POLLHUP), select() must report a read-ready event. This
+ is how the standard select() interface is supposed to work: In the case
+ of loss-of-connection, select() reports read-ready. The next time you
+ read from the socket, you detect the end-of-connection event. Change
+ submitted by Max Nekludov.
+ * arch/arm/src/armv7-m/up_fpu.S and arch/arm/src/stm32/stm32_vectors.S: Fix
+ lazy FPU register saving with CONFIG_ARCH_FPU is set in the configuration.
diff --git a/nuttx/arch/arm/src/armv7-m/up_fpu.S b/nuttx/arch/arm/src/armv7-m/up_fpu.S
index ee3644594..fd6449c2f 100644
--- a/nuttx/arch/arm/src/armv7-m/up_fpu.S
+++ b/nuttx/arch/arm/src/armv7-m/up_fpu.S
@@ -95,11 +95,15 @@ up_savefpu:
/* Some older GNU assemblers don't support all the newer UAL mnemonics. */
#if 1 /* Use UAL mnemonics */
- /* Store all floating point registers */
+ /* Store all floating point registers. Registers are stored in numeric order,
+ * s0, s1, ... in increasing address order.
+ */
vstmia r1!, {s0-s31} /* Save the full FP context */
- /* Store the floating point control and status register */
+ /* Store the floating point control and status register. At the end of the
+ * vstmia, r1 will point to the FPCSR storage location.
+ */
vmrs r2, fpscr /* Fetch the FPCSR */
str r2, [r1], #4 /* Save the floating point control and status register */
@@ -180,10 +184,11 @@ up_savefpu:
*
* Input Parameters:
* regs - A pointer to the register save area containing the floating point
- * registers
+ * registers.
*
* Returned Value:
- * None
+ * This function does not return anything explicitly. However, it is called from
+ * interrupt level assembly logic that assumes that r0 is preserved.
*
************************************************************************************/
@@ -196,16 +201,22 @@ up_restorefpu:
/* Some older GNU assemblers don't support all the newer UAL mnemonics. */
#if 1 /* Use UAL mnemonics */
- /* Load all floating point registers */
+ /* Load all floating point registers. Registers are loaded in numeric order,
+ * s0, s1, ... in increasing address order.
+ */
vldmia r1!, {s0-s31} /* Restore the full FP context */
- /* Load the floating point control and status register */
+ /* Load the floating point control and status register. At the end of the
+ * vstmia, r1 will point to the FPCSR storage location.
+ */
ldr r2, [r1], #4 /* Fetch the floating point control and status register */
vmsr fpscr, r2 /* Restore the FPCSR */
#else
- /* Load all floating point registers */
+ /* Load all floating point registers Registers are loaded in numeric order,
+ * s0, s1, ... in increasing address order.
+ */
#if 1 /* Use load multiple */
fldmias r1!, {s0-s31} /* Restore the full FP context */
@@ -260,7 +271,9 @@ up_restorefpu:
vmov d15, r2, r3 /* Save as d15 */
#endif
- /* Load the floating point control and status register */
+ /* Load the floating point control and status register. r1 points t
+ * the address of the FPCSR register.
+ */
ldr r2, [r1], #4 /* Fetch the floating point control and status register */
fmxr fpscr, r2 /* Restore the FPCSR */
diff --git a/nuttx/arch/arm/src/stm32/stm32_qencoder.c b/nuttx/arch/arm/src/stm32/stm32_qencoder.c
index 67ba1eabb..82c9e361b 100644
--- a/nuttx/arch/arm/src/stm32/stm32_qencoder.c
+++ b/nuttx/arch/arm/src/stm32/stm32_qencoder.c
@@ -499,7 +499,7 @@ static FAR struct stm32_lowerhalf_s *stm32_tim2lower(int tim)
}
/************************************************************************************
- * Name: stm32_setup
+ * Name: stm32_interrupt
*
* Description:
* Common timer interrupt handling
diff --git a/nuttx/arch/arm/src/stm32/stm32_vectors.S b/nuttx/arch/arm/src/stm32/stm32_vectors.S
index 91f530f05..1629dfc9f 100644
--- a/nuttx/arch/arm/src/stm32/stm32_vectors.S
+++ b/nuttx/arch/arm/src/stm32/stm32_vectors.S
@@ -211,16 +211,37 @@ stm32_common:
*/
adds r2, r14, #3 /* If R14=0xfffffffd, then r2 == 0 */
- ite ne /* Next two instructions are condition */
+ ite ne /* Next two instructions are conditional */
mrsne r1, msp /* R1=The main stack pointer */
mrseq r1, psp /* R1=The process stack pointer */
#else
mrs r1, msp /* R1=The main stack pointer */
#endif
+ /* r1 holds the value of the stack pointer AFTER the excption handling logic
+ * pushed the various registers onto the stack. Get r2 = the value of the
+ * stack pointer BEFORE the interrupt modified it.
+ */
+
mov r2, r1 /* R2=Copy of the main/process stack pointer */
add r2, #HW_XCPT_SIZE /* R2=MSP/PSP before the interrupt was taken */
mrs r3, primask /* R3=Current PRIMASK setting */
+
+#ifdef CONFIG_ARCH_FPU
+ /* Skip over the block of memory reserved for floating pointer register save.
+ * Lazy FPU register saving is used. FPU registers will be saved in this
+ * block only if a context switch occurs (this means, of course, that the FPU
+ * cannot be used in interrupt processing).
+ */
+
+ sub r1, #(4*SW_FPU_REGS)
+#endif
+
+ /* Save the the remaining registers on the stack after the registers pushed
+ * by the exception handling logic. r2=SP and r3=primask, r4-r11,r14=register
+ * values.
+ */
+
#ifdef CONFIG_NUTTX_KERNEL
stmdb r1!, {r2-r11,r14} /* Save the remaining registers plus the SP value */
#else
@@ -257,36 +278,47 @@ stm32_common:
cmp r0, r1 /* Context switch? */
beq 1f /* Branch if no context switch */
- /* We are returning with a pending context switch. This case is different
- * because in this case, the register save structure does not lie on the
- * stack but, rather, are within a TCB structure. We'll have to copy some
- * values to the stack.
+ /* We are returning with a pending context switch.
+ *
+ * If the FPU is enabled, then we will need to restore FPU registers.
+ * This is not done in normal interrupt save/restore because the cost
+ * is prohibitive. This is only done when switching contexts. A
+ * consequence of this is that floating point operations may not be
+ * performed in interrupt handling logic.
+ *
+ * Here:
+ * r0 = Address of the register save area
+
+ * NOTE: It is a requirement that up_restorefpu() preserve the value of
+ * r0!
+ */
+
+#ifdef CONFIG_ARCH_FPU
+ bl up_restorefpu /* Restore the FPU registers */
+#endif
+
+ /* Returning with a pending context switch is different from the normal
+ * return because in this case, the register save structure does not lie
+ * on the stack but, rather, are within a TCB structure. We'll have to
+ * copy somevalues to the new stack.
*/
add r1, r0, #SW_XCPT_SIZE /* R1=Address of HW save area in reg array */
ldmia r1, {r4-r11} /* Fetch eight registers in HW save area */
- ldr r1, [r0, #(4*REG_SP)] /* R1=Value of SP before interrupt */
+ ldr r1, [r0, #(4*REG_SP)] /* R1=Value of SP before interrupt */
stmdb r1!, {r4-r11} /* Store eight registers in HW save area */
#ifdef CONFIG_NUTTX_KERNEL
ldmia r0, {r2-r11,r14} /* Recover R4-R11, r14 + 2 temp values */
#else
ldmia r0, {r2-r11} /* Recover R4-R11 + 2 temp values */
#endif
-
- /* We may also need to restore FPU registers. This is not done in
- * normal interrupt save/restore because the cost is prohibitive. This
- * is only done when switching contexts. A consequence of this is that
- * floating point operations may not be performed in interrupt handling
- * logic.
- */
-
-#ifdef CONFIG_ARCH_FPU
- bl up_restorefpu /* Restore the FPU registers */
-#endif
b 2f /* Re-join common logic */
/* We are returning with no context switch. We simply need to "unwind"
* the same stack frame that we created
+ *
+ * Here:
+ * r1 = Address of the return stack (same as r0)
*/
1:
#ifdef CONFIG_NUTTX_KERNEL
@@ -294,6 +326,22 @@ stm32_common:
#else
ldmia r1!, {r2-r11} /* Recover R4-R11 + 2 temp values */
#endif
+#ifdef CONFIG_ARCH_FPU
+ /* Skip over the block of memory reserved for floating pointer register
+ * save. Then R1 is the address of the HW save area
+ */
+
+ add r1, #(4*SW_FPU_REGS)
+#endif
+
+ /* Set up to return from the exception
+ *
+ * Here:
+ * r1 = Address on the target thread's stack position at the start of
+ * the registers saved by hardware
+ * r3 = primask
+ * r4-r11 = restored register values
+ */
2:
#ifdef CONFIG_NUTTX_KERNEL
/* The EXC_RETURN value will be 0xfffffff9 (privileged thread) or 0xfffffff1
diff --git a/nuttx/configs/stm3240g-eval/README.txt b/nuttx/configs/stm3240g-eval/README.txt
index 2c7c09bdf..34c6a09f3 100755
--- a/nuttx/configs/stm3240g-eval/README.txt
+++ b/nuttx/configs/stm3240g-eval/README.txt
@@ -32,6 +32,8 @@ Development Environment
GNU Toolchain Options
=====================
+ Toolchain Configurations
+ ------------------------
The NuttX make system has been modified to support the following different
toolchain options.
@@ -91,12 +93,16 @@ GNU Toolchain Options
If you have problems with the dependency build (for example, if you are not
building on C:), then you may need to modify tools/mkdeps.sh
- NOTE 1: The CodeSourcery toolchain (2009q1) does not work with default optimization
+ The CodeSourcery Toolchain (2009q1)
+ -----------------------------------
+ The CodeSourcery toolchain (2009q1) does not work with default optimization
level of -Os (See Make.defs). It will work with -O0, -O1, or -O2, but not with
-Os.
- NOTE 2: The free, "Lite" version of the Atollic toolchain does not support C++
- nor does it support ar, nm, objdump, or objdcopy. If you use the Atollic "Lite"
+ The Atollic "Lite" Toolchain
+ ----------------------------
+ The free, "Lite" version of the Atollic toolchain does not support C++ nor
+ does it support ar, nm, objdump, or objdcopy. If you use the Atollic "Lite"
toolchain, you will have to set:
CONFIG_HAVE_CXX=n
@@ -122,22 +128,24 @@ GNU Toolchain Options
errors build some host binaries in tools/ when you first make. Here is my
workaround kludge.
- 1. Edit the setenv.sh to put the Atollic toolchain at the beginning of the PATH
- 2. Source the setenv.sh file: . ./setenv.sh. A side effect of this is that it
- will set an environment variable called PATH_ORIG.
- 3. Then go back to the original patch: export PATH=$PATH_ORIG
- 4. Then make. The make will build all of the host executable but will fail
- when it gets to the first ARM binary.
- 5. Then source setenv.sh again: . ./setenv.sh. That will correct the PATH
- again. When you do make again, the host executables are already made and
- now the correct PATH is in place for the ARM build.
+ 1. Edit the setenv.sh to put the Atollic toolchain at the beginning of the PATH
+ 2. Source the setenv.sh file: . ./setenv.sh. A side effect of this is that it
+ will set an environment variable called PATH_ORIG.
+ 3. Then go back to the original patch: export PATH=$PATH_ORIG
+ 4. Then make. The make will build all of the host executable but will fail
+ when it gets to the first ARM binary.
+ 5. Then source setenv.sh again: . ./setenv.sh. That will correct the PATH
+ again. When you do make again, the host executables are already made and
+ now the correct PATH is in place for the ARM build.
Also, the Atollic toolchain is the only toolchain that has built-in support for
the FPU in these configurations. If you plan to use the Cortex-M4 FPU, you will
need to use the Atollic toolchain for now. See the FPU section below for more
information.
- NOTE 3: The devkitARM toolchain includes a version of MSYS make. Make sure that
+ devkitARM
+ ---------
+ The devkitARM toolchain includes a version of MSYS make. Make sure that the
the paths to Cygwin's /bin and /usr/bin directories appear BEFORE the devkitARM
path or will get the wrong version of make.
diff --git a/nuttx/configs/stm32f4discovery/README.txt b/nuttx/configs/stm32f4discovery/README.txt
index 23e45c742..06b835b07 100755
--- a/nuttx/configs/stm32f4discovery/README.txt
+++ b/nuttx/configs/stm32f4discovery/README.txt
@@ -31,6 +31,8 @@ Development Environment
GNU Toolchain Options
=====================
+ Toolchain Configurations
+ ------------------------
The NuttX make system has been modified to support the following different
toolchain options.
@@ -90,12 +92,16 @@ GNU Toolchain Options
If you have problems with the dependency build (for example, if you are not
building on C:), then you may need to modify tools/mkdeps.sh
- NOTE 1: The CodeSourcery toolchain (2009q1) does not work with default optimization
+ The CodeSourcery Toolchain (2009q1)
+ -----------------------------------
+ The CodeSourcery toolchain (2009q1) does not work with default optimization
level of -Os (See Make.defs). It will work with -O0, -O1, or -O2, but not with
-Os.
- NOTE 2: The free, "Lite" version of the Atollic toolchain does not support C++
- nor does it support ar, nm, objdump, or objdcopy. If you use the Atollic "Lite"
+ The Atollic "Lite" Toolchain
+ ----------------------------
+ The free, "Lite" version of the Atollic toolchain does not support C++ nor
+ does it support ar, nm, objdump, or objdcopy. If you use the Atollic "Lite"
toolchain, you will have to set:
CONFIG_HAVE_CXX=n
@@ -118,25 +124,27 @@ GNU Toolchain Options
and g++.exe in the same bin/ file as their ARM binaries. If the Atollic bin/ path
appears in your PATH variable before /usr/bin, then you will get the wrong gcc
when you try to build host executables. This will cause to strange, uninterpretable
- errors build some host binaries in tools/ when you first make. Here is my
+ errors build some host binaries in tools/ when you first make. Here is my
workaround kludge.
- 1. Edit the setenv.sh to put the Atollic toolchain at the beginning of the PATH
- 2. Source the setenv.sh file: . ./setenv.sh. A side effect of this is that it
- will set an environment variable called PATH_ORIG.
- 3. Then go back to the original patch: export PATH=$PATH_ORIG
- 4. Then make. The make will build all of the host executable but will fail
- when it gets to the first ARM binary.
- 5. Then source setenv.sh again: . ./setenv.sh. That will correct the PATH
- again. When you do make again, the host executables are already made and
- now the correct PATH is in place for the ARM build.
+ 1. Edit the setenv.sh to put the Atollic toolchain at the beginning of the PATH
+ 2. Source the setenv.sh file: . ./setenv.sh. A side effect of this is that it
+ will set an environment variable called PATH_ORIG.
+ 3. Then go back to the original patch: export PATH=$PATH_ORIG
+ 4. Then make. The make will build all of the host executable but will fail
+ when it gets to the first ARM binary.
+ 5. Then source setenv.sh again: . ./setenv.sh. That will correct the PATH
+ again. When you do make again, the host executables are already made and
+ now the correct PATH is in place for the ARM build.
Also, the Atollic toolchain is the only toolchain that has built-in support for
the FPU in these configurations. If you plan to use the Cortex-M4 FPU, you will
need to use the Atollic toolchain for now. See the FPU section below for more
information.
- NOTE 3: The devkitARM toolchain includes a version of MSYS make. Make sure that
+ devkitARM
+ ---------
+ The devkitARM toolchain includes a version of MSYS make. Make sure that the
the paths to Cygwin's /bin and /usr/bin directories appear BEFORE the devkitARM
path or will get the wrong version of make.
diff --git a/nuttx/fs/fs_select.c b/nuttx/fs/fs_select.c
index 213530e44..14ccfe287 100644
--- a/nuttx/fs/fs_select.c
+++ b/nuttx/fs/fs_select.c
@@ -1,8 +1,8 @@
/****************************************************************************
* fs/fs_select.c
*
- * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Copyright (C) 2008-2009, 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -124,24 +124,37 @@ int select(int nfds, FAR fd_set *readfds, FAR fd_set *writefds,
{
int incr = 0;
+ /* The readfs set holds the set of FDs that the caller can be assured
+ * of reading from without blocking. Note that POLLHUP is included as
+ * a read-able condition. POLLHUP will be reported at the end-of-file
+ * or when a connection is lost. In either case, the read() can then
+ * be performed without blocking.
+ */
+
if (readfds && FD_ISSET(fd, readfds))
{
pollset[npfds].fd = fd;
pollset[npfds].events |= POLLIN;
- incr = 1;
+ incr = 1;
}
+ /* The writefds set holds the set of FDs that the caller can be assured
+ * of writing to without blocking.
+ */
+
if (writefds && FD_ISSET(fd, writefds))
{
pollset[npfds].fd = fd;
pollset[npfds].events |= POLLOUT;
- incr = 1;
+ 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;
+ incr = 1;
}
npfds += incr;
@@ -179,15 +192,23 @@ int select(int nfds, FAR fd_set *readfds, FAR fd_set *writefds,
ret = 0;
for (ndx = 0; ndx < npfds; ndx++)
{
+ /* Check for read conditions. Note that POLLHUP is included as a
+ * read condition. POLLHUP will be reported when no more data will
+ * be available (such as when a connection is lost). In either
+ * case, the read() can then be performed without blocking.
+ */
+
if (readfds)
{
- if (pollset[ndx].revents & POLLIN)
+ if (pollset[ndx].revents & (POLLIN|POLLHUP))
{
FD_SET(pollset[ndx].fd, readfds);
ret++;
}
}
+ /* Check for write conditions */
+
if (writefds)
{
if (pollset[ndx].revents & POLLOUT)
@@ -197,6 +218,8 @@ int select(int nfds, FAR fd_set *readfds, FAR fd_set *writefds,
}
}
+ /* Check for exceptions */
+
if (exceptfds)
{
if (pollset[ndx].revents & POLLERR)