diff --git a/bsp/imx6ull-artpi-smart/.config b/bsp/imx6ull-artpi-smart/.config index fd6a0470f75e5324056d484a16a0a245ebc111e3..59a8a0208bd4a0cb23d7eae67d5e77b048510ca3 100644 --- a/bsp/imx6ull-artpi-smart/.config +++ b/bsp/imx6ull-artpi-smart/.config @@ -170,7 +170,7 @@ CONFIG_RT_USING_PIN=y # CONFIG_RT_USING_NULL is not set # CONFIG_RT_USING_ZERO is not set # CONFIG_RT_USING_RANDOM is not set -# CONFIG_RT_USING_PWM is not set +CONFIG_RT_USING_PWM=y # CONFIG_RT_USING_MTD_NOR is not set # CONFIG_RT_USING_MTD_NAND is not set # CONFIG_RT_USING_PM is not set @@ -555,7 +555,12 @@ CONFIG_LWP_TID_MAX_NR=64 # CONFIG_PKG_USING_LITTLEFS is not set # CONFIG_PKG_USING_DFS_JFFS2 is not set # CONFIG_PKG_USING_DFS_UFFS is not set -# CONFIG_PKG_USING_LWEXT4 is not set +CONFIG_PKG_USING_LWEXT4=y +CONFIG_PKG_LWEXT4_PATH="/packages/system/lwext4" +CONFIG_RT_USING_DFS_LWEXT4=y +CONFIG_PKG_USING_LWEXT4_LATEST_VERSION=y +# CONFIG_PKG_USING_LWEXT4_V110 is not set +CONFIG_PKG_LWEXT4_VER="latest" # CONFIG_PKG_USING_THREAD_POOL is not set # CONFIG_PKG_USING_ROBOTS is not set # CONFIG_PKG_USING_EV is not set @@ -755,9 +760,17 @@ CONFIG_BSP_LCD_HEIGHT=600 # Select SDHC Driver # CONFIG_RT_USING_SDIO1=y -# CONFIG_RT_USING_SDIO2 is not set +CONFIG_RT_USING_SDIO2=y # # Select RTC Driver # CONFIG_BSP_USING_ONCHIP_RTC=y + +# +# Select PWM Driver +# +CONFIG_BSP_USING_PWM1=y +# CONFIG_BSP_USING_PWM2 is not set +# CONFIG_BSP_USING_PWM3 is not set +# CONFIG_BSP_USING_PWM4 is not set diff --git a/bsp/imx6ull-artpi-smart/drivers/Kconfig b/bsp/imx6ull-artpi-smart/drivers/Kconfig index 8d0b855e78490fffa40c06e10be7fe4605942046..fe2f0874f917886f07c5dbc087a3847461e8ac89 100644 --- a/bsp/imx6ull-artpi-smart/drivers/Kconfig +++ b/bsp/imx6ull-artpi-smart/drivers/Kconfig @@ -131,4 +131,24 @@ menu "Select RTC Driver" endif endmenu +menu "Select PWM Driver" +config RT_USING_PWM + bool "Enable PWM" + default y + if RT_USING_PWM + config BSP_USING_PWM1 + bool "Enable PWM1" + default n + config BSP_USING_PWM2 + bool "Enable PWM2" + default n + config BSP_USING_PWM3 + bool "Enable PWM3" + default n + config BSP_USING_PWM4 + bool "Enable PWM4" + default n + endif +endmenu + endmenu diff --git a/bsp/imx6ull-artpi-smart/drivers/drv_pwm.c b/bsp/imx6ull-artpi-smart/drivers/drv_pwm.c new file mode 100644 index 0000000000000000000000000000000000000000..9cc01ce902af2fa7ec40bb31b07270f8c97beea7 --- /dev/null +++ b/bsp/imx6ull-artpi-smart/drivers/drv_pwm.c @@ -0,0 +1,329 @@ +/* + * Copyright (c) 2006-2021, RT-Thread Development Team + * + * SPDX-License-Identifier: Apache-2.0 + * + * Change Logs: + * Date Author Notes + * 2019-04-28 tyustli first version + * + */ + +#include + +#ifdef RT_USING_PWM + +#define LOG_TAG "drv.pwm" +#include + +#include +#include + +#include "fsl_pwm.h" +#include "drv_pwm.h" +#include + + +#define PWM_SRC_CLK_FREQ CLOCK_GetFreq(kCLOCK_IpgClk) +/* PWMPR register value of 0xffff has the same effect as 0xfffe */ +#define IMX_PWMPR_MAX 0xfffe +#define NSEC_PER_MSEC 1000000 +#define NSEC_PER_SEC 1000 + +#define MX3_PWMCR_SWR BIT(3) +#define MX3_PWM_SWR_LOOP 5 + +#define MX3_PWMSR_FIFOAV_EMPTY 0 +#define MX3_PWMSR_FIFOAV_1WORD 1 +#define MX3_PWMSR_FIFOAV_2WORDS 2 +#define MX3_PWMSR_FIFOAV_3WORDS 3 +#define MX3_PWMSR_FIFOAV_4WORDS 4 + +#define MX3_PWMCR_STOPEN BIT(25) +#define MX3_PWMCR_DOZEN BIT(24) +#define MX3_PWMCR_WAITEN BIT(23) +#define MX3_PWMCR_DBGEN BIT(22) +#define MX3_PWMCR_BCTR BIT(21) +#define MX3_PWMCR_HCTR BIT(20) + +#define MX3_PWMCR_EN BIT(0) + + +static rt_err_t imxrt_drv_pwm_control(struct rt_device_pwm *device, int cmd, void *arg); + +static struct rt_pwm_ops imxrt_drv_ops = +{ + .control = imxrt_drv_pwm_control +}; + +static void imx6ul_pwm_reset(PWM_Type *base) +{ + int wait_count = 0; + uint32_t cr; + + base->PWMCR = MX3_PWMCR_SWR; + do { + rt_thread_mdelay(1); + cr = base->PWMCR; + } while ((cr & MX3_PWMCR_SWR) && + (wait_count++ < MX3_PWM_SWR_LOOP)); + + if (cr & MX3_PWMCR_SWR) + rt_kprintf( "software reset timeout\n"); +} + +static void imx6ul_pwm_wait_fifo_slot(PWM_Type *base, struct rt_pwm_configuration *configuration) +{ + unsigned int period_ms; + int fifoav; + uint32_t sr; + + sr = base->PWMSR; + fifoav = sr & 0x7; + if (fifoav == MX3_PWMSR_FIFOAV_4WORDS) { + period_ms = configuration->period / NSEC_PER_MSEC; + rt_thread_mdelay(period_ms); + + sr = base->PWMSR; + if (fifoav == (sr & 0x7)) + rt_kprintf("there is no free FIFO slot\n"); + } +} + +static rt_err_t imx6ul_pwm_enable(struct rt_device_pwm *device, rt_bool_t enable) +{ + PWM_Type *base; + + base = (PWM_Type *)device->parent.user_data; + + if (!enable) + { + PWM_StopTimer(base); + } + else + { + PWM_StartTimer(base); + } + + return RT_EOK; +} + +static rt_err_t imx6ul_pwm_get(struct rt_device_pwm *device, struct rt_pwm_configuration *configuration) +{ + uint32_t period, prescaler, val; + uint64_t tmp; + PWM_Type *base; + uint32_t pwm_src_clk; + + base = (PWM_Type *)device->parent.user_data; + pwm_src_clk = PWM_SRC_CLK_FREQ / 1000000; + + val = base->PWMCR; + prescaler = ((val >> 4) & 0xfff)+1; + val = base->PWMPR; + period = val >= IMX_PWMPR_MAX ? IMX_PWMPR_MAX : val; + + tmp = NSEC_PER_SEC * (uint64_t)(period + 2) * prescaler; + + configuration->period = (tmp) / pwm_src_clk; + + val = base->PWMSAR; + + tmp = NSEC_PER_SEC * (uint64_t)(val) * prescaler; + + configuration->pulse = (tmp) / pwm_src_clk; + + return RT_EOK; +} + +static rt_err_t imx6ul_pwm_set(struct rt_device_pwm *device, struct rt_pwm_configuration *configuration) +{ + RT_ASSERT(configuration->period > 0); + RT_ASSERT(configuration->pulse <= configuration->period); + + PWM_Type *base; + uint32_t period_cycles, duty_cycles, prescale; + uint32_t cr; + uint32_t pwm_src_clk; + base = (PWM_Type *)device->parent.user_data; + + pwm_src_clk = PWM_SRC_CLK_FREQ / 1000000; + period_cycles = pwm_src_clk * configuration->period / NSEC_PER_SEC; + prescale = period_cycles / 0x10000 + 1; + period_cycles /= prescale; + + duty_cycles = configuration->pulse * pwm_src_clk / NSEC_PER_SEC ; + duty_cycles /= prescale; + + /* + * according to imx pwm RM, the real period value should be PERIOD + * value in PWMPR plus 2. + */ + if (period_cycles > 2) + period_cycles -= 2; + else + period_cycles = 0; + + if (((base->PWMCR) & 0x1) == 1) + { + imx6ul_pwm_wait_fifo_slot(base, configuration); + } + else + { + + PWM_StartTimer(base); + imx6ul_pwm_reset(base); + } + + base->PWMSAR = duty_cycles; + base->PWMPR = period_cycles; + + cr = (prescale << 4) | + MX3_PWMCR_STOPEN | MX3_PWMCR_DOZEN | MX3_PWMCR_WAITEN | + 0x2<<16 |MX3_PWMCR_DBGEN; + + cr |= MX3_PWMCR_EN; + + base->PWMCR = cr; + return RT_EOK; +} + +static rt_err_t imxrt_drv_pwm_control(struct rt_device_pwm *device, int cmd, void *arg) +{ + struct rt_pwm_configuration *configuration = (struct rt_pwm_configuration *)arg; + + switch (cmd) + { + case PWM_CMD_ENABLE: + return imx6ul_pwm_enable(device, RT_TRUE); + case PWM_CMD_DISABLE: + return imx6ul_pwm_enable(device, RT_FALSE); + case PWM_CMD_SET: + return imx6ul_pwm_set(device, configuration); + case PWM_CMD_GET: + return imx6ul_pwm_get(device, configuration); + default: + return RT_EINVAL; + } +} + +static rt_err_t imxrt_drv_pwm_init(PWM_Type *base) +{ + pwm_config_t PwmConfig; + + PWM_GetDefaultConfig(&PwmConfig); + + if (PWM_Init(base, &PwmConfig) == kStatus_Fail) + { + LOG_E("init pwm failed \n"); + return RT_ERROR; + } + + return RT_EOK; +} + +int imx6ull_pwm_gpio_init(void) +{ +#ifdef BSP_USING_PWM1 + struct imx6ull_iomuxc gpio; + + gpio.muxRegister = 0x020E007C; + gpio.muxMode = 0x0; + gpio.inputRegister = 0x00000000; + gpio.inputDaisy = 0x0; + gpio.configRegister = 0x020E0308; + gpio.inputOnfield = 0; + gpio.configValue = IOMUXC_SW_PAD_CTL_PAD_DSE(2U) | IOMUXC_SW_PAD_CTL_PAD_SPEED(2U); + + imx6ull_gpio_init(&gpio); +#endif + return 0; +} + + +int rt_hw_pwm_init(void) +{ + rt_err_t ret = RT_EOK; + +#ifdef BSP_USING_PWM1 + + static struct rt_device_pwm pwm1_device; + PWM_Type *pwm1_base; + + imx6ull_pwm_gpio_init(); + pwm1_base = (PWM_Type *)rt_ioremap((void*)PWM1, 0x1000); + if (imxrt_drv_pwm_init(pwm1_base) != RT_EOK) + { + LOG_E("init pwm1 failed\n"); + } + + ret = rt_device_pwm_register(&pwm1_device, "pwm1", &imxrt_drv_ops, pwm1_base); + + if (ret != RT_EOK) + { + LOG_E("%s register failed", "pwm1"); + } + +#endif /* BSP_USING_PWM1 */ + +#ifdef BSP_USING_PWM2 + + static struct rt_device_pwm pwm2_device; + + imx6ull_pwm_gpio_init(); + if (imxrt_drv_pwm_init(PWM2) != RT_EOK) + { + LOG_E("init pwm2 failed\n"); + } + + ret = rt_device_pwm_register(&pwm2_device, "pwm2", &imxrt_drv_ops, PWM2); + + if (ret != RT_EOK) + { + LOG_E("%s register failed", "pwm2"); + } +#endif /* BSP_USING_PWM2 */ + +#ifdef BSP_USING_PWM3 + + static struct rt_device_pwm pwm3_device; + + imx6ull_pwm_gpio_init(); + if (imxrt_drv_pwm_init(PWM3) != RT_EOK) + { + LOG_E("init pwm3 failed\n"); + } + + ret = rt_device_pwm_register(&pwm3_device, "pwm3", &imxrt_drv_ops, PWM3); + + if (ret != RT_EOK) + { + LOG_E("%s register failed", "pwm3"); + } + +#endif /* BSP_USING_PWM3 */ + +#ifdef BSP_USING_PWM4 + + static struct rt_device_pwm pwm4_device; + + imx6ull_pwm_gpio_init(); + if (imxrt_drv_pwm_init(PWM4) != RT_EOK) + { + LOG_E("init pwm4 failed\n"); + } + + ret = rt_device_pwm_register(&pwm4_device, "pwm4", &imxrt_drv_ops, PWM4); + + if (ret != RT_EOK) + { + LOG_E("%s register failed", "pwm4"); + } +#endif /* BSP_USING_PWM4 */ + + return ret; +} + +INIT_DEVICE_EXPORT(rt_hw_pwm_init); + +#endif /* BSP_USING_PWM */ diff --git a/bsp/imx6ull-artpi-smart/drivers/drv_pwm.h b/bsp/imx6ull-artpi-smart/drivers/drv_pwm.h new file mode 100644 index 0000000000000000000000000000000000000000..8f5f4255ebb9518b5454bf5f4d5d40986abe5cde --- /dev/null +++ b/bsp/imx6ull-artpi-smart/drivers/drv_pwm.h @@ -0,0 +1,21 @@ +/* + * Copyright (c) 2006-2021, RT-Thread Development Team + * + * SPDX-License-Identifier: Apache-2.0 + * + * Change Logs: + * Date Author Notes + * 2019-04-28 tyustli the first version. + * + */ + +#ifndef DRV_PWM_H__ +#define DRV_PWM_H__ + +#include + +#define BIT(nr) ((1) << (nr)) + +int rt_hw_pwm_init(void); + +#endif diff --git a/bsp/imx6ull-artpi-smart/libraries/sdk/devices/MCIMX6Y2/drivers/fsl_pwm.c b/bsp/imx6ull-artpi-smart/libraries/sdk/devices/MCIMX6Y2/drivers/fsl_pwm.c new file mode 100644 index 0000000000000000000000000000000000000000..09c0ff220060155e0a67b8c6d832fad6c7d3ce1e --- /dev/null +++ b/bsp/imx6ull-artpi-smart/libraries/sdk/devices/MCIMX6Y2/drivers/fsl_pwm.c @@ -0,0 +1,137 @@ +/* + * Copyright (c) 2016, Freescale Semiconductor, Inc. + * Copyright 2016-2017 NXP + * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * + * o Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * o 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. + * + * o Neither the name of the copyright holder 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 HOLDER 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. + */ + +#include "fsl_pwm.h" + +/******************************************************************************* + * Definitions + ******************************************************************************/ + +/******************************************************************************* + * Prototypes + ******************************************************************************/ +/*! + * @brief Get the instance from the base address + * + * @param base PWM peripheral base address + * + * @return The PWM module instance + */ +static uint32_t PWM_GetInstance(PWM_Type *base); + +/******************************************************************************* + * Variables + ******************************************************************************/ +/*! @brief Pointers to PWM bases for each instance. */ +static PWM_Type *const s_pwmBases[] = PWM_BASE_PTRS; + +#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) +/* Array of PWM clock name. */ +static const clock_ip_name_t s_pwmClock[] = PWM_CLOCKS; +#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */ + +/******************************************************************************* + * Code + ******************************************************************************/ +static uint32_t PWM_GetInstance(PWM_Type *base) +{ + uint32_t instance; + uint32_t pwmArrayCount = (sizeof(s_pwmBases)/sizeof(s_pwmBases[0])); + + /* Find the instance index from base address mappings. */ + for (instance = 0; instance < pwmArrayCount; instance++) + { + if (s_pwmBases[instance] == base) + { + break; + } + } + + assert(instance < pwmArrayCount); + + return instance; +} + +status_t PWM_Init(PWM_Type *base, const pwm_config_t *config) +{ + assert(config); + +#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) + /* Ungate PWM clock */ + CLOCK_EnableClock(s_pwmClock[PWM_GetInstance(base)]); +#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */ + + /* Setup the PWM operation */ + base->PWMCR = (PWM_PWMCR_REPEAT(config->sampleRepeat) | PWM_PWMCR_PRESCALER(config->prescale) | PWM_PWMCR_CLKSRC(config->clockSource) | + PWM_PWMCR_POUTC(config->outputConfig) | PWM_PWMCR_HCTR(config->halfWordSwap) | PWM_PWMCR_BCTR(config->byteSwap) | + PWM_PWMCR_STOPEN(config->enableStopMode) | PWM_PWMCR_DBGEN(config->enableDebugMode) | PWM_PWMCR_WAITEN(config->enableWaitMode) | + PWM_PWMCR_DOZEN(config->enableDozeMode) | PWM_PWMCR_FWM(config->fifoWater)); + + return kStatus_Success; +} + +void PWM_Deinit(PWM_Type *base) +{ + /* Set clock source to none to disable counter */ + base->PWMCR &= ~(PWM_PWMCR_CLKSRC_MASK); + +#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) + /* Gate the PWM clock */ + CLOCK_DisableClock(s_pwmClock[PWM_GetInstance(base)]); +#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */ +} + +void PWM_GetDefaultConfig(pwm_config_t *config) +{ + assert(config); + + /* Stop mode disabled */ + config->enableStopMode = false; + /* Doze mode disabled */ + config->enableDozeMode = false; + /* Wait mode disabled */ + config->enableWaitMode = false; + /* Debug mode disabled */ + config->enableDebugMode = false; + /* Choose low frequency clock to control counter operation */ + config->clockSource = kPWM_LowFrequencyClock; + /* PWM clock devide by (config->prescale + 1) */ + config->prescale = 0U; + /* Output pin is set at rollover and cleared at comparison */ + config->outputConfig = kPWM_SetAtRolloverAndClearAtcomparison; + /* FIFO empty flag is set when there are more than or equal to 2 empty slots in FIFO */ + config->fifoWater = kPWM_FIFOWaterMark_2; + /* Use each sample once */ + config->sampleRepeat = kPWM_EachSampleOnce; + /* byte ordering remains the same */ + config->byteSwap = kPWM_ByteNoSwap; + /* Half word swapping does not take place */ + config->halfWordSwap = kPWM_HalfWordNoSwap; +} diff --git a/bsp/imx6ull-artpi-smart/libraries/sdk/devices/MCIMX6Y2/drivers/fsl_pwm.h b/bsp/imx6ull-artpi-smart/libraries/sdk/devices/MCIMX6Y2/drivers/fsl_pwm.h new file mode 100644 index 0000000000000000000000000000000000000000..039b547041d2bc930ed3047fbb2214463fa13773 --- /dev/null +++ b/bsp/imx6ull-artpi-smart/libraries/sdk/devices/MCIMX6Y2/drivers/fsl_pwm.h @@ -0,0 +1,425 @@ +/* + * Copyright (c) 2016, Freescale Semiconductor, Inc. + * Copyright 2016-2017 NXP + * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * + * o Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * o 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. + * + * o Neither the name of the copyright holder 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 HOLDER 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. + */ +#ifndef _FSL_PWM_H_ +#define _FSL_PWM_H_ + +#include "fsl_common.h" + +/*! + * @addtogroup pwm_driver + * @{ + */ + +/******************************************************************************* + * Definitions + ******************************************************************************/ + +/*! @name Driver version */ +/*@{*/ +#define FSL_PWM_DRIVER_VERSION (MAKE_VERSION(2, 0, 0)) /*!< Version 2.0.0 */ +/*@}*/ + +/*! @brief PWM clock source select. */ +typedef enum _pwm_clock_source +{ + kPWM_PeripheralClock = 0U, /*!< The Peripheral clock is used as the clock */ + kPWM_HighFrequencyClock, /*!< High-frequency reference clock is used as the clock */ + kPWM_LowFrequencyClock /*!< Low-frequency reference clock(32KHz) is used as the clock */ +} pwm_clock_source_t; + +/*! + * @brief PWM FIFO water mark select. + * Sets the data level at which the FIFO empty flag will be set + */ +typedef enum _pwm_fifo_water_mark +{ + kPWM_FIFOWaterMark_1 = 0U, /*!< FIFO empty flag is set when there are more than or equal to 1 empty slots */ + kPWM_FIFOWaterMark_2, /*!< FIFO empty flag is set when there are more than or equal to 2 empty slots */ + kPWM_FIFOWaterMark_3, /*!< FIFO empty flag is set when there are more than or equal to 3 empty slots */ + kPWM_FIFOWaterMark_4 /*!< FIFO empty flag is set when there are more than or equal to 4 empty slots */ +} pwm_fifo_water_mark_t; + +/*! + * @brief PWM byte data swap select. + * It determines the byte ordering of the 16-bit data when it goes into the FIFO from the sample register. + */ +typedef enum _pwm_byte_data_swap +{ + kPWM_ByteNoSwap = 0U, /*!< byte ordering remains the same */ + kPWM_ByteSwap /*!< byte ordering is reversed */ +} pwm_byte_data_swap_t; + +/*! @brief PWM half-word data swap select. */ +typedef enum _pwm_half_word_data_swap +{ + kPWM_HalfWordNoSwap = 0U, /*!< Half word swapping does not take place */ + kPWM_HalfWordSwap /*!< Half word from write data bus are swapped */ +} pwm_half_word_data_swap_t; + +/*! @brief PWM Output Configuration */ +typedef enum _pwm_output_configuration +{ + kPWM_SetAtRolloverAndClearAtcomparison = 0U, /*!< Output pin is set at rollover and cleared at comparison */ + kPWM_ClearAtRolloverAndSetAtcomparison, /*!< Output pin is cleared at rollover and set at comparison */ + kPWM_NoConfigure /*!< PWM output is disconnected */ +} pwm_output_configuration_t; + +/*! + * @brief PWM FIFO sample repeat + * It determines the number of times each sample from the FIFO is to be used. + */ +typedef enum _pwm_sample_repeat +{ + kPWM_EachSampleOnce = 0u, /*!< Use each sample once */ + kPWM_EachSampletwice, /*!< Use each sample twice */ + kPWM_EachSampleFourTimes, /*!< Use each sample four times */ + kPWM_EachSampleEightTimes /*!< Use each sample eight times */ +} pwm_sample_repeat_t; + +/*! @brief List of PWM interrupt options */ +typedef enum _pwm_interrupt_enable +{ + kPWM_FIFOEmptyInterruptEnable = (1U << 0), /*!< This bit controls the generation of the FIFO Empty interrupt. */ + kPWM_RolloverInterruptEnable = (1U << 1), /*!< This bit controls the generation of the Rollover interrupt. */ + kPWM_CompareInterruptEnable = (1U << 2) /*!< This bit controls the generation of the Compare interrupt */ +} pwm_interrupt_enable_t; + +/*! @brief List of PWM status flags */ +typedef enum _pwm_status_flags +{ + kPWM_FIFOEmptyFlag = (1U << 3), /*!< This bit indicates the FIFO data level in comparison to the water + level set by FWM field in the control register. */ + kPWM_RolloverFlag = (1U << 4), /*!< This bit shows that a roll-over event has occurred. */ + kPWM_CompareFlag = (1U << 5), /*!< This bit shows that a compare event has occurred. */ + kPWM_FIFOWriteErrorFlag = (1U << 6) /*!< This bit shows that an attempt has been made to write FIFO when it is full. */ +} pwm_status_flags_t; + +/*! @brief List of PWM FIFO available */ +typedef enum _pwm_fifo_available +{ + kPWM_NoDataInFIFOFlag = 0U, /*!< No data available */ + kPWM_OneWordInFIFOFlag, /*!< 1 word of data in FIFO */ + kPWM_TwoWordsInFIFOFlag, /*!< 2 word of data in FIFO */ + kPWM_ThreeWordsInFIFOFlag, /*!< 3 word of data in FIFO */ + kPWM_FourWordsInFIFOFlag /*!< 4 word of data in FIFO */ +} pwm_fifo_available_t; + +typedef struct _pwm_config +{ + bool enableStopMode; /*!< True: PWM continues to run in stop mode; + False: PWM is paused in stop mode. */ + bool enableDozeMode; /*!< True: PWM continues to run in doze mode; + False: PWM is paused in doze mode. */ + bool enableWaitMode; /*!< True: PWM continues to run in wait mode; + False: PWM is paused in wait mode. */ + bool enableDebugMode; /*!< True: PWM continues to run in debug mode; + False: PWM is paused in debug mode. */ + uint16_t prescale; /*!< Pre-scaler to divide down the clock + The prescaler value is not more than 0xFFF. Divide by (value + 1)*/ + pwm_clock_source_t clockSource; /*!< Clock source for the counter */ + pwm_output_configuration_t outputConfig; /*!< Set the mode of the PWM output on the output pin. */ + pwm_fifo_water_mark_t fifoWater; /*!< Set the data level for FIFO. */ + pwm_sample_repeat_t sampleRepeat; /*!< The number of times each sample from the FIFO is to be used. */ + pwm_byte_data_swap_t byteSwap; /*!< It determines the byte ordering of the 16-bit data when it goes into the + FIFO from the sample register. */ + pwm_half_word_data_swap_t halfWordSwap; /*!< It determines which half word data from the 32-bit IP Bus interface is + written into the lower 16 bits of the sample register. */ +} pwm_config_t; + +/******************************************************************************* + * API + ******************************************************************************/ + +#if defined(__cplusplus) +extern "C" { +#endif + +/*! + * @name Initialization and deinitialization + * @{ + */ + +/*! + * @brief Ungates the PWM clock and configures the peripheral for basic operation. + * + * @note This API should be called at the beginning of the application using the PWM driver. + * + * @param base PWM peripheral base address + * @param config Pointer to user's PWM config structure. + * + * @return kStatus_Success means success; else failed. + */ +status_t PWM_Init(PWM_Type *base, const pwm_config_t *config); + +/*! + * @brief Gate the PWM submodule clock + * + * @param base PWM peripheral base address + */ +void PWM_Deinit(PWM_Type *base); + +/*! + * @brief Fill in the PWM config struct with the default settings + * + * The default values are: + * @code + * config->enableStopMode = false; + * config->enableDozeMode = false; + * config->enableWaitMode = false; + * config->enableDozeMode = false; + * config->clockSource = kPWM_LowFrequencyClock; + * config->prescale = 0U; + * config->outputConfig = kPWM_SetAtRolloverAndClearAtcomparison; + * config->fifoWater = kPWM_FIFOWaterMark_2; + * config->sampleRepeat = kPWM_EachSampleOnce; + * config->byteSwap = kPWM_ByteNoSwap; + * config->halfWordSwap = kPWM_HalfWordNoSwap; + * @endcode + * @param config Pointer to user's PWM config structure. + */ +void PWM_GetDefaultConfig(pwm_config_t *config); + +/*! @}*/ + +/*! + * @name PWM start and stop. + * @{ + */ + +/*! + * @brief Starts the PWM counter when the PWM is enabled. + * + * When the PWM is enabled, it begins a new period, the output pin is set to start a new period while + * the prescaler and counter are released and counting begins. + * + * @param base PWM peripheral base address + */ +static inline void PWM_StartTimer(PWM_Type *base) +{ + base->PWMCR |= PWM_PWMCR_EN_MASK; +} + +/*! + * @brief Stops the PWM counter when the pwm is disabled. + * + * @param base PWM peripheral base address + */ +static inline void PWM_StopTimer(PWM_Type *base) +{ + base->PWMCR &= ~(PWM_PWMCR_EN_MASK); +} + +/*! @}*/ + +/*! + * @brief Sofrware reset. + * + * PWM is reset when this bit is set to 1. It is a self clearing bit. + * Setting this bit resets all the registers to their reset values except for the STOPEN, + * DOZEN, WAITEN, and DBGEN bits in this control register. + * + * @param base PWM peripheral base address + */ +static inline void PWM_SoftwareReset(PWM_Type *base) +{ + base->PWMCR |= PWM_PWMCR_SWR_MASK; +} + +/*! + * @name Interrupt Interface + * @{ + */ + +/*! + * @brief Enables the selected PWM interrupts. + * + * @param base PWM peripheral base address + * @param mask The interrupts to enable. This is a logical OR of members of the + * enumeration ::pwm_interrupt_enable_t + */ +static inline void PWM_EnableInterrupts(PWM_Type *base, uint32_t mask) +{ + base->PWMIR |= (mask & (PWM_PWMIR_FIE_MASK | PWM_PWMIR_RIE_MASK | PWM_PWMIR_CIE_MASK)); +} + +/*! + * @brief Disables the selected PWM interrupts. + * + * @param base PWM peripheral base address + * @param mask The interrupts to disable. This is a logical OR of members of the + * enumeration ::pwm_interrupt_enable_t + */ +static inline void PWM_DisableInterrupts(PWM_Type *base, uint32_t mask) +{ + base->PWMIR &= ~(mask & (PWM_PWMIR_FIE_MASK | PWM_PWMIR_RIE_MASK | PWM_PWMIR_CIE_MASK)); +} + +/*! + * @brief Gets the enabled PWM interrupts. + * + * @param base PWM peripheral base address + * + * @return The enabled interrupts. This is the logical OR of members of the + * enumeration ::pwm_interrupt_enable_t + */ +static inline uint32_t PWM_GetEnabledInterrupts(PWM_Type *base) +{ + return base->PWMIR; +} + +/*! @}*/ + +/*! + * @name Status Interface + * @{ + */ + +/*! + * @brief Gets the PWM status flags. + * + * @param base PWM peripheral base address + * + * @return The status flags. This is the logical OR of members of the + * enumeration ::pwm_status_flags_t + */ +static inline uint32_t PWM_GetStatusFlags(PWM_Type *base) +{ + uint32_t statusFlags = base->PWMSR; + + statusFlags &= (PWM_PWMSR_FE_MASK | PWM_PWMSR_ROV_MASK | PWM_PWMSR_CMP_MASK | PWM_PWMSR_FWE_MASK); + return statusFlags; +} + +/*! + * @brief Clears the PWM status flags. + * + * @param base PWM peripheral base address + * @param mask The status flags to clear. This is a logical OR of members of the + * enumeration ::pwm_status_flags_t + */ +static inline void PWM_clearStatusFlags(PWM_Type *base, uint32_t mask) +{ + base->PWMSR = (mask & (PWM_PWMSR_FE_MASK | PWM_PWMSR_ROV_MASK | + PWM_PWMSR_CMP_MASK | PWM_PWMSR_FWE_MASK)); +} + +/*! + * @brief Gets the PWM FIFO available. + * + * @param base PWM peripheral base address + * + * @return The status flags. This is the logical OR of members of the + * enumeration ::pwm_fifo_available_t + */ +static inline uint32_t PWM_GetFIFOAvailable(PWM_Type *base) +{ + return (base->PWMSR & PWM_PWMSR_FIFOAV_MASK); +} + +/*! @}*/ + +/*! + * @name Sample Interface + * @{ + */ + +/*! + * @brief Sets the PWM sample value. + * + * @param base PWM peripheral base address + * @param mask The sample value. This is the input to the 4x16 FIFO. The value in this register denotes + * the value of the sample being currently used. + */ +static inline void PWM_SetSampleValue(PWM_Type *base, uint32_t value) +{ + base->PWMSAR = (value & PWM_PWMSAR_SAMPLE_MASK); +} + +/*! + * @brief Gets the PWM sample value. + * + * @param base PWM peripheral base address + * + * @return The sample value. It can be read only when the PWM is enable. + */ +static inline uint32_t PWM_GetSampleValue(PWM_Type *base) +{ + return base->PWMSAR; +} + +/*! @}*/ + +/*! + * @brief Sets the PWM period value. + * + * @param base PWM peripheral base address + * @param mask The period value. The PWM period register (PWM_PWMPR) determines the period of + * the PWM output signal. + * Writing 0xFFFF to this register will achieve the same result as writing 0xFFFE. + * PWMO (Hz) = PCLK(Hz) / (period +2) + */ +static inline void PWM_SetPeriodValue(PWM_Type *base, uint32_t value) +{ + base->PWMPR = (value & PWM_PWMPR_PERIOD_MASK); +} + +/*! + * @brief Gets the PWM period value. + * + * @param base PWM peripheral base address + * + * @return The period value. The PWM period register (PWM_PWMPR) determines the period of + * the PWM output signal. + */ +static inline uint32_t PWM_GetPeriodValue(PWM_Type *base) +{ + return (base->PWMPR & PWM_PWMPR_PERIOD_MASK); +} + +/*! + * @brief Gets the PWM counter value. + * + * @param base PWM peripheral base address + * + * @return The counter value. The current count value. + */ +static inline uint32_t PWM_GetCounterValue(PWM_Type *base) +{ + return (base->PWMCNR & PWM_PWMCNR_COUNT_MASK); +} + + +#if defined(__cplusplus) +} +#endif + +/*! @}*/ + +#endif /* _FSL_PWM_H_ */ diff --git a/bsp/imx6ull-artpi-smart/rtconfig.h b/bsp/imx6ull-artpi-smart/rtconfig.h index e0287f7c0aec5431e17f87cd0797db3e10001c84..7871c429ef6fb03fdd3c423de99fba409b30a948 100644 --- a/bsp/imx6ull-artpi-smart/rtconfig.h +++ b/bsp/imx6ull-artpi-smart/rtconfig.h @@ -116,6 +116,7 @@ #define RT_SERIAL_RB_BUFSZ 64 #define RT_USING_I2C #define RT_USING_PIN +#define RT_USING_PWM #define RT_USING_RTC #define RT_USING_SDIO #define RT_SDIO_STACK_SIZE 512 @@ -322,4 +323,8 @@ #define BSP_USING_ONCHIP_RTC +/* Select PWM Driver */ + +#define BSP_USING_PWM1 + #endif