summaryrefslogtreecommitdiff
path: root/nuttx/arch/arm
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/arch/arm')
-rw-r--r--nuttx/arch/arm/include/cortexm3/irq.h2
-rw-r--r--nuttx/arch/arm/src/arm/up_sigdeliver.c2
-rw-r--r--nuttx/arch/arm/src/c5471/c5471_ethernet.c59
-rw-r--r--nuttx/arch/arm/src/c5471/c5471_watchdog.c2
-rw-r--r--nuttx/arch/arm/src/common/up_blocktask.c2
-rw-r--r--nuttx/arch/arm/src/common/up_exit.c2
-rw-r--r--nuttx/arch/arm/src/common/up_internal.h2
-rw-r--r--nuttx/arch/arm/src/cortexm3/up_sigdeliver.c2
-rw-r--r--nuttx/arch/arm/src/dm320/dm320_restart.S2
-rw-r--r--nuttx/arch/arm/src/dm320/dm320_serial.c2
-rw-r--r--nuttx/arch/arm/src/imx/imx_serial.c2
-rw-r--r--nuttx/arch/arm/src/lm3s/lm3s_serial.c2
-rw-r--r--nuttx/arch/arm/src/lpc214x/lpc214x_serial.c2
-rw-r--r--nuttx/arch/arm/src/str71x/str71x_serial.c2
14 files changed, 24 insertions, 61 deletions
diff --git a/nuttx/arch/arm/include/cortexm3/irq.h b/nuttx/arch/arm/include/cortexm3/irq.h
index b439ec42f..91be3e8b3 100644
--- a/nuttx/arch/arm/include/cortexm3/irq.h
+++ b/nuttx/arch/arm/include/cortexm3/irq.h
@@ -160,7 +160,7 @@ static inline irqstate_t irqsave(void)
{
unsigned short primask;
- /* Return the the current value of primask register and set
+ /* Return the current value of primask register and set
* bit 0 of the primask register to disable interrupts
*/
diff --git a/nuttx/arch/arm/src/arm/up_sigdeliver.c b/nuttx/arch/arm/src/arm/up_sigdeliver.c
index 8d1601aea..469f274e6 100644
--- a/nuttx/arch/arm/src/arm/up_sigdeliver.c
+++ b/nuttx/arch/arm/src/arm/up_sigdeliver.c
@@ -86,7 +86,7 @@ void up_sigdeliver(void)
sig_deliver_t sigdeliver;
/* Save the errno. This must be preserved throughout the
- * signal handling so that the the user code final gets
+ * signal handling so that the user code final gets
* the correct errno value (probably EINTR).
*/
diff --git a/nuttx/arch/arm/src/c5471/c5471_ethernet.c b/nuttx/arch/arm/src/c5471/c5471_ethernet.c
index 76a565fcd..322882fd4 100644
--- a/nuttx/arch/arm/src/c5471/c5471_ethernet.c
+++ b/nuttx/arch/arm/src/c5471/c5471_ethernet.c
@@ -415,53 +415,16 @@ static void c5471_macassign(struct c5471_driver_s *c5471);
****************************************************************************/
#ifdef CONFIG_C5471_NET_DUMPBUFFER
-static void c5471_dumpbuffer(const char *buffer, ssize_t nbytes)
+static inline void c5471_dumpbuffer(const char *msg, const ubyte *buffer, unsigned int nbytes)
{
-#if defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_NET)
- char line[128];
- int ch;
- int i;
- int j;
-
- for (i = 0; i < nbytes; i += 16)
- {
- sprintf(line, "%04x: ", i);
- for (j = 0; j < 16; j++)
- {
- if (i + j < nbytes)
- {
- sprintf(&line[strlen(line)], "%02x", buffer[i+j] );
- }
- else
- {
- strcpy(&line[strlen(line)], " ");
- }
-
- if (j == 7 || j == 15)
- {
- strcpy(&line[strlen(line)], " ");
- }
- }
-
- for ( j = 0; j < 16; j++)
- {
- if (i + j < nbytes)
- {
- ch = buffer[i+j];
- sprintf(&line[strlen(line)], "%c", ch >= 0x20 && ch <= 0x7e ? ch : '.');
- }
-
- if (j == 7 || j == 15)
- {
- strcpy(&line[strlen(line)], " ");
- }
- }
- ndbg("%s\n", line);
- }
-#endif
+ /* CONFIG_DEBUG, CONFIG_DEBUG_VERBOSE, and CONFIG_DEBUG_NET have to be
+ * defined or the following does nothing.
+ */
+
+ nvdbgdumpbuffer(msg, buffer, nbytes);
}
#else
-# define c5471_dumpbuffer(buffer,nbytes)
+# define c5471_dumpbuffer(msg, buffer,nbytes)
#endif
/****************************************************************************
@@ -494,7 +457,7 @@ static void c5471_mdtxbit (int bit_state)
putreg32((getreg32(GPIO_CIO) & ~GPIO_CIO_MDIO), GPIO_CIO);
- /* Select the the bit output state */
+ /* Select the bit output state */
if (bit_state)
{
@@ -907,7 +870,7 @@ static int c5471_transmit(struct c5471_driver_s *c5471)
c5471->c_lastdescstart = c5471->c_rxcpudesc;
nvdbg("Packet size: %d RX CPU desc: %08x\n", nbytes, c5471->c_rxcpudesc);
- c5471_dumpbuffer(dev->d_buf, dev->d_len);
+ c5471_dumpbuffer("Transmit packet", dev->d_buf, dev->d_len);
while (nbytes)
{
@@ -1276,7 +1239,7 @@ static void c5471_receive(struct c5471_driver_s *c5471)
dev->d_len = packetlen;
nvdbg("Received packet, packetlen: %d type: %02x\n", packetlen, ntohs(BUF->type));
- c5471_dumpbuffer(dev->d_buf, dev->d_len);
+ c5471_dumpbuffer("Received packet", dev->d_buf, dev->d_len);
/* We only accept IP packets of the configured type and ARP packets */
@@ -2006,7 +1969,7 @@ static void c5471_eimconfig(struct c5471_driver_s *c5471)
putreg32(ENET_ADR_BROADCAST|ENET_ADR_PROMISCUOUS, ENET0_ADRMODE_EN);
#else
/* The CPU port is not PROMISCUOUS, it wants a no-promiscuous address
- * match yet the the SWITCH receives packets from the PROMISCUOUS ENET0
+ * match yet the SWITCH receives packets from the PROMISCUOUS ENET0
* which routes all packets for filter matching at the CPU port which
* then allows the s/w to see the new incoming packetes that passed
* the filter. Here we are setting the main SWITCH closest the ether
diff --git a/nuttx/arch/arm/src/c5471/c5471_watchdog.c b/nuttx/arch/arm/src/c5471/c5471_watchdog.c
index 8983b7549..96ddb6529 100644
--- a/nuttx/arch/arm/src/c5471/c5471_watchdog.c
+++ b/nuttx/arch/arm/src/c5471/c5471_watchdog.c
@@ -287,7 +287,7 @@ static int wdt_ioctl(struct file *filep, int cmd, uint32 arg)
{
dbg("ioctl Call: cmd=0x%x arg=0x%x", cmd, arg);
- /* Process the the IOCTL command (see arch/watchdog.h) */
+ /* Process the IOCTL command (see arch/watchdog.h) */
switch(cmd)
{
diff --git a/nuttx/arch/arm/src/common/up_blocktask.c b/nuttx/arch/arm/src/common/up_blocktask.c
index 2590597f8..f4e31526b 100644
--- a/nuttx/arch/arm/src/common/up_blocktask.c
+++ b/nuttx/arch/arm/src/common/up_blocktask.c
@@ -74,7 +74,7 @@
*
* Inputs:
* tcb: Refers to a task in the ready-to-run list (normally
- * the task at the the head of the list). It most be
+ * the task at the head of the list). It most be
* stopped, its context saved and moved into one of the
* waiting task lists. It it was the task at the head
* of the ready-to-run list, then a context to the new
diff --git a/nuttx/arch/arm/src/common/up_exit.c b/nuttx/arch/arm/src/common/up_exit.c
index 0d62a3d28..8416a99a3 100644
--- a/nuttx/arch/arm/src/common/up_exit.c
+++ b/nuttx/arch/arm/src/common/up_exit.c
@@ -136,7 +136,7 @@ static void _up_dumponexit(FAR _TCB *tcb, FAR void *arg)
* This function causes the currently executing task to cease
* to exist. This is a special case of task_delete() where the task to
* be deleted is the currently executing task. It is more complex because
- * a context switch must be perform to the the next ready to run task.
+ * a context switch must be perform to the next ready to run task.
*
****************************************************************************/
diff --git a/nuttx/arch/arm/src/common/up_internal.h b/nuttx/arch/arm/src/common/up_internal.h
index 2fd44bb93..5442f5914 100644
--- a/nuttx/arch/arm/src/common/up_internal.h
+++ b/nuttx/arch/arm/src/common/up_internal.h
@@ -74,7 +74,7 @@
/* Macros to handle saving and restore interrupt state. In the current ARM
* model, the state is always copied to and from the stack and TCB. In the
* Cortex-M3 model, the state is copied from the stack to the TCB, but only
- * a referenced is passed to get the the state from the TCB.
+ * a referenced is passed to get the state from the TCB.
*/
#ifdef CONFIG_ARCH_CORTEXM3
diff --git a/nuttx/arch/arm/src/cortexm3/up_sigdeliver.c b/nuttx/arch/arm/src/cortexm3/up_sigdeliver.c
index d0241dfa1..98dd94e99 100644
--- a/nuttx/arch/arm/src/cortexm3/up_sigdeliver.c
+++ b/nuttx/arch/arm/src/cortexm3/up_sigdeliver.c
@@ -86,7 +86,7 @@ void up_sigdeliver(void)
sig_deliver_t sigdeliver;
/* Save the errno. This must be preserved throughout the
- * signal handling so that the the user code final gets
+ * signal handling so that the user code final gets
* the correct errno value (probably EINTR).
*/
diff --git a/nuttx/arch/arm/src/dm320/dm320_restart.S b/nuttx/arch/arm/src/dm320/dm320_restart.S
index 5990605c7..ccbdfc2d9 100644
--- a/nuttx/arch/arm/src/dm320/dm320_restart.S
+++ b/nuttx/arch/arm/src/dm320/dm320_restart.S
@@ -110,7 +110,7 @@ up_phyrestart:
bic r0, r0, #(CR_S|CR_I|CR_V|CR_RR)
mcr p15, 0, r0, c1, c0, 0 /* Write control reg */
- /* We know that the the bootloader entry point is at the
+ /* We know that the bootloader entry point is at the
* beginning of flash.
*/
#if 1
diff --git a/nuttx/arch/arm/src/dm320/dm320_serial.c b/nuttx/arch/arm/src/dm320/dm320_serial.c
index 93da27525..35d0db17d 100644
--- a/nuttx/arch/arm/src/dm320/dm320_serial.c
+++ b/nuttx/arch/arm/src/dm320/dm320_serial.c
@@ -587,7 +587,7 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
* Description:
* Called (usually) from the interrupt level to receive one
* character from the UART. Error bits associated with the
- * receipt are provided in the the return 'status'.
+ * receipt are provided in the return 'status'.
*
****************************************************************************/
diff --git a/nuttx/arch/arm/src/imx/imx_serial.c b/nuttx/arch/arm/src/imx/imx_serial.c
index 4682a2938..70dcb5f1c 100644
--- a/nuttx/arch/arm/src/imx/imx_serial.c
+++ b/nuttx/arch/arm/src/imx/imx_serial.c
@@ -911,7 +911,7 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
* Description:
* Called (usually) from the interrupt level to receive one
* character from the UART. Error bits associated with the
- * receipt are provided in the the return 'status'.
+ * receipt are provided in the return 'status'.
*
****************************************************************************/
diff --git a/nuttx/arch/arm/src/lm3s/lm3s_serial.c b/nuttx/arch/arm/src/lm3s/lm3s_serial.c
index 04a9bdbf0..3c4247da5 100644
--- a/nuttx/arch/arm/src/lm3s/lm3s_serial.c
+++ b/nuttx/arch/arm/src/lm3s/lm3s_serial.c
@@ -674,7 +674,7 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
* Description:
* Called (usually) from the interrupt level to receive one
* character from the UART. Error bits associated with the
- * receipt are provided in the the return 'status'.
+ * receipt are provided in the return 'status'.
*
****************************************************************************/
diff --git a/nuttx/arch/arm/src/lpc214x/lpc214x_serial.c b/nuttx/arch/arm/src/lpc214x/lpc214x_serial.c
index 360a252f5..74f853830 100644
--- a/nuttx/arch/arm/src/lpc214x/lpc214x_serial.c
+++ b/nuttx/arch/arm/src/lpc214x/lpc214x_serial.c
@@ -612,7 +612,7 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
* Description:
* Called (usually) from the interrupt level to receive one
* character from the UART. Error bits associated with the
- * receipt are provided in the the return 'status'.
+ * receipt are provided in the return 'status'.
*
****************************************************************************/
diff --git a/nuttx/arch/arm/src/str71x/str71x_serial.c b/nuttx/arch/arm/src/str71x/str71x_serial.c
index 1c949a9d0..481603875 100644
--- a/nuttx/arch/arm/src/str71x/str71x_serial.c
+++ b/nuttx/arch/arm/src/str71x/str71x_serial.c
@@ -783,7 +783,7 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
* Description:
* Called (usually) from the interrupt level to receive one
* character from the UART. Error bits associated with the
- * receipt are provided in the the return 'status'.
+ * receipt are provided in the return 'status'.
*
****************************************************************************/