summaryrefslogtreecommitdiff
path: root/nuttx/arch/avr
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2014-04-13 16:22:22 -0600
committerGregory Nutt <gnutt@nuttx.org>2014-04-13 16:22:22 -0600
commit70b6bb22af51defd713adfd452309f32f0e523aa (patch)
treeb483c578cf6ae76888b89188bedb03f539ab4cd3 /nuttx/arch/avr
parent3cf6b4d6577c2f467dbb25dd0da8cdc6ad32a7b4 (diff)
downloadpx4-nuttx-70b6bb22af51defd713adfd452309f32f0e523aa.tar.gz
px4-nuttx-70b6bb22af51defd713adfd452309f32f0e523aa.tar.bz2
px4-nuttx-70b6bb22af51defd713adfd452309f32f0e523aa.zip
More trailing whilespace removal
Diffstat (limited to 'nuttx/arch/avr')
-rw-r--r--nuttx/arch/avr/include/at32uc3/irq.h4
-rw-r--r--nuttx/arch/avr/include/avr/irq.h2
-rw-r--r--nuttx/arch/avr/include/avr32/irq.h2
-rw-r--r--nuttx/arch/avr/src/at32uc3/at32uc3_gpio.c6
-rw-r--r--nuttx/arch/avr/src/at32uc3/at32uc3_gpioirq.c4
-rw-r--r--nuttx/arch/avr/src/at32uc3/at32uc3_lowconsole.c8
-rw-r--r--nuttx/arch/avr/src/at32uc3/at32uc3_tc.h2
-rw-r--r--nuttx/arch/avr/src/at32uc3/at32uc3_timerisr.c6
-rwxr-xr-xnuttx/arch/avr/src/at90usb/at90usb_head.S4
-rw-r--r--nuttx/arch/avr/src/at90usb/at90usb_lowconsole.c4
-rw-r--r--nuttx/arch/avr/src/at90usb/at90usb_lowinit.c2
-rw-r--r--nuttx/arch/avr/src/at90usb/at90usb_usbdev.c14
-rw-r--r--nuttx/arch/avr/src/atmega/Make.defs2
-rwxr-xr-xnuttx/arch/avr/src/atmega/atmega_head.S2
-rw-r--r--nuttx/arch/avr/src/atmega/atmega_lowconsole.c8
-rw-r--r--nuttx/arch/avr/src/atmega/atmega_lowinit.c2
-rw-r--r--nuttx/arch/avr/src/avr/avr_internal.h4
-rw-r--r--nuttx/arch/avr/src/avr/excptmacros.h4
-rw-r--r--nuttx/arch/avr/src/avr/up_blocktask.c2
-rw-r--r--nuttx/arch/avr/src/avr/up_createstack.c2
-rw-r--r--nuttx/arch/avr/src/avr/up_releasepending.c2
-rw-r--r--nuttx/arch/avr/src/avr/up_reprioritizertr.c4
-rw-r--r--nuttx/arch/avr/src/avr/up_spi.c10
-rw-r--r--nuttx/arch/avr/src/avr/up_unblocktask.c4
-rw-r--r--nuttx/arch/avr/src/avr32/Toolchain.defs2
-rw-r--r--nuttx/arch/avr/src/avr32/avr32_internal.h2
-rw-r--r--nuttx/arch/avr/src/avr32/up_blocktask.c2
-rw-r--r--nuttx/arch/avr/src/avr32/up_createstack.c2
-rwxr-xr-xnuttx/arch/avr/src/avr32/up_exceptions.S4
-rw-r--r--nuttx/arch/avr/src/avr32/up_initialstate.c2
-rw-r--r--nuttx/arch/avr/src/avr32/up_releasepending.c2
-rw-r--r--nuttx/arch/avr/src/avr32/up_reprioritizertr.c4
-rw-r--r--nuttx/arch/avr/src/avr32/up_stackframe.c4
-rw-r--r--nuttx/arch/avr/src/avr32/up_unblocktask.c4
34 files changed, 66 insertions, 66 deletions
diff --git a/nuttx/arch/avr/include/at32uc3/irq.h b/nuttx/arch/avr/include/at32uc3/irq.h
index 00802ebab..64861001e 100644
--- a/nuttx/arch/avr/include/at32uc3/irq.h
+++ b/nuttx/arch/avr/include/at32uc3/irq.h
@@ -63,7 +63,7 @@
# undef CONFIG_AVR32_GPIOIRQSETA
# undef CONFIG_AVR32_GPIOIRQSETB
#endif
-
+
/* IRQ numbers **************************************************************/
/* Events. These exclude:
*
@@ -287,7 +287,7 @@
#if (CONFIG_AVR32_GPIOIRQSETA & 0x00000001) != 0
# define AVR32_IRQ_GPIO_PA0 __IRQ_GPPIO_PA0
# define __IRQ_GPIO_PA1 (__IRQ_GPPIO_PA0+1)
-#else
+#else
# define __IRQ_GPIO_PA1 __IRQ_GPPIO_PA0
#endif
diff --git a/nuttx/arch/avr/include/avr/irq.h b/nuttx/arch/avr/include/avr/irq.h
index 9a84d1aa7..c237ded68 100644
--- a/nuttx/arch/avr/include/avr/irq.h
+++ b/nuttx/arch/avr/include/avr/irq.h
@@ -168,7 +168,7 @@ static inline irqstate_t irqsave(void)
(
"\tin %0, __SREG__\n"
"\tcli\n"
- : "=&r" (sreg) ::
+ : "=&r" (sreg) ::
);
return sreg;
}
diff --git a/nuttx/arch/avr/include/avr32/irq.h b/nuttx/arch/avr/include/avr32/irq.h
index 09ee0296a..13326f0b7 100644
--- a/nuttx/arch/avr/include/avr32/irq.h
+++ b/nuttx/arch/avr/include/avr32/irq.h
@@ -66,7 +66,7 @@
* this makes it easier to following the ordering of pushing on a push-down
* stack.
*/
-
+
#define REG_R8 16
#define REG_R9 15
#define REG_R10 14
diff --git a/nuttx/arch/avr/src/at32uc3/at32uc3_gpio.c b/nuttx/arch/avr/src/at32uc3/at32uc3_gpio.c
index a0e39e19d..2a2996740 100644
--- a/nuttx/arch/avr/src/at32uc3/at32uc3_gpio.c
+++ b/nuttx/arch/avr/src/at32uc3/at32uc3_gpio.c
@@ -151,13 +151,13 @@ int at32uc3_configgpio(uint16_t cfgset)
if ((cfgset & GPIO_ENABLE) != 0)
{
/* Its a GPIO. Input or output? */
-
+
if ((cfgset & GPIO_OUTPUT) != 0)
{
/* Its a GPIO output. Set up the initial output value and enable
* the output driver.
*/
-
+
if ((cfgset & GPIO_VALUE) != 0)
{
putreg32(pinmask, base + AVR32_GPIO_OVRS_OFFSET);
@@ -222,7 +222,7 @@ int at32uc3_configgpio(uint16_t cfgset)
putreg32(pinmask, base + AVR32_GPIO_IERS_OFFSET);
}
-
+
return OK;
}
diff --git a/nuttx/arch/avr/src/at32uc3/at32uc3_gpioirq.c b/nuttx/arch/avr/src/at32uc3/at32uc3_gpioirq.c
index c55ba3d13..d0442babc 100644
--- a/nuttx/arch/avr/src/at32uc3/at32uc3_gpioirq.c
+++ b/nuttx/arch/avr/src/at32uc3/at32uc3_gpioirq.c
@@ -177,7 +177,7 @@ static inline int gpio_pin(unsigned int irq)
pinset >>= 1;
}
-
+
return -EINVAL;
}
@@ -309,7 +309,7 @@ void gpio_irqinitialize(void)
}
/* Then attach the GPIO interrupt handlers */
-
+
#if CONFIG_AVR32_GPIOIRQSETA != 0
irq_attach(AVR32_IRQ_GPIO0, gpio0_interrupt);
#endif
diff --git a/nuttx/arch/avr/src/at32uc3/at32uc3_lowconsole.c b/nuttx/arch/avr/src/at32uc3/at32uc3_lowconsole.c
index 509d389af..d58558852 100644
--- a/nuttx/arch/avr/src/at32uc3/at32uc3_lowconsole.c
+++ b/nuttx/arch/avr/src/at32uc3/at32uc3_lowconsole.c
@@ -164,7 +164,7 @@ static void usart_setbaudrate(uintptr_t usart_base, uint32_t baudrate)
mr &= ~USART_MR_SYNC;
mr |= USART_MR_OVER;
-
+
/* Calculate the clock divider assuming 16x oversampling */
cd = (AVR32_PBA_CLOCK + (baudrate << 2)) / (baudrate << 3);
@@ -177,7 +177,7 @@ static void usart_setbaudrate(uintptr_t usart_base, uint32_t baudrate)
/* Use the undivided PBA clock */
- cd = AVR32_PBA_CLOCK / baudrate;
+ cd = AVR32_PBA_CLOCK / baudrate;
}
DEBUGASSERT(cd > 0 && cd < 65536);
@@ -202,7 +202,7 @@ static void usart_setbaudrate(uintptr_t usart_base, uint32_t baudrate)
void usart_reset(uintptr_t usart_base)
{
irqstate_t flags;
-
+
/* Disable all USART interrupts */
flags = irqsave();
@@ -275,7 +275,7 @@ void usart_configure(uintptr_t usart_base, uint32_t baud, unsigned int parity,
{
regval |= USART_MR_CHRL_BITS(nbits);
}
-
+
usart_putreg(usart_base, AVR32_USART_MR_OFFSET, regval);
/* Set the baud rate generation register */
diff --git a/nuttx/arch/avr/src/at32uc3/at32uc3_tc.h b/nuttx/arch/avr/src/at32uc3/at32uc3_tc.h
index 821b35b33..f3773c161 100644
--- a/nuttx/arch/avr/src/at32uc3/at32uc3_tc.h
+++ b/nuttx/arch/avr/src/at32uc3/at32uc3_tc.h
@@ -355,7 +355,7 @@
# define TC_BMR_TC2XC2S_NONE (1 << TC_BMR_TC2XC2S_SHIFT) /* None */
# define TC_BMR_TC2XC2S_TIOA0 (2 << TC_BMR_TC2XC2S_SHIFT) /* TIOA0 */
# define TC_BMR_TC2XC2S_TIOA1 (3 << TC_BMR_TC2XC2S_SHIFT) /* TIOA1 */
-
+
/************************************************************************************
* Public Types
************************************************************************************/
diff --git a/nuttx/arch/avr/src/at32uc3/at32uc3_timerisr.c b/nuttx/arch/avr/src/at32uc3/at32uc3_timerisr.c
index 711cef3c9..361fb8ec2 100644
--- a/nuttx/arch/avr/src/at32uc3/at32uc3_timerisr.c
+++ b/nuttx/arch/avr/src/at32uc3/at32uc3_timerisr.c
@@ -121,7 +121,7 @@
* Therefore, the TOP interrupt should occur after 143+1=144 counts
* at a rate of 69.57us x 144 = 10.02 ms
*/
-
+
#ifdef AVR32_CLOCK_OSC32
# define AV32_PSEL 1
# define AV32_TOP (82-1)
@@ -168,7 +168,7 @@ static void rtc_waitnotbusy(void)
int up_timerisr(int irq, uint32_t *regs)
{
/* Clear the pending timer interrupt */
-
+
putreg32(RTC_INT_TOPI, AVR32_RTC_ICR);
/* Process timer interrupt */
@@ -228,7 +228,7 @@ void up_timerinit(void)
/* Enable RTC interrupts */
putreg32(RTC_INT_TOPI, AVR32_RTC_IER);
-
+
/* Enable the RTC */
rtc_waitnotbusy();
diff --git a/nuttx/arch/avr/src/at90usb/at90usb_head.S b/nuttx/arch/avr/src/at90usb/at90usb_head.S
index 1e705ba71..6d850b7f2 100755
--- a/nuttx/arch/avr/src/at90usb/at90usb_head.S
+++ b/nuttx/arch/avr/src/at90usb/at90usb_head.S
@@ -227,7 +227,7 @@ __do_copy_data:
.Lcopyloop:
lpm r0, Z+
st X+, r0
-
+
.Lcopystart:
cpi r26, lo8(_edata)
cpc r27, r17
@@ -246,7 +246,7 @@ __do_clear_bss:
.Lclearloop:
st X+, r1
-
+
.Lclearstart:
cpi r26, lo8(_ebss)
cpc r27, r17
diff --git a/nuttx/arch/avr/src/at90usb/at90usb_lowconsole.c b/nuttx/arch/avr/src/at90usb/at90usb_lowconsole.c
index 64fd50fe1..b45f119d9 100644
--- a/nuttx/arch/avr/src/at90usb/at90usb_lowconsole.c
+++ b/nuttx/arch/avr/src/at90usb/at90usb_lowconsole.c
@@ -77,7 +77,7 @@
* AVR_NORMAL_UBRR1 = 52 (rounded), actual baud = 9615
* AVR_DBLSPEED_UBRR1 = 104 (rounded), actual baud = 9615
*/
-
+
#undef UART1_DOUBLE_SPEED
#if BOARD_CPU_CLOCK <= 4000000
# if CONFIG_USART1_BAUD <= 9600
@@ -194,7 +194,7 @@ void usart1_configure(void)
ucsr1b = ((1 << TXEN1) | (1 << RXEN1));
ucsr1c = 0;
-
+
/* Select parity */
#if CONFIG_USART1_PARITY == 1
diff --git a/nuttx/arch/avr/src/at90usb/at90usb_lowinit.c b/nuttx/arch/avr/src/at90usb/at90usb_lowinit.c
index 5f8964f6c..89de8b8ca 100644
--- a/nuttx/arch/avr/src/at90usb/at90usb_lowinit.c
+++ b/nuttx/arch/avr/src/at90usb/at90usb_lowinit.c
@@ -50,7 +50,7 @@
**************************************************************************/
#if defined(CONFIG_WDTO_15MS)
-# define WDTO_VALUE WDTO_15MS
+# define WDTO_VALUE WDTO_15MS
#elif defined(CONFIG_WDTO_30MS)
# define WDTO_VALUE WDTO_30MS
#elif defined(CONFIG_WDTO_60MS)
diff --git a/nuttx/arch/avr/src/at90usb/at90usb_usbdev.c b/nuttx/arch/avr/src/at90usb/at90usb_usbdev.c
index a5fb64c36..57741250a 100644
--- a/nuttx/arch/avr/src/at90usb/at90usb_usbdev.c
+++ b/nuttx/arch/avr/src/at90usb/at90usb_usbdev.c
@@ -624,7 +624,7 @@ static inline int avr_epNsend(FAR struct avr_ep_s *privep,
}
/* Send the USB data. The outer loop handles for each packet of data
- * (including zero-length packets)
+ * (including zero-length packets)
*/
do
@@ -1531,7 +1531,7 @@ static inline void avr_ep0setup(void)
case USB_REQ_RECIPIENT_ENDPOINT:
if (g_usbdev.paddrset != 0 &&
value == USB_FEATURE_ENDPOINTHALT &&
- len == 0 &&
+ len == 0 &&
(privep = avr_epfindbyaddr(index)) != NULL)
{
avr_epstall(&privep->ep, false);
@@ -1579,7 +1579,7 @@ static inline void avr_ep0setup(void)
case USB_REQ_RECIPIENT_ENDPOINT:
if (g_usbdev.paddrset != 0 &&
value == USB_FEATURE_ENDPOINTHALT &&
- len == 0 &&
+ len == 0 &&
(privep = avr_epfindbyaddr(index)) != NULL)
{
avr_epstall(&privep->ep, true);
@@ -2493,8 +2493,8 @@ static int avr_epcancel(FAR struct usbdev_ep_s *ep,
usbtrace(TRACE_EPCANCEL, privep->ep.eplog);
- /* FIXME: if the request is the first, then we need to flush the EP otherwise
- * just remove it from the list but ... all other implementations cancel all
+ /* FIXME: if the request is the first, then we need to flush the EP otherwise
+ * just remove it from the list but ... all other implementations cancel all
* requests ... */
flags = irqsave();
@@ -2716,7 +2716,7 @@ static int avr_wakeup(struct usbdev_s *dev)
* Name: avr_selfpowered
*
* Description:
- * Sets/clears the device selfpowered feature
+ * Sets/clears the device selfpowered feature
*
*******************************************************************************/
@@ -2949,7 +2949,7 @@ int usbdev_unregister(struct usbdevclass_driver_s *driver)
*
* Description:
* Sample VBUS to see if there are changes in our connection status. There
- * is actually an interrupt to signal this case so it should not be necessary
+ * is actually an interrupt to signal this case so it should not be necessary
* to poll our connection status. However, on certain "noisy" systems, VBUS
* may bounce and provide inaccurate information in the interrupt handler
* (especially if a relay is used to switch VBUS!). This poll is, then,
diff --git a/nuttx/arch/avr/src/atmega/Make.defs b/nuttx/arch/avr/src/atmega/Make.defs
index a7d3a881b..826d372a1 100644
--- a/nuttx/arch/avr/src/atmega/Make.defs
+++ b/nuttx/arch/avr/src/atmega/Make.defs
@@ -74,7 +74,7 @@ CHIP_CSRCS = atmega_lowconsole.c atmega_lowinit.c atmega_serial.c atmega_timeris
# Configuration-dependent ATMEGA files
ifeq ($(CONFIG_AVR_GPIOIRQ),y)
-CHIP_CSRCS +=
+CHIP_CSRCS +=
endif
diff --git a/nuttx/arch/avr/src/atmega/atmega_head.S b/nuttx/arch/avr/src/atmega/atmega_head.S
index dc35cd879..b272e54c3 100755
--- a/nuttx/arch/avr/src/atmega/atmega_head.S
+++ b/nuttx/arch/avr/src/atmega/atmega_head.S
@@ -240,7 +240,7 @@ __do_clear_bss:
.Lclearloop:
st X+, r1
-
+
.Lclearstart:
cpi r26, lo8(_ebss)
cpc r27, r17
diff --git a/nuttx/arch/avr/src/atmega/atmega_lowconsole.c b/nuttx/arch/avr/src/atmega/atmega_lowconsole.c
index ccf56dc33..ba3255741 100644
--- a/nuttx/arch/avr/src/atmega/atmega_lowconsole.c
+++ b/nuttx/arch/avr/src/atmega/atmega_lowconsole.c
@@ -76,7 +76,7 @@
* AVR_NORMAL_UBRR1 = 52 (rounded), actual baud = 9615
* AVR_DBLSPEED_UBRR1 = 104 (rounded), actual baud = 9615
*/
-
+
#undef UART0_DOUBLE_SPEED
#if BOARD_CPU_CLOCK <= 4000000
# if CONFIG_USART0_BAUD <= 9600
@@ -136,7 +136,7 @@
* AVR_NORMAL_UBRR1 = 52 (rounded), actual baud = 9615
* AVR_DBLSPEED_UBRR1 = 104 (rounded), actual baud = 9615
*/
-
+
#undef UART1_DOUBLE_SPEED
#if BOARD_CPU_CLOCK <= 4000000
# if CONFIG_USART1_BAUD <= 9600
@@ -275,7 +275,7 @@ void usart0_configure(void)
ucsr0b = ((1 << TXEN0) | (1 << RXEN0));
ucsr0c = 0;
-
+
/* Select parity */
#if CONFIG_USART0_PARITY == 1
@@ -352,7 +352,7 @@ void usart1_configure(void)
ucsr1b = ((1 << TXEN1) | (1 << RXEN1));
ucsr1c = 0;
-
+
/* Select parity */
#if CONFIG_USART1_PARITY == 1
diff --git a/nuttx/arch/avr/src/atmega/atmega_lowinit.c b/nuttx/arch/avr/src/atmega/atmega_lowinit.c
index 075a6413a..1ac5661f6 100644
--- a/nuttx/arch/avr/src/atmega/atmega_lowinit.c
+++ b/nuttx/arch/avr/src/atmega/atmega_lowinit.c
@@ -50,7 +50,7 @@
**************************************************************************/
#if defined(CONFIG_WDTO_15MS)
-# define WDTO_VALUE WDTO_15MS
+# define WDTO_VALUE WDTO_15MS
#elif defined(CONFIG_WDTO_30MS)
# define WDTO_VALUE WDTO_30MS
#elif defined(CONFIG_WDTO_60MS)
diff --git a/nuttx/arch/avr/src/avr/avr_internal.h b/nuttx/arch/avr/src/avr/avr_internal.h
index 8fb3fae28..f74d682e5 100644
--- a/nuttx/arch/avr/src/avr/avr_internal.h
+++ b/nuttx/arch/avr/src/avr/avr_internal.h
@@ -54,7 +54,7 @@
****************************************************************************/
/* Macros to handle saving and restore interrupt state. The state is copied
- * from the stack to the TCB, but only a referenced is passed to get the
+ * from the stack to the TCB, but only a referenced is passed to get the
* state from the TCB.
*/
@@ -142,7 +142,7 @@ uint8_t *up_doirq(uint8_t irq, uint8_t *regs);
* Description:
* These external functions must be provided by board-specific logic. They are
* implementations of the select, status, and cmddata methods of the SPI interface
- * defined by struct spi_ops_s (see include/nuttx/spi/spi.h). All other methods
+ * defined by struct spi_ops_s (see include/nuttx/spi/spi.h). All other methods
* including up_spiinitialize()) are provided by common LPC17xx logic. To use
* this common SPI logic on your board:
*
diff --git a/nuttx/arch/avr/src/avr/excptmacros.h b/nuttx/arch/avr/src/avr/excptmacros.h
index 730f02acc..c46e0024a 100644
--- a/nuttx/arch/avr/src/avr/excptmacros.h
+++ b/nuttx/arch/avr/src/avr/excptmacros.h
@@ -92,7 +92,7 @@
*
* Description:
* This macro provides the exception entry logic. It is called with the PC already on the
- * stack. It simply saves one register on the stack (r24) and passes the IRQ number to
+ * stack. It simply saves one register on the stack (r24) and passes the IRQ number to
* common logic (see EXCPT_PROLOGUE).
*
* On Entry:
@@ -437,7 +437,7 @@
out _SFR_IO_ADDR(SPH), r25 /* (SPH then SPL) */
ld r24, x+
out _SFR_IO_ADDR(SPL), r24
-
+
/* Fetch the return address and save it at the bottom of the new stack so
* that we can iret to switch contexts. The new stack is now:
*
diff --git a/nuttx/arch/avr/src/avr/up_blocktask.c b/nuttx/arch/avr/src/avr/up_blocktask.c
index 82fcd65db..004bf6e44 100644
--- a/nuttx/arch/avr/src/avr/up_blocktask.c
+++ b/nuttx/arch/avr/src/avr/up_blocktask.c
@@ -130,7 +130,7 @@ void up_block_task(struct tcb_s *tcb, tstate_t task_state)
up_savestate(rtcb->xcp.regs);
- /* Restore the exception context of the rtcb at the (new) head
+ /* Restore the exception context of the rtcb at the (new) head
* of the g_readytorun task list.
*/
diff --git a/nuttx/arch/avr/src/avr/up_createstack.c b/nuttx/arch/avr/src/avr/up_createstack.c
index 521213126..1dd7e5006 100644
--- a/nuttx/arch/avr/src/avr/up_createstack.c
+++ b/nuttx/arch/avr/src/avr/up_createstack.c
@@ -118,7 +118,7 @@ int up_create_stack(FAR struct tcb_s *tcb, size_t stack_size, uint8_t ttype)
}
/* Do we need to allocate a new stack? */
-
+
if (!tcb->stack_alloc_ptr)
{
/* Allocate the stack. If DEBUG is enabled (but not stack debug),
diff --git a/nuttx/arch/avr/src/avr/up_releasepending.c b/nuttx/arch/avr/src/avr/up_releasepending.c
index 0a63189fe..a3646f6f9 100644
--- a/nuttx/arch/avr/src/avr/up_releasepending.c
+++ b/nuttx/arch/avr/src/avr/up_releasepending.c
@@ -97,7 +97,7 @@ void up_release_pending(void)
up_savestate(rtcb->xcp.regs);
- /* Restore the exception context of the rtcb at the (new) head
+ /* Restore the exception context of the rtcb at the (new) head
* of the g_readytorun task list.
*/
diff --git a/nuttx/arch/avr/src/avr/up_reprioritizertr.c b/nuttx/arch/avr/src/avr/up_reprioritizertr.c
index 4c510f4ea..773b0ede8 100644
--- a/nuttx/arch/avr/src/avr/up_reprioritizertr.c
+++ b/nuttx/arch/avr/src/avr/up_reprioritizertr.c
@@ -69,7 +69,7 @@
*
* Description:
* Called when the priority of a running or
- * ready-to-run task changes and the reprioritization will
+ * ready-to-run task changes and the reprioritization will
* cause a context switch. Two cases:
*
* 1) The priority of the currently running task drops and the next
@@ -152,7 +152,7 @@ void up_reprioritize_rtr(struct tcb_s *tcb, uint8_t priority)
up_savestate(rtcb->xcp.regs);
- /* Restore the exception context of the rtcb at the (new) head
+ /* Restore the exception context of the rtcb at the (new) head
* of the g_readytorun task list.
*/
diff --git a/nuttx/arch/avr/src/avr/up_spi.c b/nuttx/arch/avr/src/avr/up_spi.c
index 8a243c2d9..78a4fa9ba 100644
--- a/nuttx/arch/avr/src/avr/up_spi.c
+++ b/nuttx/arch/avr/src/avr/up_spi.c
@@ -140,7 +140,7 @@ static const struct spi_ops_s g_spiops =
static struct avr_spidev_s g_spidev =
{
.spidev = { &g_spiops },
-};
+};
/****************************************************************************
* Public Data
@@ -319,19 +319,19 @@ static void spi_setmode(FAR struct spi_dev_s *dev, enum spi_mode_e mode)
{
case SPIDEV_MODE0: /* CPOL=0; CPHA=0 */
break;
-
+
case SPIDEV_MODE1: /* CPOL=0; CPHA=1 */
regval |= (1 << CPHA);
break;
-
+
case SPIDEV_MODE2: /* CPOL=1; CPHA=0 */
regval |= (1 << CPOL);
break;
-
+
case SPIDEV_MODE3: /* CPOL=1; CPHA=1 */
regval |= ((1 << CPOL) | (1 << CPHA));
break;
-
+
default:
DEBUGASSERT(FALSE);
return;
diff --git a/nuttx/arch/avr/src/avr/up_unblocktask.c b/nuttx/arch/avr/src/avr/up_unblocktask.c
index 970deedd6..305e057a8 100644
--- a/nuttx/arch/avr/src/avr/up_unblocktask.c
+++ b/nuttx/arch/avr/src/avr/up_unblocktask.c
@@ -109,7 +109,7 @@ void up_unblock_task(struct tcb_s *tcb)
/* The currently active task has changed! We need to do
* a context switch to the new task.
*
- * Are we in an interrupt handler?
+ * Are we in an interrupt handler?
*/
if (current_regs)
@@ -120,7 +120,7 @@ void up_unblock_task(struct tcb_s *tcb)
up_savestate(rtcb->xcp.regs);
- /* Restore the exception context of the rtcb at the (new) head
+ /* Restore the exception context of the rtcb at the (new) head
* of the g_readytorun task list.
*/
diff --git a/nuttx/arch/avr/src/avr32/Toolchain.defs b/nuttx/arch/avr/src/avr32/Toolchain.defs
index 9c3bed04c..51fe4fbba 100644
--- a/nuttx/arch/avr/src/avr32/Toolchain.defs
+++ b/nuttx/arch/avr/src/avr32/Toolchain.defs
@@ -44,7 +44,7 @@
# that we are operating on a Windows platform. But in the case where we
# have an AVR32 toolchain built under Cygwin, the correct setting would be
# GNU, not AVRTOOLSW.
-#
+#
CROSSDEV = avr32-
ARCHCPUFLAGS = -mpart=uc3b0256
diff --git a/nuttx/arch/avr/src/avr32/avr32_internal.h b/nuttx/arch/avr/src/avr32/avr32_internal.h
index 906cffc78..c98f0b5cc 100644
--- a/nuttx/arch/avr/src/avr32/avr32_internal.h
+++ b/nuttx/arch/avr/src/avr32/avr32_internal.h
@@ -52,7 +52,7 @@
****************************************************************************/
/* Macros to handle saving and restore interrupt state. The state is copied
- * from the stack to the TCB, but only a referenced is passed to get the
+ * from the stack to the TCB, but only a referenced is passed to get the
* state from the TCB.
*/
diff --git a/nuttx/arch/avr/src/avr32/up_blocktask.c b/nuttx/arch/avr/src/avr32/up_blocktask.c
index 1da4eb573..955d3b1d2 100644
--- a/nuttx/arch/avr/src/avr32/up_blocktask.c
+++ b/nuttx/arch/avr/src/avr32/up_blocktask.c
@@ -130,7 +130,7 @@ void up_block_task(struct tcb_s *tcb, tstate_t task_state)
up_savestate(rtcb->xcp.regs);
- /* Restore the exception context of the rtcb at the (new) head
+ /* Restore the exception context of the rtcb at the (new) head
* of the g_readytorun task list.
*/
diff --git a/nuttx/arch/avr/src/avr32/up_createstack.c b/nuttx/arch/avr/src/avr32/up_createstack.c
index f9968d555..fd1af6782 100644
--- a/nuttx/arch/avr/src/avr32/up_createstack.c
+++ b/nuttx/arch/avr/src/avr32/up_createstack.c
@@ -117,7 +117,7 @@ int up_create_stack(FAR struct tcb_s *tcb, size_t stack_size, uint8_t ttype)
}
/* Do we need to allocate a new stack? */
-
+
if (!tcb->stack_alloc_ptr)
{
/* Allocate the stack. If DEBUG is enabled (but not stack debug),
diff --git a/nuttx/arch/avr/src/avr32/up_exceptions.S b/nuttx/arch/avr/src/avr32/up_exceptions.S
index 53a5b9c4f..b4d399cdb 100755
--- a/nuttx/arch/avr/src/avr32/up_exceptions.S
+++ b/nuttx/arch/avr/src/avr32/up_exceptions.S
@@ -179,7 +179,7 @@ avr32_intcommon:
/* On entry to each, the context save area looks like this: */
/* xx xx xx xx xx xx xx xx xx xx xx xx xx xx xx SR PC */
/* ^ ^+2*4 */
-
+
HANDLER avr32_unrec, AVR32_IRQ_UNREC /* Unrecoverable xcptn */
HANDLER avr32_tlbmult, AVR32_IRQ_TLBMULT /* TLB multiple hit */
HANDLER avr32_busdata, AVR32_IRQ_BUSDATA /* Bus error data fetch */
@@ -240,7 +240,7 @@ avr32_xcptcommon:
/* Save r8 and r8: */
/* xx xx xx xx xx xx xx xx xx SR PC LI 12 11 10 SR PC */
/* ^ ^+6*4 ^+8*4 */
-
+
st.w sp[6*4], r9
st.w sp[7*4], r8
diff --git a/nuttx/arch/avr/src/avr32/up_initialstate.c b/nuttx/arch/avr/src/avr32/up_initialstate.c
index adfc95596..86138b616 100644
--- a/nuttx/arch/avr/src/avr32/up_initialstate.c
+++ b/nuttx/arch/avr/src/avr32/up_initialstate.c
@@ -91,7 +91,7 @@ void up_initial_state(struct tcb_s *tcb)
/* No pending signal delivery */
xcp->sigdeliver = NULL;
-
+
/* Clear the frame pointer and link register since this is the outermost
* frame.
*/
diff --git a/nuttx/arch/avr/src/avr32/up_releasepending.c b/nuttx/arch/avr/src/avr32/up_releasepending.c
index 00956e442..e144ca904 100644
--- a/nuttx/arch/avr/src/avr32/up_releasepending.c
+++ b/nuttx/arch/avr/src/avr32/up_releasepending.c
@@ -97,7 +97,7 @@ void up_release_pending(void)
up_savestate(rtcb->xcp.regs);
- /* Restore the exception context of the rtcb at the (new) head
+ /* Restore the exception context of the rtcb at the (new) head
* of the g_readytorun task list.
*/
diff --git a/nuttx/arch/avr/src/avr32/up_reprioritizertr.c b/nuttx/arch/avr/src/avr32/up_reprioritizertr.c
index 621f08613..07ee9c6a4 100644
--- a/nuttx/arch/avr/src/avr32/up_reprioritizertr.c
+++ b/nuttx/arch/avr/src/avr32/up_reprioritizertr.c
@@ -69,7 +69,7 @@
*
* Description:
* Called when the priority of a running or
- * ready-to-run task changes and the reprioritization will
+ * ready-to-run task changes and the reprioritization will
* cause a context switch. Two cases:
*
* 1) The priority of the currently running task drops and the next
@@ -152,7 +152,7 @@ void up_reprioritize_rtr(struct tcb_s *tcb, uint8_t priority)
up_savestate(rtcb->xcp.regs);
- /* Restore the exception context of the rtcb at the (new) head
+ /* Restore the exception context of the rtcb at the (new) head
* of the g_readytorun task list.
*/
diff --git a/nuttx/arch/avr/src/avr32/up_stackframe.c b/nuttx/arch/avr/src/avr32/up_stackframe.c
index a38370801..e53eee5ae 100644
--- a/nuttx/arch/avr/src/avr32/up_stackframe.c
+++ b/nuttx/arch/avr/src/avr32/up_stackframe.c
@@ -53,7 +53,7 @@
* Pre-processor Macros
****************************************************************************/
-/* The AVR32 stack must be aligned at word (4 byte) boundaries. If necessary
+/* The AVR32 stack must be aligned at word (4 byte) boundaries. If necessary
* frame_size must be rounded up to the next boundary
*/
@@ -116,7 +116,7 @@ FAR void *up_stack_frame(FAR struct tcb_s *tcb, size_t frame_size)
/* Align the frame_size */
frame_size = STACK_ALIGN_UP(frame_size);
-
+
/* Is there already a stack allocated? Is it big enough? */
if (!tcb->stack_alloc_ptr || tcb->adj_stack_size <= frame_size)
diff --git a/nuttx/arch/avr/src/avr32/up_unblocktask.c b/nuttx/arch/avr/src/avr32/up_unblocktask.c
index 1fcfa1dd7..42dc3d52a 100644
--- a/nuttx/arch/avr/src/avr32/up_unblocktask.c
+++ b/nuttx/arch/avr/src/avr32/up_unblocktask.c
@@ -109,7 +109,7 @@ void up_unblock_task(struct tcb_s *tcb)
/* The currently active task has changed! We need to do
* a context switch to the new task.
*
- * Are we in an interrupt handler?
+ * Are we in an interrupt handler?
*/
if (current_regs)
@@ -120,7 +120,7 @@ void up_unblock_task(struct tcb_s *tcb)
up_savestate(rtcb->xcp.regs);
- /* Restore the exception context of the rtcb at the (new) head
+ /* Restore the exception context of the rtcb at the (new) head
* of the g_readytorun task list.
*/