summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/ChangeLog4
-rw-r--r--nuttx/arch/arm/src/arm/arm.h46
-rw-r--r--nuttx/arch/arm/src/arm/up_initialstate.c34
-rw-r--r--nuttx/arch/arm/src/cortexm3/svcall.h2
-rwxr-xr-xnuttx/arch/arm/src/cortexm3/up_fullcontextrestore.S4
-rwxr-xr-xnuttx/arch/arm/src/cortexm3/up_saveusercontext.S4
-rwxr-xr-xnuttx/arch/arm/src/cortexm3/up_switchcontext.S4
-rwxr-xr-xnuttx/arch/arm/src/stm32/Make.defs2
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_i2c.c33
-rwxr-xr-xnuttx/arch/arm/src/stm32/stm32_waste.c84
-rw-r--r--nuttx/drivers/usbdev/usbdev_serial.c34
-rw-r--r--nuttx/sched/os_bringup.c1
-rw-r--r--nuttx/sched/os_internal.h4
13 files changed, 172 insertions, 84 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 479a5c529..453c85c9c 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -1658,4 +1658,8 @@
capability to support nested interrupts (not fully realized for all
architectures).
* sched/task_create.c: Add support for starting kernel-mode thread.
+ * drivers/usbdev/usbdev_serial.c: Fix reported by Sheref Younan. USB
+ was being reset after serial driver was closed. As a result, you could
+ no reopen the serial driver.
+
diff --git a/nuttx/arch/arm/src/arm/arm.h b/nuttx/arch/arm/src/arm/arm.h
index 4dd39e840..433283814 100644
--- a/nuttx/arch/arm/src/arm/arm.h
+++ b/nuttx/arch/arm/src/arm/arm.h
@@ -54,28 +54,30 @@
/* PSR bits */
-#define MODE_MASK 0x0000001f
-#define USR26_MODE 0x00000000
-#define FIQ26_MODE 0x00000001
-#define IRQ26_MODE 0x00000002
-#define SVC26_MODE 0x00000003
-#define USR_MODE 0x00000010
-#define FIQ_MODE 0x00000011
-#define IRQ_MODE 0x00000012
-#define SVC_MODE 0x00000013
-#define ABT_MODE 0x00000017
-#define UND_MODE 0x0000001b
-#define MODE32_BIT 0x00000010
-#define SYSTEM_MODE 0x0000001f
-#define PSR_T_BIT 0x00000020
-#define PSR_F_BIT 0x00000040
-#define PSR_I_BIT 0x00000080
-#define PSR_J_BIT 0x01000000
-#define PSR_Q_BIT 0x08000000
-#define PSR_V_BIT 0x10000000
-#define PSR_C_BIT 0x20000000
-#define PSR_Z_BIT 0x40000000
-#define PSR_N_BIT 0x80000000
+#define MODE_MASK 0x0000001f /* Bits 0-4: Mode bits */
+# define USR26_MODE 0x00000000 /* 26-bit User mode */
+# define FIQ26_MODE 0x00000001 /* 26-bit FIQ mode */
+# define IRQ26_MODE 0x00000002 /* 26-bit IRQ mode */
+# define SVC26_MODE 0x00000003 /* 26-bit Supervisor mode */
+# define MODE32_BIT 0x00000010 /* Bit 4: 32-bit mode */
+# define USR_MODE 0x00000010 /* 32-bit User mode */
+# define FIQ_MODE 0x00000011 /* 32-bit FIQ mode */
+# define IRQ_MODE 0x00000012 /* 32-bit IRQ mode */
+# define SVC_MODE 0x00000013 /* 32-bit Supervisor mode */
+# define ABT_MODE 0x00000017 /* 32-bit Abort mode */
+# define UND_MODE 0x0000001b /* 32-bit Undefined mode */
+# define SYSTEM_MODE 0x0000001f /* 32-bit System mode */
+#define PSR_T_BIT 0x00000020 /* Bit 5: Thumb state */
+#define PSR_F_BIT 0x00000040 /* Bit 6: FIQ disable */
+#define PSR_I_BIT 0x00000080 /* Bit 7: IRQ disable */
+ /* Bits 8-23: Reserved */
+#define PSR_J_BIT 0x01000000 /* Bit 24: Jazelle state bit */
+ /* Bits 25-26: Reserved */
+#define PSR_Q_BIT 0x08000000 /* Bit 27: Sticky overflow */
+#define PSR_V_BIT 0x10000000 /* Bit 28: Overflow */
+#define PSR_C_BIT 0x20000000 /* Bit 29: Carry/Borrow/Extend */
+#define PSR_Z_BIT 0x40000000 /* Bit 30: Zero */
+#define PSR_N_BIT 0x80000000 /* Bit 31: Negative/Less than */
/* CR1 bits (CP#15 CR1) */
diff --git a/nuttx/arch/arm/src/arm/up_initialstate.c b/nuttx/arch/arm/src/arm/up_initialstate.c
index 180385d6a..570a11459 100644
--- a/nuttx/arch/arm/src/arm/up_initialstate.c
+++ b/nuttx/arch/arm/src/arm/up_initialstate.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/arm/up_initialstate.c
*
- * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -81,6 +81,7 @@
void up_initial_state(_TCB *tcb)
{
struct xcptcontext *xcp = &tcb->xcp;
+ uint32_t cpsr;
/* Initialize the initial exception register context structure */
@@ -109,12 +110,37 @@ void up_initial_state(_TCB *tcb)
}
#endif
+ /* Set supervisor- or user-mode, depending on how NuttX is configured nd
+ * what kind of thread is being started. Disable FIQs in any event
+ */
+
+#ifdef CONFIG_NUTTX_KERNEL
+ if ((tcb->flags & TCB_FLAG_TTYPE_MASK) == TCB_FLAG_TTYPE_KERNEL)
+ {
+ /* It is a kernel thread.. set supervisor mode */
+
+ cpsr = SVC_MODE | PSR_F_BIT;
+ }
+ else
+ {
+ /* It is a normal task or a pthread. Set user mode */
+
+ cpsr = USR_MODE | PSR_F_BIT;
+ }
+#else
+ /* If the kernel build is not selected, then all threads run in
+ * supervisor-mode.
+ */
+
+ cpsr = SVC_MODE | PSR_F_BIT;
+#endif
+
/* Enable or disable interrupts, based on user configuration */
# ifdef CONFIG_SUPPRESS_INTERRUPTS
- xcp->regs[REG_CPSR] = SVC_MODE | PSR_I_BIT | PSR_F_BIT;
-# else
- xcp->regs[REG_CPSR] = SVC_MODE | PSR_F_BIT;
+ cpsr |= PSR_I_BIT;
# endif
+
+ xcp->regs[REG_CPSR] = cpsr;
}
diff --git a/nuttx/arch/arm/src/cortexm3/svcall.h b/nuttx/arch/arm/src/cortexm3/svcall.h
index bca3e0799..74f7a3438 100644
--- a/nuttx/arch/arm/src/cortexm3/svcall.h
+++ b/nuttx/arch/arm/src/cortexm3/svcall.h
@@ -79,7 +79,7 @@
#define SYS_restore_context (1)
-/* SYS call 1:
+/* SYS call 2:
*
* void up_switchcontext(uint32_t *saveregs, uint32_t *restoreregs);
*/
diff --git a/nuttx/arch/arm/src/cortexm3/up_fullcontextrestore.S b/nuttx/arch/arm/src/cortexm3/up_fullcontextrestore.S
index 1194510b9..6709967d7 100755
--- a/nuttx/arch/arm/src/cortexm3/up_fullcontextrestore.S
+++ b/nuttx/arch/arm/src/cortexm3/up_fullcontextrestore.S
@@ -63,7 +63,7 @@
* Public Functions
************************************************************************************/
-/**************************************************************************
+/************************************************************************************
* Name: up_fullcontextrestore
*
* Description:
@@ -74,7 +74,7 @@
* Return:
* None
*
- **************************************************************************/
+ ************************************************************************************/
.thumb_func
.globl up_fullcontextrestore
diff --git a/nuttx/arch/arm/src/cortexm3/up_saveusercontext.S b/nuttx/arch/arm/src/cortexm3/up_saveusercontext.S
index 2ca11aa28..8fc073a51 100755
--- a/nuttx/arch/arm/src/cortexm3/up_saveusercontext.S
+++ b/nuttx/arch/arm/src/cortexm3/up_saveusercontext.S
@@ -63,7 +63,7 @@
* Public Functions
************************************************************************************/
-/**************************************************************************
+/************************************************************************************
* Name: up_saveusercontext
*
* Description:
@@ -75,7 +75,7 @@
* 0: Normal return
* 1: Context switch return
*
- **************************************************************************/
+ ************************************************************************************/
.text
.thumb_func
diff --git a/nuttx/arch/arm/src/cortexm3/up_switchcontext.S b/nuttx/arch/arm/src/cortexm3/up_switchcontext.S
index 1b91e0938..6e60942b3 100755
--- a/nuttx/arch/arm/src/cortexm3/up_switchcontext.S
+++ b/nuttx/arch/arm/src/cortexm3/up_switchcontext.S
@@ -63,7 +63,7 @@
* Public Functions
************************************************************************************/
-/**************************************************************************
+/************************************************************************************
* Name: up_switchcontext
*
* Description:
@@ -75,7 +75,7 @@
* Return:
* None
*
- **************************************************************************/
+ ************************************************************************************/
.thumb_func
.globl up_switchcontext
diff --git a/nuttx/arch/arm/src/stm32/Make.defs b/nuttx/arch/arm/src/stm32/Make.defs
index 9dd63950d..4b6228b0c 100755
--- a/nuttx/arch/arm/src/stm32/Make.defs
+++ b/nuttx/arch/arm/src/stm32/Make.defs
@@ -48,5 +48,5 @@ CHIP_ASRCS =
CHIP_CSRCS = stm32_start.c stm32_rcc.c stm32_gpio.c stm32_idle.c \
stm32_irq.c stm32_timerisr.c stm32_dma.c stm32_lowputc.c \
stm32_serial.c stm32_spi.c stm32_usbdev.c stm32_sdio.c \
- stm32_tim.c stm32_i2c.c
+ stm32_tim.c stm32_i2c.c stm32_waste.c
diff --git a/nuttx/arch/arm/src/stm32/stm32_i2c.c b/nuttx/arch/arm/src/stm32/stm32_i2c.c
index dbbc11d5f..90673ef62 100644
--- a/nuttx/arch/arm/src/stm32/stm32_i2c.c
+++ b/nuttx/arch/arm/src/stm32/stm32_i2c.c
@@ -221,16 +221,15 @@ static void stm32_i2c_setclock(FAR struct stm32_i2c_priv_s *priv, uint32_t frequ
* Duty: t_low / t_high = 1
*/
stm32_i2c_putreg(priv, STM32_I2C_CCR_OFFSET, STM32_BOARD_HCLK/200000);
- stm32_i2c_putreg(priv, STM32_I2C_TRISE_OFFSET, 1 + STM32_BOARD_HCLK/1000000);
+ stm32_i2c_putreg(priv, STM32_I2C_TRISE_OFFSET, STM32_BOARD_HCLK/1000000 + 1);
}
else {
/* Speed: 400 kHz
- * Risetime: 1000 ns ??? \todo check rise time for 400 kHz devices
* Duty: t_low / t_high = 2
*/
stm32_i2c_putreg(priv, STM32_I2C_CCR_OFFSET, STM32_BOARD_HCLK/1200000);
- stm32_i2c_putreg(priv, STM32_I2C_TRISE_OFFSET, 1 + STM32_BOARD_HCLK/1000000);
+ stm32_i2c_putreg(priv, STM32_I2C_TRISE_OFFSET, 300*(STM32_BOARD_HCLK / 1000000)/1000 + 1);
}
/* Restore state */
@@ -594,26 +593,26 @@ int stm32_i2c_process(FAR struct i2c_dev_s *dev, FAR struct i2c_msg_s *msgs, int
uint32_t status = 0;
int status_errno = 0;
- ASSERT(count);
+ extern void up_waste(void);
- /* The semaphore already ensures that I2C is ours, since we do not yet support
- * non-blocking operation.
+ ASSERT(count);
+
+ /* wait as stop might still be in progress
+ *
+ * \todo GET RID OF THIS PERFORMANCE LOSS and for() loop
*/
-
+ for (; stm32_i2c_getreg(inst->priv, STM32_I2C_CR1_OFFSET) & I2C_CR1_STOP; ) up_waste();
+
+ /* Old transfers are done */
inst->priv->msgv = msgs;
inst->priv->msgc = count;
-
+
+ /* Set clock (on change it toggles I2C_CR1_PE !) */
stm32_i2c_setclock(inst->priv, inst->frequency);
-
- /* Trigger start condition, then the process moves into the ISR,
- * waiting again for the samaphore ... the resulting status is
- * found in the local status variable.
- */
-
-// inst->priv->status = 0;
-// printf("isr_count = %d\n", isr_count); fflush(stdout);
-
+
+ /* Trigger start condition, then the process moves into the ISR */
stm32_i2c_sendstart(inst->priv);
+
#ifdef NON_ISR
do {
diff --git a/nuttx/arch/arm/src/stm32/stm32_waste.c b/nuttx/arch/arm/src/stm32/stm32_waste.c
new file mode 100755
index 000000000..057e2eb37
--- /dev/null
+++ b/nuttx/arch/arm/src/stm32/stm32_waste.c
@@ -0,0 +1,84 @@
+/****************************************************************************
+ * arch/arm/src/stm32/stm32_waste.c
+ *
+ * Copyright (C) 2011 Uros Platise. All rights reserved.
+ * Author: Uros Platise <uros.platise@isotel.eu>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <stdint.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+uint32_t idle_wastecounter = 0;
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_waste
+ *
+ * Description:
+ * up_waste() is the logic that will be executed when portions of kernel
+ * or user-app is polling some register or similar, waiting for desired
+ * status. This time is wasted away. This function offers a measure of
+ * badly written piece of software or some undesired behavior.
+ *
+ * At the same time this function adds to some IDLE time which portion
+ * cannot be used for other purposes (yet).
+ *
+ ****************************************************************************/
+
+void up_waste(void)
+{
+ idle_wastecounter++;
+}
+
+
diff --git a/nuttx/drivers/usbdev/usbdev_serial.c b/nuttx/drivers/usbdev/usbdev_serial.c
index 25753cb1e..68c39200f 100644
--- a/nuttx/drivers/usbdev/usbdev_serial.c
+++ b/nuttx/drivers/usbdev/usbdev_serial.c
@@ -255,8 +255,7 @@ struct usbser_dev_s
uint8_t config; /* Configuration number */
uint8_t nwrq; /* Number of queue write requests (in reqlist)*/
uint8_t nrdq; /* Number of queue read requests (in epbulkout) */
- uint8_t open : 1; /* 1: Driver has been opened */
- uint8_t rxenabled : 1; /* 1: UART RX "interrupts" enabled */
+ bool rxenabled; /* true: UART RX "interrupts" enabled */
uint8_t linest[7]; /* Fake line status */
int16_t rxhead; /* Working head; used when rx int disabled */
@@ -1883,9 +1882,6 @@ static int usbser_setup(FAR struct uart_dev_s *dev)
return -ENOTCONN;
}
- /* Mark the device as opened */
-
- priv->open = 1;
return OK;
}
@@ -1903,9 +1899,6 @@ static int usbser_setup(FAR struct uart_dev_s *dev)
static void usbser_shutdown(FAR struct uart_dev_s *dev)
{
- FAR struct usbser_dev_s *priv;
- irqstate_t flags;
-
usbtrace(USBSER_CLASSAPI_SHUTDOWN, 0);
/* Sanity check */
@@ -1914,29 +1907,8 @@ static void usbser_shutdown(FAR struct uart_dev_s *dev)
if (!dev || !dev->priv)
{
usbtrace(TRACE_CLSERROR(USBSER_TRACEERR_INVALIDARG), 0);
- return;
- }
-#endif
-
- /* Extract reference to private data */
-
- priv = (FAR struct usbser_dev_s*)dev->priv;
- flags = irqsave();
-
-#if CONFIG_DEBUG
- if (!priv->open)
- {
- usbtrace(TRACE_CLSERROR(USBSER_TRACEERR_ALREADYCLOSED), 0);
- irqrestore(flags);
- return;
}
#endif
-
- /* Make sure that we are disconnected from the host */
-
- usbclass_resetconfig(priv);
- priv->open = 0;
- irqrestore(flags);
}
/****************************************************************************
@@ -2038,7 +2010,7 @@ static void usbser_rxint(FAR struct uart_dev_s *dev, bool enable)
/* RX "interrupts are no longer disabled */
- priv->rxenabled = 1;
+ priv->rxenabled = true;
}
}
@@ -2057,7 +2029,7 @@ static void usbser_rxint(FAR struct uart_dev_s *dev, bool enable)
*/
priv->rxhead = serdev->recv.head;
- priv->rxenabled = 0;
+ priv->rxenabled = false;
}
irqrestore(flags);
}
diff --git a/nuttx/sched/os_bringup.c b/nuttx/sched/os_bringup.c
index 9f05a3c70..7cdd06dcb 100644
--- a/nuttx/sched/os_bringup.c
+++ b/nuttx/sched/os_bringup.c
@@ -48,6 +48,7 @@
#include <nuttx/init.h>
+#include "os_internal.h"
#ifdef CONFIG_PAGING
# include "pg_internal.h"
#endif
diff --git a/nuttx/sched/os_internal.h b/nuttx/sched/os_internal.h
index ceeb70df1..b25ee1c5e 100644
--- a/nuttx/sched/os_internal.h
+++ b/nuttx/sched/os_internal.h
@@ -113,9 +113,9 @@ enum os_crash_codes_e
*/
#ifndef CONFIG_CUSTOM_STACK
-# define KERNEL_THREAD(n,p,s,e,a) task_create(n,p,s,e,a)
+# define KERNEL_THREAD(n,p,s,e,a) kernel_thread(n,p,s,e,a)
#else
-# define KERNEL_THREAD(n,p,s,e,a) task_create(n,p,e,a)
+# define KERNEL_THREAD(n,p,s,e,a) kernel_thread(n,p,e,a)
#endif
/* A more efficient ways to access the errno */