Update submodule NuttX ==upstream_kinetis

Latest Upstrem
   removed back ports for i2c-hotfix, stm32f7-serial-dma, and
   add-set-ex-to-nsh in upstream
This commit is contained in:
David Sidrane 2017-04-07 13:34:53 -10:00 committed by Daniel Agar
parent 5922e08f5e
commit deecf98f6e
4 changed files with 1 additions and 1004 deletions

2
NuttX

@ -1 +1 @@
Subproject commit 26e94f6453b86aadce5bab0b39e82155b62cf8c8 Subproject commit 65fd3f04c4519c0a6305cbbf70a698aecf92b3e3

View File

@ -1,325 +0,0 @@
diff --git NuttX/nuttx/arch/arm/src/stm32/stm32_i2c.c NuttX/nuttx/arch/arm/src/stm32/stm32_i2c.c
index 631ba66..669e0db 100644
--- NuttX/nuttx/arch/arm/src/stm32/stm32_i2c.c
+++ NuttX/nuttx/arch/arm/src/stm32/stm32_i2c.c
@@ -7,7 +7,7 @@
*
* With extensions, modifications by:
*
- * Copyright (C) 2011-2014, 2016 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011-2014, 2016-2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -670,15 +670,15 @@ static inline int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv)
do
{
+ /* Calculate the elapsed time */
+
+ elapsed = clock_systimer() - start;
+
/* Poll by simply calling the timer interrupt handler until it
* reports that it is done.
*/
stm32_i2c_isr(priv);
-
- /* Calculate the elapsed time */
-
- elapsed = clock_systimer() - start;
}
/* Loop until the transfer is complete. */
@@ -729,6 +729,10 @@ static inline void stm32_i2c_sem_waitstop(FAR struct stm32_i2c_priv_s *priv)
start = clock_systimer();
do
{
+ /* Calculate the elapsed time */
+
+ elapsed = clock_systimer() - start;
+
/* Check for STOP condition */
cr1 = stm32_i2c_getreg(priv, STM32_I2C_CR1_OFFSET);
@@ -744,10 +748,6 @@ static inline void stm32_i2c_sem_waitstop(FAR struct stm32_i2c_priv_s *priv)
{
return;
}
-
- /* Calculate the elapsed time */
-
- elapsed = clock_systimer() - start;
}
/* Loop until the stop is complete or a timeout occurs. */
diff --git NuttX/nuttx/arch/arm/src/stm32/stm32_i2c_alt.c NuttX/nuttx/arch/arm/src/stm32/stm32_i2c_alt.c
index 545a647..981edb6 100644
--- NuttX/nuttx/arch/arm/src/stm32/stm32_i2c_alt.c
+++ NuttX/nuttx/arch/arm/src/stm32/stm32_i2c_alt.c
@@ -7,7 +7,7 @@
*
* With extensions, modifications by:
*
- * Copyright (C) 2011-2014, 2016 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011-2014, 2016-2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Copyright( C) 2014 Patrizio Simona. All rights reserved.
@@ -678,15 +678,15 @@ static int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv)
do
{
+ /* Calculate the elapsed time */
+
+ elapsed = clock_systimer() - start;
+
/* Poll by simply calling the timer interrupt handler until it
* reports that it is done.
*/
stm32_i2c_isr(priv);
-
- /* Calculate the elapsed time */
-
- elapsed = clock_systimer() - start;
}
/* Loop until the transfer is complete. */
@@ -737,6 +737,10 @@ static inline void stm32_i2c_sem_waitstop(FAR struct stm32_i2c_priv_s *priv)
start = clock_systimer();
do
{
+ /* Calculate the elapsed time */
+
+ elapsed = clock_systimer() - start;
+
/* Check for STOP condition */
cr1 = stm32_i2c_getreg(priv, STM32_I2C_CR1_OFFSET);
@@ -753,9 +757,6 @@ static inline void stm32_i2c_sem_waitstop(FAR struct stm32_i2c_priv_s *priv)
return;
}
- /* Calculate the elapsed time */
-
- elapsed = clock_systimer() - start;
}
/* Loop until the stop is complete or a timeout occurs. */
diff --git NuttX/nuttx/arch/arm/src/stm32/stm32f30xxx_i2c.c NuttX/nuttx/arch/arm/src/stm32/stm32f30xxx_i2c.c
index 312e0b4..b2da861 100644
--- NuttX/nuttx/arch/arm/src/stm32/stm32f30xxx_i2c.c
+++ NuttX/nuttx/arch/arm/src/stm32/stm32f30xxx_i2c.c
@@ -7,7 +7,7 @@
*
* With extensions and modifications for the F1, F2, and F4 by:
*
- * Copyright (C) 2011-2013, 2016 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011-2013, 2016-2017 Gregory Nutt. All rights reserved.
* Author: Gregroy Nutt <gnutt@nuttx.org>
*
* And this version for the STM32 F3 by
@@ -704,15 +704,15 @@ static inline int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv)
do
{
+ /* Calculate the elapsed time */
+
+ elapsed = clock_systimer() - start;
+
/* Poll by simply calling the timer interrupt handler until it
* reports that it is done.
*/
stm32_i2c_isr(priv);
-
- /* Calculate the elapsed time */
-
- elapsed = clock_systimer() - start;
}
/* Loop until the transfer is complete. */
@@ -844,6 +844,10 @@ static inline void stm32_i2c_sem_waitstop(FAR struct stm32_i2c_priv_s *priv)
start = clock_systimer();
do
{
+ /* Calculate the elapsed time */
+
+ elapsed = clock_systimer() - start;
+
/* Check for STOP condition */
cr = stm32_i2c_getreg32(priv, STM32_I2C_CR2_OFFSET);
@@ -860,9 +864,6 @@ static inline void stm32_i2c_sem_waitstop(FAR struct stm32_i2c_priv_s *priv)
return;
}
- /* Calculate the elapsed time */
-
- elapsed = clock_systimer() - start;
}
/* Loop until the stop is complete or a timeout occurs. */
diff --git NuttX/nuttx/arch/arm/src/stm32/stm32f40xxx_i2c.c NuttX/nuttx/arch/arm/src/stm32/stm32f40xxx_i2c.c
index 2bb715c..e91058a 100644
--- NuttX/nuttx/arch/arm/src/stm32/stm32f40xxx_i2c.c
+++ NuttX/nuttx/arch/arm/src/stm32/stm32f40xxx_i2c.c
@@ -7,7 +7,7 @@
*
* With extensions, modifications by:
*
- * Copyright (C) 2011-2014, 2016 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011-2014, 2016-2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -672,15 +672,15 @@ static inline int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv)
do
{
+ /* Calculate the elapsed time */
+
+ elapsed = clock_systimer() - start;
+
/* Poll by simply calling the timer interrupt handler until it
* reports that it is done.
*/
stm32_i2c_isr(priv);
-
- /* Calculate the elapsed time */
-
- elapsed = clock_systimer() - start;
}
/* Loop until the transfer is complete. */
@@ -731,6 +731,10 @@ static inline void stm32_i2c_sem_waitstop(FAR struct stm32_i2c_priv_s *priv)
start = clock_systimer();
do
{
+ /* Calculate the elapsed time */
+
+ elapsed = clock_systimer() - start;
+
/* Check for STOP condition */
cr1 = stm32_i2c_getreg(priv, STM32_I2C_CR1_OFFSET);
@@ -747,9 +751,6 @@ static inline void stm32_i2c_sem_waitstop(FAR struct stm32_i2c_priv_s *priv)
return;
}
- /* Calculate the elapsed time */
-
- elapsed = clock_systimer() - start;
}
/* Loop until the stop is complete or a timeout occurs. */
diff --git NuttX/nuttx/arch/arm/src/stm32f7/stm32_i2c.c NuttX/nuttx/arch/arm/src/stm32f7/stm32_i2c.c
index d089db9..fd73457 100644
--- NuttX/nuttx/arch/arm/src/stm32f7/stm32_i2c.c
+++ NuttX/nuttx/arch/arm/src/stm32f7/stm32_i2c.c
@@ -7,7 +7,7 @@
*
* With extensions and modifications for the F1, F2, and F4 by:
*
- * Copyright (C) 2016 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2016-2017 Gregory Nutt. All rights reserved.
* Authors: Gregroy Nutt <gnutt@nuttx.org>
* John Wharington
* David Sidrane <david_s5@nscdg.com>
@@ -897,15 +897,15 @@ static inline int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv)
do
{
+ /* Calculate the elapsed time */
+
+ elapsed = clock_systimer() - start;
+
/* Poll by simply calling the timer interrupt handler until it
* reports that it is done.
*/
stm32_i2c_isr(priv);
-
- /* Calculate the elapsed time */
-
- elapsed = clock_systimer() - start;
}
/* Loop until the transfer is complete. */
@@ -1034,6 +1034,10 @@ static inline void stm32_i2c_sem_waitstop(FAR struct stm32_i2c_priv_s *priv)
start = clock_systimer();
do
{
+ /* Calculate the elapsed time */
+
+ elapsed = clock_systimer() - start;
+
/* Check for STOP condition */
cr = stm32_i2c_getreg32(priv, STM32_I2C_CR2_OFFSET);
@@ -1050,9 +1054,6 @@ static inline void stm32_i2c_sem_waitstop(FAR struct stm32_i2c_priv_s *priv)
return;
}
- /* Calculate the elapsed time */
-
- elapsed = clock_systimer() - start;
}
/* Loop until the stop is complete or a timeout occurs. */
diff --git NuttX/nuttx/arch/arm/src/stm32l4/stm32l4_i2c.c NuttX/nuttx/arch/arm/src/stm32l4/stm32l4_i2c.c
index eed199f..be46524 100644
--- NuttX/nuttx/arch/arm/src/stm32l4/stm32l4_i2c.c
+++ NuttX/nuttx/arch/arm/src/stm32l4/stm32l4_i2c.c
@@ -4,7 +4,7 @@
*
* Copyright (C) 2011 Uros Platise. All rights reserved.
* Author: Uros Platise <uros.platise@isotel.eu>
- * Copyright (C) 2011-2013, 2016 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011-2013, 2016-2017 Gregory Nutt. All rights reserved.
* Author: Gregroy Nutt <gnutt@nuttx.org>
* Author: John Wharington
* Author: Sebastien Lorquet
@@ -648,15 +648,15 @@ static inline int stm32l4_i2c_sem_waitdone(FAR struct stm32l4_i2c_priv_s *priv)
do
{
+ /* Calculate the elapsed time */
+
+ elapsed = clock_systimer() - start;
+
/* Poll by simply calling the timer interrupt handler until it
* reports that it is done.
*/
stm32l4_i2c_isr(priv);
-
- /* Calculate the elapsed time */
-
- elapsed = clock_systimer() - start;
}
/* Loop until the transfer is complete. */
@@ -788,6 +788,10 @@ static inline void stm32l4_i2c_sem_waitstop(FAR struct stm32l4_i2c_priv_s *priv)
start = clock_systimer();
do
{
+ /* Calculate the elapsed time */
+
+ elapsed = clock_systimer() - start;
+
/* Check for STOP condition */
cr = stm32l4_i2c_getreg32(priv, STM32L4_I2C_CR2_OFFSET);
@@ -804,9 +808,6 @@ static inline void stm32l4_i2c_sem_waitstop(FAR struct stm32l4_i2c_priv_s *priv)
return;
}
- /* Calculate the elapsed time */
-
- elapsed = clock_systimer() - start;
}
/* Loop until the stop is complete or a timeout occurs. */

