summaryrefslogtreecommitdiff
path: root/nuttx/arch/arm
diff options
context:
space:
mode:
authorSarthak Kaingade <sarthakkaingade@yahoo.com>2014-02-24 18:06:22 +0530
committerSarthak Kaingade <sarthakkaingade@yahoo.com>2014-02-24 18:06:22 +0530
commit8c25e0afe2b179f7b8bd7ca4f49016d98012af6d (patch)
tree49a24a6fde718538160b3ced1bc38fb2a01003a9 /nuttx/arch/arm
parent98f4615853570603a0138fe2ee0706811184f2e8 (diff)
parent454523bebfbaca9a77ba9827ba11454caffaa31d (diff)
downloadpx4-nuttx-8c25e0afe2b179f7b8bd7ca4f49016d98012af6d.tar.gz
px4-nuttx-8c25e0afe2b179f7b8bd7ca4f49016d98012af6d.tar.bz2
px4-nuttx-8c25e0afe2b179f7b8bd7ca4f49016d98012af6d.zip
Merge https://github.com/PX4/NuttX
Diffstat (limited to 'nuttx/arch/arm')
-rw-r--r--nuttx/arch/arm/src/armv7-m/up_memcpy.S32
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_serial.c58
2 files changed, 51 insertions, 39 deletions
diff --git a/nuttx/arch/arm/src/armv7-m/up_memcpy.S b/nuttx/arch/arm/src/armv7-m/up_memcpy.S
index a154cab61..ea267f78f 100644
--- a/nuttx/arch/arm/src/armv7-m/up_memcpy.S
+++ b/nuttx/arch/arm/src/armv7-m/up_memcpy.S
@@ -152,7 +152,7 @@ memcpy:
/* Quickly check for very short copies */
cmp r2, #4
- blt MEM_DataCopyBytes
+ blt.n MEM_DataCopyBytes
and r14, r0, #3 /* Get destination alignment bits */
bfi r14, r1, #2, #2 /* Get source alignment bits */
@@ -199,7 +199,7 @@ MEM_DataCopy0:
/* Check for short word-aligned copy */
cmp r2, #0x28
- blt MEM_DataCopy0_2
+ blt.n MEM_DataCopy0_2
/* Bulk copy loop */
@@ -208,7 +208,7 @@ MEM_DataCopy0_1:
stmia r0!, {r3-r12}
sub r2, r2, #0x28
cmp r2, #0x28
- bge MEM_DataCopy0_1
+ bge.n MEM_DataCopy0_1
/* Copy remaining long words */
@@ -224,28 +224,28 @@ MEM_DataCopy0_2:
MEM_LongCopyJump:
ldr.w r3, [r1], #0x04 /* 4 bytes remain */
str.w r3, [r0], #0x04
- b MEM_LongCopyEnd
+ b.n MEM_LongCopyEnd
ldmia.w r1!, {r3-r4} /* 8 bytes remain */
stmia.w r0!, {r3-r4}
- b MEM_LongCopyEnd
+ b.n MEM_LongCopyEnd
ldmia.w r1!, {r3-r5} /* 12 bytes remain */
stmia.w r0!, {r3-r5}
- b MEM_LongCopyEnd
+ b.n MEM_LongCopyEnd
ldmia.w r1!, {r3-r6} /* 16 bytes remain */
stmia.w r0!, {r3-r6}
- b MEM_LongCopyEnd
+ b.n MEM_LongCopyEnd
ldmia.w r1!, {r3-r7} /* 20 bytes remain */
stmia.w r0!, {r3-r7}
- b MEM_LongCopyEnd
+ b.n MEM_LongCopyEnd
ldmia.w r1!, {r3-r8} /* 24 bytes remain */
stmia.w r0!, {r3-r8}
- b MEM_LongCopyEnd
+ b.n MEM_LongCopyEnd
ldmia.w r1!, {r3-r9} /* 28 bytes remain */
stmia.w r0!, {r3-r9}
- b MEM_LongCopyEnd
+ b.n MEM_LongCopyEnd
ldmia.w r1!, {r3-r10} /* 32 bytes remain */
stmia.w r0!, {r3-r10}
- b MEM_LongCopyEnd
+ b.n MEM_LongCopyEnd
ldmia.w r1!, {r3-r11} /* 36 bytes remain */
stmia.w r0!, {r3-r11}
@@ -308,7 +308,7 @@ MEM_DataCopy13:
MEM_DataCopy2:
cmp r2, #0x28
- blt MEM_DataCopy2_1
+ blt.n MEM_DataCopy2_1
/* Save regs */
@@ -345,18 +345,18 @@ MEM_DataCopy2_2:
sub r2, r2, #0x28
cmp r2, #0x28
- bge MEM_DataCopy2_2
+ bge.n MEM_DataCopy2_2
pop {r4-r12}
MEM_DataCopy2_1: /* Read longs and write 2 x half words */
cmp r2, #4
- blt MEM_DataCopyBytes
+ blt.n MEM_DataCopyBytes
ldr r3, [r1], #0x04
strh r3, [r0], #0x02
lsr r3, r3, #0x10
strh r3, [r0], #0x02
sub r2, r2, #0x04
- b MEM_DataCopy2
+ b.n MEM_DataCopy2
/* Bits: Src=01, Dst=00 - Byte before half word to long
* Bits: Src=01, Dst=10 - Byte before half word to half word
@@ -410,7 +410,7 @@ MEM_DataCopy3:
lsr r3, r3, #0x10
strb r3, [r0], #0x01
sub r2, r2, #0x04
- b MEM_DataCopy3
+ b.n MEM_DataCopy3
.size memcpy, .-memcpy
.end
diff --git a/nuttx/arch/arm/src/stm32/stm32_serial.c b/nuttx/arch/arm/src/stm32/stm32_serial.c
index d751b0f36..89c31addc 100644
--- a/nuttx/arch/arm/src/stm32/stm32_serial.c
+++ b/nuttx/arch/arm/src/stm32/stm32_serial.c
@@ -519,10 +519,10 @@ static struct up_dev_s g_usart1priv =
.usartbase = STM32_USART1_BASE,
.tx_gpio = GPIO_USART1_TX,
.rx_gpio = GPIO_USART1_RX,
-#if defined(CONFIG_SERIAL_OFLOWCONROL) && defined(CONFIG_USART1_OFLOWCONTROL)
+#if defined(CONFIG_SERIAL_OFLOWCONTROL) && defined(CONFIG_USART1_OFLOWCONTROL)
.cts_gpio = GPIO_USART1_CTS,
#endif
-#if defined(CONFIG_SERIAL_IFLOWCONROL) && defined(CONFIG_USART1_IFLOWCONTROL)
+#if defined(CONFIG_SERIAL_IFLOWCONTROL) && defined(CONFIG_USART1_IFLOWCONTROL)
.rts_gpio = GPIO_USART1_RTS,
#endif
#ifdef CONFIG_USART1_RXDMA
@@ -585,10 +585,10 @@ static struct up_dev_s g_usart2priv =
.usartbase = STM32_USART2_BASE,
.tx_gpio = GPIO_USART2_TX,
.rx_gpio = GPIO_USART2_RX,
-#if defined(CONFIG_SERIAL_OFLOWCONROL) && defined(CONFIG_USART2_OFLOWCONTROL)
+#if defined(CONFIG_SERIAL_OFLOWCONTROL) && defined(CONFIG_USART2_OFLOWCONTROL)
.cts_gpio = GPIO_USART2_CTS,
#endif
-#if defined(CONFIG_SERIAL_IFLOWCONROL) && defined(CONFIG_USART2_IFLOWCONTROL)
+#if defined(CONFIG_SERIAL_IFLOWCONTROL) && defined(CONFIG_USART2_IFLOWCONTROL)
.rts_gpio = GPIO_USART2_RTS,
#endif
#ifdef CONFIG_USART2_RXDMA
@@ -651,10 +651,10 @@ static struct up_dev_s g_usart3priv =
.usartbase = STM32_USART3_BASE,
.tx_gpio = GPIO_USART3_TX,
.rx_gpio = GPIO_USART3_RX,
-#if defined(CONFIG_SERIAL_OFLOWCONROL) && defined(CONFIG_USART3_OFLOWCONTROL)
+#if defined(CONFIG_SERIAL_OFLOWCONTROL) && defined(CONFIG_USART3_OFLOWCONTROL)
.cts_gpio = GPIO_USART3_CTS,
#endif
-#if defined(CONFIG_SERIAL_IFLOWCONROL) && defined(CONFIG_USART3_IFLOWCONTROL)
+#if defined(CONFIG_SERIAL_IFLOWCONTROL) && defined(CONFIG_USART3_IFLOWCONTROL)
.rts_gpio = GPIO_USART3_RTS,
#endif
#ifdef CONFIG_USART3_RXDMA
@@ -717,10 +717,10 @@ static struct up_dev_s g_uart4priv =
.usartbase = STM32_UART4_BASE,
.tx_gpio = GPIO_UART4_TX,
.rx_gpio = GPIO_UART4_RX,
-#ifdef CONFIG_SERIAL_OFLOWCONROL
+#ifdef CONFIG_SERIAL_OFLOWCONTROL
.cts_gpio = 0,
#endif
-#ifdef CONFIG_SERIAL_IFLOWCONROL
+#ifdef CONFIG_SERIAL_IFLOWCONTROL
.rts_gpio = 0,
#endif
#ifdef CONFIG_UART4_RXDMA
@@ -783,10 +783,10 @@ static struct up_dev_s g_uart5priv =
.usartbase = STM32_UART5_BASE,
.tx_gpio = GPIO_UART5_TX,
.rx_gpio = GPIO_UART5_RX,
-#ifdef CONFIG_SERIAL_OFLOWCONROL
+#ifdef CONFIG_SERIAL_OFLOWCONTROL
.cts_gpio = 0,
#endif
-#ifdef CONFIG_SERIAL_IFLOWCONROL
+#ifdef CONFIG_SERIAL_IFLOWCONTROL
.rts_gpio = 0,
#endif
#ifdef CONFIG_UART5_RXDMA
@@ -849,10 +849,10 @@ static struct up_dev_s g_usart6priv =
.usartbase = STM32_USART6_BASE,
.tx_gpio = GPIO_USART6_TX,
.rx_gpio = GPIO_USART6_RX,
-#if defined(CONFIG_SERIAL_OFLOWCONROL) && defined(CONFIG_USART6_OFLOWCONTROL)
+#if defined(CONFIG_SERIAL_OFLOWCONTROL) && defined(CONFIG_USART6_OFLOWCONTROL)
.cts_gpio = GPIO_USART6_CTS,
#endif
-#if defined(CONFIG_SERIAL_IFLOWCONROL) && defined(CONFIG_USART6_IFLOWCONTROL)
+#if defined(CONFIG_SERIAL_IFLOWCONTROL) && defined(CONFIG_USART6_IFLOWCONTROL)
.rts_gpio = GPIO_USART6_RTS,
#endif
#ifdef CONFIG_USART6_RXDMA
@@ -909,10 +909,10 @@ static struct up_dev_s g_uart7priv =
.usartbase = STM32_UART7_BASE,
.tx_gpio = GPIO_UART7_TX,
.rx_gpio = GPIO_UART7_RX,
-#if defined(CONFIG_SERIAL_OFLOWCONROL) && defined(CONFIG_USART7_OFLOWCONTROL)
+#if defined(CONFIG_SERIAL_OFLOWCONTROL) && defined(CONFIG_USART7_OFLOWCONTROL)
.cts_gpio = GPIO_UART7_CTS,
#endif
-#if defined(CONFIG_SERIAL_IFLOWCONROL) && defined(CONFIG_USART7_IFLOWCONTROL)
+#if defined(CONFIG_SERIAL_IFLOWCONTROL) && defined(CONFIG_USART7_IFLOWCONTROL)
.rts_gpio = GPIO_UART7_RTS,
#endif
#ifdef CONFIG_UART7_RXDMA
@@ -969,10 +969,10 @@ static struct up_dev_s g_uart8priv =
.usartbase = STM32_UART8_BASE,
.tx_gpio = GPIO_UART8_TX,
.rx_gpio = GPIO_UART8_RX,
-#if defined(CONFIG_SERIAL_OFLOWCONROL) && defined(CONFIG_USART8_OFLOWCONTROL)
+#if defined(CONFIG_SERIAL_OFLOWCONTROL) && defined(CONFIG_USART8_OFLOWCONTROL)
.cts_gpio = GPIO_UART8_CTS,
#endif
-#if defined(CONFIG_SERIAL_IFLOWCONROL) && defined(CONFIG_USART8_IFLOWCONTROL)
+#if defined(CONFIG_SERIAL_IFLOWCONTROL) && defined(CONFIG_USART8_IFLOWCONTROL)
.rts_gpio = GPIO_UART8_RTS,
#endif
#ifdef CONFIG_UART8_RXDMA
@@ -1329,14 +1329,14 @@ static int up_setup(struct uart_dev_s *dev)
stm32_configgpio(priv->tx_gpio);
stm32_configgpio(priv->rx_gpio);
-#ifdef CONFIG_SERIAL_OFLOWCONROL
+#ifdef CONFIG_SERIAL_OFLOWCONTROL
if (priv->cts_gpio != 0)
{
stm32_configgpio(priv->cts_gpio);
}
#endif
-#ifdef CONFIG_SERIAL_IFLOWCONROL
+#ifdef CONFIG_SERIAL_IFLOWCONTROL
if (priv->rts_gpio != 0)
{
stm32_configgpio(priv->rts_gpio);
@@ -1743,6 +1743,18 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
*/
uint32_t cr = up_serialin(priv, STM32_USART_CR3_OFFSET);
+#if defined(CONFIG_STM32_STM32F10XX)
+ if (arg == SER_SINGLEWIRE_ENABLED)
+ {
+ stm32_configgpio((priv->tx_gpio & ~(GPIO_CNF_MASK)) | GPIO_CNF_AFOD);
+ cr |= USART_CR3_HDSEL;
+ }
+ else
+ {
+ stm32_configgpio((priv->tx_gpio & ~(GPIO_CNF_MASK)) | GPIO_CNF_AFPP);
+ cr &= ~USART_CR3_HDSEL;
+ }
+#else
if (arg == SER_SINGLEWIRE_ENABLED)
{
@@ -1754,6 +1766,7 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
stm32_configgpio(priv->tx_gpio | GPIO_PUSHPULL);
cr &= ~USART_CR3_HDSEL;
}
+#endif
up_serialout(priv, STM32_USART_CR3_OFFSET, cr);
}
@@ -1806,10 +1819,10 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
/* Perform some sanity checks before accepting any changes */
if (((termiosp->c_cflag & CSIZE) != CS8)
-#ifdef CONFIG_SERIAL_IFLOWCONROL
+#ifdef CONFIG_SERIAL_IFLOWCONTROL
|| ((termiosp->c_cflag & CCTS_OFLOW) && (priv->cts_gpio == 0))
#endif
-#ifdef CONFIG_SERIAL_IFLOWCONROL
+#ifdef CONFIG_SERIAL_IFLOWCONTROL
|| ((termiosp->c_cflag & CRTS_IFLOW) && (priv->rts_gpio == 0))
#endif
)
@@ -2424,13 +2437,12 @@ void up_serialinit(void)
(void)uart_register("/dev/ttyS0", &uart_devs[CONSOLE_UART - 1]->dev);
minor = 1;
- /* If we need to re-initialise the console to enable DMA do that here. */
+#endif /* CONFIG_SERIAL_DISABLE_REORDERING not defined */
+/* If we need to re-initialise the console to enable DMA do that here. */
# ifdef SERIAL_HAVE_CONSOLE_DMA
up_dma_setup(&uart_devs[CONSOLE_UART - 1]->dev);
# endif
-#endif /* CONFIG_SERIAL_DISABLE_REORDERING not defined */
-
#endif /* CONSOLE_UART > 0 */
/* Register all remaining USARTs */