summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/ChangeLog3
-rw-r--r--nuttx/Kconfig9
-rw-r--r--nuttx/arch/arm/src/sama5/Kconfig12
-rw-r--r--nuttx/arch/arm/src/sama5/sam_pwm.c6
-rw-r--r--nuttx/configs/sama5d3x-ek/Kconfig12
-rw-r--r--nuttx/configs/sama5d3x-ek/README.txt125
-rw-r--r--nuttx/configs/sama5d3x-ek/include/board.h68
-rw-r--r--nuttx/configs/sama5d3x-ek/src/Makefile4
-rw-r--r--nuttx/configs/sama5d3x-ek/src/sam_pwm.c161
9 files changed, 386 insertions, 14 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 1d9bd09a9..54b4b816c 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -5977,4 +5977,5 @@
* arch/arm/src/sama5/Make.defs and Kconfig: SAMA5 PWM driver now
incorporated into build and configuration system. Builds with
no errors (2013-11-6).
-
+ * configs/sama5d3x-ek: Add support for the PWM test for the
+ SAMA5D3x-EK board (2013-11-6).
diff --git a/nuttx/Kconfig b/nuttx/Kconfig
index 164324bb0..7ea297a4e 100644
--- a/nuttx/Kconfig
+++ b/nuttx/Kconfig
@@ -490,6 +490,15 @@ config DEBUG_CAN
Support for this debug option is architecture-specific and may not
be available for some MCUs.
+config DEBUG_PWM
+ bool "PWM Debug Output"
+ default n
+ depends on PWM
+ ---help---
+ Enable PWM driver debug SYSLOG output (disabled by default).
+ Support for this debug option is architecture-specific and may not
+ be available for some MCUs.
+
config DEBUG_SDIO
bool "SDIO Debug Output"
default n
diff --git a/nuttx/arch/arm/src/sama5/Kconfig b/nuttx/arch/arm/src/sama5/Kconfig
index ea47a6301..86383e8d0 100644
--- a/nuttx/arch/arm/src/sama5/Kconfig
+++ b/nuttx/arch/arm/src/sama5/Kconfig
@@ -2380,7 +2380,7 @@ config SAMA5_PWM_CLKA
config SAMA5_PWM_CLKA_FREQUENCY
int "CLKA frequency"
- default 100
+ default 1000
depends on SAMA5_PWM_CLKA
---help---
If the CLKA source is enabled, then you must also provide the
@@ -2396,7 +2396,7 @@ config SAMA5_PWM_CLKB
config SAMA5_PWM_CLKB_FREQUENCY
int "CLKB frequency"
- default 100
+ default 1000
depends on SAMA5_PWM_CLKB
---help---
If the CLKB source is enabled, then you must also provide the
@@ -2439,7 +2439,7 @@ config SAMA5_PWM_CHAN0_MCKDIV
config SAMA5_PWM_CHAN0_OUTPUTH
bool "Configure OUTPUT H pin"
- default n
+ default y
config SAMA5_PWM_CHAN0_OUTPUTL
bool "Configure OUTPUT L pin"
@@ -2486,7 +2486,7 @@ config SAMA5_PWM_CHAN1_MCKDIV
config SAMA5_PWM_CHAN1_OUTPUTH
bool "Configure OUTPUT H pin"
- default n
+ default y
config SAMA5_PWM_CHAN1_OUTPUTL
bool "Configure OUTPUT L pin"
@@ -2533,7 +2533,7 @@ config SAMA5_PWM_CHAN2_MCKDIV
config SAMA5_PWM_CHAN2_OUTPUTH
bool "Configure OUTPUT H pin"
- default n
+ default y
config SAMA5_PWM_CHAN2_OUTPUTL
bool "Configure OUTPUT L pin"
@@ -2580,7 +2580,7 @@ config SAMA5_PWM_CHAN3_MCKDIV
config SAMA5_PWM_CHAN3_OUTPUTH
bool "Configure OUTPUT H pin"
- default n
+ default y
config SAMA5_PWM_CHAN3_OUTPUTL
bool "Configure OUTPUT L pin"
diff --git a/nuttx/arch/arm/src/sama5/sam_pwm.c b/nuttx/arch/arm/src/sama5/sam_pwm.c
index e84c4cc4f..e2c3b27a2 100644
--- a/nuttx/arch/arm/src/sama5/sam_pwm.c
+++ b/nuttx/arch/arm/src/sama5/sam_pwm.c
@@ -1076,18 +1076,22 @@ static int pwm_start(FAR struct pwm_lowerhalf_s *dev,
fsrc = BOARD_MCK_FREQUENCY >> chan->divlog2;
break;
+#ifdef CONFIG_SAMA5_PWM_CLKA
case PWM_CLKSRC_CLKA:
regval = PWM_CMR_CPRE_CLKA;
fsrc = CLKA_FREQUENCY;
break;
+#endif
+#ifdef CONFIG_SAMA5_PWM_CLKB
case PWM_CLKSRC_CLKB:
regval = PWM_CMR_CPRE_CLKB;
fsrc = CLKB_FREQUENCY;
break;
+#endif
default:
- pwmdbg("ERROR: Bad clock source value: %d\n", chan->clksrc);
+ pwmdbg("ERROR: Invalid or unsupported clock source value: %d\n", chan->clksrc);
return -EINVAL;
}
diff --git a/nuttx/configs/sama5d3x-ek/Kconfig b/nuttx/configs/sama5d3x-ek/Kconfig
index 9f3b4124b..bcc388ff4 100644
--- a/nuttx/configs/sama5d3x-ek/Kconfig
+++ b/nuttx/configs/sama5d3x-ek/Kconfig
@@ -121,4 +121,16 @@ config SAMA5_AT24_NXFFS
endchoice
+config SAMA5D3X_EK_CHANNEL
+ int "PWM channel number"
+ default 0 if SAMA5_PWM_CHAN0
+ default 1 if SAMA5_PWM_CHAN1
+ default 2 if SAMA5_PWM_CHAN2
+ default 3 if SAMA5_PWM_CHAN3
+ range 0 3
+ depends on PWM && SAMA5_PWM
+ ---help---
+ Selects the PWM channel number that will be used to perform the PWM
+ test. See apps/examples/pwm.
+
endif
diff --git a/nuttx/configs/sama5d3x-ek/README.txt b/nuttx/configs/sama5d3x-ek/README.txt
index 233111e4a..04c1ea381 100644
--- a/nuttx/configs/sama5d3x-ek/README.txt
+++ b/nuttx/configs/sama5d3x-ek/README.txt
@@ -79,6 +79,7 @@ Contents
- AT24 Serial EEPROM
- CAN Usage
- SAMA5 ADC Support
+ - SAMA5 PWM Support
- OV2640 Camera interface
- SAMA5D3x-EK Configuration Options
- Configurations
@@ -742,14 +743,14 @@ CAN Usage
SAMA5 ADC Support
=================
+ Basic driver configuration
+ --------------------------
ADC support can be added to the NSH configuration. However, there are no
ADC input pins available to the user for ADC testing (the touchscreen ADC
inputs are intended for other functionality). Because of this, there is
not much motivation to enable ADC support on the SAMA5D3x-EK. This
paragraph is included here, however, for people using a custom SAMA5D3x
- board thay requires ADC support.
-
- Basic driver configuration:
+ board that requires ADC support.
System Type -> SAMA5 Peripheral Support
CONFIG_SAMA5_ADC=y : Enable ADC driver support
@@ -780,16 +781,20 @@ SAMA5 ADC Support
Library routines
CONFIG_SCHED_WORKQUEUE=y
+ ADC Test Example
+ ----------------
For testing purposes, there is an ADC program at apps/examples/adc that
will collect a specified number of samples. This test program can be
enabled as follows:
- Application Configuration -> Examples -> ADC eample
+ Application Configuration -> Examples -> ADC example
CONFIG_EXAMPLES_ADC=y : Enables the example code
CONFIG_EXAMPLES_ADC_DEVPATH="/dev/adc0"
Other default settings for the ADC example should be okay.
+ ADC DMA Support
+ ---------------
At 2Hz, DMA is not necessary nor desire-able. The ADC driver has support
for DMA transfers of converted data (although that support has not been
tested as of this writing). DMA support can be added by include the
@@ -805,9 +810,117 @@ SAMA5 ADC Support
Drivers -> Analog device (ADC/DAC) support
CONFIG_ADC_FIFOSIZE=16 : Driver may need a large ring buffer
- Application Configuration -> Examples -> ADC eample
+ Application Configuration -> Examples -> ADC example
CONFIG_EXAMPLES_ADC_GROUPSIZE=16 : Larger buffers in the test
+SAMA5 PWM Support
+=================
+
+ Basic driver configuration
+ --------------------------
+ PWM support can be added to the NSH configuration. However, there are no
+ PWM output pins available to the user for PWM testing. Because of this,
+ there is not much motivation to enable PWM support on the SAMA5D3x-EK. This
+ paragraph is included here, however, for people using a custom SAMA5D3x
+ board that requires PWM support.
+
+ Basic driver configuration:
+
+ System Type -> SAMA5 Peripheral Support
+ CONFIG_SAMA5_PWM=y : Enable PWM driver support
+
+ Drivers
+ CONFIG_PWM=y : Should be automatically selected
+
+ PWM Channel/Output Selection
+ ----------------------------
+ In order to use the PWM, you must enable one or more PWM Channels:
+
+ System Type -> PWM Configuration
+ CONFIG_SAMA5_PWM_CHAN0=y : Enable one or more of channels 0-3
+ CONFIG_SAMA5_PWM_CHAN1=y
+ CONFIG_SAMA5_PWM_CHAN2=y
+ CONFIG_SAMA5_PWM_CHAN3=y
+
+ For each channel that is enabled, you must also specify the output pins
+ to be enabled and the clocking supplied to the PWM channel.
+
+ CONFIG_SAMA5_PWM_CHANx_FAULTINPUT=n : (not used currently)
+ CONFIG_SAMA5_PWM_CHANx_OUTPUTH=y : Enable One of both of the H and L output pins
+ CONFIG_SAMA5_PWM_CHANx_OUTPUTL=y
+
+ Where x=0..3.
+
+ Care must be taken because all PWM output pins conflict with some other
+ usage of the pin by other devices:
+
+ -----+---+---+----+--------------------
+ PWM PIN PER PIO CONFLICTS
+ -----+---+---+----+--------------------
+ PWM0 FI B PC28 SPI1, ISI
+ H B PB0 GMAC
+ B PA20 LCDC, ISI
+ L B PB1 GMAC
+ B PA21 LCDC, ISI
+ -----+---+---+----+--------------------
+ PWM1 FI B PC31 HDMI
+ H B PB4 GMAC
+ B PA22 LCDC, ISI
+ L B PB5 GMAC
+ B PE31 ISI, HDMI
+ B PA23 LCDC, ISI
+ -----+---+---+----+--------------------
+ PWM2 FI B PC29 UART0, ISI, HDMI
+ H C PD5 HSMCI0
+ B PB8 GMAC
+ L C PD6 HSMCI0
+ B PB9 GMAC
+ -----+---+---+----+--------------------
+ PWM3 FI C PD16 SPI0, Audio
+ H C PD7 HSMCI0
+ B PB12 GMAC
+ L C PD8 HSMCI0
+ B PB13 GMAC
+ -----+---+---+----+--------------------
+
+ Clocking is addressed in the next paragraph.
+
+ PWM Clock Configuration
+ -----------------------
+ PWM Channels can be clocked from either a coarsely divided divided down
+ MCK or from a custom frequency from PWM CLKA and/or CLKB. If you want
+ to use CLKA or CLKB, you must enable and configuratino them.
+
+ System Type -> PWM Configuration
+ CONFIG_SAMA5_PWM_CLKA=y
+ CONFIG_SAMA5_PWM_CLKA_FREQUENCY=3300
+ CONFIG_SAMA5_PWM_CLKB=y
+ CONFIG_SAMA5_PWM_CLKB_FREQUENCY=3300
+
+ Then for each of the enabled, channels you must select the input clock
+ for that channel:
+
+ System Type -> PWM Configuration
+ CONFIG_SAMA5_PWM_CHANx_CLKA=y : Pick one of MCK, CLKA, or CLKB
+ CONFIG_SAMA5_PWM_CHANx_CLKB=y
+ CONFIG_SAMA5_PWM_CHANx_MCK=y
+ CONFIG_SAMA5_PWM_CHANx_MCKDIV=128 : If MCK is selected, then the MCK divider must
+ : also be provided (1,2,4,8,16,32,64,128,256,512, or 1024).
+
+ PWM Test Example
+ ----------------
+ For testing purposes, there is an PWM program at apps/examples/pwm that
+ will collect a specified number of samples. This test program can be
+ enabled as follows:
+
+ Application Configuration -> Examples -> PWM example
+ CONFIG_EXAMPLES_PWM=y : Enables the example code
+
+ Other default settings for the PWM example should be okay.
+
+ CONFIG_EXAMPLES_PWM_DEVPATH="/dev/pwm0"
+ CONFIG_EXAMPLES_PWM_FREQUENCY=100
+
OV2640 Camera interface
=======================
@@ -2158,7 +2271,7 @@ Configurations
o The I2C dev command may have bad side effects on your I2C devices.
Use only at your own risk.
- As an eample, the I2C dev comman can be used to list all devices
+ As an example, the I2C dev comman can be used to list all devices
responding on TWI0 (the default) like this:
nsh> i2c dev 0x03 0x77
diff --git a/nuttx/configs/sama5d3x-ek/include/board.h b/nuttx/configs/sama5d3x-ek/include/board.h
index f810ead63..59d184906 100644
--- a/nuttx/configs/sama5d3x-ek/include/board.h
+++ b/nuttx/configs/sama5d3x-ek/include/board.h
@@ -176,6 +176,74 @@
#define PIO_LCD_DAT22 PIO_LCD_DAT22_1
#define PIO_LCD_DAT23 PIO_LCD_DAT23_1
+/* PWM. There are no dedicated PWM output pins available to the user for PWM
+ * testing. Care must be taken because all PWM output pins conflict with some other
+ * usage of the pin by other devices:
+ *
+ * -----+---+---+----+--------------------
+ * PWM PIN PER PIO CONFLICTS
+ * -----+---+---+----+--------------------
+ * PWM0 FI B PC28 SPI1, ISI
+ * H B PB0 GMAC
+ * B PA20 LCDC, ISI
+ * L B PB1 GMAC
+ * B PA21 LCDC, ISI
+ * -----+---+---+----+--------------------
+ * PWM1 FI B PC31 HDMI
+ * H B PB4 GMAC
+ * B PA22 LCDC, ISI
+ * L B PB5 GMAC
+ * B PE31 ISI, HDMI
+ * B PA23 LCDC, ISI
+ * -----+---+---+----+--------------------
+ * PWM2 FI B PC29 UART0, ISI, HDMI
+ * H C PD5 HSMCI0
+ * B PB8 GMAC
+ * L C PD6 HSMCI0
+ * B PB9 GMAC
+ * -----+---+---+----+--------------------
+ * PWM3 FI C PD16 SPI0, Audio
+ * H C PD7 HSMCI0
+ * B PB12 GMAC
+ * L C PD8 HSMCI0
+ * B PB13 GMAC
+ * -----+---+---+----+--------------------
+ */
+
+#if !defined(CONFIG_SAMA5_GMAC)
+# define PIO_PWM0_H PIO_PWM0_H_1
+# define PIO_PWM0_L PIO_PWM0_L_1
+#elif !defined(CONFIG_SAMA5_LCDC) && !defined(CONFIG_SAMA5_ISI)
+# define PIO_PWM0_H PIO_PWM0_H_2
+# define PIO_PWM0_L PIO_PWM0_L_3
+#endif
+
+#if !defined(CONFIG_SAMA5_GMAC)
+# define PIO_PWM1_H PIO_PWM1_H_1
+# define PIO_PWM1_L PIO_PWM1_L_1
+#elif !defined(CONFIG_SAMA5_LCDC) && !defined(CONFIG_SAMA5_ISI)
+# define PIO_PWM1_H PIO_PWM1_H_2
+# define PIO_PWM1_L PIO_PWM1_L_3
+#elif !defined(CONFIG_SAMA5_ISI)
+# define PIO_PWM1_L PIO_PWM1_L_2
+#endif
+
+#if !defined(CONFIG_SAMA5_HSMCI0)
+# define PIO_PWM2_H PIO_PWM2_H_1
+# define PIO_PWM2_L PIO_PWM2_L_1
+#elif !defined(CONFIG_SAMA5_GMAC)
+# define PIO_PWM2_H PIO_PWM2_H_2
+# define PIO_PWM2_L PIO_PWM2_L_2
+#endif
+
+#if !defined(CONFIG_SAMA5_HSMCI0)
+# define PIO_PWM3_H PIO_PWM3_H_1
+# define PIO_PWM3_L PIO_PWM3_L_1
+#elif !defined(CONFIG_SAMA5_GMAC)
+# define PIO_PWM3_H PIO_PWM3_H_2
+# define PIO_PWM3_L PIO_PWM3_L_2
+#endif
+
/************************************************************************************
* Assembly Language Macros
************************************************************************************/
diff --git a/nuttx/configs/sama5d3x-ek/src/Makefile b/nuttx/configs/sama5d3x-ek/src/Makefile
index 6d492cb1e..dee4d74a6 100644
--- a/nuttx/configs/sama5d3x-ek/src/Makefile
+++ b/nuttx/configs/sama5d3x-ek/src/Makefile
@@ -110,6 +110,10 @@ ifeq ($(CONFIG_ADC),y)
CSRCS += sam_adc.c
endif
+ifeq ($(CONFIG_PWM),y)
+CSRCS += sam_pwm.c
+endif
+
ifeq ($(CONFIG_CAN),y)
CSRCS += sam_can.c
endif
diff --git a/nuttx/configs/sama5d3x-ek/src/sam_pwm.c b/nuttx/configs/sama5d3x-ek/src/sam_pwm.c
new file mode 100644
index 000000000..90216f4f2
--- /dev/null
+++ b/nuttx/configs/sama5d3x-ek/src/sam_pwm.c
@@ -0,0 +1,161 @@
+/************************************************************************************
+ * configs/sama5d3x-ek/src/sam_pwm.c
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/pwm.h>
+#include <arch/board/board.h>
+
+#include "sam_pwm.h"
+#include "sama5d3x-ek.h"
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+/* Configuration ********************************************************************/
+/* PWM. There are no dedicated PWM output pins available to the user for PWM
+ * testing. Care must be taken because all PWM output pins conflict with some other
+ * usage of the pin by other devices:
+ *
+ * -----+---+---+----+--------------------
+ * PWM PIN PER PIO CONFLICTS
+ * -----+---+---+----+--------------------
+ * PWM0 FI B PC28 SPI1, ISI
+ * H B PB0 GMAC
+ * B PA20 LCDC, ISI
+ * L B PB1 GMAC
+ * B PA21 LCDC, ISI
+ * -----+---+---+----+--------------------
+ * PWM1 FI B PC31 HDMI
+ * H B PB4 GMAC
+ * B PA22 LCDC, ISI
+ * L B PB5 GMAC
+ * B PE31 ISI, HDMI
+ * B PA23 LCDC, ISI
+ * -----+---+---+----+--------------------
+ * PWM2 FI B PC29 UART0, ISI, HDMI
+ * H C PD5 HSMCI0
+ * B PB8 GMAC
+ * L C PD6 HSMCI0
+ * B PB9 GMAC
+ * -----+---+---+----+--------------------
+ * PWM3 FI C PD16 SPI0, Audio
+ * H C PD7 HSMCI0
+ * B PB12 GMAC
+ * L C PD8 HSMCI0
+ * B PB13 GMAC
+ * -----+---+---+----+--------------------
+ */
+
+#ifndef CONFIG_SAMA5D3X_EK_CHANNEL
+# if defined(CONFIG_SAMA5_PWM_CHAN0)
+# warning Assuming PWM channel 0
+# define CONFIG_SAMA5D3X_EK_CHANNEL 0
+# elif defined(CONFIG_SAMA5_PWM_CHAN1)
+# warning Assuming PWM channel 1
+# define CONFIG_SAMA5D3X_EK_CHANNEL 1
+# elif defined(CONFIG_SAMA5_PWM_CHAN2)
+# warning Assuming PWM channel 2
+# define CONFIG_SAMA5D3X_EK_CHANNEL 2
+# elif defined(CONFIG_SAMA5_PWM_CHAN3)
+# warning Assuming PWM channel 3
+# define CONFIG_SAMA5D3X_EK_CHANNEL 3
+# endif
+#endif
+
+#if defined(CONFIG_PWM) && defined(CONFIG_SAMA5_PWM)
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: pwm_devinit
+ *
+ * Description:
+ * All SAMA5 architectures must provide the following interface to work with
+ * examples/pwm.
+ *
+ ************************************************************************************/
+
+int pwm_devinit(void)
+{
+ static bool initialized = false;
+ struct pwm_lowerhalf_s *pwm;
+ int ret;
+
+ /* Have we already initialized? */
+
+ if (!initialized)
+ {
+ /* Call sam_pwminitialize() to get an instance of the PWM interface */
+
+ pwm = sam_pwminitialize(CONFIG_SAMA5D3X_EK_CHANNEL);
+ if (!pwm)
+ {
+ dbg("Failed to get the SAMA5 PWM lower half\n");
+ return -ENODEV;
+ }
+
+ /* Register the PWM driver at "/dev/pwm0" */
+
+ ret = pwm_register("/dev/pwm0", pwm);
+ if (ret < 0)
+ {
+ adbg("pwm_register failed: %d\n", ret);
+ return ret;
+ }
+
+ /* Now we are initialized */
+
+ initialized = true;
+ }
+
+ return OK;
+}
+
+#endif /* CONFIG_PWM */