View File

@ -1,364 +0,0 @@
diff --git NuttX/nuttx/arch/arm/src/stm32f7/stm32_serial.c NuttX/nuttx/arch/arm/src/stm32f7/stm32_serial.c
index 1f5445a..a51bb02 100644
--- NuttX/nuttx/arch/arm/src/stm32f7/stm32_serial.c
+++ NuttX/nuttx/arch/arm/src/stm32f7/stm32_serial.c
@@ -1,8 +1,9 @@
/****************************************************************************
* arch/arm/src/stm32f7/stm32_serial.c
*
- * Copyright (C) 2015-2016 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
+ * Copyright (C) 2015-2017 Gregory Nutt. All rights reserved.
+ * Authors: Gregory Nutt <gnutt@nuttx.org>
+ * David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -189,16 +190,6 @@
CONFIG_USART_DMAPRIO | \
DMA_SCR_PBURST_SINGLE | \
DMA_SCR_MBURST_SINGLE)
-# ifdef CONFIG_SERIAL_IFLOWCONTROL
-# define SERIAL_DMA_IFLOW_CONTROL_WORD \
- (DMA_SCR_DIR_P2M | \
- DMA_SCR_MINC | \
- DMA_SCR_PSIZE_8BITS | \
- DMA_SCR_MSIZE_8BITS | \
- CONFIG_USART_DMAPRIO | \
- DMA_SCR_PBURST_SINGLE | \
- DMA_SCR_MBURST_SINGLE)
-# endif
#endif /* SERIAL_HAVE_DMA */
/* Power management definitions */
@@ -288,8 +279,7 @@ struct up_dev_s
#ifdef SERIAL_HAVE_DMA
DMA_HANDLE rxdma; /* currently-open receive DMA stream */
bool rxenable; /* DMA-based reception en/disable */
- uint16_t rxdmain; /* Next byte in the DMA where hardware will write */
- uint16_t rxdmaout; /* Next byte in the DMA buffer to be read */
+ uint32_t rxdmanext; /* Next byte in the DMA buffer to be read */
char *const rxfifo; /* Receive DMA buffer */
#endif
@@ -1174,7 +1164,23 @@ static void up_set_format(struct uart_dev_s *dev)
uint32_t regval;
uint32_t usartdiv8;
uint32_t cr1;
+ uint32_t cr1_ue;
uint32_t brr;
+ irqstate_t flags;
+
+
+ flags = enter_critical_section();
+
+ /* Get the original state of UE */
+
+ cr1 = up_serialin(priv, STM32_USART_CR1_OFFSET);
+ cr1_ue = cr1 & USART_CR1_UE;
+ cr1 &= ~USART_CR1_UE;
+
+ /* Disable UE as the format bits and baud rate registers can not be
+ * updated while UE = 1 */
+
+ up_serialout(priv, STM32_USART_CR1_OFFSET, cr1);
/* In case of oversampling by 8, the equation is:
*
@@ -1194,7 +1200,6 @@ static void up_set_format(struct uart_dev_s *dev)
/* Use oversamply by 8 only if the divisor is small. But what is small? */
- cr1 = up_serialin(priv, STM32_USART_CR1_OFFSET);
if (usartdiv8 > 100)
{
/* Use usartdiv16 */
@@ -1223,30 +1228,43 @@ static void up_set_format(struct uart_dev_s *dev)
/* Configure parity mode */
- regval = up_serialin(priv, STM32_USART_CR1_OFFSET);
- regval &= ~(USART_CR1_PCE | USART_CR1_PS | USART_CR1_M0);
+ cr1 &= ~(USART_CR1_PCE | USART_CR1_PS | USART_CR1_M0 | USART_CR1_M1);
if (priv->parity == 1) /* Odd parity */
{
- regval |= (USART_CR1_PCE | USART_CR1_PS);
+ cr1 |= (USART_CR1_PCE | USART_CR1_PS);
}
else if (priv->parity == 2) /* Even parity */
{
- regval |= USART_CR1_PCE;
+ cr1 |= USART_CR1_PCE;
}
- /* Configure word length (Default: 8-bits) */
+ /* Configure word length (parity uses one of configured bits)
+ *
+ * Default: 1 start, 8 data (no parity), n stop, OR
+ * 1 start, 7 data + parity, n stop
+ */
- if (priv->bits == 7)
+ if (priv->bits == 9 || (priv->bits == 8 && priv->parity != 0))
{
- regval |= USART_CR1_M1;
+ /* Select: 1 start, 8 data + parity, n stop, OR
+ * 1 start, 9 data (no parity), n stop.
+ */
+
+ cr1 |= USART_CR1_M0;
}
- else if (priv->bits == 9)
+ else if (priv->bits == 7 && priv->parity == 0)
{
- regval |= USART_CR1_M0;
+ /* Select: 1 start, 7 data (no parity), n stop, OR
+ */
+
+ cr1 |= USART_CR1_M1;
}
+ /* Else Select: 1 start, 7 data + parity, n stop, OR
+ * 1 start, 8 data (no parity), n stop.
+ */
- up_serialout(priv, STM32_USART_CR1_OFFSET, regval);
+ up_serialout(priv, STM32_USART_CR1_OFFSET, cr1);
/* Configure STOP bits */
@@ -1265,7 +1283,8 @@ static void up_set_format(struct uart_dev_s *dev)
regval = up_serialin(priv, STM32_USART_CR3_OFFSET);
regval &= ~(USART_CR3_CTSE | USART_CR3_RTSE);
-#if defined(CONFIG_SERIAL_IFLOWCONTROL) && !defined(CONFIG_STM32F7_FLOWCONTROL_BROKEN)
+#if defined(CONFIG_SERIAL_IFLOWCONTROL) && \
+ !defined(CONFIG_STM32F7_FLOWCONTROL_BROKEN)
if (priv->iflow && (priv->rts_gpio != 0))
{
regval |= USART_CR3_RTSE;
@@ -1280,6 +1299,9 @@ static void up_set_format(struct uart_dev_s *dev)
#endif
up_serialout(priv, STM32_USART_CR3_OFFSET, regval);
+ up_serialout(priv, STM32_USART_CR1_OFFSET, cr1 | cr1_ue);
+ leave_critical_section(flags);
+
}
#endif /* CONFIG_SUPPRESS_UART_CONFIG */
@@ -1508,35 +1530,19 @@ static int up_dma_setup(struct uart_dev_s *dev)
priv->rxdma = stm32_dmachannel(priv->rxdma_channel);
-#ifdef CONFIG_SERIAL_IFLOWCONTROL
- if (priv->iflow)
- {
- /* Configure for non-circular DMA reception into the RX FIFO */
+ /* Configure for circular DMA reception into the RX FIFO */
- stm32_dmasetup(priv->rxdma,
- priv->usartbase + STM32_USART_RDR_OFFSET,
- (uint32_t)priv->rxfifo,
- RXDMA_BUFFER_SIZE,
- SERIAL_DMA_IFLOW_CONTROL_WORD);
- }
- else
-#endif
- {
- /* Configure for circular DMA reception into the RX FIFO */
-
- stm32_dmasetup(priv->rxdma,
- priv->usartbase + STM32_USART_RDR_OFFSET,
- (uint32_t)priv->rxfifo,
- RXDMA_BUFFER_SIZE,
- SERIAL_DMA_CONTROL_WORD);
- }
+ stm32_dmasetup(priv->rxdma,
+ priv->usartbase + STM32_USART_RDR_OFFSET,
+ (uint32_t)priv->rxfifo,
+ RXDMA_BUFFER_SIZE,
+ SERIAL_DMA_CONTROL_WORD);
/* Reset our DMA shadow pointer to match the address just
* programmed above.
*/
- priv->rxdmaout = 0;
- priv->rxdmain = 0;
+ priv->rxdmanext = 0;
/* Enable receive DMA for the UART */
@@ -1544,26 +1550,12 @@ static int up_dma_setup(struct uart_dev_s *dev)
regval |= USART_CR3_DMAR;
up_serialout(priv, STM32_USART_CR3_OFFSET, regval);
-#ifdef CONFIG_SERIAL_IFLOWCONTROL
- if (priv->iflow)
- {
- /* Start the DMA channel, and arrange for callbacks at the full point
- * in the FIFO. After buffer gets full, hardware flow-control kicks
- * in and DMA transfer is stopped.
- */
-
- stm32_dmastart(priv->rxdma, up_dma_rxcallback, (void *)priv, false);
- }
- else
-#endif
- {
- /* Start the DMA channel, and arrange for callbacks at the half and
- * full points in the FIFO. This ensures that we have half a FIFO
- * worth of time to claim bytes before they are overwritten.
- */
+ /* Start the DMA channel, and arrange for callbacks at the half and
+ * full points in the FIFO. This ensures that we have half a FIFO
+ * worth of time to claim bytes before they are overwritten.
+ */
- stm32_dmastart(priv->rxdma, up_dma_rxcallback, (void *)priv, true);
- }
+ stm32_dmastart(priv->rxdma, up_dma_rxcallback, (void *)priv, true);
return OK;
}
@@ -2258,49 +2250,27 @@ static bool up_rxflowcontrol(struct uart_dev_s *dev,
static int up_dma_receive(struct uart_dev_s *dev, unsigned int *status)
{
struct up_dev_s *priv = (struct up_dev_s *)dev->priv;
- uint32_t rxdmain;
int c = 0;
/* If additional bytes have been added to the DMA buffer, then we will need
* to invalidate the DMA buffer before reading the byte.
*/
- rxdmain = up_dma_nextrx(priv);
- if (rxdmain != priv->rxdmain)
+ if (up_dma_nextrx(priv) != priv->rxdmanext)
{
/* Invalidate the DMA buffer */
arch_invalidate_dcache((uintptr_t)priv->rxfifo,
(uintptr_t)priv->rxfifo + RXDMA_BUFFER_SIZE - 1);
- /* Since DMA is ongoing, there are lots of race conditions here. We
- * just have to hope that the rxdmaout stays well ahead of rxdmain.
- */
+ /* Now read from the DMA buffer */
- priv->rxdmain = rxdmain;
- }
+ c = priv->rxfifo[priv->rxdmanext];
- /* Now check if there are any bytes to read from the DMA buffer */
-
- if (rxdmain != priv->rxdmaout)
- {
- c = priv->rxfifo[priv->rxdmaout];
-
- priv->rxdmaout++;
- if (priv->rxdmaout == RXDMA_BUFFER_SIZE)
+ priv->rxdmanext++;
+ if (priv->rxdmanext == RXDMA_BUFFER_SIZE)
{
-#ifdef CONFIG_SERIAL_IFLOWCONTROL
- if (priv->iflow)
- {
- /* RX DMA buffer full. RX paused, RTS line pulled up to prevent
- * more input data from other end.
- */
- }
- else
-#endif
- {
- priv->rxdmaout = 0;
- }
+ priv->rxdmanext = 0;
}
}
@@ -2309,41 +2279,6 @@ static int up_dma_receive(struct uart_dev_s *dev, unsigned int *status)
#endif
/****************************************************************************
- * Name: up_dma_reenable
- *
- * Description:
- * Call to re-enable RX DMA.
- *
- ****************************************************************************/
-
-#if defined(SERIAL_HAVE_DMA) && defined(CONFIG_SERIAL_IFLOWCONTROL)
-static void up_dma_reenable(struct up_dev_s *priv)
-{
- /* Configure for non-circular DMA reception into the RX FIFO */
-
- stm32_dmasetup(priv->rxdma,
- priv->usartbase + STM32_USART_RDR_OFFSET,
- (uint32_t)priv->rxfifo,
- RXDMA_BUFFER_SIZE,
- SERIAL_DMA_IFLOW_CONTROL_WORD);
-
- /* Reset our DMA shadow pointer to match the address just programmed
- * above.
- */
-
- priv->rxdmaout = 0;
- priv->rxdmain = 0;
-
- /* Start the DMA channel, and arrange for callbacks at the full point in
- * the FIFO. After buffer gets full, hardware flow-control kicks in and
- * DMA transfer is stopped.
- */
-
- stm32_dmastart(priv->rxdma, up_dma_rxcallback, (void *)priv, false);
-}
-#endif
-
-/****************************************************************************
* Name: up_dma_rxint
*
* Description:
@@ -2365,15 +2300,6 @@ static void up_dma_rxint(struct uart_dev_s *dev, bool enable)
*/
priv->rxenable = enable;
-
-#ifdef CONFIG_SERIAL_IFLOWCONTROL
- if (priv->iflow && priv->rxenable && (priv->rxdmaout == RXDMA_BUFFER_SIZE))
- {
- /* Re-enable RX DMA. */
-
- up_dma_reenable(priv);
- }
-#endif
}
#endif
@@ -2394,7 +2320,7 @@ static bool up_dma_rxavailable(struct uart_dev_s *dev)
* do not match, then there are bytes to be received.
*/
- return (up_dma_nextrx(priv) != priv->rxdmaout);
+ return (up_dma_nextrx(priv) != priv->rxdmanext);
}
#endif
@@ -2582,16 +2508,6 @@ static void up_dma_rxcallback(DMA_HANDLE handle, uint8_t status, void *arg)
if (priv->rxenable && up_dma_rxavailable(&priv->dev))
{
uart_recvchars(&priv->dev);
-
-#ifdef CONFIG_SERIAL_IFLOWCONTROL
- if (priv->iflow && priv->rxenable &&
- (priv->rxdmaout == RXDMA_BUFFER_SIZE))
- {
- /* Re-enable RX DMA. */
-
- up_dma_reenable(priv);
- }
-#endif
}
}
#endif

