summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2014-02-17 19:22:53 -0600
committerGregory Nutt <gnutt@nuttx.org>2014-02-17 19:22:53 -0600
commit34f8b40f7145ced0da75670d9ff4aaa711169b6a (patch)
tree2c60f5025dbc10482e39efd77f7341f5241d0144
parent601422a19569fa1805e681be6a989c9a3a2e1cb4 (diff)
downloadpx4-nuttx-34f8b40f7145ced0da75670d9ff4aaa711169b6a.tar.gz
px4-nuttx-34f8b40f7145ced0da75670d9ff4aaa711169b6a.tar.bz2
px4-nuttx-34f8b40f7145ced0da75670d9ff4aaa711169b6a.zip
Mostly cosmetic clean-up of comments
-rw-r--r--nuttx/arch/arm/src/kl/kl_idle.c2
-rw-r--r--nuttx/arch/arm/src/kl/kl_irq.c2
-rw-r--r--nuttx/arch/arm/src/kl/kl_irqprio.c3
-rw-r--r--nuttx/arch/arm/src/kl/kl_pwm.c6
-rw-r--r--nuttx/arch/arm/src/kl/kl_pwm.h12
-rw-r--r--nuttx/arch/arm/src/samd/Make.defs2
-rw-r--r--nuttx/arch/arm/src/samd/sam_irqprio.c3
-rw-r--r--nuttx/configs/samd20-xplained/include/board.h18
8 files changed, 20 insertions, 28 deletions
diff --git a/nuttx/arch/arm/src/kl/kl_idle.c b/nuttx/arch/arm/src/kl/kl_idle.c
index 8891cf7cb..6ec2ab46f 100644
--- a/nuttx/arch/arm/src/kl/kl_idle.c
+++ b/nuttx/arch/arm/src/kl/kl_idle.c
@@ -1,5 +1,5 @@
/****************************************************************************
- * arch/arm/src/stm32/kl_idle.c
+ * arch/arm/src/kl/kl_idle.c
*
* Copyright (C) 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
diff --git a/nuttx/arch/arm/src/kl/kl_irq.c b/nuttx/arch/arm/src/kl/kl_irq.c
index 127a667a6..4c910a15f 100644
--- a/nuttx/arch/arm/src/kl/kl_irq.c
+++ b/nuttx/arch/arm/src/kl/kl_irq.c
@@ -1,5 +1,5 @@
/****************************************************************************
- * arch/arm/src/stm32/kl_irq.c
+ * arch/arm/src/kl/kl_irq.c
*
* Copyright (C) 2013-2014 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
diff --git a/nuttx/arch/arm/src/kl/kl_irqprio.c b/nuttx/arch/arm/src/kl/kl_irqprio.c
index 17611aeea..a7aba8b8f 100644
--- a/nuttx/arch/arm/src/kl/kl_irqprio.c
+++ b/nuttx/arch/arm/src/kl/kl_irqprio.c
@@ -1,6 +1,5 @@
/****************************************************************************
- * arch/arm/src/stm32/kl_irqprio.c
- * arch/arm/src/chip/kl_irqprio.c
+ * arch/arm/src/kl/kl_irqprio.c
*
* Copyright (C) 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
diff --git a/nuttx/arch/arm/src/kl/kl_pwm.c b/nuttx/arch/arm/src/kl/kl_pwm.c
index 0b675fe1c..df6961ed8 100644
--- a/nuttx/arch/arm/src/kl/kl_pwm.c
+++ b/nuttx/arch/arm/src/kl/kl_pwm.c
@@ -693,12 +693,10 @@ static int pwm_ioctl(FAR struct pwm_lowerhalf_s *dev, int cmd, unsigned long arg
* Initialize one timer for use with the upper_level PWM driver.
*
* Input Parameters:
- * timer - A number identifying the timer use. The number of valid timer
- * IDs varies with the STM32 MCU and MCU family but is somewhere in
- * the range of {1,..,14}.
+ * timer - A number identifying the timer use.
*
* Returned Value:
- * On success, a pointer to the STM32 lower half PWM driver is returned.
+ * On success, a pointer to the KL lower half PWM driver is returned.
* NULL is returned on any failure.
*
****************************************************************************/
diff --git a/nuttx/arch/arm/src/kl/kl_pwm.h b/nuttx/arch/arm/src/kl/kl_pwm.h
index 104df3bf9..f15441576 100644
--- a/nuttx/arch/arm/src/kl/kl_pwm.h
+++ b/nuttx/arch/arm/src/kl/kl_pwm.h
@@ -77,13 +77,9 @@
* configuration settings:
*
* CONFIG_KL_TPMx_CHANNEL - Specifies the timer output channel {1,..,4}
- * PWM_TPMx_CHn - One of the values defined in chip/stm32*_pinmap.h. In the case
+ * PWM_TPMx_CHn - One of the values defined in chip/kl*_pinmap.h. In the case
* where there are multiple pin selections, the correct setting must be provided
* in the arch/board/board.h file.
- *
- * NOTE: The STM32 timers are each capable of generating different signals on
- * each of the four channels with different duty cycles. That capability is
- * not supported by this driver: Only one output channel per timer.
*/
#ifdef CONFIG_KL_TPM0_PWM
@@ -175,12 +171,10 @@ extern "C" {
* Initialize one timer for use with the upper_level PWM driver.
*
* Input Parameters:
- * timer - A number identifying the timer use. The number of valid timer
- * IDs varies with the STM32 MCU and MCU family but is somewhere in
- * the range of {1,..,14}.
+ * timer - A number identifying the timer use.
*
* Returned Value:
- * On success, a pointer to the STM32 lower half PWM driver is returned.
+ * On success, a pointer to the KL lower half PWM driver is returned.
* NULL is returned on any failure.
*
************************************************************************************/
diff --git a/nuttx/arch/arm/src/samd/Make.defs b/nuttx/arch/arm/src/samd/Make.defs
index d4ed5f200..a60ff623e 100644
--- a/nuttx/arch/arm/src/samd/Make.defs
+++ b/nuttx/arch/arm/src/samd/Make.defs
@@ -75,6 +75,6 @@ ifeq ($(CONFIG_NUTTX_KERNEL),y)
CHIP_CSRCS += sam_userspace.c
endif
-ifeq ($(CONFIG_NUTTX_KERNEL),y)
+ifeq ($(CONFIG_ARCH_IRQPRIO),y)
CHIP_CSRCS += sam_irqprio.c
endif
diff --git a/nuttx/arch/arm/src/samd/sam_irqprio.c b/nuttx/arch/arm/src/samd/sam_irqprio.c
index 30046c1a2..8948f6492 100644
--- a/nuttx/arch/arm/src/samd/sam_irqprio.c
+++ b/nuttx/arch/arm/src/samd/sam_irqprio.c
@@ -1,6 +1,5 @@
/****************************************************************************
- * arch/arm/src/stm32/kl_irqprio.c
- * arch/arm/src/chip/kl_irqprio.c
+ * arch/arm/src/samd/sam_irqprio.c
*
* Copyright (C) 2014 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
diff --git a/nuttx/configs/samd20-xplained/include/board.h b/nuttx/configs/samd20-xplained/include/board.h
index c7956e8ba..78e30528b 100644
--- a/nuttx/configs/samd20-xplained/include/board.h
+++ b/nuttx/configs/samd20-xplained/include/board.h
@@ -351,17 +351,19 @@
#define BOARD_FLASH_WAITSTATES 1
/* SERCOM definitions ***************************************************************/
-/* SERCOM4 is available on connectors EXT1 and EXT3
+/* SERCOM4 is available on connectors EXT1, EXT2, and EXT3
*
- * PIN EXT1 EXT3 GPIO Function
- * ---- ---- ------ -----------
- * 13 PB09 PB13 SERCOM4 / USART RX
- * 14 PB08 PB12 SERCOM4 / USART TX
- * 19 19 GND
- * 20 20 VCC
+ * PIN EXT1 EXT2 EXT3 GPIO Function
+ * ---- ---- ---- ---- ------------------
+ * 13 PB09 PB13 PB11 SERCOM4 / USART RX
+ * 14 PB08 PB12 PB12 SERCOM4 / USART TX
+ * 19 GND GND GND N/A
+ * 20 VCC VCC VCC N/A
*
* If you have a TTL to RS-232 converter then this is the most convenient
- * serial console to use. It is the default in all of these configurations.
+ * serial console to use (because you don't lose the console device each time
+ * you lose the USB connection). It is the default in all of the SAMD20
+ * configurations.
*/
#define BOARD_SERCOM4_GCLKGEN GCLK_CLKCTRL_GEN0