View File

@ -1,314 +0,0 @@
diff --git NuttX/apps/nshlib/README.txt NuttX/apps/nshlib/README.txt
index 151387a..28e1247 100644
--- NuttX/apps/nshlib/README.txt
+++ NuttX/apps/nshlib/README.txt
@@ -1000,10 +1000,10 @@ o rmmod <module-name>
NAME INIT UNINIT ARG TEXT SIZE DATA SIZE
nsh>
-o set <name> <value>
+o set [{+|-}{e|x|xe|ex}] [<name> <value>]
- Set the environment variable <name> to the sting <value>.
- For example,
+ Set the environment variable <name> to the sting <value> and or set NSH
+ parser control options. For example,
nsh> echo $foobar
@@ -1012,6 +1012,38 @@ o set <name> <value>
foovalue
nsh>
+ Set the 'exit on error control' and/or 'print a trace' of commands when parsing
+ scripts in NSH. The settings are in effect from the point of exection, until
+ they are changed again, or in the case of the init script, the settings are
+ returned to the default settings when it exits. Included child scripts will run
+ with the parents settings and changes made in the child script will effect the
+ parent on return.
+
+ Use 'set -e' to enable and 'set +e' to disable (ignore) the exit condition on commands.
+ The default is -e. Errors cause script to exit.
+
+ Use 'set -x' to enable and 'set +x' to disable (silence) printing a trace of the script
+ commands as they are ececuted.
+ The default is +x. No printing of a trace of script commands as they are executed.
+
+ Example 1 - no exit on command not found
+ set +e
+ notacommand
+
+ Example 2 - will exit on command not found
+ set -e
+ notacommand
+
+ Example 3 - will exit on command not found, and print a trace of the script commmands
+ set -ex
+
+ Example 4 - will exit on command not found, and print a trace of the script commmands
+ and set foobar to foovalue.
+ set -ex foobar foovalue
+ nsh> echo $foobar
+ foovalue
+
+
o sh <script-path>
Execute the sequence of NSH commands in the file referred
diff --git NuttX/apps/nshlib/nsh.h NuttX/apps/nshlib/nsh.h
index eef16ed..013357a 100644
--- NuttX/apps/nshlib/nsh.h
+++ NuttX/apps/nshlib/nsh.h
@@ -690,6 +690,15 @@
# undef NSH_HAVE_TRIMSPACES
#endif
+#ifndef CONFIG_NSH_DISABLESCRIPT
+# define NSH_NP_SET_OPTIONS "ex" /* Maintain order see nsh_npflags_e */
+# define NSH_NP_SET_OPTIONS_INIT (NSH_PFLAG_SILENT)
+#endif
+
+#if defined(CONFIG_DISABLE_ENVIRON) && defined(CONFIG_NSH_DISABLESCRIPT)
+# define CONFIG_NSH_DISABLE_SET
+#endif
+
/****************************************************************************
* Public Types
****************************************************************************/
@@ -741,6 +750,22 @@ struct nsh_loop_s
};
#endif
+#ifndef CONFIG_NSH_DISABLESCRIPT
+/* Define the bits that correspond to the option defined in
+ * NSH_NP_SET_OPTIONS. The bit value is 1 shifted left the offset
+ * of the char in NSH_NP_SET_OPTIONS string.
+ */
+
+enum nsh_npflags_e
+{
+ NSH_PFLAG_IGNORE = 1, /* set for +e no exit on errors,
+ * cleared -e exit on error */
+ NSH_PFLAG_SILENT = 2, /* cleared -x print a trace of commands
+ * when parsing.
+ * set +x no print a trace of commands */
+};
+#endif
+
/* These structure provides the overall state of the parser */
struct nsh_parser_s
@@ -752,6 +777,9 @@ struct nsh_parser_s
bool np_redirect; /* true: Output from the last command was re-directed */
#endif
bool np_fail; /* true: The last command failed */
+#ifndef CONFIG_NSH_DISABLESCRIPT
+ uint8_t np_flags; /* See nsh_npflags_e above */
+#endif
#ifndef CONFIG_NSH_DISABLEBG
int np_nice; /* "nice" value applied to last background cmd */
#endif
@@ -1169,10 +1197,10 @@ int cmd_lsmod(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv);
int cmd_uname(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv);
#endif
-#ifndef CONFIG_DISABLE_ENVIRON
-# ifndef CONFIG_NSH_DISABLE_SET
+#ifndef CONFIG_NSH_DISABLE_SET
int cmd_set(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv);
-# endif
+#endif
+#ifndef CONFIG_DISABLE_ENVIRON
# ifndef CONFIG_NSH_DISABLE_UNSET
int cmd_unset(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv);
# endif
diff --git NuttX/apps/nshlib/nsh_command.c NuttX/apps/nshlib/nsh_command.c
index d466fbf..d507845 100644
--- NuttX/apps/nshlib/nsh_command.c
+++ NuttX/apps/nshlib/nsh_command.c
@@ -424,10 +424,14 @@ static const struct cmdmap_s g_cmdmap[] =
{ "rmmod", cmd_rmmod, 2, 2, "<module-name>" },
#endif
-#ifndef CONFIG_DISABLE_ENVIRON
-# ifndef CONFIG_NSH_DISABLE_SET
+#ifndef CONFIG_NSH_DISABLE_SET
+# if !defined(CONFIG_DISABLE_ENVIRON) && !defined(CONFIG_NSH_DISABLESCRIPT)
+ { "set", cmd_set, 2, 4, "[{+|-}{e|x|xe|ex}] [<name> <value>]" },
+# elif !defined(CONFIG_DISABLE_ENVIRON) && defined(CONFIG_NSH_DISABLESCRIPT)
{ "set", cmd_set, 3, 3, "<name> <value>" },
-# endif
+# elif defined(CONFIG_DISABLE_ENVIRON) && !defined(CONFIG_NSH_DISABLESCRIPT)
+ { "set", cmd_set, 2, 2, "{+|-}{e|x|xe|ex}" },
+# endif
#endif
#if CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0 && !defined(CONFIG_NSH_DISABLESCRIPT)
diff --git NuttX/apps/nshlib/nsh_console.c NuttX/apps/nshlib/nsh_console.c
index 6d68e3a..2c52409 100644
--- NuttX/apps/nshlib/nsh_console.c
+++ NuttX/apps/nshlib/nsh_console.c
@@ -479,6 +479,10 @@ FAR struct console_stdio_s *nsh_newconsole(void)
pstate->cn_outstream = OUTSTREAM(pstate);
#endif
}
+#ifndef CONFIG_NSH_DISABLESCRIPT
+ /* Set the initial option flags */
+ pstate->cn_vtbl.np.np_flags = NSH_NP_SET_OPTIONS_INIT;
+#endif
return pstate;
}
diff --git NuttX/apps/nshlib/nsh_consolemain.c NuttX/apps/nshlib/nsh_consolemain.c
index f89944f..2797610 100644
--- NuttX/apps/nshlib/nsh_consolemain.c
+++ NuttX/apps/nshlib/nsh_consolemain.c
@@ -85,6 +85,11 @@ int nsh_consolemain(int argc, char *argv[])
/* Execute the start-up script */
(void)nsh_initscript(&pstate->cn_vtbl);
+#ifndef CONFIG_NSH_DISABLESCRIPT
+ /* Reset the option flags */
+
+ pstate->cn_vtbl.np.np_flags = NSH_NP_SET_OPTIONS_INIT;
+#endif
#endif
#ifdef CONFIG_NSH_USBDEV_TRACE
diff --git NuttX/apps/nshlib/nsh_envcmds.c NuttX/apps/nshlib/nsh_envcmds.c
index cbda78b..277665b 100644
--- NuttX/apps/nshlib/nsh_envcmds.c
+++ NuttX/apps/nshlib/nsh_envcmds.c
@@ -311,29 +311,84 @@ int cmd_pwd(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv)
* Name: cmd_set
****************************************************************************/
-#ifndef CONFIG_DISABLE_ENVIRON
#ifndef CONFIG_NSH_DISABLE_SET
int cmd_set(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv)
{
FAR char *value;
- int ret;
+ int ret = OK;
+ int ndx = 1;
+#ifndef CONFIG_NSH_DISABLESCRIPT
+ FAR char *popt;
+ const char opts[] = NSH_NP_SET_OPTIONS;
+ int op;
- /* Trim whitespace from the value */
+ /* Support set [{+|-}{e|x|xe|ex}] [<name> <value>] */
- value = nsh_trimspaces(argv[2]);
+ if (argc == 2 || argc == 4)
+ {
+ if (strlen(argv[1]) < 2)
+ {
+ ret = -EINVAL;
+ nsh_output(vtbl, g_fmtargrequired, argv[0], "set", NSH_ERRNO);
+ }
+ else
+ {
+ op = argv[1][0];
+ if (op != '-' && op != '+')
+ {
+ ret = -EINVAL;
+ nsh_output(vtbl, g_fmtarginvalid, argv[0], "set", NSH_ERRNO);
+ }
+ else
+ {
+ value = &argv[1][1];
+ while(*value && *value != ' ')
+ {
+ popt = strchr(opts, *value++);
+ if (popt == NULL)
+ {
+ nsh_output(vtbl, g_fmtarginvalid, argv[0], "set", NSH_ERRNO);
+ ret = -EINVAL;
+ break;
+ }
+ if (op == '+')
+ {
+ vtbl->np.np_flags |= 1 << (popt-opts);
+ }
+ else
+ {
+ vtbl->np.np_flags &= ~(1 << (popt-opts));
+ }
+ }
+ if (ret == OK)
+ {
+ ndx = 2;
+ }
+ }
+ }
+ }
+# ifndef CONFIG_DISABLE_ENVIRON
+ if (ret == OK && (argc == 3 || argc == 4))
+# endif
+#endif
+#ifndef CONFIG_DISABLE_ENVIRON
+ {
+ /* Trim whitespace from the value */
- /* Set the environment variable */
+ value = nsh_trimspaces(argv[ndx+1]);
- ret = setenv(argv[1], value, TRUE);
- if (ret < 0)
- {
- nsh_output(vtbl, g_fmtcmdfailed, argv[0], "setenv", NSH_ERRNO);
- }
+ /* Set the environment variable */
+ ret = setenv(argv[ndx], value, TRUE);
+ if (ret < 0)
+ {
+ nsh_output(vtbl, g_fmtcmdfailed, argv[0], "setenv", NSH_ERRNO);
+ }
+ }
+#endif
return ret;
}
#endif
-#endif
/****************************************************************************
* Name: cmd_unset
diff --git NuttX/apps/nshlib/nsh_parse.c NuttX/apps/nshlib/nsh_parse.c
index 97c2d04..4bc6794 100644
--- NuttX/apps/nshlib/nsh_parse.c
+++ NuttX/apps/nshlib/nsh_parse.c
@@ -1169,6 +1169,11 @@ static FAR char *nsh_argexpand(FAR struct nsh_vtbl_s *vtbl, FAR char *cmdline,
envstr = nsh_envexpand(vtbl, ptr);
+ if ((vtbl->np.np_flags & NSH_PFLAG_SILENT) == 0)
+ {
+ nsh_output(vtbl," %s=%s\n", ptr, envstr ? envstr :"(null)");
+ }
+
/* Concatenate the result of the operation with the accumulated
* string. On failures to allocation memory, nsh_strcat will
* just return value value of argument
diff --git NuttX/apps/nshlib/nsh_script.c NuttX/apps/nshlib/nsh_script.c
index 2c4a369..cc20a82 100644
--- NuttX/apps/nshlib/nsh_script.c
+++ NuttX/apps/nshlib/nsh_script.c
@@ -136,10 +136,15 @@ int nsh_script(FAR struct nsh_vtbl_s *vtbl, FAR const char *cmd,
* considerable amount of stack may be used.
*/
+ if ((vtbl->np.np_flags & NSH_PFLAG_SILENT) == 0)
+ {
+ nsh_output(vtbl,"%s", buffer);
+ }
+
ret = nsh_parse(vtbl, buffer);
}
}
- while (pret && ret == OK);
+ while (pret && (ret == OK || (vtbl->np.np_flags & NSH_PFLAG_IGNORE)));
/* Close the script file */