summaryrefslogtreecommitdiff
path: root/drivers
diff options
context:
space:
mode:
Diffstat (limited to 'drivers')
-rw-r--r--drivers/fsl_adc16.c364
-rw-r--r--drivers/fsl_adc16.h526
-rw-r--r--drivers/fsl_clock.c1751
-rw-r--r--drivers/fsl_clock.h1492
-rw-r--r--drivers/fsl_cmp.c279
-rw-r--r--drivers/fsl_cmp.h345
-rw-r--r--drivers/fsl_cmt.c260
-rw-r--r--drivers/fsl_cmt.h401
-rw-r--r--drivers/fsl_common.c95
-rw-r--r--drivers/fsl_common.h254
-rw-r--r--drivers/fsl_crc.c280
-rw-r--r--drivers/fsl_crc.h192
-rw-r--r--drivers/fsl_dac.c214
-rw-r--r--drivers/fsl_dac.h378
-rw-r--r--drivers/fsl_dmamux.c87
-rw-r--r--drivers/fsl_dmamux.h175
-rw-r--r--drivers/fsl_dspi.c1661
-rw-r--r--drivers/fsl_dspi.h1181
-rw-r--r--drivers/fsl_dspi_edma.c1263
-rw-r--r--drivers/fsl_dspi_edma.h282
-rw-r--r--drivers/fsl_edma.c1313
-rw-r--r--drivers/fsl_edma.h880
-rw-r--r--drivers/fsl_ewm.c92
-rw-r--r--drivers/fsl_ewm.h241
-rw-r--r--drivers/fsl_flash.c2630
-rw-r--r--drivers/fsl_flash.h1209
-rw-r--r--drivers/fsl_flexbus.c196
-rw-r--r--drivers/fsl_flexbus.h265
-rw-r--r--drivers/fsl_flexcan.c1345
-rw-r--r--drivers/fsl_flexcan.h1052
-rw-r--r--drivers/fsl_ftm.c896
-rw-r--r--drivers/fsl_ftm.h861
-rw-r--r--drivers/fsl_gpio.c179
-rw-r--r--drivers/fsl_gpio.h389
-rw-r--r--drivers/fsl_i2c.c1633
-rw-r--r--drivers/fsl_i2c.h788
-rw-r--r--drivers/fsl_i2c_edma.c526
-rw-r--r--drivers/fsl_i2c_edma.h132
-rw-r--r--drivers/fsl_llwu.c404
-rw-r--r--drivers/fsl_llwu.h320
-rw-r--r--drivers/fsl_lptmr.c117
-rw-r--r--drivers/fsl_lptmr.h370
-rw-r--r--drivers/fsl_mpu.c239
-rw-r--r--drivers/fsl_mpu.h422
-rw-r--r--drivers/fsl_pdb.c135
-rw-r--r--drivers/fsl_pdb.h575
-rw-r--r--drivers/fsl_pit.c119
-rw-r--r--drivers/fsl_pit.h354
-rw-r--r--drivers/fsl_pmc.c93
-rw-r--r--drivers/fsl_pmc.h421
-rw-r--r--drivers/fsl_port.h381
-rw-r--r--drivers/fsl_rcm.c65
-rw-r--r--drivers/fsl_rcm.h431
-rw-r--r--drivers/fsl_rtc.c379
-rw-r--r--drivers/fsl_rtc.h412
-rw-r--r--drivers/fsl_sai.c1066
-rw-r--r--drivers/fsl_sai.h849
-rw-r--r--drivers/fsl_sai_edma.c379
-rw-r--r--drivers/fsl_sai_edma.h231
-rw-r--r--drivers/fsl_sdhc.c1297
-rw-r--r--drivers/fsl_sdhc.h1081
-rw-r--r--drivers/fsl_sim.c53
-rw-r--r--drivers/fsl_sim.h127
-rw-r--r--drivers/fsl_smc.c366
-rw-r--r--drivers/fsl_smc.h418
-rw-r--r--drivers/fsl_tsi_v2.c211
-rw-r--r--drivers/fsl_tsi_v2.h777
-rw-r--r--drivers/fsl_uart.c1128
-rw-r--r--drivers/fsl_uart.h774
-rw-r--r--drivers/fsl_uart_edma.c358
-rw-r--r--drivers/fsl_uart_edma.h189
-rw-r--r--drivers/fsl_vref.c224
-rw-r--r--drivers/fsl_vref.h256
-rw-r--r--drivers/fsl_wdog.c153
-rw-r--r--drivers/fsl_wdog.h433
75 files changed, 41714 insertions, 0 deletions
diff --git a/drivers/fsl_adc16.c b/drivers/fsl_adc16.c
new file mode 100644
index 0000000..4fee1a8
--- /dev/null
+++ b/drivers/fsl_adc16.c
@@ -0,0 +1,364 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_adc16.h"
+
+/*******************************************************************************
+ * Prototypes
+ ******************************************************************************/
+/*!
+ * @brief Get instance number for ADC16 module.
+ *
+ * @param base ADC16 peripheral base address
+ */
+static uint32_t ADC16_GetInstance(ADC_Type *base);
+
+/*******************************************************************************
+ * Variables
+ ******************************************************************************/
+/*! @brief Pointers to ADC16 bases for each instance. */
+static ADC_Type *const s_adc16Bases[] = ADC_BASE_PTRS;
+
+/*! @brief Pointers to ADC16 clocks for each instance. */
+static const clock_ip_name_t s_adc16Clocks[] = ADC16_CLOCKS;
+
+/*******************************************************************************
+ * Code
+ ******************************************************************************/
+static uint32_t ADC16_GetInstance(ADC_Type *base)
+{
+ uint32_t instance;
+
+ /* Find the instance index from base address mappings. */
+ for (instance = 0; instance < FSL_FEATURE_SOC_ADC16_COUNT; instance++)
+ {
+ if (s_adc16Bases[instance] == base)
+ {
+ break;
+ }
+ }
+
+ assert(instance < FSL_FEATURE_SOC_ADC16_COUNT);
+
+ return instance;
+}
+
+void ADC16_Init(ADC_Type *base, const adc16_config_t *config)
+{
+ assert(NULL != config);
+
+ uint32_t tmp32;
+
+ /* Enable the clock. */
+ CLOCK_EnableClock(s_adc16Clocks[ADC16_GetInstance(base)]);
+
+ /* ADCx_CFG1. */
+ tmp32 = ADC_CFG1_ADICLK(config->clockSource) | ADC_CFG1_MODE(config->resolution);
+ if (kADC16_LongSampleDisabled != config->longSampleMode)
+ {
+ tmp32 |= ADC_CFG1_ADLSMP_MASK;
+ }
+ tmp32 |= ADC_CFG1_ADIV(config->clockDivider);
+ if (config->enableLowPower)
+ {
+ tmp32 |= ADC_CFG1_ADLPC_MASK;
+ }
+ base->CFG1 = tmp32;
+
+ /* ADCx_CFG2. */
+ tmp32 = base->CFG2 & ~(ADC_CFG2_ADACKEN_MASK | ADC_CFG2_ADHSC_MASK | ADC_CFG2_ADLSTS_MASK);
+ if (kADC16_LongSampleDisabled != config->longSampleMode)
+ {
+ tmp32 |= ADC_CFG2_ADLSTS(config->longSampleMode);
+ }
+ if (config->enableHighSpeed)
+ {
+ tmp32 |= ADC_CFG2_ADHSC_MASK;
+ }
+ if (config->enableAsynchronousClock)
+ {
+ tmp32 |= ADC_CFG2_ADACKEN_MASK;
+ }
+ base->CFG2 = tmp32;
+
+ /* ADCx_SC2. */
+ tmp32 = base->SC2 & ~(ADC_SC2_REFSEL_MASK);
+ tmp32 |= ADC_SC2_REFSEL(config->referenceVoltageSource);
+ base->SC2 = tmp32;
+
+ /* ADCx_SC3. */
+ if (config->enableContinuousConversion)
+ {
+ base->SC3 |= ADC_SC3_ADCO_MASK;
+ }
+ else
+ {
+ base->SC3 &= ~ADC_SC3_ADCO_MASK;
+ }
+}
+
+void ADC16_Deinit(ADC_Type *base)
+{
+ /* Disable the clock. */
+ CLOCK_DisableClock(s_adc16Clocks[ADC16_GetInstance(base)]);
+}
+
+void ADC16_GetDefaultConfig(adc16_config_t *config)
+{
+ assert(NULL != config);
+
+ config->referenceVoltageSource = kADC16_ReferenceVoltageSourceVref;
+ config->clockSource = kADC16_ClockSourceAsynchronousClock;
+ config->enableAsynchronousClock = true;
+ config->clockDivider = kADC16_ClockDivider8;
+ config->resolution = kADC16_ResolutionSE12Bit;
+ config->longSampleMode = kADC16_LongSampleDisabled;
+ config->enableHighSpeed = false;
+ config->enableLowPower = false;
+ config->enableContinuousConversion = false;
+}
+
+#if defined(FSL_FEATURE_ADC16_HAS_CALIBRATION) && FSL_FEATURE_ADC16_HAS_CALIBRATION
+status_t ADC16_DoAutoCalibration(ADC_Type *base)
+{
+ bool bHWTrigger = false;
+ volatile uint32_t tmp32; /* 'volatile' here is for the dummy read of ADCx_R[0] register. */
+ status_t status = kStatus_Success;
+
+ /* The calibration would be failed when in hardwar mode.
+ * Remember the hardware trigger state here and restore it later if the hardware trigger is enabled.*/
+ if (0U != (ADC_SC2_ADTRG_MASK & base->SC2))
+ {
+ bHWTrigger = true;
+ base->SC2 &= ~ADC_SC2_ADTRG_MASK;
+ }
+
+ /* Clear the CALF and launch the calibration. */
+ base->SC3 |= ADC_SC3_CAL_MASK | ADC_SC3_CALF_MASK;
+ while (0U == (kADC16_ChannelConversionDoneFlag & ADC16_GetChannelStatusFlags(base, 0U)))
+ {
+ /* Check the CALF when the calibration is active. */
+ if (0U != (kADC16_CalibrationFailedFlag & ADC16_GetStatusFlags(base)))
+ {
+ status = kStatus_Fail;
+ break;
+ }
+ }
+ tmp32 = base->R[0]; /* Dummy read to clear COCO caused by calibration. */
+
+ /* Restore the hardware trigger setting if it was enabled before. */
+ if (bHWTrigger)
+ {
+ base->SC2 |= ADC_SC2_ADTRG_MASK;
+ }
+ /* Check the CALF at the end of calibration. */
+ if (0U != (kADC16_CalibrationFailedFlag & ADC16_GetStatusFlags(base)))
+ {
+ status = kStatus_Fail;
+ }
+ if (kStatus_Success != status) /* Check if the calibration process is succeed. */
+ {
+ return status;
+ }
+
+ /* Calculate the calibration values. */
+ tmp32 = base->CLP0 + base->CLP1 + base->CLP2 + base->CLP3 + base->CLP4 + base->CLPS;
+ tmp32 = 0x8000U | (tmp32 >> 1U);
+ base->PG = tmp32;
+
+#if defined(FSL_FEATURE_ADC16_HAS_DIFF_MODE) && FSL_FEATURE_ADC16_HAS_DIFF_MODE
+ tmp32 = base->CLM0 + base->CLM1 + base->CLM2 + base->CLM3 + base->CLM4 + base->CLMS;
+ tmp32 = 0x8000U | (tmp32 >> 1U);
+ base->MG = tmp32;
+#endif /* FSL_FEATURE_ADC16_HAS_DIFF_MODE */
+
+ return kStatus_Success;
+}
+#endif /* FSL_FEATURE_ADC16_HAS_CALIBRATION */
+
+#if defined(FSL_FEATURE_ADC16_HAS_MUX_SELECT) && FSL_FEATURE_ADC16_HAS_MUX_SELECT
+void ADC16_SetChannelMuxMode(ADC_Type *base, adc16_channel_mux_mode_t mode)
+{
+ if (kADC16_ChannelMuxA == mode)
+ {
+ base->CFG2 &= ~ADC_CFG2_MUXSEL_MASK;
+ }
+ else /* kADC16_ChannelMuxB. */
+ {
+ base->CFG2 |= ADC_CFG2_MUXSEL_MASK;
+ }
+}
+#endif /* FSL_FEATURE_ADC16_HAS_MUX_SELECT */
+
+void ADC16_SetHardwareCompareConfig(ADC_Type *base, const adc16_hardware_compare_config_t *config)
+{
+ uint32_t tmp32 = base->SC2 & ~(ADC_SC2_ACFE_MASK | ADC_SC2_ACFGT_MASK | ADC_SC2_ACREN_MASK);
+
+ if (!config) /* Pass "NULL" to disable the feature. */
+ {
+ base->SC2 = tmp32;
+ return;
+ }
+ /* Enable the feature. */
+ tmp32 |= ADC_SC2_ACFE_MASK;
+
+ /* Select the hardware compare working mode. */
+ switch (config->hardwareCompareMode)
+ {
+ case kADC16_HardwareCompareMode0:
+ break;
+ case kADC16_HardwareCompareMode1:
+ tmp32 |= ADC_SC2_ACFGT_MASK;
+ break;
+ case kADC16_HardwareCompareMode2:
+ tmp32 |= ADC_SC2_ACREN_MASK;
+ break;
+ case kADC16_HardwareCompareMode3:
+ tmp32 |= ADC_SC2_ACFGT_MASK | ADC_SC2_ACREN_MASK;
+ break;
+ default:
+ break;
+ }
+ base->SC2 = tmp32;
+
+ /* Load the compare values. */
+ base->CV1 = ADC_CV1_CV(config->value1);
+ base->CV2 = ADC_CV2_CV(config->value2);
+}
+
+#if defined(FSL_FEATURE_ADC16_HAS_HW_AVERAGE) && FSL_FEATURE_ADC16_HAS_HW_AVERAGE
+void ADC16_SetHardwareAverage(ADC_Type *base, adc16_hardware_average_mode_t mode)
+{
+ uint32_t tmp32 = base->SC3 & ~(ADC_SC3_AVGE_MASK | ADC_SC3_AVGS_MASK);
+
+ if (kADC16_HardwareAverageDisabled != mode)
+ {
+ tmp32 |= ADC_SC3_AVGE_MASK | ADC_SC3_AVGS(mode);
+ }
+ base->SC3 = tmp32;
+}
+#endif /* FSL_FEATURE_ADC16_HAS_HW_AVERAGE */
+
+#if defined(FSL_FEATURE_ADC16_HAS_PGA) && FSL_FEATURE_ADC16_HAS_PGA
+void ADC16_SetPGAConfig(ADC_Type *base, const adc16_pga_config_t *config)
+{
+ uint32_t tmp32;
+
+ if (!config) /* Passing "NULL" is to disable the feature. */
+ {
+ base->PGA = 0U;
+ return;
+ }
+
+ /* Enable the PGA and set the gain value. */
+ tmp32 = ADC_PGA_PGAEN_MASK | ADC_PGA_PGAG(config->pgaGain);
+
+ /* Configure the misc features for PGA. */
+ if (config->enableRunInNormalMode)
+ {
+ tmp32 |= ADC_PGA_PGALPb_MASK;
+ }
+#if defined(FSL_FEATURE_ADC16_HAS_PGA_CHOPPING) && FSL_FEATURE_ADC16_HAS_PGA_CHOPPING
+ if (config->disablePgaChopping)
+ {
+ tmp32 |= ADC_PGA_PGACHPb_MASK;
+ }
+#endif /* FSL_FEATURE_ADC16_HAS_PGA_CHOPPING */
+#if defined(FSL_FEATURE_ADC16_HAS_PGA_OFFSET_MEASUREMENT) && FSL_FEATURE_ADC16_HAS_PGA_OFFSET_MEASUREMENT
+ if (config->enableRunInOffsetMeasurement)
+ {
+ tmp32 |= ADC_PGA_PGAOFSM_MASK;
+ }
+#endif /* FSL_FEATURE_ADC16_HAS_PGA_OFFSET_MEASUREMENT */
+ base->PGA = tmp32;
+}
+#endif /* FSL_FEATURE_ADC16_HAS_PGA */
+
+uint32_t ADC16_GetStatusFlags(ADC_Type *base)
+{
+ uint32_t ret = 0;
+
+ if (0U != (base->SC2 & ADC_SC2_ADACT_MASK))
+ {
+ ret |= kADC16_ActiveFlag;
+ }
+#if defined(FSL_FEATURE_ADC16_HAS_CALIBRATION) && FSL_FEATURE_ADC16_HAS_CALIBRATION
+ if (0U != (base->SC3 & ADC_SC3_CALF_MASK))
+ {
+ ret |= kADC16_CalibrationFailedFlag;
+ }
+#endif /* FSL_FEATURE_ADC16_HAS_CALIBRATION */
+ return ret;
+}
+
+void ADC16_ClearStatusFlags(ADC_Type *base, uint32_t mask)
+{
+#if defined(FSL_FEATURE_ADC16_HAS_CALIBRATION) && FSL_FEATURE_ADC16_HAS_CALIBRATION
+ if (0U != (mask & kADC16_CalibrationFailedFlag))
+ {
+ base->SC3 |= ADC_SC3_CALF_MASK;
+ }
+#endif /* FSL_FEATURE_ADC16_HAS_CALIBRATION */
+}
+
+void ADC16_SetChannelConfig(ADC_Type *base, uint32_t channelGroup, const adc16_channel_config_t *config)
+{
+ assert(channelGroup < ADC_SC1_COUNT);
+ assert(NULL != config);
+
+ uint32_t sc1 = ADC_SC1_ADCH(config->channelNumber); /* Set the channel number. */
+
+#if defined(FSL_FEATURE_ADC16_HAS_DIFF_MODE) && FSL_FEATURE_ADC16_HAS_DIFF_MODE
+ /* Enable the differential conversion. */
+ if (config->enableDifferentialConversion)
+ {
+ sc1 |= ADC_SC1_DIFF_MASK;
+ }
+#endif /* FSL_FEATURE_ADC16_HAS_DIFF_MODE */
+ /* Enable the interrupt when the conversion is done. */
+ if (config->enableInterruptOnConversionCompleted)
+ {
+ sc1 |= ADC_SC1_AIEN_MASK;
+ }
+ base->SC1[channelGroup] = sc1;
+}
+
+uint32_t ADC16_GetChannelStatusFlags(ADC_Type *base, uint32_t channelGroup)
+{
+ assert(channelGroup < ADC_SC1_COUNT);
+
+ uint32_t ret = 0U;
+
+ if (0U != (base->SC1[channelGroup] & ADC_SC1_COCO_MASK))
+ {
+ ret |= kADC16_ChannelConversionDoneFlag;
+ }
+ return ret;
+}
diff --git a/drivers/fsl_adc16.h b/drivers/fsl_adc16.h
new file mode 100644
index 0000000..7f5169a
--- /dev/null
+++ b/drivers/fsl_adc16.h
@@ -0,0 +1,526 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_ADC16_H_
+#define _FSL_ADC16_H_
+
+#include "fsl_common.h"
+
+/*!
+ * @addtogroup adc16
+ * @{
+ */
+
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+/*! @name Driver version */
+/*@{*/
+/*! @brief ADC16 driver version 2.0.0. */
+#define FSL_ADC16_DRIVER_VERSION (MAKE_VERSION(2, 0, 0))
+/*@}*/
+
+/*!
+ * @brief Channel status flags.
+ */
+enum _adc16_channel_status_flags
+{
+ kADC16_ChannelConversionDoneFlag = ADC_SC1_COCO_MASK, /*!< Conversion done. */
+};
+
+/*!
+ * @brief Converter status flags.
+ */
+enum _adc16_status_flags
+{
+ kADC16_ActiveFlag = ADC_SC2_ADACT_MASK, /*!< Converter is active. */
+#if defined(FSL_FEATURE_ADC16_HAS_CALIBRATION) && FSL_FEATURE_ADC16_HAS_CALIBRATION
+ kADC16_CalibrationFailedFlag = ADC_SC3_CALF_MASK, /*!< Calibration is failed. */
+#endif /* FSL_FEATURE_ADC16_HAS_CALIBRATION */
+};
+
+#if defined(FSL_FEATURE_ADC16_HAS_MUX_SELECT) && FSL_FEATURE_ADC16_HAS_MUX_SELECT
+/*!
+ * @brief Channel multiplexer mode for each channel.
+ *
+ * For some ADC16 channels, there are two pin selections in channel multiplexer. For example, ADC0_SE4a and ADC0_SE4b
+ * are the different channels but share the same channel number.
+ */
+typedef enum _adc_channel_mux_mode
+{
+ kADC16_ChannelMuxA = 0U, /*!< For channel with channel mux a. */
+ kADC16_ChannelMuxB = 1U, /*!< For channel with channel mux b. */
+} adc16_channel_mux_mode_t;
+#endif /* FSL_FEATURE_ADC16_HAS_MUX_SELECT */
+
+/*!
+ * @brief Clock divider for the converter.
+ */
+typedef enum _adc16_clock_divider
+{
+ kADC16_ClockDivider1 = 0U, /*!< For divider 1 from the input clock to the module. */
+ kADC16_ClockDivider2 = 1U, /*!< For divider 2 from the input clock to the module. */
+ kADC16_ClockDivider4 = 2U, /*!< For divider 4 from the input clock to the module. */
+ kADC16_ClockDivider8 = 3U, /*!< For divider 8 from the input clock to the module. */
+} adc16_clock_divider_t;
+
+/*!
+ *@brief Converter's resolution.
+ */
+typedef enum _adc16_resolution
+{
+ /* This group of enumeration is for internal use which is related to register setting. */
+ kADC16_Resolution8or9Bit = 0U, /*!< Single End 8-bit or Differential Sample 9-bit. */
+ kADC16_Resolution12or13Bit = 1U, /*!< Single End 12-bit or Differential Sample 13-bit. */
+ kADC16_Resolution10or11Bit = 2U, /*!< Single End 10-bit or Differential Sample 11-bit. */
+
+ /* This group of enumeration is for public user. */
+ kADC16_ResolutionSE8Bit = kADC16_Resolution8or9Bit, /*!< Single End 8-bit. */
+ kADC16_ResolutionSE12Bit = kADC16_Resolution12or13Bit, /*!< Single End 12-bit. */
+ kADC16_ResolutionSE10Bit = kADC16_Resolution10or11Bit, /*!< Single End 10-bit. */
+#if defined(FSL_FEATURE_ADC16_HAS_DIFF_MODE) && FSL_FEATURE_ADC16_HAS_DIFF_MODE
+ kADC16_ResolutionDF9Bit = kADC16_Resolution8or9Bit, /*!< Differential Sample 9-bit. */
+ kADC16_ResolutionDF13Bit = kADC16_Resolution12or13Bit, /*!< Differential Sample 13-bit. */
+ kADC16_ResolutionDF11Bit = kADC16_Resolution10or11Bit, /*!< Differential Sample 11-bit. */
+#endif /* FSL_FEATURE_ADC16_HAS_DIFF_MODE */
+
+#if defined(FSL_FEATURE_ADC16_MAX_RESOLUTION) && (FSL_FEATURE_ADC16_MAX_RESOLUTION >= 16U)
+ /* 16-bit is supported by default. */
+ kADC16_Resolution16Bit = 3U, /*!< Single End 16-bit or Differential Sample 16-bit. */
+ kADC16_ResolutionSE16Bit = kADC16_Resolution16Bit, /*!< Single End 16-bit. */
+#if defined(FSL_FEATURE_ADC16_HAS_DIFF_MODE) && FSL_FEATURE_ADC16_HAS_DIFF_MODE
+ kADC16_ResolutionDF16Bit = kADC16_Resolution16Bit, /*!< Differential Sample 16-bit. */
+#endif /* FSL_FEATURE_ADC16_HAS_DIFF_MODE */
+#endif /* FSL_FEATURE_ADC16_MAX_RESOLUTION >= 16U */
+} adc16_resolution_t;
+
+/*!
+ * @brief Clock source.
+ */
+typedef enum _adc16_clock_source
+{
+ kADC16_ClockSourceAlt0 = 0U, /*!< Selection 0 of the clock source. */
+ kADC16_ClockSourceAlt1 = 1U, /*!< Selection 1 of the clock source. */
+ kADC16_ClockSourceAlt2 = 2U, /*!< Selection 2 of the clock source. */
+ kADC16_ClockSourceAlt3 = 3U, /*!< Selection 3 of the clock source. */
+
+ /* Chip defined clock source */
+ kADC16_ClockSourceAsynchronousClock = kADC16_ClockSourceAlt3, /*!< Using internal asynchronous clock. */
+} adc16_clock_source_t;
+
+/*!
+ * @brief Long sample mode.
+ */
+typedef enum _adc16_long_sample_mode
+{
+ kADC16_LongSampleCycle24 = 0U, /*!< 20 extra ADCK cycles, 24 ADCK cycles total. */
+ kADC16_LongSampleCycle16 = 1U, /*!< 12 extra ADCK cycles, 16 ADCK cycles total. */
+ kADC16_LongSampleCycle10 = 2U, /*!< 6 extra ADCK cycles, 10 ADCK cycles total. */
+ kADC16_LongSampleCycle6 = 3U, /*!< 2 extra ADCK cycles, 6 ADCK cycles total. */
+ kADC16_LongSampleDisabled = 4U, /*!< Disable the long sample feature. */
+} adc16_long_sample_mode_t;
+
+/*!
+ * @brief Reference voltage source.
+ */
+typedef enum _adc16_reference_voltage_source
+{
+ kADC16_ReferenceVoltageSourceVref = 0U, /*!< For external pins pair of VrefH and VrefL. */
+ kADC16_ReferenceVoltageSourceValt = 1U, /*!< For alternate reference pair of ValtH and ValtL. */
+} adc16_reference_voltage_source_t;
+
+#if defined(FSL_FEATURE_ADC16_HAS_HW_AVERAGE) && FSL_FEATURE_ADC16_HAS_HW_AVERAGE
+/*!
+ * @brief Hardware average mode.
+ */
+typedef enum _adc16_hardware_average_mode
+{
+ kADC16_HardwareAverageCount4 = 0U, /*!< For hardware average with 4 samples. */
+ kADC16_HardwareAverageCount8 = 1U, /*!< For hardware average with 8 samples. */
+ kADC16_HardwareAverageCount16 = 2U, /*!< For hardware average with 16 samples. */
+ kADC16_HardwareAverageCount32 = 3U, /*!< For hardware average with 32 samples. */
+ kADC16_HardwareAverageDisabled = 4U, /*!< Disable the hardware average feature.*/
+} adc16_hardware_average_mode_t;
+#endif /* FSL_FEATURE_ADC16_HAS_HW_AVERAGE */
+
+/*!
+ * @brief Hardware compare mode.
+ */
+typedef enum _adc16_hardware_compare_mode
+{
+ kADC16_HardwareCompareMode0 = 0U, /*!< x < value1. */
+ kADC16_HardwareCompareMode1 = 1U, /*!< x > value1. */
+ kADC16_HardwareCompareMode2 = 2U, /*!< if value1 <= value2, then x < value1 || x > value2;
+ else, value1 > x > value2. */
+ kADC16_HardwareCompareMode3 = 3U, /*!< if value1 <= value2, then value1 <= x <= value2;
+ else x >= value1 || x <= value2. */
+} adc16_hardware_compare_mode_t;
+
+#if defined(FSL_FEATURE_ADC16_HAS_PGA) && FSL_FEATURE_ADC16_HAS_PGA
+/*!
+ * @brief PGA's Gain mode.
+ */
+typedef enum _adc16_pga_gain
+{
+ kADC16_PGAGainValueOf1 = 0U, /*!< For amplifier gain of 1. */
+ kADC16_PGAGainValueOf2 = 1U, /*!< For amplifier gain of 2. */
+ kADC16_PGAGainValueOf4 = 2U, /*!< For amplifier gain of 4. */
+ kADC16_PGAGainValueOf8 = 3U, /*!< For amplifier gain of 8. */
+ kADC16_PGAGainValueOf16 = 4U, /*!< For amplifier gain of 16. */
+ kADC16_PGAGainValueOf32 = 5U, /*!< For amplifier gain of 32. */
+ kADC16_PGAGainValueOf64 = 6U, /*!< For amplifier gain of 64. */
+} adc16_pga_gain_t;
+#endif /* FSL_FEATURE_ADC16_HAS_PGA */
+
+/*!
+ * @brief ADC16 converter configuration .
+ */
+typedef struct _adc16_config
+{
+ adc16_reference_voltage_source_t referenceVoltageSource; /*!< Select the reference voltage source. */
+ adc16_clock_source_t clockSource; /*!< Select the input clock source to converter. */
+ bool enableAsynchronousClock; /*!< Enable the asynchronous clock output. */
+ adc16_clock_divider_t clockDivider; /*!< Select the divider of input clock source. */
+ adc16_resolution_t resolution; /*!< Select the sample resolution mode. */
+ adc16_long_sample_mode_t longSampleMode; /*!< Select the long sample mode. */
+ bool enableHighSpeed; /*!< Enable the high-speed mode. */
+ bool enableLowPower; /*!< Enable low power. */
+ bool enableContinuousConversion; /*!< Enable continuous conversion mode. */
+} adc16_config_t;
+
+/*!
+ * @brief ADC16 Hardware compare configuration.
+ */
+typedef struct _adc16_hardware_compare_config
+{
+ adc16_hardware_compare_mode_t hardwareCompareMode; /*!< Select the hardware compare mode.
+ See "adc16_hardware_compare_mode_t". */
+ int16_t value1; /*!< Setting value1 for hardware compare mode. */
+ int16_t value2; /*!< Setting value2 for hardware compare mode. */
+} adc16_hardware_compare_config_t;
+
+/*!
+ * @brief ADC16 channel conversion configuration.
+ */
+typedef struct _adc16_channel_config
+{
+ uint32_t channelNumber; /*!< Setting the conversion channel number. The available range is 0-31.
+ See channel connection information for each chip in Reference
+ Manual document. */
+ bool enableInterruptOnConversionCompleted; /*!< Generate an interrupt request once the conversion is completed. */
+#if defined(FSL_FEATURE_ADC16_HAS_DIFF_MODE) && FSL_FEATURE_ADC16_HAS_DIFF_MODE
+ bool enableDifferentialConversion; /*!< Using Differential sample mode. */
+#endif /* FSL_FEATURE_ADC16_HAS_DIFF_MODE */
+} adc16_channel_config_t;
+
+#if defined(FSL_FEATURE_ADC16_HAS_PGA) && FSL_FEATURE_ADC16_HAS_PGA
+/*!
+ * @brief ADC16 programmable gain amplifier configuration.
+ */
+typedef struct _adc16_pga_config
+{
+ adc16_pga_gain_t pgaGain; /*!< Setting PGA gain. */
+ bool enableRunInNormalMode; /*!< Enable PGA working in normal mode, or low power mode by default. */
+#if defined(FSL_FEATURE_ADC16_HAS_PGA_CHOPPING) && FSL_FEATURE_ADC16_HAS_PGA_CHOPPING
+ bool disablePgaChopping; /*!< Disable the PGA chopping function.
+ The PGA employs chopping to remove/reduce offset and 1/f noise and offers
+ an offset measurement configuration that aids the offset calibration. */
+#endif /* FSL_FEATURE_ADC16_HAS_PGA_CHOPPING */
+#if defined(FSL_FEATURE_ADC16_HAS_PGA_OFFSET_MEASUREMENT) && FSL_FEATURE_ADC16_HAS_PGA_OFFSET_MEASUREMENT
+ bool enableRunInOffsetMeasurement; /*!< Enable the PGA working in offset measurement mode.
+ When this feature is enabled, the PGA disconnects itself from the external
+ inputs and auto-configures into offset measurement mode. With this field
+ set, run the ADC in the recommended settings and enable the maximum hardware
+ averaging to get the PGA offset number. The output is the
+ (PGA offset * (64+1)) for the given PGA setting. */
+#endif /* FSL_FEATURE_ADC16_HAS_PGA_OFFSET_MEASUREMENT */
+} adc16_pga_config_t;
+#endif /* FSL_FEATURE_ADC16_HAS_PGA */
+
+#if defined(__cplusplus)
+extern "C" {
+#endif
+
+/*******************************************************************************
+ * API
+ ******************************************************************************/
+
+/*!
+ * @name Initialization
+ * @{
+ */
+
+/*!
+ * @brief Initializes the ADC16 module.
+ *
+ * @param base ADC16 peripheral base address.
+ * @param config Pointer to configuration structure. See "adc16_config_t".
+ */
+void ADC16_Init(ADC_Type *base, const adc16_config_t *config);
+
+/*!
+ * @brief De-initializes the ADC16 module.
+ *
+ * @param base ADC16 peripheral base address.
+ */
+void ADC16_Deinit(ADC_Type *base);
+
+/*!
+ * @brief Gets an available pre-defined settings for converter's configuration.
+ *
+ * This function initializes the converter configuration structure with an available settings. The default values are:
+ * @code
+ * config->referenceVoltageSource = kADC16_ReferenceVoltageSourceVref;
+ * config->clockSource = kADC16_ClockSourceAsynchronousClock;
+ * config->enableAsynchronousClock = true;
+ * config->clockDivider = kADC16_ClockDivider8;
+ * config->resolution = kADC16_ResolutionSE12Bit;
+ * config->longSampleMode = kADC16_LongSampleDisabled;
+ * config->enableHighSpeed = false;
+ * config->enableLowPower = false;
+ * config->enableContinuousConversion = false;
+ * @endcode
+ * @param config Pointer to configuration structure.
+ */
+void ADC16_GetDefaultConfig(adc16_config_t *config);
+
+#if defined(FSL_FEATURE_ADC16_HAS_CALIBRATION) && FSL_FEATURE_ADC16_HAS_CALIBRATION
+/*!
+ * @brief Automates the hardware calibration.
+ *
+ * This auto calibration helps to adjust the plus/minus side gain automatically on the converter's working situation.
+ * Execute the calibration before using the converter. Note that the hardware trigger should be used
+ * during calibration.
+ *
+ * @param base ADC16 peripheral base address.
+ *
+ * @return Execution status.
+ * @retval kStatus_Success Calibration is done successfully.
+ * @retval kStatus_Fail Calibration is failed.
+ */
+status_t ADC16_DoAutoCalibration(ADC_Type *base);
+#endif /* FSL_FEATURE_ADC16_HAS_CALIBRATION */
+
+#if defined(FSL_FEATURE_ADC16_HAS_OFFSET_CORRECTION) && FSL_FEATURE_ADC16_HAS_OFFSET_CORRECTION
+/*!
+ * @brief Sets the offset value for the conversion result.
+ *
+ * This offset value takes effect on the conversion result. If the offset value is not zero, the reading result
+ * is subtracted by it. Note, the hardware calibration fills the offset value automatically.
+ *
+ * @param base ADC16 peripheral base address.
+ * @param value Setting offset value.
+ */
+static inline void ADC16_SetOffsetValue(ADC_Type *base, int16_t value)
+{
+ base->OFS = (uint32_t)(value);
+}
+#endif /* FSL_FEATURE_ADC16_HAS_OFFSET_CORRECTION */
+
+/* @} */
+
+/*!
+ * @name Advanced Feature
+ * @{
+ */
+
+#if defined(FSL_FEATURE_ADC16_HAS_DMA) && FSL_FEATURE_ADC16_HAS_DMA
+/*!
+ * @brief Enables generating the DMA trigger when conversion is completed.
+ *
+ * @param base ADC16 peripheral base address.
+ * @param enable Switcher of DMA feature. "true" means to enable, "false" means not.
+ */
+static inline void ADC16_EnableDMA(ADC_Type *base, bool enable)
+{
+ if (enable)
+ {
+ base->SC2 |= ADC_SC2_DMAEN_MASK;
+ }
+ else
+ {
+ base->SC2 &= ~ADC_SC2_DMAEN_MASK;
+ }
+}
+#endif /* FSL_FEATURE_ADC16_HAS_DMA */
+
+/*!
+ * @brief Enables the hardware trigger mode.
+ *
+ * @param base ADC16 peripheral base address.
+ * @param enable Switcher of hardware trigger feature. "true" means to enable, "false" means not.
+ */
+static inline void ADC16_EnableHardwareTrigger(ADC_Type *base, bool enable)
+{
+ if (enable)
+ {
+ base->SC2 |= ADC_SC2_ADTRG_MASK;
+ }
+ else
+ {
+ base->SC2 &= ~ADC_SC2_ADTRG_MASK;
+ }
+}
+
+#if defined(FSL_FEATURE_ADC16_HAS_MUX_SELECT) && FSL_FEATURE_ADC16_HAS_MUX_SELECT
+/*!
+ * @brief Sets the channel mux mode.
+ *
+ * Some sample pins share the same channel index. The channel mux mode decides which pin is used for an
+ * indicated channel.
+ *
+ * @param base ADC16 peripheral base address.
+ * @param mode Setting channel mux mode. See "adc16_channel_mux_mode_t".
+ */
+void ADC16_SetChannelMuxMode(ADC_Type *base, adc16_channel_mux_mode_t mode);
+#endif /* FSL_FEATURE_ADC16_HAS_MUX_SELECT */
+
+/*!
+ * @brief Configures the hardware compare mode.
+ *
+ * The hardware compare mode provides a way to process the conversion result automatically by hardware. Only the result
+ * in
+ * compare range is available. To compare the range, see "adc16_hardware_compare_mode_t", or the reference
+ * manual document for more detailed information.
+ *
+ * @param base ADC16 peripheral base address.
+ * @param config Pointer to "adc16_hardware_compare_config_t" structure. Passing "NULL" is to disable the feature.
+ */
+void ADC16_SetHardwareCompareConfig(ADC_Type *base, const adc16_hardware_compare_config_t *config);
+
+#if defined(FSL_FEATURE_ADC16_HAS_HW_AVERAGE) && FSL_FEATURE_ADC16_HAS_HW_AVERAGE
+/*!
+ * @brief Sets the hardware average mode.
+ *
+ * Hardware average mode provides a way to process the conversion result automatically by hardware. The multiple
+ * conversion results are accumulated and averaged internally. This aids reading results.
+ *
+ * @param base ADC16 peripheral base address.
+ * @param mode Setting hardware average mode. See "adc16_hardware_average_mode_t".
+ */
+void ADC16_SetHardwareAverage(ADC_Type *base, adc16_hardware_average_mode_t mode);
+#endif /* FSL_FEATURE_ADC16_HAS_HW_AVERAGE */
+
+#if defined(FSL_FEATURE_ADC16_HAS_PGA) && FSL_FEATURE_ADC16_HAS_PGA
+/*!
+ * @brief Configures the PGA for converter's front end.
+ *
+ * @param base ADC16 peripheral base address.
+ * @param config Pointer to "adc16_pga_config_t" structure. Passing "NULL" is to disable the feature.
+ */
+void ADC16_SetPGAConfig(ADC_Type *base, const adc16_pga_config_t *config);
+#endif /* FSL_FEATURE_ADC16_HAS_PGA */
+
+/*!
+ * @brief Gets the status flags of the converter.
+ *
+ * @param base ADC16 peripheral base address.
+ *
+ * @return Flags' mask if indicated flags are asserted. See "_adc16_status_flags".
+ */
+uint32_t ADC16_GetStatusFlags(ADC_Type *base);
+
+/*!
+ * @brief Clears the status flags of the converter.
+ *
+ * @param base ADC16 peripheral base address.
+ * @param mask Mask value for the cleared flags. See "_adc16_status_flags".
+ */
+void ADC16_ClearStatusFlags(ADC_Type *base, uint32_t mask);
+
+/* @} */
+
+/*!
+ * @name Conversion Channel
+ * @{
+ */
+
+/*!
+ * @brief Configures the conversion channel.
+ *
+ * This operation triggers the conversion if in software trigger mode. When in hardware trigger mode, this API
+ * configures the channel while the external trigger source helps to trigger the conversion.
+ *
+ * Note that the "Channel Group" has a detailed description.
+ * To allow sequential conversions of the ADC to be triggered by internal peripherals, the ADC can have more than one
+ * group of status and control register, one for each conversion. The channel group parameter indicates which group of
+ * registers are used channel group 0 is for Group A registers and channel group 1 is for Group B registers. The
+ * channel groups are used in a "ping-pong" approach to control the ADC operation. At any point, only one of
+ * the channel groups is actively controlling ADC conversions. Channel group 0 is used for both software and hardware
+ * trigger modes of operation. Channel groups 1 and greater indicate potentially multiple channel group registers for
+ * use only in hardware trigger mode. See the chip configuration information in the MCU reference manual about the
+ * number of SC1n registers (channel groups) specific to this device. None of the channel groups 1 or greater are used
+ * for software trigger operation and therefore writes to these channel groups do not initiate a new conversion.
+ * Updating channel group 0 while a different channel group is actively controlling a conversion is allowed and
+ * vice versa. Writing any of the channel group registers while that specific channel group is actively controlling a
+ * conversion aborts the current conversion.
+ *
+ * @param base ADC16 peripheral base address.
+ * @param channelGroup Channel group index.
+ * @param config Pointer to "adc16_channel_config_t" structure for conversion channel.
+ */
+void ADC16_SetChannelConfig(ADC_Type *base, uint32_t channelGroup, const adc16_channel_config_t *config);
+
+/*!
+ * @brief Gets the conversion value.
+ *
+ * @param base ADC16 peripheral base address.
+ * @param channelGroup Channel group index.
+ *
+ * @return Conversion value.
+ */
+static inline uint32_t ADC16_GetChannelConversionValue(ADC_Type *base, uint32_t channelGroup)
+{
+ assert(channelGroup < ADC_R_COUNT);
+
+ return base->R[channelGroup];
+}
+
+/*!
+ * @brief Gets the status flags of channel.
+ *
+ * @param base ADC16 peripheral base address.
+ * @param channelGroup Channel group index.
+ *
+ * @return Flags' mask if indicated flags are asserted. See "_adc16_channel_status_flags".
+ */
+uint32_t ADC16_GetChannelStatusFlags(ADC_Type *base, uint32_t channelGroup);
+
+/* @} */
+
+#if defined(__cplusplus)
+}
+#endif
+/*!
+ * @}
+ */
+#endif /* _FSL_ADC16_H_ */
diff --git a/drivers/fsl_clock.c b/drivers/fsl_clock.c
new file mode 100644
index 0000000..b5549aa
--- /dev/null
+++ b/drivers/fsl_clock.c
@@ -0,0 +1,1751 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_common.h"
+#include "fsl_clock.h"
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+/* Macro definition remap workaround. */
+#if (defined(MCG_C2_EREFS_MASK) && !(defined(MCG_C2_EREFS0_MASK)))
+#define MCG_C2_EREFS0_MASK MCG_C2_EREFS_MASK
+#endif
+#if (defined(MCG_C2_HGO_MASK) && !(defined(MCG_C2_HGO0_MASK)))
+#define MCG_C2_HGO0_MASK MCG_C2_HGO_MASK
+#endif
+#if (defined(MCG_C2_RANGE_MASK) && !(defined(MCG_C2_RANGE0_MASK)))
+#define MCG_C2_RANGE0_MASK MCG_C2_RANGE_MASK
+#endif
+#if (defined(MCG_C6_CME_MASK) && !(defined(MCG_C6_CME0_MASK)))
+#define MCG_C6_CME0_MASK MCG_C6_CME_MASK
+#endif
+
+/* PLL fixed multiplier when there is not PRDIV and VDIV. */
+#define PLL_FIXED_MULT (375U)
+/* Max frequency of the reference clock used for internal clock trim. */
+#define TRIM_REF_CLK_MIN (8000000U)
+/* Min frequency of the reference clock used for internal clock trim. */
+#define TRIM_REF_CLK_MAX (16000000U)
+/* Max trim value of fast internal reference clock. */
+#define TRIM_FIRC_MAX (5000000U)
+/* Min trim value of fast internal reference clock. */
+#define TRIM_FIRC_MIN (3000000U)
+/* Max trim value of fast internal reference clock. */
+#define TRIM_SIRC_MAX (39063U)
+/* Min trim value of fast internal reference clock. */
+#define TRIM_SIRC_MIN (31250U)
+
+#define MCG_S_IRCST_VAL ((MCG->S & MCG_S_IRCST_MASK) >> MCG_S_IRCST_SHIFT)
+#define MCG_S_CLKST_VAL ((MCG->S & MCG_S_CLKST_MASK) >> MCG_S_CLKST_SHIFT)
+#define MCG_S_IREFST_VAL ((MCG->S & MCG_S_IREFST_MASK) >> MCG_S_IREFST_SHIFT)
+#define MCG_S_PLLST_VAL ((MCG->S & MCG_S_PLLST_MASK) >> MCG_S_PLLST_SHIFT)
+#define MCG_C1_FRDIV_VAL ((MCG->C1 & MCG_C1_FRDIV_MASK) >> MCG_C1_FRDIV_SHIFT)
+#define MCG_C2_LP_VAL ((MCG->C2 & MCG_C2_LP_MASK) >> MCG_C2_LP_SHIFT)
+#define MCG_C2_RANGE_VAL ((MCG->C2 & MCG_C2_RANGE_MASK) >> MCG_C2_RANGE_SHIFT)
+#define MCG_SC_FCRDIV_VAL ((MCG->SC & MCG_SC_FCRDIV_MASK) >> MCG_SC_FCRDIV_SHIFT)
+#define MCG_S2_PLLCST_VAL ((MCG->S2 & MCG_S2_PLLCST_MASK) >> MCG_S2_PLLCST_SHIFT)
+#define MCG_C7_OSCSEL_VAL ((MCG->C7 & MCG_C7_OSCSEL_MASK) >> MCG_C7_OSCSEL_SHIFT)
+#define MCG_C4_DMX32_VAL ((MCG->C4 & MCG_C4_DMX32_MASK) >> MCG_C4_DMX32_SHIFT)
+#define MCG_C4_DRST_DRS_VAL ((MCG->C4 & MCG_C4_DRST_DRS_MASK) >> MCG_C4_DRST_DRS_SHIFT)
+#define MCG_C7_PLL32KREFSEL_VAL ((MCG->C7 & MCG_C7_PLL32KREFSEL_MASK) >> MCG_C7_PLL32KREFSEL_SHIFT)
+#define MCG_C5_PLLREFSEL0_VAL ((MCG->C5 & MCG_C5_PLLREFSEL0_MASK) >> MCG_C5_PLLREFSEL0_SHIFT)
+#define MCG_C11_PLLREFSEL1_VAL ((MCG->C11 & MCG_C11_PLLREFSEL1_MASK) >> MCG_C11_PLLREFSEL1_SHIFT)
+#define MCG_C11_PRDIV1_VAL ((MCG->C11 & MCG_C11_PRDIV1_MASK) >> MCG_C11_PRDIV1_SHIFT)
+#define MCG_C12_VDIV1_VAL ((MCG->C12 & MCG_C12_VDIV1_MASK) >> MCG_C12_VDIV1_SHIFT)
+#define MCG_C5_PRDIV0_VAL ((MCG->C5 & MCG_C5_PRDIV0_MASK) >> MCG_C5_PRDIV0_SHIFT)
+#define MCG_C6_VDIV0_VAL ((MCG->C6 & MCG_C6_VDIV0_MASK) >> MCG_C6_VDIV0_SHIFT)
+
+#define OSC_MODE_MASK (MCG_C2_EREFS0_MASK | MCG_C2_HGO0_MASK | MCG_C2_RANGE0_MASK)
+
+#define SIM_CLKDIV1_OUTDIV1_VAL ((SIM->CLKDIV1 & SIM_CLKDIV1_OUTDIV1_MASK) >> SIM_CLKDIV1_OUTDIV1_SHIFT)
+#define SIM_CLKDIV1_OUTDIV2_VAL ((SIM->CLKDIV1 & SIM_CLKDIV1_OUTDIV2_MASK) >> SIM_CLKDIV1_OUTDIV2_SHIFT)
+#define SIM_CLKDIV1_OUTDIV3_VAL ((SIM->CLKDIV1 & SIM_CLKDIV1_OUTDIV3_MASK) >> SIM_CLKDIV1_OUTDIV3_SHIFT)
+#define SIM_CLKDIV1_OUTDIV4_VAL ((SIM->CLKDIV1 & SIM_CLKDIV1_OUTDIV4_MASK) >> SIM_CLKDIV1_OUTDIV4_SHIFT)
+#define SIM_SOPT1_OSC32KSEL_VAL ((SIM->SOPT1 & SIM_SOPT1_OSC32KSEL_MASK) >> SIM_SOPT1_OSC32KSEL_SHIFT)
+#define SIM_SOPT2_PLLFLLSEL_VAL ((SIM->SOPT2 & SIM_SOPT2_PLLFLLSEL_MASK) >> SIM_SOPT2_PLLFLLSEL_SHIFT)
+
+/* MCG_S_CLKST definition. */
+enum _mcg_clkout_stat
+{
+ kMCG_ClkOutStatFll, /* FLL. */
+ kMCG_ClkOutStatInt, /* Internal clock. */
+ kMCG_ClkOutStatExt, /* External clock. */
+ kMCG_ClkOutStatPll /* PLL. */
+};
+
+/* MCG_S_PLLST definition. */
+enum _mcg_pllst
+{
+ kMCG_PllstFll, /* FLL is used. */
+ kMCG_PllstPll /* PLL is used. */
+};
+
+/*******************************************************************************
+ * Variables
+ ******************************************************************************/
+
+/* Slow internal reference clock frequency. */
+static uint32_t s_slowIrcFreq = 32768U;
+/* Fast internal reference clock frequency. */
+static uint32_t s_fastIrcFreq = 4000000U;
+
+/* External XTAL0 (OSC0) clock frequency. */
+uint32_t g_xtal0Freq;
+/* External XTAL32K clock frequency. */
+uint32_t g_xtal32Freq;
+
+/*******************************************************************************
+ * Prototypes
+ ******************************************************************************/
+
+/*!
+ * @brief Get the MCG external reference clock frequency.
+ *
+ * Get the current MCG external reference clock frequency in Hz. It is
+ * the frequency select by MCG_C7[OSCSEL]. This is an internal function.
+ *
+ * @return MCG external reference clock frequency in Hz.
+ */
+static uint32_t CLOCK_GetMcgExtClkFreq(void);
+
+/*!
+ * @brief Get the MCG FLL external reference clock frequency.
+ *
+ * Get the current MCG FLL external reference clock frequency in Hz. It is
+ * the frequency after by MCG_C1[FRDIV]. This is an internal function.
+ *
+ * @return MCG FLL external reference clock frequency in Hz.
+ */
+static uint32_t CLOCK_GetFllExtRefClkFreq(void);
+
+/*!
+ * @brief Get the MCG FLL reference clock frequency.
+ *
+ * Get the current MCG FLL reference clock frequency in Hz. It is
+ * the frequency select by MCG_C1[IREFS]. This is an internal function.
+ *
+ * @return MCG FLL reference clock frequency in Hz.
+ */
+static uint32_t CLOCK_GetFllRefClkFreq(void);
+
+/*!
+ * @brief Get the frequency of clock selected by MCG_C2[IRCS].
+ *
+ * This clock's two output:
+ * 1. MCGOUTCLK when MCG_S[CLKST]=0.
+ * 2. MCGIRCLK when MCG_C1[IRCLKEN]=1.
+ *
+ * @return The frequency in Hz.
+ */
+static uint32_t CLOCK_GetInternalRefClkSelectFreq(void);
+
+/*!
+ * @brief Get the MCG PLL/PLL0 reference clock frequency.
+ *
+ * Get the current MCG PLL/PLL0 reference clock frequency in Hz.
+ * This is an internal function.
+ *
+ * @return MCG PLL/PLL0 reference clock frequency in Hz.
+ */
+static uint32_t CLOCK_GetPll0RefFreq(void);
+
+/*!
+ * @brief Calculate the RANGE value base on crystal frequency.
+ *
+ * To setup external crystal oscillator, must set the register bits RANGE
+ * base on the crystal frequency. This function returns the RANGE base on the
+ * input frequency. This is an internal function.
+ *
+ * @param freq Crystal frequency in Hz.
+ * @return The RANGE value.
+ */
+static uint8_t CLOCK_GetOscRangeFromFreq(uint32_t freq);
+
+/*!
+ * @brief Delay function to wait FLL stable.
+ *
+ * Delay function to wait FLL stable in FEI mode or FEE mode, should wait at least
+ * 1ms. Every time changes FLL setting, should wait this time for FLL stable.
+ */
+static void CLOCK_FllStableDelay(void);
+
+/*******************************************************************************
+ * Code
+ ******************************************************************************/
+
+static uint32_t CLOCK_GetMcgExtClkFreq(void)
+{
+ uint32_t freq;
+
+ switch (MCG_C7_OSCSEL_VAL)
+ {
+ case 0U:
+ /* Please call CLOCK_SetXtal0Freq base on board setting before using OSC0 clock. */
+ assert(g_xtal0Freq);
+ freq = g_xtal0Freq;
+ break;
+ case 1U:
+ /* Please call CLOCK_SetXtal32Freq base on board setting before using XTAL32K/RTC_CLKIN clock. */
+ assert(g_xtal32Freq);
+ freq = g_xtal32Freq;
+ break;
+ default:
+ freq = 0U;
+ break;
+ }
+
+ return freq;
+}
+
+static uint32_t CLOCK_GetFllExtRefClkFreq(void)
+{
+ /* FllExtRef = McgExtRef / FllExtRefDiv */
+ uint8_t frdiv;
+ uint8_t range;
+ uint8_t oscsel;
+
+ uint32_t freq = CLOCK_GetMcgExtClkFreq();
+
+ if (!freq)
+ {
+ return freq;
+ }
+
+ frdiv = MCG_C1_FRDIV_VAL;
+ freq >>= frdiv;
+
+ range = MCG_C2_RANGE_VAL;
+ oscsel = MCG_C7_OSCSEL_VAL;
+
+ /*
+ When should use divider 32, 64, 128, 256, 512, 1024, 1280, 1536.
+ 1. MCG_C7[OSCSEL] selects IRC48M.
+ 2. MCG_C7[OSCSEL] selects OSC0 and MCG_C2[RANGE] is not 0.
+ */
+ if (((0U != range) && (kMCG_OscselOsc == oscsel)))
+ {
+ switch (frdiv)
+ {
+ case 0:
+ case 1:
+ case 2:
+ case 3:
+ case 4:
+ case 5:
+ freq >>= 5u;
+ break;
+ case 6:
+ /* 64*20=1280 */
+ freq /= 20u;
+ break;
+ case 7:
+ /* 128*12=1536 */
+ freq /= 12u;
+ break;
+ default:
+ freq = 0u;
+ break;
+ }
+ }
+
+ return freq;
+}
+
+static uint32_t CLOCK_GetInternalRefClkSelectFreq(void)
+{
+ if (kMCG_IrcSlow == MCG_S_IRCST_VAL)
+ {
+ /* Slow internal reference clock selected*/
+ return s_slowIrcFreq;
+ }
+ else
+ {
+ /* Fast internal reference clock selected*/
+ return s_fastIrcFreq >> MCG_SC_FCRDIV_VAL;
+ }
+}
+
+static uint32_t CLOCK_GetFllRefClkFreq(void)
+{
+ /* If use external reference clock. */
+ if (kMCG_FllSrcExternal == MCG_S_IREFST_VAL)
+ {
+ return CLOCK_GetFllExtRefClkFreq();
+ }
+ /* If use internal reference clock. */
+ else
+ {
+ return s_slowIrcFreq;
+ }
+}
+
+static uint32_t CLOCK_GetPll0RefFreq(void)
+{
+ /* MCG external reference clock. */
+ return CLOCK_GetMcgExtClkFreq();
+}
+
+static uint8_t CLOCK_GetOscRangeFromFreq(uint32_t freq)
+{
+ uint8_t range;
+
+ if (freq <= 39063U)
+ {
+ range = 0U;
+ }
+ else if (freq <= 8000000U)
+ {
+ range = 1U;
+ }
+ else
+ {
+ range = 2U;
+ }
+
+ return range;
+}
+
+static void CLOCK_FllStableDelay(void)
+{
+ /*
+ Should wait at least 1ms. Because in these modes, the core clock is 100MHz
+ at most, so this function could obtain the 1ms delay.
+ */
+ volatile uint32_t i = 30000U;
+ while (i--)
+ {
+ __NOP();
+ }
+}
+
+uint32_t CLOCK_GetOsc0ErClkFreq(void)
+{
+ if (OSC0->CR & OSC_CR_ERCLKEN_MASK)
+ {
+ /* Please call CLOCK_SetXtal0Freq base on board setting before using OSC0 clock. */
+ assert(g_xtal0Freq);
+ return g_xtal0Freq;
+ }
+ else
+ {
+ return 0U;
+ }
+}
+
+uint32_t CLOCK_GetEr32kClkFreq(void)
+{
+ uint32_t freq;
+
+ switch (SIM_SOPT1_OSC32KSEL_VAL)
+ {
+ case 0U: /* OSC 32k clock */
+ freq = (CLOCK_GetOsc0ErClkFreq() == 32768U) ? 32768U : 0U;
+ break;
+ case 2U: /* RTC 32k clock */
+ /* Please call CLOCK_SetXtal32Freq base on board setting before using XTAL32K/RTC_CLKIN clock. */
+ assert(g_xtal32Freq);
+ freq = g_xtal32Freq;
+ break;
+ case 3U: /* LPO clock */
+ freq = LPO_CLK_FREQ;
+ break;
+ default:
+ freq = 0U;
+ break;
+ }
+ return freq;
+}
+
+uint32_t CLOCK_GetPllFllSelClkFreq(void)
+{
+ uint32_t freq;
+
+ switch (SIM_SOPT2_PLLFLLSEL_VAL)
+ {
+ case 0U: /* FLL. */
+ freq = CLOCK_GetFllFreq();
+ break;
+ case 1U: /* PLL. */
+ freq = CLOCK_GetPll0Freq();
+ break;
+ default:
+ freq = 0U;
+ break;
+ }
+
+ return freq;
+}
+
+uint32_t CLOCK_GetPlatClkFreq(void)
+{
+ return CLOCK_GetOutClkFreq() / (SIM_CLKDIV1_OUTDIV1_VAL + 1);
+}
+
+uint32_t CLOCK_GetFlashClkFreq(void)
+{
+ return CLOCK_GetOutClkFreq() / (SIM_CLKDIV1_OUTDIV4_VAL + 1);
+}
+
+uint32_t CLOCK_GetFlexBusClkFreq(void)
+{
+ return CLOCK_GetOutClkFreq() / (SIM_CLKDIV1_OUTDIV3_VAL + 1);
+}
+
+uint32_t CLOCK_GetBusClkFreq(void)
+{
+ return CLOCK_GetOutClkFreq() / (SIM_CLKDIV1_OUTDIV2_VAL + 1);
+}
+
+uint32_t CLOCK_GetCoreSysClkFreq(void)
+{
+ return CLOCK_GetOutClkFreq() / (SIM_CLKDIV1_OUTDIV1_VAL + 1);
+}
+
+uint32_t CLOCK_GetFreq(clock_name_t clockName)
+{
+ uint32_t freq;
+
+ switch (clockName)
+ {
+ case kCLOCK_CoreSysClk:
+ case kCLOCK_PlatClk:
+ freq = CLOCK_GetOutClkFreq() / (SIM_CLKDIV1_OUTDIV1_VAL + 1);
+ break;
+ case kCLOCK_BusClk:
+ freq = CLOCK_GetOutClkFreq() / (SIM_CLKDIV1_OUTDIV2_VAL + 1);
+ break;
+ case kCLOCK_FlexBusClk:
+ freq = CLOCK_GetOutClkFreq() / (SIM_CLKDIV1_OUTDIV3_VAL + 1);
+ break;
+ case kCLOCK_FlashClk:
+ freq = CLOCK_GetOutClkFreq() / (SIM_CLKDIV1_OUTDIV4_VAL + 1);
+ break;
+ case kCLOCK_PllFllSelClk:
+ freq = CLOCK_GetPllFllSelClkFreq();
+ break;
+ case kCLOCK_Er32kClk:
+ freq = CLOCK_GetEr32kClkFreq();
+ break;
+ case kCLOCK_Osc0ErClk:
+ freq = CLOCK_GetOsc0ErClkFreq();
+ break;
+ case kCLOCK_McgFixedFreqClk:
+ freq = CLOCK_GetFixedFreqClkFreq();
+ break;
+ case kCLOCK_McgInternalRefClk:
+ freq = CLOCK_GetInternalRefClkFreq();
+ break;
+ case kCLOCK_McgFllClk:
+ freq = CLOCK_GetFllFreq();
+ break;
+ case kCLOCK_McgPll0Clk:
+ freq = CLOCK_GetPll0Freq();
+ break;
+ case kCLOCK_LpoClk:
+ freq = LPO_CLK_FREQ;
+ break;
+ default:
+ freq = 0U;
+ break;
+ }
+
+ return freq;
+}
+
+void CLOCK_SetSimConfig(sim_clock_config_t const *config)
+{
+ SIM->CLKDIV1 = config->clkdiv1;
+ CLOCK_SetPllFllSelClock(config->pllFllSel);
+ CLOCK_SetEr32kClock(config->er32kSrc);
+}
+
+bool CLOCK_EnableUsbfs0Clock(clock_usb_src_t src, uint32_t freq)
+{
+ bool ret = true;
+
+ CLOCK_DisableClock(kCLOCK_Usbfs0);
+
+ if (kCLOCK_UsbSrcExt == src)
+ {
+ SIM->SOPT2 &= ~SIM_SOPT2_USBSRC_MASK;
+ }
+ else
+ {
+ switch (freq)
+ {
+ case 120000000U:
+ SIM->CLKDIV2 = SIM_CLKDIV2_USBDIV(4) | SIM_CLKDIV2_USBFRAC(1);
+ break;
+ case 96000000U:
+ SIM->CLKDIV2 = SIM_CLKDIV2_USBDIV(1) | SIM_CLKDIV2_USBFRAC(0);
+ break;
+ case 72000000U:
+ SIM->CLKDIV2 = SIM_CLKDIV2_USBDIV(2) | SIM_CLKDIV2_USBFRAC(1);
+ break;
+ case 48000000U:
+ SIM->CLKDIV2 = SIM_CLKDIV2_USBDIV(0) | SIM_CLKDIV2_USBFRAC(0);
+ break;
+ default:
+ ret = false;
+ break;
+ }
+
+ SIM->SOPT2 = ((SIM->SOPT2 & ~(SIM_SOPT2_PLLFLLSEL_MASK | SIM_SOPT2_USBSRC_MASK)) | (uint32_t)src);
+ }
+
+ CLOCK_EnableClock(kCLOCK_Usbfs0);
+
+ return ret;
+}
+
+uint32_t CLOCK_GetOutClkFreq(void)
+{
+ uint32_t mcgoutclk;
+ uint32_t clkst = MCG_S_CLKST_VAL;
+
+ switch (clkst)
+ {
+ case kMCG_ClkOutStatPll:
+ mcgoutclk = CLOCK_GetPll0Freq();
+ break;
+ case kMCG_ClkOutStatFll:
+ mcgoutclk = CLOCK_GetFllFreq();
+ break;
+ case kMCG_ClkOutStatInt:
+ mcgoutclk = CLOCK_GetInternalRefClkSelectFreq();
+ break;
+ case kMCG_ClkOutStatExt:
+ mcgoutclk = CLOCK_GetMcgExtClkFreq();
+ break;
+ default:
+ mcgoutclk = 0U;
+ break;
+ }
+ return mcgoutclk;
+}
+
+uint32_t CLOCK_GetFllFreq(void)
+{
+ static const uint16_t fllFactorTable[4][2] = {{640, 732}, {1280, 1464}, {1920, 2197}, {2560, 2929}};
+
+ uint8_t drs, dmx32;
+ uint32_t freq;
+
+ /* If FLL is not enabled currently, then return 0U. */
+ if ((MCG->C2 & MCG_C2_LP_MASK) || (MCG->S & MCG_S_PLLST_MASK))
+ {
+ return 0U;
+ }
+
+ /* Get FLL reference clock frequency. */
+ freq = CLOCK_GetFllRefClkFreq();
+ if (!freq)
+ {
+ return freq;
+ }
+
+ drs = MCG_C4_DRST_DRS_VAL;
+ dmx32 = MCG_C4_DMX32_VAL;
+
+ return freq * fllFactorTable[drs][dmx32];
+}
+
+uint32_t CLOCK_GetInternalRefClkFreq(void)
+{
+ /* If MCGIRCLK is gated. */
+ if (!(MCG->C1 & MCG_C1_IRCLKEN_MASK))
+ {
+ return 0U;
+ }
+
+ return CLOCK_GetInternalRefClkSelectFreq();
+}
+
+uint32_t CLOCK_GetFixedFreqClkFreq(void)
+{
+ uint32_t freq = CLOCK_GetFllRefClkFreq();
+
+ /* MCGFFCLK must be no more than MCGOUTCLK/8. */
+ if ((freq) && (freq <= (CLOCK_GetOutClkFreq() / 8U)))
+ {
+ return freq;
+ }
+ else
+ {
+ return 0U;
+ }
+}
+
+uint32_t CLOCK_GetPll0Freq(void)
+{
+ uint32_t mcgpll0clk;
+
+ /* If PLL0 is not enabled, return 0. */
+ if (!(MCG->S & MCG_S_LOCK0_MASK))
+ {
+ return 0U;
+ }
+
+ mcgpll0clk = CLOCK_GetPll0RefFreq();
+
+ /*
+ * Please call CLOCK_SetXtal0Freq base on board setting before using OSC0 clock.
+ * Please call CLOCK_SetXtal1Freq base on board setting before using OSC1 clock.
+ */
+ assert(mcgpll0clk);
+
+ mcgpll0clk /= (FSL_FEATURE_MCG_PLL_PRDIV_BASE + MCG_C5_PRDIV0_VAL);
+ mcgpll0clk *= (FSL_FEATURE_MCG_PLL_VDIV_BASE + MCG_C6_VDIV0_VAL);
+
+ return mcgpll0clk;
+}
+
+status_t CLOCK_SetExternalRefClkConfig(mcg_oscsel_t oscsel)
+{
+ bool needDelay;
+ uint32_t i;
+
+#if (defined(MCG_CONFIG_CHECK_PARAM) && MCG_CONFIG_CHECK_PARAM)
+ /* If change MCG_C7[OSCSEL] and external reference clock is system clock source, return error. */
+ if ((MCG_C7_OSCSEL_VAL != oscsel) && (!(MCG->S & MCG_S_IREFST_MASK)))
+ {
+ return kStatus_MCG_SourceUsed;
+ }
+#endif /* MCG_CONFIG_CHECK_PARAM */
+
+ if (MCG_C7_OSCSEL_VAL != oscsel)
+ {
+ /* If change OSCSEL, need to delay, ERR009878. */
+ needDelay = true;
+ }
+ else
+ {
+ needDelay = false;
+ }
+
+ MCG->C7 = (MCG->C7 & ~MCG_C7_OSCSEL_MASK) | MCG_C7_OSCSEL(oscsel);
+ if (kMCG_OscselOsc == oscsel)
+ {
+ if (MCG->C2 & MCG_C2_EREFS_MASK)
+ {
+ while (!(MCG->S & MCG_S_OSCINIT0_MASK))
+ {
+ }
+ }
+ }
+
+ if (needDelay)
+ {
+ /* ERR009878 Delay at least 50 micro-seconds for external clock change valid. */
+ i = 1500U;
+ while (i--)
+ {
+ __NOP();
+ }
+ }
+
+ return kStatus_Success;
+}
+
+status_t CLOCK_SetInternalRefClkConfig(uint8_t enableMode, mcg_irc_mode_t ircs, uint8_t fcrdiv)
+{
+ uint32_t mcgOutClkState = MCG_S_CLKST_VAL;
+ mcg_irc_mode_t curIrcs = (mcg_irc_mode_t)MCG_S_IRCST_VAL;
+ uint8_t curFcrdiv = MCG_SC_FCRDIV_VAL;
+
+#if (defined(MCG_CONFIG_CHECK_PARAM) && MCG_CONFIG_CHECK_PARAM)
+ /* If MCGIRCLK is used as system clock source. */
+ if (kMCG_ClkOutStatInt == mcgOutClkState)
+ {
+ /* If need to change MCGIRCLK source or driver, return error. */
+ if (((kMCG_IrcFast == curIrcs) && (fcrdiv != curFcrdiv)) || (ircs != curIrcs))
+ {
+ return kStatus_MCG_SourceUsed;
+ }
+ }
+#endif
+
+ /* If need to update the FCRDIV. */
+ if (fcrdiv != curFcrdiv)
+ {
+ /* If fast IRC is in use currently, change to slow IRC. */
+ if ((kMCG_IrcFast == curIrcs) && ((mcgOutClkState == kMCG_ClkOutStatInt) || (MCG->C1 & MCG_C1_IRCLKEN_MASK)))
+ {
+ MCG->C2 = ((MCG->C2 & ~MCG_C2_IRCS_MASK) | (MCG_C2_IRCS(kMCG_IrcSlow)));
+ while (MCG_S_IRCST_VAL != kMCG_IrcSlow)
+ {
+ }
+ }
+ /* Update FCRDIV. */
+ MCG->SC = (MCG->SC & ~(MCG_SC_FCRDIV_MASK | MCG_SC_ATMF_MASK | MCG_SC_LOCS0_MASK)) | MCG_SC_FCRDIV(fcrdiv);
+ }
+
+ /* Set internal reference clock selection. */
+ MCG->C2 = (MCG->C2 & ~MCG_C2_IRCS_MASK) | (MCG_C2_IRCS(ircs));
+ MCG->C1 = (MCG->C1 & ~(MCG_C1_IRCLKEN_MASK | MCG_C1_IREFSTEN_MASK)) | (uint8_t)enableMode;
+
+ /* If MCGIRCLK is used, need to wait for MCG_S_IRCST. */
+ if ((mcgOutClkState == kMCG_ClkOutStatInt) || (enableMode & kMCG_IrclkEnable))
+ {
+ while (MCG_S_IRCST_VAL != ircs)
+ {
+ }
+ }
+
+ return kStatus_Success;
+}
+
+uint32_t CLOCK_CalcPllDiv(uint32_t refFreq, uint32_t desireFreq, uint8_t *prdiv, uint8_t *vdiv)
+{
+ uint8_t ret_prdiv; /* PRDIV to return. */
+ uint8_t ret_vdiv; /* VDIV to return. */
+ uint8_t prdiv_min; /* Min PRDIV value to make reference clock in allowed range. */
+ uint8_t prdiv_max; /* Max PRDIV value to make reference clock in allowed range. */
+ uint8_t prdiv_cur; /* PRDIV value for iteration. */
+ uint8_t vdiv_cur; /* VDIV value for iteration. */
+ uint32_t ret_freq = 0U; /* PLL output fequency to return. */
+ uint32_t diff = 0xFFFFFFFFU; /* Difference between desireFreq and return frequency. */
+ uint32_t ref_div; /* Reference frequency after PRDIV. */
+
+ /*
+ Steps:
+ 1. Get allowed prdiv with such rules:
+ 1). refFreq / prdiv >= FSL_FEATURE_MCG_PLL_REF_MIN.
+ 2). refFreq / prdiv <= FSL_FEATURE_MCG_PLL_REF_MAX.
+ 2. For each allowed prdiv, there are two candidate vdiv values:
+ 1). (desireFreq / (refFreq / prdiv)).
+ 2). (desireFreq / (refFreq / prdiv)) + 1.
+ If could get the precise desired frequency, return current prdiv and
+ vdiv directly. Otherwise choose the one which is closer to desired
+ frequency.
+ */
+
+ /* Reference frequency is out of range. */
+ if ((refFreq < FSL_FEATURE_MCG_PLL_REF_MIN) ||
+ (refFreq > (FSL_FEATURE_MCG_PLL_REF_MAX * (FSL_FEATURE_MCG_PLL_PRDIV_MAX + FSL_FEATURE_MCG_PLL_PRDIV_BASE))))
+ {
+ return 0U;
+ }
+
+ /* refFreq/PRDIV must in a range. First get the allowed PRDIV range. */
+ prdiv_max = refFreq / FSL_FEATURE_MCG_PLL_REF_MIN;
+ prdiv_min = (refFreq + FSL_FEATURE_MCG_PLL_REF_MAX - 1U) / FSL_FEATURE_MCG_PLL_REF_MAX;
+
+ /* PRDIV traversal. */
+ for (prdiv_cur = prdiv_max; prdiv_cur >= prdiv_min; prdiv_cur--)
+ {
+ /* Reference frequency after PRDIV. */
+ ref_div = refFreq / prdiv_cur;
+
+ vdiv_cur = desireFreq / ref_div;
+
+ if ((vdiv_cur < FSL_FEATURE_MCG_PLL_VDIV_BASE - 1U) || (vdiv_cur > FSL_FEATURE_MCG_PLL_VDIV_BASE + 31U))
+ {
+ /* No VDIV is available with this PRDIV. */
+ continue;
+ }
+
+ ret_freq = vdiv_cur * ref_div;
+
+ if (vdiv_cur >= FSL_FEATURE_MCG_PLL_VDIV_BASE)
+ {
+ if (ret_freq == desireFreq) /* If desire frequency is got. */
+ {
+ *prdiv = prdiv_cur - FSL_FEATURE_MCG_PLL_PRDIV_BASE;
+ *vdiv = vdiv_cur - FSL_FEATURE_MCG_PLL_VDIV_BASE;
+ return ret_freq;
+ }
+ /* New PRDIV/VDIV is closer. */
+ if (diff > desireFreq - ret_freq)
+ {
+ diff = desireFreq - ret_freq;
+ ret_prdiv = prdiv_cur;
+ ret_vdiv = vdiv_cur;
+ }
+ }
+ vdiv_cur++;
+ if (vdiv_cur <= (FSL_FEATURE_MCG_PLL_VDIV_BASE + 31U))
+ {
+ ret_freq += ref_div;
+ /* New PRDIV/VDIV is closer. */
+ if (diff > ret_freq - desireFreq)
+ {
+ diff = ret_freq - desireFreq;
+ ret_prdiv = prdiv_cur;
+ ret_vdiv = vdiv_cur;
+ }
+ }
+ }
+
+ if (0xFFFFFFFFU != diff)
+ {
+ /* PRDIV/VDIV found. */
+ *prdiv = ret_prdiv - FSL_FEATURE_MCG_PLL_PRDIV_BASE;
+ *vdiv = ret_vdiv - FSL_FEATURE_MCG_PLL_VDIV_BASE;
+ ret_freq = (refFreq / ret_prdiv) * ret_vdiv;
+ return ret_freq;
+ }
+ else
+ {
+ /* No proper PRDIV/VDIV found. */
+ return 0U;
+ }
+}
+
+void CLOCK_EnablePll0(mcg_pll_config_t const *config)
+{
+ assert(config);
+
+ uint8_t mcg_c5 = 0U;
+
+ mcg_c5 |= MCG_C5_PRDIV0(config->prdiv);
+ MCG->C5 = mcg_c5; /* Disable the PLL first. */
+
+ MCG->C6 = (MCG->C6 & ~MCG_C6_VDIV0_MASK) | MCG_C6_VDIV0(config->vdiv);
+
+ /* Set enable mode. */
+ MCG->C5 |= ((uint32_t)kMCG_PllEnableIndependent | (uint32_t)config->enableMode);
+
+ /* Wait for PLL lock. */
+ while (!(MCG->S & MCG_S_LOCK0_MASK))
+ {
+ }
+}
+
+void CLOCK_SetOsc0MonitorMode(mcg_monitor_mode_t mode)
+{
+ /* Clear the previous flag, MCG_SC[LOCS0]. */
+ MCG->SC &= ~MCG_SC_ATMF_MASK;
+
+ if (kMCG_MonitorNone == mode)
+ {
+ MCG->C6 &= ~MCG_C6_CME0_MASK;
+ }
+ else
+ {
+ if (kMCG_MonitorInt == mode)
+ {
+ MCG->C2 &= ~MCG_C2_LOCRE0_MASK;
+ }
+ else
+ {
+ MCG->C2 |= MCG_C2_LOCRE0_MASK;
+ }
+ MCG->C6 |= MCG_C6_CME0_MASK;
+ }
+}
+
+void CLOCK_SetRtcOscMonitorMode(mcg_monitor_mode_t mode)
+{
+ uint8_t mcg_c8 = MCG->C8;
+
+ mcg_c8 &= ~(MCG_C8_CME1_MASK | MCG_C8_LOCRE1_MASK);
+
+ if (kMCG_MonitorNone != mode)
+ {
+ if (kMCG_MonitorReset == mode)
+ {
+ mcg_c8 |= MCG_C8_LOCRE1_MASK;
+ }
+ mcg_c8 |= MCG_C8_CME1_MASK;
+ }
+ MCG->C8 = mcg_c8;
+}
+
+void CLOCK_SetPll0MonitorMode(mcg_monitor_mode_t mode)
+{
+ uint8_t mcg_c8;
+
+ /* Clear previous flag. */
+ MCG->S = MCG_S_LOLS0_MASK;
+
+ if (kMCG_MonitorNone == mode)
+ {
+ MCG->C6 &= ~MCG_C6_LOLIE0_MASK;
+ }
+ else
+ {
+ mcg_c8 = MCG->C8;
+
+ mcg_c8 &= ~MCG_C8_LOCS1_MASK;
+
+ if (kMCG_MonitorInt == mode)
+ {
+ mcg_c8 &= ~MCG_C8_LOLRE_MASK;
+ }
+ else
+ {
+ mcg_c8 |= MCG_C8_LOLRE_MASK;
+ }
+ MCG->C8 = mcg_c8;
+ MCG->C6 |= MCG_C6_LOLIE0_MASK;
+ }
+}
+
+uint32_t CLOCK_GetStatusFlags(void)
+{
+ uint32_t ret = 0U;
+ uint8_t mcg_s = MCG->S;
+
+ if (MCG->SC & MCG_SC_LOCS0_MASK)
+ {
+ ret |= kMCG_Osc0LostFlag;
+ }
+ if (mcg_s & MCG_S_OSCINIT0_MASK)
+ {
+ ret |= kMCG_Osc0InitFlag;
+ }
+ if (MCG->C8 & MCG_C8_LOCS1_MASK)
+ {
+ ret |= kMCG_RtcOscLostFlag;
+ }
+ if (mcg_s & MCG_S_LOLS0_MASK)
+ {
+ ret |= kMCG_Pll0LostFlag;
+ }
+ if (mcg_s & MCG_S_LOCK0_MASK)
+ {
+ ret |= kMCG_Pll0LockFlag;
+ }
+ return ret;
+}
+
+void CLOCK_ClearStatusFlags(uint32_t mask)
+{
+ uint8_t reg;
+
+ if (mask & kMCG_Osc0LostFlag)
+ {
+ MCG->SC &= ~MCG_SC_ATMF_MASK;
+ }
+ if (mask & kMCG_RtcOscLostFlag)
+ {
+ reg = MCG->C8;
+ MCG->C8 = reg;
+ }
+ if (mask & kMCG_Pll0LostFlag)
+ {
+ MCG->S = MCG_S_LOLS0_MASK;
+ }
+}
+
+void CLOCK_InitOsc0(osc_config_t const *config)
+{
+ uint8_t range = CLOCK_GetOscRangeFromFreq(config->freq);
+
+ OSC_SetCapLoad(OSC0, config->capLoad);
+ OSC_SetExtRefClkConfig(OSC0, &config->oscerConfig);
+
+ MCG->C2 = ((MCG->C2 & ~OSC_MODE_MASK) | MCG_C2_RANGE(range) | (uint8_t)config->workMode);
+
+ if ((kOSC_ModeExt != config->workMode) && (OSC0->CR & OSC_CR_ERCLKEN_MASK))
+ {
+ /* Wait for stable. */
+ while (!(MCG->S & MCG_S_OSCINIT0_MASK))
+ {
+ }
+ }
+}
+
+void CLOCK_DeinitOsc0(void)
+{
+ OSC0->CR = 0U;
+ MCG->C2 &= ~OSC_MODE_MASK;
+}
+
+status_t CLOCK_TrimInternalRefClk(uint32_t extFreq, uint32_t desireFreq, uint32_t *actualFreq, mcg_atm_select_t atms)
+{
+ uint32_t multi; /* extFreq / desireFreq */
+ uint32_t actv; /* Auto trim value. */
+ uint8_t mcg_sc;
+
+ static const uint32_t trimRange[2][2] = {
+ /* Min Max */
+ {TRIM_SIRC_MIN, TRIM_SIRC_MAX}, /* Slow IRC. */
+ {TRIM_FIRC_MIN, TRIM_FIRC_MAX} /* Fast IRC. */
+ };
+
+ if ((extFreq > TRIM_REF_CLK_MAX) || (extFreq < TRIM_REF_CLK_MIN))
+ {
+ return kStatus_MCG_AtmBusClockInvalid;
+ }
+
+ /* Check desired frequency range. */
+ if ((desireFreq < trimRange[atms][0]) || (desireFreq > trimRange[atms][1]))
+ {
+ return kStatus_MCG_AtmDesiredFreqInvalid;
+ }
+
+ /*
+ Make sure internal reference clock is not used to generate bus clock.
+ Here only need to check (MCG_S_IREFST == 1).
+ */
+ if (MCG_S_IREFST(kMCG_FllSrcInternal) == (MCG->S & MCG_S_IREFST_MASK))
+ {
+ return kStatus_MCG_AtmIrcUsed;
+ }
+
+ multi = extFreq / desireFreq;
+ actv = multi * 21U;
+
+ if (kMCG_AtmSel4m == atms)
+ {
+ actv *= 128U;
+ }
+
+ /* Now begin to start trim. */
+ MCG->ATCVL = (uint8_t)actv;
+ MCG->ATCVH = (uint8_t)(actv >> 8U);
+
+ mcg_sc = MCG->SC;
+ mcg_sc &= ~(MCG_SC_ATMS_MASK | MCG_SC_LOCS0_MASK);
+ mcg_sc |= (MCG_SC_ATMF_MASK | MCG_SC_ATMS(atms));
+ MCG->SC = (mcg_sc | MCG_SC_ATME_MASK);
+
+ /* Wait for finished. */
+ while (MCG->SC & MCG_SC_ATME_MASK)
+ {
+ }
+
+ /* Error occurs? */
+ if (MCG->SC & MCG_SC_ATMF_MASK)
+ {
+ /* Clear the failed flag. */
+ MCG->SC = mcg_sc;
+ return kStatus_MCG_AtmHardwareFail;
+ }
+
+ *actualFreq = extFreq / multi;
+
+ if (kMCG_AtmSel4m == atms)
+ {
+ s_fastIrcFreq = *actualFreq;
+ }
+ else
+ {
+ s_slowIrcFreq = *actualFreq;
+ }
+
+ return kStatus_Success;
+}
+
+mcg_mode_t CLOCK_GetMode(void)
+{
+ mcg_mode_t mode = kMCG_ModeError;
+ uint32_t clkst = MCG_S_CLKST_VAL;
+ uint32_t irefst = MCG_S_IREFST_VAL;
+ uint32_t lp = MCG_C2_LP_VAL;
+ uint32_t pllst = MCG_S_PLLST_VAL;
+
+ /*------------------------------------------------------------------
+ Mode and Registers
+ ____________________________________________________________________
+
+ Mode | CLKST | IREFST | PLLST | LP
+ ____________________________________________________________________
+
+ FEI | 00(FLL) | 1(INT) | 0(FLL) | X
+ ____________________________________________________________________
+
+ FEE | 00(FLL) | 0(EXT) | 0(FLL) | X
+ ____________________________________________________________________
+
+ FBE | 10(EXT) | 0(EXT) | 0(FLL) | 0(NORMAL)
+ ____________________________________________________________________
+
+ FBI | 01(INT) | 1(INT) | 0(FLL) | 0(NORMAL)
+ ____________________________________________________________________
+
+ BLPI | 01(INT) | 1(INT) | 0(FLL) | 1(LOW POWER)
+ ____________________________________________________________________
+
+ BLPE | 10(EXT) | 0(EXT) | X | 1(LOW POWER)
+ ____________________________________________________________________
+
+ PEE | 11(PLL) | 0(EXT) | 1(PLL) | X
+ ____________________________________________________________________
+
+ PBE | 10(EXT) | 0(EXT) | 1(PLL) | O(NORMAL)
+ ____________________________________________________________________
+
+ PBI | 01(INT) | 1(INT) | 1(PLL) | 0(NORMAL)
+ ____________________________________________________________________
+
+ PEI | 11(PLL) | 1(INT) | 1(PLL) | X
+ ____________________________________________________________________
+
+ ----------------------------------------------------------------------*/
+
+ switch (clkst)
+ {
+ case kMCG_ClkOutStatFll:
+ if (kMCG_FllSrcExternal == irefst)
+ {
+ mode = kMCG_ModeFEE;
+ }
+ else
+ {
+ mode = kMCG_ModeFEI;
+ }
+ break;
+ case kMCG_ClkOutStatInt:
+ if (lp)
+ {
+ mode = kMCG_ModeBLPI;
+ }
+ else
+ {
+ {
+ mode = kMCG_ModeFBI;
+ }
+ }
+ break;
+ case kMCG_ClkOutStatExt:
+ if (lp)
+ {
+ mode = kMCG_ModeBLPE;
+ }
+ else
+ {
+ if (kMCG_PllstPll == pllst)
+ {
+ mode = kMCG_ModePBE;
+ }
+ else
+ {
+ mode = kMCG_ModeFBE;
+ }
+ }
+ break;
+ case kMCG_ClkOutStatPll:
+ {
+ mode = kMCG_ModePEE;
+ }
+ break;
+ default:
+ break;
+ }
+
+ return mode;
+}
+
+status_t CLOCK_SetFeiMode(mcg_dmx32_t dmx32, mcg_drs_t drs, void (*fllStableDelay)(void))
+{
+ uint8_t mcg_c4;
+ bool change_drs = false;
+
+#if (defined(MCG_CONFIG_CHECK_PARAM) && MCG_CONFIG_CHECK_PARAM)
+ mcg_mode_t mode = CLOCK_GetMode();
+ if (!((kMCG_ModeFEI == mode) || (kMCG_ModeFBI == mode) || (kMCG_ModeFBE == mode) || (kMCG_ModeFEE == mode)))
+ {
+ return kStatus_MCG_ModeUnreachable;
+ }
+#endif
+ mcg_c4 = MCG->C4;
+
+ /*
+ Errata: ERR007993
+ Workaround: Invert MCG_C4[DMX32] or change MCG_C4[DRST_DRS] before
+ reference clock source changes, then reset to previous value after
+ reference clock changes.
+ */
+ if (kMCG_FllSrcExternal == MCG_S_IREFST_VAL)
+ {
+ change_drs = true;
+ /* Change the LSB of DRST_DRS. */
+ MCG->C4 ^= (1U << MCG_C4_DRST_DRS_SHIFT);
+ }
+
+ /* Set CLKS and IREFS. */
+ MCG->C1 =
+ ((MCG->C1 & ~(MCG_C1_CLKS_MASK | MCG_C1_IREFS_MASK))) | (MCG_C1_CLKS(kMCG_ClkOutSrcOut) /* CLKS = 0 */
+ | MCG_C1_IREFS(kMCG_FllSrcInternal)); /* IREFS = 1 */
+
+ /* Wait and check status. */
+ while (kMCG_FllSrcInternal != MCG_S_IREFST_VAL)
+ {
+ }
+
+ /* Errata: ERR007993 */
+ if (change_drs)
+ {
+ MCG->C4 = mcg_c4;
+ }
+
+ /* In FEI mode, the MCG_C4[DMX32] is set to 0U. */
+ MCG->C4 = (mcg_c4 & ~(MCG_C4_DMX32_MASK | MCG_C4_DRST_DRS_MASK)) | (MCG_C4_DMX32(dmx32) | MCG_C4_DRST_DRS(drs));
+
+ /* Check MCG_S[CLKST] */
+ while (kMCG_ClkOutStatFll != MCG_S_CLKST_VAL)
+ {
+ }
+
+ /* Wait for FLL stable time. */
+ if (fllStableDelay)
+ {
+ fllStableDelay();
+ }
+
+ return kStatus_Success;
+}
+
+status_t CLOCK_SetFeeMode(uint8_t frdiv, mcg_dmx32_t dmx32, mcg_drs_t drs, void (*fllStableDelay)(void))
+{
+ uint8_t mcg_c4;
+ bool change_drs = false;
+
+#if (defined(MCG_CONFIG_CHECK_PARAM) && MCG_CONFIG_CHECK_PARAM)
+ mcg_mode_t mode = CLOCK_GetMode();
+ if (!((kMCG_ModeFEE == mode) || (kMCG_ModeFBI == mode) || (kMCG_ModeFBE == mode) || (kMCG_ModeFEI == mode)))
+ {
+ return kStatus_MCG_ModeUnreachable;
+ }
+#endif
+ mcg_c4 = MCG->C4;
+
+ /*
+ Errata: ERR007993
+ Workaround: Invert MCG_C4[DMX32] or change MCG_C4[DRST_DRS] before
+ reference clock source changes, then reset to previous value after
+ reference clock changes.
+ */
+ if (kMCG_FllSrcInternal == MCG_S_IREFST_VAL)
+ {
+ change_drs = true;
+ /* Change the LSB of DRST_DRS. */
+ MCG->C4 ^= (1U << MCG_C4_DRST_DRS_SHIFT);
+ }
+
+ /* Set CLKS and IREFS. */
+ MCG->C1 = ((MCG->C1 & ~(MCG_C1_CLKS_MASK | MCG_C1_FRDIV_MASK | MCG_C1_IREFS_MASK)) |
+ (MCG_C1_CLKS(kMCG_ClkOutSrcOut) /* CLKS = 0 */
+ | MCG_C1_FRDIV(frdiv) /* FRDIV */
+ | MCG_C1_IREFS(kMCG_FllSrcExternal))); /* IREFS = 0 */
+
+ /* Wait and check status. */
+ while (kMCG_FllSrcExternal != MCG_S_IREFST_VAL)
+ {
+ }
+
+ /* Errata: ERR007993 */
+ if (change_drs)
+ {
+ MCG->C4 = mcg_c4;
+ }
+
+ /* Set DRS and DMX32. */
+ mcg_c4 = ((mcg_c4 & ~(MCG_C4_DMX32_MASK | MCG_C4_DRST_DRS_MASK)) | (MCG_C4_DMX32(dmx32) | MCG_C4_DRST_DRS(drs)));
+ MCG->C4 = mcg_c4;
+
+ /* Wait for DRST_DRS update. */
+ while (MCG->C4 != mcg_c4)
+ {
+ }
+
+ /* Check MCG_S[CLKST] */
+ while (kMCG_ClkOutStatFll != MCG_S_CLKST_VAL)
+ {
+ }
+
+ /* Wait for FLL stable time. */
+ if (fllStableDelay)
+ {
+ fllStableDelay();
+ }
+
+ return kStatus_Success;
+}
+
+status_t CLOCK_SetFbiMode(mcg_dmx32_t dmx32, mcg_drs_t drs, void (*fllStableDelay)(void))
+{
+ uint8_t mcg_c4;
+ bool change_drs = false;
+
+#if (defined(MCG_CONFIG_CHECK_PARAM) && MCG_CONFIG_CHECK_PARAM)
+ mcg_mode_t mode = CLOCK_GetMode();
+
+ if (!((kMCG_ModeFEE == mode) || (kMCG_ModeFBI == mode) || (kMCG_ModeFBE == mode) || (kMCG_ModeFEI == mode) ||
+ (kMCG_ModeBLPI == mode)))
+
+ {
+ return kStatus_MCG_ModeUnreachable;
+ }
+#endif
+
+ mcg_c4 = MCG->C4;
+
+ MCG->C2 &= ~MCG_C2_LP_MASK; /* Disable lowpower. */
+
+ /*
+ Errata: ERR007993
+ Workaround: Invert MCG_C4[DMX32] or change MCG_C4[DRST_DRS] before
+ reference clock source changes, then reset to previous value after
+ reference clock changes.
+ */
+ if (kMCG_FllSrcExternal == MCG_S_IREFST_VAL)
+ {
+ change_drs = true;
+ /* Change the LSB of DRST_DRS. */
+ MCG->C4 ^= (1U << MCG_C4_DRST_DRS_SHIFT);
+ }
+
+ /* Set CLKS and IREFS. */
+ MCG->C1 =
+ ((MCG->C1 & ~(MCG_C1_CLKS_MASK | MCG_C1_IREFS_MASK)) | (MCG_C1_CLKS(kMCG_ClkOutSrcInternal) /* CLKS = 1 */
+ | MCG_C1_IREFS(kMCG_FllSrcInternal))); /* IREFS = 1 */
+
+ /* Wait and check status. */
+ while (kMCG_FllSrcInternal != MCG_S_IREFST_VAL)
+ {
+ }
+
+ /* Errata: ERR007993 */
+ if (change_drs)
+ {
+ MCG->C4 = mcg_c4;
+ }
+
+ while (kMCG_ClkOutStatInt != MCG_S_CLKST_VAL)
+ {
+ }
+
+ MCG->C4 = (mcg_c4 & ~(MCG_C4_DMX32_MASK | MCG_C4_DRST_DRS_MASK)) | (MCG_C4_DMX32(dmx32) | MCG_C4_DRST_DRS(drs));
+
+ /* Wait for FLL stable time. */
+ if (fllStableDelay)
+ {
+ fllStableDelay();
+ }
+
+ return kStatus_Success;
+}
+
+status_t CLOCK_SetFbeMode(uint8_t frdiv, mcg_dmx32_t dmx32, mcg_drs_t drs, void (*fllStableDelay)(void))
+{
+ uint8_t mcg_c4;
+ bool change_drs = false;
+
+#if (defined(MCG_CONFIG_CHECK_PARAM) && MCG_CONFIG_CHECK_PARAM)
+ mcg_mode_t mode = CLOCK_GetMode();
+ if (!((kMCG_ModeFEE == mode) || (kMCG_ModeFBI == mode) || (kMCG_ModeFBE == mode) || (kMCG_ModeFEI == mode) ||
+ (kMCG_ModePBE == mode) || (kMCG_ModeBLPE == mode)))
+ {
+ return kStatus_MCG_ModeUnreachable;
+ }
+#endif
+
+ /* Change to FLL mode. */
+ MCG->C6 &= ~MCG_C6_PLLS_MASK;
+ while (MCG->S & MCG_S_PLLST_MASK)
+ {
+ }
+
+ /* Set LP bit to enable the FLL */
+ MCG->C2 &= ~MCG_C2_LP_MASK;
+
+ mcg_c4 = MCG->C4;
+
+ /*
+ Errata: ERR007993
+ Workaround: Invert MCG_C4[DMX32] or change MCG_C4[DRST_DRS] before
+ reference clock source changes, then reset to previous value after
+ reference clock changes.
+ */
+ if (kMCG_FllSrcInternal == MCG_S_IREFST_VAL)
+ {
+ change_drs = true;
+ /* Change the LSB of DRST_DRS. */
+ MCG->C4 ^= (1U << MCG_C4_DRST_DRS_SHIFT);
+ }
+
+ /* Set CLKS and IREFS. */
+ MCG->C1 = ((MCG->C1 & ~(MCG_C1_CLKS_MASK | MCG_C1_FRDIV_MASK | MCG_C1_IREFS_MASK)) |
+ (MCG_C1_CLKS(kMCG_ClkOutSrcExternal) /* CLKS = 2 */
+ | MCG_C1_FRDIV(frdiv) /* FRDIV = frdiv */
+ | MCG_C1_IREFS(kMCG_FllSrcExternal))); /* IREFS = 0 */
+
+ /* Wait for Reference clock Status bit to clear */
+ while (kMCG_FllSrcExternal != MCG_S_IREFST_VAL)
+ {
+ }
+
+ /* Errata: ERR007993 */
+ if (change_drs)
+ {
+ MCG->C4 = mcg_c4;
+ }
+
+ /* Set DRST_DRS and DMX32. */
+ mcg_c4 = ((mcg_c4 & ~(MCG_C4_DMX32_MASK | MCG_C4_DRST_DRS_MASK)) | (MCG_C4_DMX32(dmx32) | MCG_C4_DRST_DRS(drs)));
+
+ /* Wait for clock status bits to show clock source is ext ref clk */
+ while (kMCG_ClkOutStatExt != MCG_S_CLKST_VAL)
+ {
+ }
+
+ /* Wait for fll stable time. */
+ if (fllStableDelay)
+ {
+ fllStableDelay();
+ }
+
+ return kStatus_Success;
+}
+
+status_t CLOCK_SetBlpiMode(void)
+{
+#if (defined(MCG_CONFIG_CHECK_PARAM) && MCG_CONFIG_CHECK_PARAM)
+ if (MCG_S_CLKST_VAL != kMCG_ClkOutStatInt)
+ {
+ return kStatus_MCG_ModeUnreachable;
+ }
+#endif /* MCG_CONFIG_CHECK_PARAM */
+
+ /* Set LP. */
+ MCG->C2 |= MCG_C2_LP_MASK;
+
+ return kStatus_Success;
+}
+
+status_t CLOCK_SetBlpeMode(void)
+{
+#if (defined(MCG_CONFIG_CHECK_PARAM) && MCG_CONFIG_CHECK_PARAM)
+ if (MCG_S_CLKST_VAL != kMCG_ClkOutStatExt)
+ {
+ return kStatus_MCG_ModeUnreachable;
+ }
+#endif
+
+ /* Set LP bit to enter BLPE mode. */
+ MCG->C2 |= MCG_C2_LP_MASK;
+
+ return kStatus_Success;
+}
+
+status_t CLOCK_SetPbeMode(mcg_pll_clk_select_t pllcs, mcg_pll_config_t const *config)
+{
+ /*
+ This function is designed to change MCG to PBE mode from PEE/BLPE/FBE,
+ but with this workflow, the source mode could be all modes except PEI/PBI.
+ */
+ MCG->C2 &= ~MCG_C2_LP_MASK; /* Disable lowpower. */
+
+ /* Change to use external clock first. */
+ MCG->C1 = ((MCG->C1 & ~(MCG_C1_CLKS_MASK | MCG_C1_IREFS_MASK)) | MCG_C1_CLKS(kMCG_ClkOutSrcExternal));
+
+ /* Wait for CLKST clock status bits to show clock source is ext ref clk */
+ while ((MCG->S & (MCG_S_IREFST_MASK | MCG_S_CLKST_MASK)) !=
+ (MCG_S_IREFST(kMCG_FllSrcExternal) | MCG_S_CLKST(kMCG_ClkOutStatExt)))
+ {
+ }
+
+ /* Disable PLL first, then configure PLL. */
+ MCG->C6 &= ~MCG_C6_PLLS_MASK;
+ while (MCG->S & MCG_S_PLLST_MASK)
+ {
+ }
+
+ /* Configure the PLL. */
+ {
+ CLOCK_EnablePll0(config);
+ }
+
+ /* Change to PLL mode. */
+ MCG->C6 |= MCG_C6_PLLS_MASK;
+ while (!(MCG->S & MCG_S_PLLST_MASK))
+ {
+ }
+
+ return kStatus_Success;
+}
+
+status_t CLOCK_SetPeeMode(void)
+{
+#if (defined(MCG_CONFIG_CHECK_PARAM) && MCG_CONFIG_CHECK_PARAM)
+ mcg_mode_t mode = CLOCK_GetMode();
+ if (kMCG_ModePBE != mode)
+ {
+ return kStatus_MCG_ModeUnreachable;
+ }
+#endif
+
+ /* Change to use PLL/FLL output clock first. */
+ MCG->C1 = (MCG->C1 & ~MCG_C1_CLKS_MASK) | MCG_C1_CLKS(kMCG_ClkOutSrcOut);
+
+ /* Wait for clock status bits to update */
+ while (MCG_S_CLKST_VAL != kMCG_ClkOutStatPll)
+ {
+ }
+
+ return kStatus_Success;
+}
+
+status_t CLOCK_ExternalModeToFbeModeQuick(void)
+{
+#if (defined(MCG_CONFIG_CHECK_PARAM) && MCG_CONFIG_CHECK_PARAM)
+ if (MCG->S & MCG_S_IREFST_MASK)
+ {
+ return kStatus_MCG_ModeInvalid;
+ }
+#endif /* MCG_CONFIG_CHECK_PARAM */
+
+ /* Disable low power */
+ MCG->C2 &= ~MCG_C2_LP_MASK;
+
+ MCG->C1 = ((MCG->C1 & ~MCG_C1_CLKS_MASK) | MCG_C1_CLKS(kMCG_ClkOutSrcExternal));
+ while (MCG_S_CLKST_VAL != kMCG_ClkOutStatExt)
+ {
+ }
+
+ /* Disable PLL. */
+ MCG->C6 &= ~MCG_C6_PLLS_MASK;
+ while (MCG->S & MCG_S_PLLST_MASK)
+ {
+ }
+
+ return kStatus_Success;
+}
+
+status_t CLOCK_InternalModeToFbiModeQuick(void)
+{
+#if (defined(MCG_CONFIG_CHECK_PARAM) && MCG_CONFIG_CHECK_PARAM)
+ if (!(MCG->S & MCG_S_IREFST_MASK))
+ {
+ return kStatus_MCG_ModeInvalid;
+ }
+#endif
+
+ /* Disable low power */
+ MCG->C2 &= ~MCG_C2_LP_MASK;
+
+ MCG->C1 = ((MCG->C1 & ~MCG_C1_CLKS_MASK) | MCG_C1_CLKS(kMCG_ClkOutSrcInternal));
+ while (MCG_S_CLKST_VAL != kMCG_ClkOutStatInt)
+ {
+ }
+
+ return kStatus_Success;
+}
+
+status_t CLOCK_BootToFeiMode(mcg_dmx32_t dmx32, mcg_drs_t drs, void (*fllStableDelay)(void))
+{
+ return CLOCK_SetFeiMode(dmx32, drs, fllStableDelay);
+}
+
+status_t CLOCK_BootToFeeMode(
+ mcg_oscsel_t oscsel, uint8_t frdiv, mcg_dmx32_t dmx32, mcg_drs_t drs, void (*fllStableDelay)(void))
+{
+ CLOCK_SetExternalRefClkConfig(oscsel);
+
+ return CLOCK_SetFeeMode(frdiv, dmx32, drs, fllStableDelay);
+}
+
+status_t CLOCK_BootToBlpiMode(uint8_t fcrdiv, mcg_irc_mode_t ircs, uint8_t ircEnableMode)
+{
+ /* If reset mode is FEI mode, set MCGIRCLK and always success. */
+ CLOCK_SetInternalRefClkConfig(ircEnableMode, ircs, fcrdiv);
+
+ /* If reset mode is not BLPI, first enter FBI mode. */
+ MCG->C1 = (MCG->C1 & ~MCG_C1_CLKS_MASK) | MCG_C1_CLKS(kMCG_ClkOutSrcInternal);
+ while (MCG_S_CLKST_VAL != kMCG_ClkOutStatInt)
+ {
+ }
+
+ /* Enter BLPI mode. */
+ MCG->C2 |= MCG_C2_LP_MASK;
+
+ return kStatus_Success;
+}
+
+status_t CLOCK_BootToBlpeMode(mcg_oscsel_t oscsel)
+{
+ CLOCK_SetExternalRefClkConfig(oscsel);
+
+ /* Set to FBE mode. */
+ MCG->C1 =
+ ((MCG->C1 & ~(MCG_C1_CLKS_MASK | MCG_C1_IREFS_MASK)) | (MCG_C1_CLKS(kMCG_ClkOutSrcExternal) /* CLKS = 2 */
+ | MCG_C1_IREFS(kMCG_FllSrcExternal))); /* IREFS = 0 */
+
+ /* Wait for MCG_S[CLKST] and MCG_S[IREFST]. */
+ while ((MCG->S & (MCG_S_IREFST_MASK | MCG_S_CLKST_MASK)) !=
+ (MCG_S_IREFST(kMCG_FllSrcExternal) | MCG_S_CLKST(kMCG_ClkOutStatExt)))
+ {
+ }
+
+ /* In FBE now, start to enter BLPE. */
+ MCG->C2 |= MCG_C2_LP_MASK;
+
+ return kStatus_Success;
+}
+
+status_t CLOCK_BootToPeeMode(mcg_oscsel_t oscsel, mcg_pll_clk_select_t pllcs, mcg_pll_config_t const *config)
+{
+ assert(config);
+
+ CLOCK_SetExternalRefClkConfig(oscsel);
+
+ CLOCK_SetPbeMode(pllcs, config);
+
+ /* Change to use PLL output clock. */
+ MCG->C1 = (MCG->C1 & ~MCG_C1_CLKS_MASK) | MCG_C1_CLKS(kMCG_ClkOutSrcOut);
+ while (MCG_S_CLKST_VAL != kMCG_ClkOutStatPll)
+ {
+ }
+
+ return kStatus_Success;
+}
+
+/*
+ The transaction matrix. It defines the path for mode switch, the row is for
+ current mode and the column is target mode.
+ For example, switch from FEI to PEE:
+ 1. Current mode FEI, next mode is mcgModeMatrix[FEI][PEE] = FBE, so swith to FBE.
+ 2. Current mode FBE, next mode is mcgModeMatrix[FBE][PEE] = PBE, so swith to PBE.
+ 3. Current mode PBE, next mode is mcgModeMatrix[PBE][PEE] = PEE, so swith to PEE.
+ Thus the MCG mode has changed from FEI to PEE.
+ */
+static const mcg_mode_t mcgModeMatrix[8][8] = {
+ {kMCG_ModeFEI, kMCG_ModeFBI, kMCG_ModeFBI, kMCG_ModeFEE, kMCG_ModeFBE, kMCG_ModeFBE, kMCG_ModeFBE,
+ kMCG_ModeFBE}, /* FEI */
+ {kMCG_ModeFEI, kMCG_ModeFBI, kMCG_ModeBLPI, kMCG_ModeFEE, kMCG_ModeFBE, kMCG_ModeFBE, kMCG_ModeFBE,
+ kMCG_ModeFBE}, /* FBI */
+ {kMCG_ModeFBI, kMCG_ModeFBI, kMCG_ModeBLPI, kMCG_ModeFBI, kMCG_ModeFBI, kMCG_ModeFBI, kMCG_ModeFBI,
+ kMCG_ModeFBI}, /* BLPI */
+ {kMCG_ModeFEI, kMCG_ModeFBI, kMCG_ModeFBI, kMCG_ModeFEE, kMCG_ModeFBE, kMCG_ModeFBE, kMCG_ModeFBE,
+ kMCG_ModeFBE}, /* FEE */
+ {kMCG_ModeFEI, kMCG_ModeFBI, kMCG_ModeFBI, kMCG_ModeFEE, kMCG_ModeFBE, kMCG_ModeBLPE, kMCG_ModePBE,
+ kMCG_ModePBE}, /* FBE */
+ {kMCG_ModeFBE, kMCG_ModeFBE, kMCG_ModeFBE, kMCG_ModeFBE, kMCG_ModeFBE, kMCG_ModeBLPE, kMCG_ModePBE,
+ kMCG_ModePBE}, /* BLPE */
+ {kMCG_ModeFBE, kMCG_ModeFBE, kMCG_ModeFBE, kMCG_ModeFBE, kMCG_ModeFBE, kMCG_ModeBLPE, kMCG_ModePBE,
+ kMCG_ModePEE}, /* PBE */
+ {kMCG_ModePBE, kMCG_ModePBE, kMCG_ModePBE, kMCG_ModePBE, kMCG_ModePBE, kMCG_ModePBE, kMCG_ModePBE,
+ kMCG_ModePBE} /* PEE */
+ /* FEI FBI BLPI FEE FBE BLPE PBE PEE */
+};
+
+status_t CLOCK_SetMcgConfig(const mcg_config_t *config)
+{
+ mcg_mode_t next_mode;
+ status_t status = kStatus_Success;
+
+ mcg_pll_clk_select_t pllcs = kMCG_PllClkSelPll0;
+
+ /* If need to change external clock, MCG_C7[OSCSEL]. */
+ if (MCG_C7_OSCSEL_VAL != config->oscsel)
+ {
+ /* If external clock is in use, change to FEI first. */
+ if (!(MCG->S & MCG_S_IRCST_MASK))
+ {
+ CLOCK_ExternalModeToFbeModeQuick();
+ CLOCK_SetFeiMode(config->dmx32, config->drs, (void (*)(void))0);
+ }
+
+ CLOCK_SetExternalRefClkConfig(config->oscsel);
+ }
+
+ /* Re-configure MCGIRCLK, if MCGIRCLK is used as system clock source, then change to FEI/PEI first. */
+ if (MCG_S_CLKST_VAL == kMCG_ClkOutStatInt)
+ {
+ MCG->C2 &= ~MCG_C2_LP_MASK; /* Disable lowpower. */
+
+ {
+ CLOCK_SetFeiMode(config->dmx32, config->drs, CLOCK_FllStableDelay);
+ }
+ }
+
+ /* Configure MCGIRCLK. */
+ CLOCK_SetInternalRefClkConfig(config->irclkEnableMode, config->ircs, config->fcrdiv);
+
+ next_mode = CLOCK_GetMode();
+
+ do
+ {
+ next_mode = mcgModeMatrix[next_mode][config->mcgMode];
+
+ switch (next_mode)
+ {
+ case kMCG_ModeFEI:
+ status = CLOCK_SetFeiMode(config->dmx32, config->drs, CLOCK_FllStableDelay);
+ break;
+ case kMCG_ModeFEE:
+ status = CLOCK_SetFeeMode(config->frdiv, config->dmx32, config->drs, CLOCK_FllStableDelay);
+ break;
+ case kMCG_ModeFBI:
+ status = CLOCK_SetFbiMode(config->dmx32, config->drs, (void (*)(void))0);
+ break;
+ case kMCG_ModeFBE:
+ status = CLOCK_SetFbeMode(config->frdiv, config->dmx32, config->drs, (void (*)(void))0);
+ break;
+ case kMCG_ModeBLPI:
+ status = CLOCK_SetBlpiMode();
+ break;
+ case kMCG_ModeBLPE:
+ status = CLOCK_SetBlpeMode();
+ break;
+ case kMCG_ModePBE:
+ /* If target mode is not PBE or PEE, then only need to set CLKS = EXT here. */
+ if ((kMCG_ModePEE == config->mcgMode) || (kMCG_ModePBE == config->mcgMode))
+ {
+ {
+ status = CLOCK_SetPbeMode(pllcs, &config->pll0Config);
+ }
+ }
+ else
+ {
+ MCG->C1 = ((MCG->C1 & ~MCG_C1_CLKS_MASK) | MCG_C1_CLKS(kMCG_ClkOutSrcExternal));
+ while (MCG_S_CLKST_VAL != kMCG_ClkOutStatExt)
+ {
+ }
+ }
+ break;
+ case kMCG_ModePEE:
+ status = CLOCK_SetPeeMode();
+ break;
+ default:
+ break;
+ }
+ if (kStatus_Success != status)
+ {
+ return status;
+ }
+ } while (next_mode != config->mcgMode);
+
+ if (config->pll0Config.enableMode & kMCG_PllEnableIndependent)
+ {
+ CLOCK_EnablePll0(&config->pll0Config);
+ }
+ else
+ {
+ MCG->C5 &= ~(uint32_t)kMCG_PllEnableIndependent;
+ }
+ return kStatus_Success;
+}
diff --git a/drivers/fsl_clock.h b/drivers/fsl_clock.h
new file mode 100644
index 0000000..4c4fb59
--- /dev/null
+++ b/drivers/fsl_clock.h
@@ -0,0 +1,1492 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_CLOCK_H_
+#define _FSL_CLOCK_H_
+
+#include "fsl_device_registers.h"
+#include <stdint.h>
+#include <stdbool.h>
+#include <assert.h>
+
+/*! @addtogroup clock */
+/*! @{ */
+
+/*! @file */
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+/*! @name Driver version */
+/*@{*/
+/*! @brief CLOCK driver version 2.2.0. */
+#define FSL_CLOCK_DRIVER_VERSION (MAKE_VERSION(2, 2, 0))
+/*@}*/
+
+/*! @brief External XTAL0 (OSC0) clock frequency.
+ *
+ * The XTAL0/EXTAL0 (OSC0) clock frequency in Hz, when the clock is setup, use the
+ * function CLOCK_SetXtal0Freq to set the value in to clock driver. For example,
+ * if XTAL0 is 8MHz,
+ * @code
+ * CLOCK_InitOsc0(...); // Setup the OSC0
+ * CLOCK_SetXtal0Freq(80000000); // Set the XTAL0 value to clock driver.
+ * @endcode
+ *
+ * This is important for the multicore platforms, only one core needs to setup
+ * OSC0 using CLOCK_InitOsc0, all other cores need to call CLOCK_SetXtal0Freq
+ * to get valid clock frequency.
+ */
+extern uint32_t g_xtal0Freq;
+
+/*! @brief External XTAL32/EXTAL32/RTC_CLKIN clock frequency.
+ *
+ * The XTAL32/EXTAL32/RTC_CLKIN clock frequency in Hz, when the clock is setup, use the
+ * function CLOCK_SetXtal32Freq to set the value in to clock driver.
+ *
+ * This is important for the multicore platforms, only one core needs to setup
+ * the clock, all other cores need to call CLOCK_SetXtal32Freq
+ * to get valid clock frequency.
+ */
+extern uint32_t g_xtal32Freq;
+
+#if (defined(OSC) && !(defined(OSC0)))
+#define OSC0 OSC
+#endif
+
+/*! @brief Clock ip name array for DMAMUX. */
+#define DMAMUX_CLOCKS \
+ { \
+ kCLOCK_Dmamux0 \
+ }
+
+/*! @brief Clock ip name array for RTC. */
+#define RTC_CLOCKS \
+ { \
+ kCLOCK_Rtc0 \
+ }
+
+/*! @brief Clock ip name array for PORT. */
+#define PORT_CLOCKS \
+ { \
+ kCLOCK_PortA, kCLOCK_PortB, kCLOCK_PortC, kCLOCK_PortD, kCLOCK_PortE \
+ }
+
+/*! @brief Clock ip name array for SAI. */
+#define SAI_CLOCKS \
+ { \
+ kCLOCK_Sai0 \
+ }
+
+/*! @brief Clock ip name array for FLEXBUS. */
+#define FLEXBUS_CLOCKS \
+ { \
+ kCLOCK_Flexbus0 \
+ }
+
+/*! @brief Clock ip name array for TSI. */
+#define TSI_CLOCKS \
+ { \
+ kCLOCK_Tsi0 \
+ }
+
+/*! @brief Clock ip name array for EWM. */
+#define EWM_CLOCKS \
+ { \
+ kCLOCK_Ewm0 \
+ }
+
+/*! @brief Clock ip name array for PIT. */
+#define PIT_CLOCKS \
+ { \
+ kCLOCK_Pit0 \
+ }
+
+/*! @brief Clock ip name array for DSPI. */
+#define DSPI_CLOCKS \
+ { \
+ kCLOCK_Spi0, kCLOCK_Spi1, kCLOCK_Spi2 \
+ }
+
+/*! @brief Clock ip name array for LPTMR. */
+#define LPTMR_CLOCKS \
+ { \
+ kCLOCK_Lptmr0 \
+ }
+
+/*! @brief Clock ip name array for SDHC. */
+#define SDHC_CLOCKS \
+ { \
+ kCLOCK_Sdhc0 \
+ }
+
+/*! @brief Clock ip name array for FTM. */
+#define FTM_CLOCKS \
+ { \
+ kCLOCK_Ftm0, kCLOCK_Ftm1, kCLOCK_Ftm2 \
+ }
+
+/*! @brief Clock ip name array for LLWU. */
+#define LLWU_CLOCKS \
+ { \
+ kCLOCK_Llwu0 \
+ }
+
+/*! @brief Clock ip name array for EDMA. */
+#define EDMA_CLOCKS \
+ { \
+ kCLOCK_Dma0 \
+ }
+
+/*! @brief Clock ip name array for FLEXCAN. */
+#define FLEXCAN_CLOCKS \
+ { \
+ kCLOCK_Flexcan0, kCLOCK_Flexcan1 \
+ }
+
+/*! @brief Clock ip name array for DAC. */
+#define DAC_CLOCKS \
+ { \
+ kCLOCK_Dac0, kCLOCK_Dac1 \
+ }
+
+/*! @brief Clock ip name array for ADC16. */
+#define ADC16_CLOCKS \
+ { \
+ kCLOCK_Adc0, kCLOCK_Adc1 \
+ }
+
+/*! @brief Clock ip name array for MPU. */
+#define MPU_CLOCKS \
+ { \
+ kCLOCK_Mpu0 \
+ }
+
+/*! @brief Clock ip name array for VREF. */
+#define VREF_CLOCKS \
+ { \
+ kCLOCK_Vref0 \
+ }
+
+/*! @brief Clock ip name array for CMT. */
+#define CMT_CLOCKS \
+ { \
+ kCLOCK_Cmt0 \
+ }
+
+/*! @brief Clock ip name array for UART. */
+#define UART_CLOCKS \
+ { \
+ kCLOCK_Uart0, kCLOCK_Uart1, kCLOCK_Uart2, kCLOCK_Uart3, kCLOCK_Uart4, kCLOCK_Uart5 \
+ }
+
+/*! @brief Clock ip name array for CRC. */
+#define CRC_CLOCKS \
+ { \
+ kCLOCK_Crc0 \
+ }
+
+/*! @brief Clock ip name array for I2C. */
+#define I2C_CLOCKS \
+ { \
+ kCLOCK_I2c0, kCLOCK_I2c1 \
+ }
+
+/*! @brief Clock ip name array for PDB. */
+#define PDB_CLOCKS \
+ { \
+ kCLOCK_Pdb0 \
+ }
+
+/*! @brief Clock ip name array for FTF. */
+#define FTF_CLOCKS \
+ { \
+ kCLOCK_Ftf0 \
+ }
+
+/*! @brief Clock ip name array for CMP. */
+#define CMP_CLOCKS \
+ { \
+ kCLOCK_Cmp0, kCLOCK_Cmp1, kCLOCK_Cmp2 \
+ }
+
+/*!
+ * @brief LPO clock frequency.
+ */
+#define LPO_CLK_FREQ 1000U
+
+/*! @brief Peripherals clock source definition. */
+#define SYS_CLK kCLOCK_CoreSysClk
+#define BUS_CLK kCLOCK_BusClk
+
+#define I2C0_CLK_SRC BUS_CLK
+#define I2C1_CLK_SRC BUS_CLK
+#define DSPI0_CLK_SRC BUS_CLK
+#define DSPI1_CLK_SRC BUS_CLK
+#define DSPI2_CLK_SRC BUS_CLK
+#define UART0_CLK_SRC SYS_CLK
+#define UART1_CLK_SRC SYS_CLK
+#define UART2_CLK_SRC BUS_CLK
+#define UART3_CLK_SRC BUS_CLK
+#define UART4_CLK_SRC BUS_CLK
+#define UART5_CLK_SRC BUS_CLK
+
+/*! @brief Clock name used to get clock frequency. */
+typedef enum _clock_name
+{
+
+ /* ----------------------------- System layer clock -------------------------------*/
+ kCLOCK_CoreSysClk, /*!< Core/system clock */
+ kCLOCK_PlatClk, /*!< Platform clock */
+ kCLOCK_BusClk, /*!< Bus clock */
+ kCLOCK_FlexBusClk, /*!< FlexBus clock */
+ kCLOCK_FlashClk, /*!< Flash clock */
+ kCLOCK_FastPeriphClk, /*!< Fast peripheral clock */
+ kCLOCK_PllFllSelClk, /*!< The clock after SIM[PLLFLLSEL]. */
+
+ /* ---------------------------------- OSC clock -----------------------------------*/
+ kCLOCK_Er32kClk, /*!< External reference 32K clock (ERCLK32K) */
+ kCLOCK_Osc0ErClk, /*!< OSC0 external reference clock (OSC0ERCLK) */
+ kCLOCK_Osc1ErClk, /*!< OSC1 external reference clock (OSC1ERCLK) */
+ kCLOCK_Osc0ErClkUndiv, /*!< OSC0 external reference undivided clock(OSC0ERCLK_UNDIV). */
+
+ /* ----------------------------- MCG and MCG-Lite clock ---------------------------*/
+ kCLOCK_McgFixedFreqClk, /*!< MCG fixed frequency clock (MCGFFCLK) */
+ kCLOCK_McgInternalRefClk, /*!< MCG internal reference clock (MCGIRCLK) */
+ kCLOCK_McgFllClk, /*!< MCGFLLCLK */
+ kCLOCK_McgPll0Clk, /*!< MCGPLL0CLK */
+ kCLOCK_McgPll1Clk, /*!< MCGPLL1CLK */
+ kCLOCK_McgExtPllClk, /*!< EXT_PLLCLK */
+ kCLOCK_McgPeriphClk, /*!< MCG peripheral clock (MCGPCLK) */
+ kCLOCK_McgIrc48MClk, /*!< MCG IRC48M clock */
+
+ /* --------------------------------- Other clock ----------------------------------*/
+ kCLOCK_LpoClk, /*!< LPO clock */
+
+} clock_name_t;
+
+/*! @brief USB clock source definition. */
+typedef enum _clock_usb_src
+{
+ kCLOCK_UsbSrcPll0 = SIM_SOPT2_USBSRC(1U) | SIM_SOPT2_PLLFLLSEL(1U), /*!< Use PLL0. */
+ kCLOCK_UsbSrcExt = SIM_SOPT2_USBSRC(0U) /*!< Use USB_CLKIN. */
+} clock_usb_src_t;
+
+/*------------------------------------------------------------------------------
+
+ clock_gate_t definition:
+
+ 31 16 0
+ -----------------------------------------------------------------
+ | SIM_SCGC register offset | control bit offset in SCGC |
+ -----------------------------------------------------------------
+
+ For example, the SDHC clock gate is controlled by SIM_SCGC3[17], the
+ SIM_SCGC3 offset in SIM is 0x1030, then kCLOCK_GateSdhc0 is defined as
+
+ kCLOCK_GateSdhc0 = (0x1030 << 16) | 17;
+
+------------------------------------------------------------------------------*/
+
+#define CLK_GATE_REG_OFFSET_SHIFT 16U
+#define CLK_GATE_REG_OFFSET_MASK 0xFFFF0000U
+#define CLK_GATE_BIT_SHIFT_SHIFT 0U
+#define CLK_GATE_BIT_SHIFT_MASK 0x0000FFFFU
+
+#define CLK_GATE_DEFINE(reg_offset, bit_shift) \
+ ((((reg_offset) << CLK_GATE_REG_OFFSET_SHIFT) & CLK_GATE_REG_OFFSET_MASK) | \
+ (((bit_shift) << CLK_GATE_BIT_SHIFT_SHIFT) & CLK_GATE_BIT_SHIFT_MASK))
+
+#define CLK_GATE_ABSTRACT_REG_OFFSET(x) (((x)&CLK_GATE_REG_OFFSET_MASK) >> CLK_GATE_REG_OFFSET_SHIFT)
+#define CLK_GATE_ABSTRACT_BITS_SHIFT(x) (((x)&CLK_GATE_BIT_SHIFT_MASK) >> CLK_GATE_BIT_SHIFT_SHIFT)
+
+/*! @brief Clock gate name used for CLOCK_EnableClock/CLOCK_DisableClock. */
+typedef enum _clock_ip_name
+{
+ kCLOCK_IpInvalid = 0U,
+ kCLOCK_Uart4 = CLK_GATE_DEFINE(0x1028U, 10U),
+ kCLOCK_Uart5 = CLK_GATE_DEFINE(0x1028U, 11U),
+
+ kCLOCK_Dac0 = CLK_GATE_DEFINE(0x102CU, 12U),
+ kCLOCK_Dac1 = CLK_GATE_DEFINE(0x102CU, 13U),
+
+ kCLOCK_Flexcan1 = CLK_GATE_DEFINE(0x1030U, 4U),
+ kCLOCK_Spi2 = CLK_GATE_DEFINE(0x1030U, 12U),
+ kCLOCK_Sdhc0 = CLK_GATE_DEFINE(0x1030U, 17U),
+ kCLOCK_Ftm2 = CLK_GATE_DEFINE(0x1030U, 24U),
+ kCLOCK_Adc1 = CLK_GATE_DEFINE(0x1030U, 27U),
+
+ kCLOCK_Ewm0 = CLK_GATE_DEFINE(0x1034U, 1U),
+ kCLOCK_Cmt0 = CLK_GATE_DEFINE(0x1034U, 2U),
+ kCLOCK_I2c0 = CLK_GATE_DEFINE(0x1034U, 6U),
+ kCLOCK_I2c1 = CLK_GATE_DEFINE(0x1034U, 7U),
+ kCLOCK_Uart0 = CLK_GATE_DEFINE(0x1034U, 10U),
+ kCLOCK_Uart1 = CLK_GATE_DEFINE(0x1034U, 11U),
+ kCLOCK_Uart2 = CLK_GATE_DEFINE(0x1034U, 12U),
+ kCLOCK_Uart3 = CLK_GATE_DEFINE(0x1034U, 13U),
+ kCLOCK_Usbfs0 = CLK_GATE_DEFINE(0x1034U, 18U),
+ kCLOCK_Cmp0 = CLK_GATE_DEFINE(0x1034U, 19U),
+ kCLOCK_Cmp1 = CLK_GATE_DEFINE(0x1034U, 19U),
+ kCLOCK_Cmp2 = CLK_GATE_DEFINE(0x1034U, 19U),
+ kCLOCK_Vref0 = CLK_GATE_DEFINE(0x1034U, 20U),
+ kCLOCK_Llwu0 = CLK_GATE_DEFINE(0x1034U, 28U),
+
+ kCLOCK_Lptmr0 = CLK_GATE_DEFINE(0x1038U, 0U),
+ kCLOCK_Tsi0 = CLK_GATE_DEFINE(0x1038U, 5U),
+ kCLOCK_PortA = CLK_GATE_DEFINE(0x1038U, 9U),
+ kCLOCK_PortB = CLK_GATE_DEFINE(0x1038U, 10U),
+ kCLOCK_PortC = CLK_GATE_DEFINE(0x1038U, 11U),
+ kCLOCK_PortD = CLK_GATE_DEFINE(0x1038U, 12U),
+ kCLOCK_PortE = CLK_GATE_DEFINE(0x1038U, 13U),
+
+ kCLOCK_Ftf0 = CLK_GATE_DEFINE(0x103CU, 0U),
+ kCLOCK_Dmamux0 = CLK_GATE_DEFINE(0x103CU, 1U),
+ kCLOCK_Flexcan0 = CLK_GATE_DEFINE(0x103CU, 4U),
+ kCLOCK_Spi0 = CLK_GATE_DEFINE(0x103CU, 12U),
+ kCLOCK_Spi1 = CLK_GATE_DEFINE(0x103CU, 13U),
+ kCLOCK_Sai0 = CLK_GATE_DEFINE(0x103CU, 15U),
+ kCLOCK_Crc0 = CLK_GATE_DEFINE(0x103CU, 18U),
+ kCLOCK_Usbdcd0 = CLK_GATE_DEFINE(0x103CU, 21U),
+ kCLOCK_Pdb0 = CLK_GATE_DEFINE(0x103CU, 22U),
+ kCLOCK_Pit0 = CLK_GATE_DEFINE(0x103CU, 23U),
+ kCLOCK_Ftm0 = CLK_GATE_DEFINE(0x103CU, 24U),
+ kCLOCK_Ftm1 = CLK_GATE_DEFINE(0x103CU, 25U),
+ kCLOCK_Adc0 = CLK_GATE_DEFINE(0x103CU, 27U),
+ kCLOCK_Rtc0 = CLK_GATE_DEFINE(0x103CU, 29U),
+
+ kCLOCK_Flexbus0 = CLK_GATE_DEFINE(0x1040U, 0U),
+ kCLOCK_Dma0 = CLK_GATE_DEFINE(0x1040U, 1U),
+ kCLOCK_Mpu0 = CLK_GATE_DEFINE(0x1040U, 2U),
+} clock_ip_name_t;
+
+/*!@brief SIM configuration structure for clock setting. */
+typedef struct _sim_clock_config
+{
+ uint8_t pllFllSel; /*!< PLL/FLL/IRC48M selection. */
+ uint8_t er32kSrc; /*!< ERCLK32K source selection. */
+ uint32_t clkdiv1; /*!< SIM_CLKDIV1. */
+} sim_clock_config_t;
+
+/*! @brief OSC work mode. */
+typedef enum _osc_mode
+{
+ kOSC_ModeExt = 0U, /*!< Use external clock. */
+#if (defined(MCG_C2_EREFS_MASK) && !(defined(MCG_C2_EREFS0_MASK)))
+ kOSC_ModeOscLowPower = MCG_C2_EREFS_MASK, /*!< Oscillator low power. */
+#else
+ kOSC_ModeOscLowPower = MCG_C2_EREFS0_MASK, /*!< Oscillator low power. */
+#endif
+ kOSC_ModeOscHighGain = 0U
+#if (defined(MCG_C2_EREFS_MASK) && !(defined(MCG_C2_EREFS0_MASK)))
+ |
+ MCG_C2_EREFS_MASK
+#else
+ |
+ MCG_C2_EREFS0_MASK
+#endif
+#if (defined(MCG_C2_HGO_MASK) && !(defined(MCG_C2_HGO0_MASK)))
+ |
+ MCG_C2_HGO_MASK, /*!< Oscillator high gain. */
+#else
+ |
+ MCG_C2_HGO0_MASK, /*!< Oscillator high gain. */
+#endif
+} osc_mode_t;
+
+/*! @brief Oscillator capacitor load setting.*/
+enum _osc_cap_load
+{
+ kOSC_Cap2P = OSC_CR_SC2P_MASK, /*!< 2 pF capacitor load */
+ kOSC_Cap4P = OSC_CR_SC4P_MASK, /*!< 4 pF capacitor load */
+ kOSC_Cap8P = OSC_CR_SC8P_MASK, /*!< 8 pF capacitor load */
+ kOSC_Cap16P = OSC_CR_SC16P_MASK /*!< 16 pF capacitor load */
+};
+
+/*! @brief OSCERCLK enable mode. */
+enum _oscer_enable_mode
+{
+ kOSC_ErClkEnable = OSC_CR_ERCLKEN_MASK, /*!< Enable. */
+ kOSC_ErClkEnableInStop = OSC_CR_EREFSTEN_MASK /*!< Enable in stop mode. */
+};
+
+/*! @brief OSC configuration for OSCERCLK. */
+typedef struct _oscer_config
+{
+ uint8_t enableMode; /*!< OSCERCLK enable mode. OR'ed value of @ref _oscer_enable_mode. */
+
+} oscer_config_t;
+
+/*!
+ * @brief OSC Initialization Configuration Structure
+ *
+ * Defines the configuration data structure to initialize the OSC.
+ * When porting to a new board, please set the following members
+ * according to board setting:
+ * 1. freq: The external frequency.
+ * 2. workMode: The OSC module mode.
+ */
+typedef struct _osc_config
+{
+ uint32_t freq; /*!< External clock frequency. */
+ uint8_t capLoad; /*!< Capacitor load setting. */
+ osc_mode_t workMode; /*!< OSC work mode setting. */
+ oscer_config_t oscerConfig; /*!< Configuration for OSCERCLK. */
+} osc_config_t;
+
+/*! @brief MCG FLL reference clock source select. */
+typedef enum _mcg_fll_src
+{
+ kMCG_FllSrcExternal, /*!< External reference clock is selected */
+ kMCG_FllSrcInternal /*!< The slow internal reference clock is selected */
+} mcg_fll_src_t;
+
+/*! @brief MCG internal reference clock select */
+typedef enum _mcg_irc_mode
+{
+ kMCG_IrcSlow, /*!< Slow internal reference clock selected */
+ kMCG_IrcFast /*!< Fast internal reference clock selected */
+} mcg_irc_mode_t;
+
+/*! @brief MCG DCO Maximum Frequency with 32.768 kHz Reference */
+typedef enum _mcg_dmx32
+{
+ kMCG_Dmx32Default, /*!< DCO has a default range of 25% */
+ kMCG_Dmx32Fine /*!< DCO is fine-tuned for maximum frequency with 32.768 kHz reference */
+} mcg_dmx32_t;
+
+/*! @brief MCG DCO range select */
+typedef enum _mcg_drs
+{
+ kMCG_DrsLow, /*!< Low frequency range */
+ kMCG_DrsMid, /*!< Mid frequency range */
+ kMCG_DrsMidHigh, /*!< Mid-High frequency range */
+ kMCG_DrsHigh /*!< High frequency range */
+} mcg_drs_t;
+
+/*! @brief MCG PLL reference clock select */
+typedef enum _mcg_pll_ref_src
+{
+ kMCG_PllRefOsc0, /*!< Selects OSC0 as PLL reference clock */
+ kMCG_PllRefOsc1 /*!< Selects OSC1 as PLL reference clock */
+} mcg_pll_ref_src_t;
+
+/*! @brief MCGOUT clock source. */
+typedef enum _mcg_clkout_src
+{
+ kMCG_ClkOutSrcOut, /*!< Output of the FLL is selected (reset default) */
+ kMCG_ClkOutSrcInternal, /*!< Internal reference clock is selected */
+ kMCG_ClkOutSrcExternal, /*!< External reference clock is selected */
+} mcg_clkout_src_t;
+
+/*! @brief MCG Automatic Trim Machine Select */
+typedef enum _mcg_atm_select
+{
+ kMCG_AtmSel32k, /*!< 32 kHz Internal Reference Clock selected */
+ kMCG_AtmSel4m /*!< 4 MHz Internal Reference Clock selected */
+} mcg_atm_select_t;
+
+/*! @brief MCG OSC Clock Select */
+typedef enum _mcg_oscsel
+{
+ kMCG_OscselOsc, /*!< Selects System Oscillator (OSCCLK) */
+ kMCG_OscselRtc, /*!< Selects 32 kHz RTC Oscillator */
+} mcg_oscsel_t;
+
+/*! @brief MCG PLLCS select */
+typedef enum _mcg_pll_clk_select
+{
+ kMCG_PllClkSelPll0, /*!< PLL0 output clock is selected */
+ kMCG_PllClkSelPll1 /* PLL1 output clock is selected */
+} mcg_pll_clk_select_t;
+
+/*! @brief MCG clock monitor mode. */
+typedef enum _mcg_monitor_mode
+{
+ kMCG_MonitorNone, /*!< Clock monitor is disabled. */
+ kMCG_MonitorInt, /*!< Trigger interrupt when clock lost. */
+ kMCG_MonitorReset /*!< System reset when clock lost. */
+} mcg_monitor_mode_t;
+
+/*! @brief MCG status. */
+enum _mcg_status
+{
+ kStatus_MCG_ModeUnreachable = MAKE_STATUS(kStatusGroup_MCG, 0), /*!< Can't switch to target mode. */
+ kStatus_MCG_ModeInvalid = MAKE_STATUS(kStatusGroup_MCG, 1), /*!< Current mode invalid for the specific
+ function. */
+ kStatus_MCG_AtmBusClockInvalid = MAKE_STATUS(kStatusGroup_MCG, 2), /*!< Invalid bus clock for ATM. */
+ kStatus_MCG_AtmDesiredFreqInvalid = MAKE_STATUS(kStatusGroup_MCG, 3), /*!< Invalid desired frequency for ATM. */
+ kStatus_MCG_AtmIrcUsed = MAKE_STATUS(kStatusGroup_MCG, 4), /*!< IRC is used when using ATM. */
+ kStatus_MCG_AtmHardwareFail = MAKE_STATUS(kStatusGroup_MCG, 5), /*!< Hardware fail occurs during ATM. */
+ kStatus_MCG_SourceUsed = MAKE_STATUS(kStatusGroup_MCG, 6) /*!< Could not change clock source because
+ it is used currently. */
+};
+
+/*! @brief MCG status flags. */
+enum _mcg_status_flags_t
+{
+ kMCG_Osc0LostFlag = (1U << 0U), /*!< OSC0 lost. */
+ kMCG_Osc0InitFlag = (1U << 1U), /*!< OSC0 crystal initialized. */
+ kMCG_RtcOscLostFlag = (1U << 4U), /*!< RTC OSC lost. */
+ kMCG_Pll0LostFlag = (1U << 5U), /*!< PLL0 lost. */
+ kMCG_Pll0LockFlag = (1U << 6U), /*!< PLL0 locked. */
+};
+
+/*! @brief MCG internal reference clock (MCGIRCLK) enable mode definition. */
+enum _mcg_irclk_enable_mode
+{
+ kMCG_IrclkEnable = MCG_C1_IRCLKEN_MASK, /*!< MCGIRCLK enable. */
+ kMCG_IrclkEnableInStop = MCG_C1_IREFSTEN_MASK /*!< MCGIRCLK enable in stop mode. */
+};
+
+/*! @brief MCG PLL clock enable mode definition. */
+enum _mcg_pll_enable_mode
+{
+ kMCG_PllEnableIndependent = MCG_C5_PLLCLKEN0_MASK, /*!< MCGPLLCLK enable indepencent of
+ MCG clock mode. Generally, PLL
+ is disabled in FLL modes
+ (FEI/FBI/FEE/FBE), set PLL clock
+ enable independent will enable
+ PLL in the FLL modes. */
+ kMCG_PllEnableInStop = MCG_C5_PLLSTEN0_MASK /*!< MCGPLLCLK enable in STOP mode. */
+};
+
+/*! @brief MCG mode definitions */
+typedef enum _mcg_mode
+{
+ kMCG_ModeFEI = 0U, /*!< FEI - FLL Engaged Internal */
+ kMCG_ModeFBI, /*!< FBI - FLL Bypassed Internal */
+ kMCG_ModeBLPI, /*!< BLPI - Bypassed Low Power Internal */
+ kMCG_ModeFEE, /*!< FEE - FLL Engaged External */
+ kMCG_ModeFBE, /*!< FBE - FLL Bypassed External */
+ kMCG_ModeBLPE, /*!< BLPE - Bypassed Low Power External */
+ kMCG_ModePBE, /*!< PBE - PLL Bypassed External */
+ kMCG_ModePEE, /*!< PEE - PLL Engaged External */
+ kMCG_ModeError /*!< Unknown mode */
+} mcg_mode_t;
+
+/*! @brief MCG PLL configuration. */
+typedef struct _mcg_pll_config
+{
+ uint8_t enableMode; /*!< Enable mode. OR'ed value of @ref _mcg_pll_enable_mode. */
+ uint8_t prdiv; /*!< Reference divider PRDIV. */
+ uint8_t vdiv; /*!< VCO divider VDIV. */
+} mcg_pll_config_t;
+
+/*! @brief MCG configure structure for mode change.
+ *
+ * When porting to a new board, please set the following members
+ * according to board setting:
+ * 1. frdiv: If FLL uses the external reference clock, please set this
+ * value to make sure external reference clock divided by frdiv is
+ * in the range 31.25kHz to 39.0625kHz.
+ * 2. The PLL reference clock divider PRDIV: PLL reference clock frequency after
+ * PRDIV should be in the range of FSL_FEATURE_MCG_PLL_REF_MIN to
+ * FSL_FEATURE_MCG_PLL_REF_MAX.
+ */
+typedef struct _mcg_config
+{
+ mcg_mode_t mcgMode; /*!< MCG mode. */
+
+ /* ----------------------- MCGIRCCLK settings ------------------------ */
+ uint8_t irclkEnableMode; /*!< MCGIRCLK enable mode. */
+ mcg_irc_mode_t ircs; /*!< Source, MCG_C2[IRCS]. */
+ uint8_t fcrdiv; /*!< Divider, MCG_SC[FCRDIV]. */
+
+ /* ------------------------ MCG FLL settings ------------------------- */
+ uint8_t frdiv; /*!< Divider MCG_C1[FRDIV]. */
+ mcg_drs_t drs; /*!< DCO range MCG_C4[DRST_DRS]. */
+ mcg_dmx32_t dmx32; /*!< MCG_C4[DMX32]. */
+ mcg_oscsel_t oscsel; /*!< OSC select MCG_C7[OSCSEL]. */
+
+ /* ------------------------ MCG PLL settings ------------------------- */
+ mcg_pll_config_t pll0Config; /*!< MCGPLL0CLK configuration. */
+
+} mcg_config_t;
+
+/*******************************************************************************
+ * API
+ ******************************************************************************/
+
+#if defined(__cplusplus)
+extern "C" {
+#endif /* __cplusplus */
+
+/*!
+ * @brief Enable the clock for specific IP.
+ *
+ * @param name Which clock to enable, see \ref clock_ip_name_t.
+ */
+static inline void CLOCK_EnableClock(clock_ip_name_t name)
+{
+ uint32_t regAddr = SIM_BASE + CLK_GATE_ABSTRACT_REG_OFFSET((uint32_t)name);
+ (*(volatile uint32_t *)regAddr) |= (1U << CLK_GATE_ABSTRACT_BITS_SHIFT((uint32_t)name));
+}
+
+/*!
+ * @brief Disable the clock for specific IP.
+ *
+ * @param name Which clock to disable, see \ref clock_ip_name_t.
+ */
+static inline void CLOCK_DisableClock(clock_ip_name_t name)
+{
+ uint32_t regAddr = SIM_BASE + CLK_GATE_ABSTRACT_REG_OFFSET((uint32_t)name);
+ (*(volatile uint32_t *)regAddr) &= ~(1U << CLK_GATE_ABSTRACT_BITS_SHIFT((uint32_t)name));
+}
+
+/*!
+ * @brief Set ERCLK32K source.
+ *
+ * @param src The value to set ERCLK32K clock source.
+ */
+static inline void CLOCK_SetEr32kClock(uint32_t src)
+{
+ SIM->SOPT1 = ((SIM->SOPT1 & ~SIM_SOPT1_OSC32KSEL_MASK) | SIM_SOPT1_OSC32KSEL(src));
+}
+
+/*!
+ * @brief Set SDHC0 clock source.
+ *
+ * @param src The value to set SDHC0 clock source.
+ */
+static inline void CLOCK_SetSdhc0Clock(uint32_t src)
+{
+ SIM->SOPT2 = ((SIM->SOPT2 & ~SIM_SOPT2_SDHCSRC_MASK) | SIM_SOPT2_SDHCSRC(src));
+}
+
+/*!
+ * @brief Set debug trace clock source.
+ *
+ * @param src The value to set debug trace clock source.
+ */
+static inline void CLOCK_SetTraceClock(uint32_t src)
+{
+ SIM->SOPT2 = ((SIM->SOPT2 & ~SIM_SOPT2_TRACECLKSEL_MASK) | SIM_SOPT2_TRACECLKSEL(src));
+}
+
+/*!
+ * @brief Set PLLFLLSEL clock source.
+ *
+ * @param src The value to set PLLFLLSEL clock source.
+ */
+static inline void CLOCK_SetPllFllSelClock(uint32_t src)
+{
+ SIM->SOPT2 = ((SIM->SOPT2 & ~SIM_SOPT2_PLLFLLSEL_MASK) | SIM_SOPT2_PLLFLLSEL(src));
+}
+/*!
+ * @brief Set CLKOUT source.
+ *
+ * @param src The value to set CLKOUT source.
+ */
+static inline void CLOCK_SetClkOutClock(uint32_t src)
+{
+ SIM->SOPT2 = ((SIM->SOPT2 & ~SIM_SOPT2_CLKOUTSEL_MASK) | SIM_SOPT2_CLKOUTSEL(src));
+}
+
+/*!
+ * @brief Set RTC_CLKOUT source.
+ *
+ * @param src The value to set RTC_CLKOUT source.
+ */
+static inline void CLOCK_SetRtcClkOutClock(uint32_t src)
+{
+ SIM->SOPT2 = ((SIM->SOPT2 & ~SIM_SOPT2_RTCCLKOUTSEL_MASK) | SIM_SOPT2_RTCCLKOUTSEL(src));
+}
+
+/*! @brief Enable USB FS clock.
+ *
+ * @param src USB FS clock source.
+ * @param freq The frequency specified by src.
+ * @retval true The clock is set successfully.
+ * @retval false The clock source is invalid to get proper USB FS clock.
+ */
+bool CLOCK_EnableUsbfs0Clock(clock_usb_src_t src, uint32_t freq);
+
+/*! @brief Disable USB FS clock.
+ *
+ * Disable USB FS clock.
+ */
+static inline void CLOCK_DisableUsbfs0Clock(void)
+{
+ CLOCK_DisableClock(kCLOCK_Usbfs0);
+}
+
+/*!
+ * @brief System clock divider
+ *
+ * Set the SIM_CLKDIV1[OUTDIV1], SIM_CLKDIV1[OUTDIV2], SIM_CLKDIV1[OUTDIV3], SIM_CLKDIV1[OUTDIV4].
+ *
+ * @param outdiv1 Clock 1 output divider value.
+ *
+ * @param outdiv2 Clock 2 output divider value.
+ *
+ * @param outdiv3 Clock 3 output divider value.
+ *
+ * @param outdiv4 Clock 4 output divider value.
+ */
+static inline void CLOCK_SetOutDiv(uint32_t outdiv1, uint32_t outdiv2, uint32_t outdiv3, uint32_t outdiv4)
+{
+ SIM->CLKDIV1 = SIM_CLKDIV1_OUTDIV1(outdiv1) | SIM_CLKDIV1_OUTDIV2(outdiv2) | SIM_CLKDIV1_OUTDIV3(outdiv3) |
+ SIM_CLKDIV1_OUTDIV4(outdiv4);
+}
+
+/*!
+ * @brief Gets the clock frequency for a specific clock name.
+ *
+ * This function checks the current clock configurations and then calculates
+ * the clock frequency for a specific clock name defined in clock_name_t.
+ * The MCG must be properly configured before using this function.
+ *
+ * @param clockName Clock names defined in clock_name_t
+ * @return Clock frequency value in Hertz
+ */
+uint32_t CLOCK_GetFreq(clock_name_t clockName);
+
+/*!
+ * @brief Get the core clock or system clock frequency.
+ *
+ * @return Clock frequency in Hz.
+ */
+uint32_t CLOCK_GetCoreSysClkFreq(void);
+
+/*!
+ * @brief Get the platform clock frequency.
+ *
+ * @return Clock frequency in Hz.
+ */
+uint32_t CLOCK_GetPlatClkFreq(void);
+
+/*!
+ * @brief Get the bus clock frequency.
+ *
+ * @return Clock frequency in Hz.
+ */
+uint32_t CLOCK_GetBusClkFreq(void);
+
+/*!
+ * @brief Get the flexbus clock frequency.
+ *
+ * @return Clock frequency in Hz.
+ */
+uint32_t CLOCK_GetFlexBusClkFreq(void);
+
+/*!
+ * @brief Get the flash clock frequency.
+ *
+ * @return Clock frequency in Hz.
+ */
+uint32_t CLOCK_GetFlashClkFreq(void);
+
+/*!
+ * @brief Get the output clock frequency selected by SIM[PLLFLLSEL].
+ *
+ * @return Clock frequency in Hz.
+ */
+uint32_t CLOCK_GetPllFllSelClkFreq(void);
+
+/*!
+ * @brief Get the external reference 32K clock frequency (ERCLK32K).
+ *
+ * @return Clock frequency in Hz.
+ */
+uint32_t CLOCK_GetEr32kClkFreq(void);
+
+/*!
+ * @brief Get the OSC0 external reference clock frequency (OSC0ERCLK).
+ *
+ * @return Clock frequency in Hz.
+ */
+uint32_t CLOCK_GetOsc0ErClkFreq(void);
+
+/*!
+ * @brief Set the clock configure in SIM module.
+ *
+ * This function sets system layer clock settings in SIM module.
+ *
+ * @param config Pointer to the configure structure.
+ */
+void CLOCK_SetSimConfig(sim_clock_config_t const *config);
+
+/*!
+ * @brief Set the system clock dividers in SIM to safe value.
+ *
+ * The system level clocks (core clock, bus clock, flexbus clock and flash clock)
+ * must be in allowed ranges. During MCG clock mode switch, the MCG output clock
+ * changes then the system level clocks may be out of range. This function could
+ * be used before MCG mode change, to make sure system level clocks are in allowed
+ * range.
+ *
+ * @param config Pointer to the configure structure.
+ */
+static inline void CLOCK_SetSimSafeDivs(void)
+{
+ SIM->CLKDIV1 = 0x01240000U;
+}
+
+/*! @name MCG frequency functions. */
+/*@{*/
+
+/*!
+ * @brief Get the MCG output clock(MCGOUTCLK) frequency.
+ *
+ * This function gets the MCG output clock frequency (Hz) based on current MCG
+ * register value.
+ *
+ * @return The frequency of MCGOUTCLK.
+ */
+uint32_t CLOCK_GetOutClkFreq(void);
+
+/*!
+ * @brief Get the MCG FLL clock(MCGFLLCLK) frequency.
+ *
+ * This function gets the MCG FLL clock frequency (Hz) based on current MCG
+ * register value. The FLL is only enabled in FEI/FBI/FEE/FBE mode, in other
+ * modes, FLL is disabled in low power state.
+ *
+ * @return The frequency of MCGFLLCLK.
+ */
+uint32_t CLOCK_GetFllFreq(void);
+
+/*!
+ * @brief Get the MCG internal reference clock(MCGIRCLK) frequency.
+ *
+ * This function gets the MCG internal reference clock frequency (Hz) based
+ * on current MCG register value.
+ *
+ * @return The frequency of MCGIRCLK.
+ */
+uint32_t CLOCK_GetInternalRefClkFreq(void);
+
+/*!
+ * @brief Get the MCG fixed frequency clock(MCGFFCLK) frequency.
+ *
+ * This function gets the MCG fixed frequency clock frequency (Hz) based
+ * on current MCG register value.
+ *
+ * @return The frequency of MCGFFCLK.
+ */
+uint32_t CLOCK_GetFixedFreqClkFreq(void);
+
+/*!
+ * @brief Get the MCG PLL0 clock(MCGPLL0CLK) frequency.
+ *
+ * This function gets the MCG PLL0 clock frequency (Hz) based on current MCG
+ * register value.
+ *
+ * @return The frequency of MCGPLL0CLK.
+ */
+uint32_t CLOCK_GetPll0Freq(void);
+
+/*@}*/
+
+/*! @name MCG clock configuration. */
+/*@{*/
+
+/*!
+ * @brief Enable or disable MCG low power.
+ *
+ * Enable MCG low power will disable the PLL and FLL in bypass modes. That is,
+ * in FBE and PBE modes, enable low power will set MCG to BLPE mode, in FBI and
+ * PBI mode, enable low power will set MCG to BLPI mode.
+ * When disable MCG low power, the PLL or FLL will be enabled based on MCG setting.
+ *
+ * @param enable True to enable MCG low power, false to disable MCG low power.
+ */
+static inline void CLOCK_SetLowPowerEnable(bool enable)
+{
+ if (enable)
+ {
+ MCG->C2 |= MCG_C2_LP_MASK;
+ }
+ else
+ {
+ MCG->C2 &= ~MCG_C2_LP_MASK;
+ }
+}
+
+/*!
+ * @brief Configure the Internal Reference clock (MCGIRCLK)
+ *
+ * This function setups the \c MCGIRCLK base on parameters. It selects the IRC
+ * source, if fast IRC is used, this function also sets the fast IRC divider.
+ * This function also sets whether enable \c MCGIRCLK in stop mode.
+ * Calling this function in FBI/PBI/BLPI modes may change the system clock, so
+ * it is not allowed to use this in these modes.
+ *
+ * @param enableMode MCGIRCLK enable mode, OR'ed value of @ref _mcg_irclk_enable_mode.
+ * @param ircs MCGIRCLK clock source, choose fast or slow.
+ * @param fcrdiv Fast IRC divider setting (\c FCRDIV).
+ * @retval kStatus_MCG_SourceUsed MCGIRCLK is used as system clock, should not configure MCGIRCLK.
+ * @retval kStatus_Success MCGIRCLK configuration finished successfully.
+ */
+status_t CLOCK_SetInternalRefClkConfig(uint8_t enableMode, mcg_irc_mode_t ircs, uint8_t fcrdiv);
+
+/*!
+ * @brief Select the MCG external reference clock.
+ *
+ * Select the MCG external reference clock source, it changes the MCG_C7[OSCSEL]
+ * and wait for the clock source stable. Should not change external reference
+ * clock in FEE/FBE/BLPE/PBE/PEE mdes, so don't call this function in these modes.
+ *
+ * @param oscsel MCG external reference clock source, MCG_C7[OSCSEL].
+ * @retval kStatus_MCG_SourceUsed External reference clock is used, should not change.
+ * @retval kStatus_Success External reference clock set successfully.
+ */
+status_t CLOCK_SetExternalRefClkConfig(mcg_oscsel_t oscsel);
+
+/*!
+ * @brief Enables the PLL0 in FLL mode.
+ *
+ * This function setups the PLL0 in FLL mode, make sure the PLL reference
+ * clock is enabled before calling this function. This function reconfigures
+ * the PLL0, make sure the PLL0 is not used as a clock source while calling
+ * this function. The function CLOCK_CalcPllDiv can help to get the proper PLL
+ * divider values.
+ *
+ * @param config Pointer to the configuration structure.
+ */
+void CLOCK_EnablePll0(mcg_pll_config_t const *config);
+
+/*!
+ * @brief Disables the PLL0 in FLL mode.
+ *
+ * This function disables the PLL0 in FLL mode, it should be used together with
+ * @ref CLOCK_EnablePll0.
+ */
+static inline void CLOCK_DisablePll0(void)
+{
+ MCG->C5 &= ~(MCG_C5_PLLCLKEN0_MASK | MCG_C5_PLLSTEN0_MASK);
+}
+
+/*!
+ * @brief Calculates the PLL divider setting for desired output frequency.
+ *
+ * This function calculates the proper reference clock divider (\c PRDIV) and
+ * VCO divider (\c VDIV) to generate desired PLL output frequency. It returns the
+ * closest frequency PLL could generate, the corresponding \c PRDIV/VDIV are
+ * returned from parameters. If desired frequency is not valid, this function
+ * returns 0.
+ *
+ * @param refFreq PLL reference clock frequency.
+ * @param desireFreq Desired PLL output frequency.
+ * @param prdiv PRDIV value to generate desired PLL frequency.
+ * @param vdiv VDIV value to generate desired PLL frequency.
+ * @return Closest frequency PLL could generate.
+ */
+uint32_t CLOCK_CalcPllDiv(uint32_t refFreq, uint32_t desireFreq, uint8_t *prdiv, uint8_t *vdiv);
+
+/*@}*/
+
+/*! @name MCG clock lock monitor functions. */
+/*@{*/
+
+/*!
+ * @brief Set the OSC0 clock monitor mode.
+ *
+ * Set the OSC0 clock monitor mode, see @ref mcg_monitor_mode_t for details.
+ *
+ * @param mode The monitor mode to set.
+ */
+void CLOCK_SetOsc0MonitorMode(mcg_monitor_mode_t mode);
+
+/*!
+ * @brief Set the RTC OSC clock monitor mode.
+ *
+ * Set the RTC OSC clock monitor mode, see @ref mcg_monitor_mode_t for details.
+ *
+ * @param mode The monitor mode to set.
+ */
+void CLOCK_SetRtcOscMonitorMode(mcg_monitor_mode_t mode);
+
+/*!
+ * @brief Set the PLL0 clock monitor mode.
+ *
+ * Set the PLL0 clock monitor mode, see @ref mcg_monitor_mode_t for details.
+ *
+ * @param mode The monitor mode to set.
+ */
+void CLOCK_SetPll0MonitorMode(mcg_monitor_mode_t mode);
+
+/*!
+ * @brief Get the MCG status flags.
+ *
+ * This function gets the MCG clock status flags, all the status flags are
+ * returned as a logical OR of the enumeration @ref _mcg_status_flags_t. To
+ * check specific flags, compare the return value with the flags.
+ *
+ * Example:
+ * @code
+ // To check the clock lost lock status of OSC0 and PLL0.
+ uint32_t mcgFlags;
+
+ mcgFlags = CLOCK_GetStatusFlags();
+
+ if (mcgFlags & kMCG_Osc0LostFlag)
+ {
+ // OSC0 clock lock lost. Do something.
+ }
+ if (mcgFlags & kMCG_Pll0LostFlag)
+ {
+ // PLL0 clock lock lost. Do something.
+ }
+ @endcode
+ *
+ * @return Logical OR value of the @ref _mcg_status_flags_t.
+ */
+uint32_t CLOCK_GetStatusFlags(void);
+
+/*!
+ * @brief Clears the MCG status flags.
+ *
+ * This function clears the MCG clock lock lost status. The parameter is logical
+ * OR value of the flags to clear, see @ref _mcg_status_flags_t.
+ *
+ * Example:
+ * @code
+ // To clear the clock lost lock status flags of OSC0 and PLL0.
+
+ CLOCK_ClearStatusFlags(kMCG_Osc0LostFlag | kMCG_Pll0LostFlag);
+ @endcode
+ *
+ * @param mask The status flags to clear. This is a logical OR of members of the
+ * enumeration @ref _mcg_status_flags_t.
+ */
+void CLOCK_ClearStatusFlags(uint32_t mask);
+
+/*@}*/
+
+/*!
+ * @name OSC configuration
+ * @{
+ */
+
+/*!
+ * @brief Configures the OSC external reference clock (OSCERCLK).
+ *
+ * This function configures the OSC external reference clock (OSCERCLK).
+ * For example, to enable the OSCERCLK in normal mode and stop mode, and also set
+ * the output divider to 1, as follows:
+ *
+ @code
+ oscer_config_t config =
+ {
+ .enableMode = kOSC_ErClkEnable | kOSC_ErClkEnableInStop,
+ .erclkDiv = 1U,
+ };
+
+ OSC_SetExtRefClkConfig(OSC, &config);
+ @endcode
+ *
+ * @param base OSC peripheral address.
+ * @param config Pointer to the configuration structure.
+ */
+static inline void OSC_SetExtRefClkConfig(OSC_Type *base, oscer_config_t const *config)
+{
+ uint8_t reg = base->CR;
+
+ reg &= ~(OSC_CR_ERCLKEN_MASK | OSC_CR_EREFSTEN_MASK);
+ reg |= config->enableMode;
+
+ base->CR = reg;
+}
+
+/*!
+ * @brief Sets the capacitor load configuration for the oscillator.
+ *
+ * This function sets the specified capacitors configuration for the oscillator.
+ * This should be done in the early system level initialization function call
+ * based on the system configuration.
+ *
+ * @param base OSC peripheral address.
+ * @param capLoad OR'ed value for the capacitor load option, see \ref _osc_cap_load.
+ *
+ * Example:
+ @code
+ // To enable only 2 pF and 8 pF capacitor load, please use like this.
+ OSC_SetCapLoad(OSC, kOSC_Cap2P | kOSC_Cap8P);
+ @endcode
+ */
+static inline void OSC_SetCapLoad(OSC_Type *base, uint8_t capLoad)
+{
+ uint8_t reg = base->CR;
+
+ reg &= ~(OSC_CR_SC2P_MASK | OSC_CR_SC4P_MASK | OSC_CR_SC8P_MASK | OSC_CR_SC16P_MASK);
+ reg |= capLoad;
+
+ base->CR = reg;
+}
+
+/*!
+ * @brief Initialize OSC0.
+ *
+ * This function initializes OSC0 according to board configuration.
+ *
+ * @param config Pointer to the OSC0 configuration structure.
+ */
+void CLOCK_InitOsc0(osc_config_t const *config);
+
+/*!
+ * @brief Deinitialize OSC0.
+ *
+ * This function deinitializes OSC0.
+ */
+void CLOCK_DeinitOsc0(void);
+
+/* @} */
+
+/*!
+ * @name External clock frequency
+ * @{
+ */
+
+/*!
+ * @brief Set the XTAL0 frequency based on board setting.
+ *
+ * @param freq The XTAL0/EXTAL0 input clock frequency in Hz.
+ */
+static inline void CLOCK_SetXtal0Freq(uint32_t freq)
+{
+ g_xtal0Freq = freq;
+}
+
+/*!
+ * @brief Set the XTAL32/RTC_CLKIN frequency based on board setting.
+ *
+ * @param freq The XTAL32/EXTAL32/RTC_CLKIN input clock frequency in Hz.
+ */
+static inline void CLOCK_SetXtal32Freq(uint32_t freq)
+{
+ g_xtal32Freq = freq;
+}
+/* @} */
+
+/*!
+ * @name MCG auto-trim machine.
+ * @{
+ */
+
+/*!
+ * @brief Auto trim the internal reference clock.
+ *
+ * This function trims the internal reference clock using external clock. If
+ * successful, it returns the kStatus_Success and the frequency after
+ * trimming is received in the parameter @p actualFreq. If an error occurs,
+ * the error code is returned.
+ *
+ * @param extFreq External clock frequency, should be bus clock.
+ * @param desireFreq Frequency want to trim to.
+ * @param actualFreq Actual frequency after trim.
+ * @param atms Trim fast or slow internal reference clock.
+ * @retval kStatus_Success ATM success.
+ * @retval kStatus_MCG_AtmBusClockInvalid The bus clock is not in allowed range for ATM.
+ * @retval kStatus_MCG_AtmDesiredFreqInvalid MCGIRCLK could not be trimmed to the desired frequency.
+ * @retval kStatus_MCG_AtmIrcUsed Could not trim because MCGIRCLK is used as bus clock source.
+ * @retval kStatus_MCG_AtmHardwareFail Hardware fails during trim.
+ */
+status_t CLOCK_TrimInternalRefClk(uint32_t extFreq, uint32_t desireFreq, uint32_t *actualFreq, mcg_atm_select_t atms);
+/* @} */
+
+/*! @name MCG mode functions. */
+/*@{*/
+
+/*!
+ * @brief Gets the current MCG mode.
+ *
+ * This function checks the MCG registers and determine current MCG mode.
+ *
+ * @return Current MCG mode or error code, see @ref mcg_mode_t.
+ */
+mcg_mode_t CLOCK_GetMode(void);
+
+/*!
+ * @brief Set MCG to FEI mode.
+ *
+ * This function sets MCG to FEI mode. If could not set to FEI mode directly
+ * from current mode, this function returns error.
+ *
+ * @param dmx32 DMX32 in FEI mode.
+ * @param drs The DCO range selection.
+ * @param fllStableDelay Delay function to make sure FLL is stable, if pass
+ * in NULL, then does not delay.
+ * @retval kStatus_MCG_ModeUnreachable Could not switch to the target mode.
+ * @retval kStatus_Success Switch to target mode successfully.
+ * @note If @p dmx32 is set to kMCG_Dmx32Fine, the slow IRC must not be trimmed
+ * to frequency above 32768Hz.
+ */
+status_t CLOCK_SetFeiMode(mcg_dmx32_t dmx32, mcg_drs_t drs, void (*fllStableDelay)(void));
+
+/*!
+ * @brief Set MCG to FEE mode.
+ *
+ * This function sets MCG to FEE mode. If could not set to FEE mode directly
+ * from current mode, this function returns error.
+ *
+ * @param frdiv FLL reference clock divider setting, FRDIV.
+ * @param dmx32 DMX32 in FEE mode.
+ * @param drs The DCO range selection.
+ * @param fllStableDelay Delay function to make sure FLL is stable, if pass
+ * in NULL, then does not delay.
+ *
+ * @retval kStatus_MCG_ModeUnreachable Could not switch to the target mode.
+ * @retval kStatus_Success Switch to target mode successfully.
+ */
+status_t CLOCK_SetFeeMode(uint8_t frdiv, mcg_dmx32_t dmx32, mcg_drs_t drs, void (*fllStableDelay)(void));
+
+/*!
+ * @brief Set MCG to FBI mode.
+ *
+ * This function sets MCG to FBI mode. If could not set to FBI mode directly
+ * from current mode, this function returns error.
+ *
+ * @param dmx32 DMX32 in FBI mode.
+ * @param drs The DCO range selection.
+ * @param fllStableDelay Delay function to make sure FLL is stable. If FLL
+ * is not used in FBI mode, this parameter could be NULL. Pass in
+ * NULL does not delay.
+ * @retval kStatus_MCG_ModeUnreachable Could not switch to the target mode.
+ * @retval kStatus_Success Switch to target mode successfully.
+ * @note If @p dmx32 is set to kMCG_Dmx32Fine, the slow IRC must not be trimmed
+ * to frequency above 32768Hz.
+ */
+status_t CLOCK_SetFbiMode(mcg_dmx32_t dmx32, mcg_drs_t drs, void (*fllStableDelay)(void));
+
+/*!
+ * @brief Set MCG to FBE mode.
+ *
+ * This function sets MCG to FBE mode. If could not set to FBE mode directly
+ * from current mode, this function returns error.
+ *
+ * @param frdiv FLL reference clock divider setting, FRDIV.
+ * @param dmx32 DMX32 in FBE mode.
+ * @param drs The DCO range selection.
+ * @param fllStableDelay Delay function to make sure FLL is stable. If FLL
+ * is not used in FBE mode, this parameter could be NULL. Pass in NULL
+ * does not delay.
+ * @retval kStatus_MCG_ModeUnreachable Could not switch to the target mode.
+ * @retval kStatus_Success Switch to target mode successfully.
+ */
+status_t CLOCK_SetFbeMode(uint8_t frdiv, mcg_dmx32_t dmx32, mcg_drs_t drs, void (*fllStableDelay)(void));
+
+/*!
+ * @brief Set MCG to BLPI mode.
+ *
+ * This function sets MCG to BLPI mode. If could not set to BLPI mode directly
+ * from current mode, this function returns error.
+ *
+ * @retval kStatus_MCG_ModeUnreachable Could not switch to the target mode.
+ * @retval kStatus_Success Switch to target mode successfully.
+ */
+status_t CLOCK_SetBlpiMode(void);
+
+/*!
+ * @brief Set MCG to BLPE mode.
+ *
+ * This function sets MCG to BLPE mode. If could not set to BLPE mode directly
+ * from current mode, this function returns error.
+ *
+ * @retval kStatus_MCG_ModeUnreachable Could not switch to the target mode.
+ * @retval kStatus_Success Switch to target mode successfully.
+ */
+status_t CLOCK_SetBlpeMode(void);
+
+/*!
+ * @brief Set MCG to PBE mode.
+ *
+ * This function sets MCG to PBE mode. If could not set to PBE mode directly
+ * from current mode, this function returns error.
+ *
+ * @param pllcs The PLL selection, PLLCS.
+ * @param config Pointer to the PLL configuration.
+ * @retval kStatus_MCG_ModeUnreachable Could not switch to the target mode.
+ * @retval kStatus_Success Switch to target mode successfully.
+ *
+ * @note
+ * 1. The parameter \c pllcs selects the PLL, for some platforms, there is
+ * only one PLL, the parameter pllcs is kept for interface compatible.
+ * 2. The parameter \c config is the PLL configuration structure, on some
+ * platforms, could choose the external PLL directly. This means that the
+ * configuration structure is not necessary, pass in NULL for this case.
+ * For example: CLOCK_SetPbeMode(kMCG_OscselOsc, kMCG_PllClkSelExtPll, NULL);
+ */
+status_t CLOCK_SetPbeMode(mcg_pll_clk_select_t pllcs, mcg_pll_config_t const *config);
+
+/*!
+ * @brief Set MCG to PEE mode.
+ *
+ * This function sets MCG to PEE mode.
+ *
+ * @retval kStatus_MCG_ModeUnreachable Could not switch to the target mode.
+ * @retval kStatus_Success Switch to target mode successfully.
+ *
+ * @note This function only change CLKS to use PLL/FLL output. If the
+ * PRDIV/VDIV are different from PBE mode, please setup these
+ * settings in PBE mode and wait for stable then switch to PEE mode.
+ */
+status_t CLOCK_SetPeeMode(void);
+
+/*!
+ * @brief Switch MCG to FBE mode quickly from external mode.
+ *
+ * This function changes MCG from external modes (PEE/PBE/BLPE/FEE) to FBE mode quickly.
+ * It only changes to use external clock as the system clock souce and disable PLL, but does not
+ * configure FLL settings. This is a lite function with small code size, it is useful
+ * during mode switch. For example, to switch from PEE mode to FEI mode:
+ *
+ * @code
+ * CLOCK_ExternalModeToFbeModeQuick();
+ * CLOCK_SetFeiMode(...);
+ * @endcode
+ *
+ * @retval kStatus_Success Change successfully.
+ * @retval kStatus_MCG_ModeInvalid Current mode is not external modes, should not call this function.
+ */
+status_t CLOCK_ExternalModeToFbeModeQuick(void);
+
+/*!
+ * @brief Switch MCG to FBI mode quickly from internal modes.
+ *
+ * This function changes MCG from internal modes (PEI/PBI/BLPI/FEI) to FBI mode quickly.
+ * It only changes to use MCGIRCLK as the system clock souce and disable PLL, but does not
+ * configure FLL settings. This is a lite function with small code size, it is useful
+ * during mode switch. For example, to switch from PEI mode to FEE mode:
+ *
+ * @code
+ * CLOCK_InternalModeToFbiModeQuick();
+ * CLOCK_SetFeeMode(...);
+ * @endcode
+ *
+ * @retval kStatus_Success Change successfully.
+ * @retval kStatus_MCG_ModeInvalid Current mode is not internal mode, should not call this function.
+ */
+status_t CLOCK_InternalModeToFbiModeQuick(void);
+
+/*!
+ * @brief Set MCG to FEI mode during system boot up.
+ *
+ * This function sets MCG to FEI mode from reset mode, it could be used to
+ * set up MCG during system boot up.
+ *
+ * @param dmx32 DMX32 in FEI mode.
+ * @param drs The DCO range selection.
+ * @param fllStableDelay Delay function to make sure FLL is stable.
+ *
+ * @retval kStatus_MCG_ModeUnreachable Could not switch to the target mode.
+ * @retval kStatus_Success Switch to target mode successfully.
+ * @note If @p dmx32 is set to kMCG_Dmx32Fine, the slow IRC must not be trimmed
+ * to frequency above 32768Hz.
+ */
+status_t CLOCK_BootToFeiMode(mcg_dmx32_t dmx32, mcg_drs_t drs, void (*fllStableDelay)(void));
+
+/*!
+ * @brief Set MCG to FEE mode during system bootup.
+ *
+ * This function sets MCG to FEE mode from reset mode, it could be used to
+ * set up MCG during system boot up.
+ *
+ * @param oscsel OSC clock select, OSCSEL.
+ * @param frdiv FLL reference clock divider setting, FRDIV.
+ * @param dmx32 DMX32 in FEE mode.
+ * @param drs The DCO range selection.
+ * @param fllStableDelay Delay function to make sure FLL is stable.
+ *
+ * @retval kStatus_MCG_ModeUnreachable Could not switch to the target mode.
+ * @retval kStatus_Success Switch to target mode successfully.
+ */
+status_t CLOCK_BootToFeeMode(
+ mcg_oscsel_t oscsel, uint8_t frdiv, mcg_dmx32_t dmx32, mcg_drs_t drs, void (*fllStableDelay)(void));
+
+/*!
+ * @brief Set MCG to BLPI mode during system boot up.
+ *
+ * This function sets MCG to BLPI mode from reset mode, it could be used to
+ * setup MCG during sytem boot up.
+ *
+ * @param fcrdiv Fast IRC divider, FCRDIV.
+ * @param ircs The internal reference clock to select, IRCS.
+ * @param ircEnableMode The MCGIRCLK enable mode, OR'ed value of @ref _mcg_irclk_enable_mode.
+ *
+ * @retval kStatus_MCG_SourceUsed Could not change MCGIRCLK setting.
+ * @retval kStatus_Success Switch to target mode successfully.
+ */
+status_t CLOCK_BootToBlpiMode(uint8_t fcrdiv, mcg_irc_mode_t ircs, uint8_t ircEnableMode);
+
+/*!
+ * @brief Set MCG to BLPE mode during sytem boot up.
+ *
+ * This function sets MCG to BLPE mode from reset mode, it could be used to
+ * setup MCG during sytem boot up.
+ *
+ * @param oscsel OSC clock select, MCG_C7[OSCSEL].
+ *
+ * @retval kStatus_MCG_ModeUnreachable Could not switch to the target mode.
+ * @retval kStatus_Success Switch to target mode successfully.
+ */
+status_t CLOCK_BootToBlpeMode(mcg_oscsel_t oscsel);
+
+/*!
+ * @brief Set MCG to PEE mode during system boot up.
+ *
+ * This function sets MCG to PEE mode from reset mode, it could be used to
+ * setup MCG during system boot up.
+ *
+ * @param oscsel OSC clock select, MCG_C7[OSCSEL].
+ * @param pllcs The PLL selection, PLLCS.
+ * @param config Pointer to the PLL configuration.
+ *
+ * @retval kStatus_MCG_ModeUnreachable Could not switch to the target mode.
+ * @retval kStatus_Success Switch to target mode successfully.
+ */
+status_t CLOCK_BootToPeeMode(mcg_oscsel_t oscsel, mcg_pll_clk_select_t pllcs, mcg_pll_config_t const *config);
+
+/*!
+ * @brief Set MCG to some target mode.
+ *
+ * This function sets MCG to some target mode defined by the configure
+ * structure, if cannot switch to target mode directly, this function will
+ * choose the proper path.
+ *
+ * @param config Pointer to the target MCG mode configuration structure.
+ * @return Return kStatus_Success if switch successfully, otherwise return error code #_mcg_status.
+ *
+ * @note If external clock is used in the target mode, please make sure it is
+ * enabled, for example, if the OSC0 is used, please setup OSC0 correctly before
+ * this funciton.
+ */
+status_t CLOCK_SetMcgConfig(mcg_config_t const *config);
+
+/*@}*/
+
+#if defined(__cplusplus)
+}
+#endif /* __cplusplus */
+
+/*! @} */
+
+#endif /* _FSL_CLOCK_H_ */
diff --git a/drivers/fsl_cmp.c b/drivers/fsl_cmp.c
new file mode 100644
index 0000000..557a0c5
--- /dev/null
+++ b/drivers/fsl_cmp.c
@@ -0,0 +1,279 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_cmp.h"
+
+/*******************************************************************************
+ * Prototypes
+ ******************************************************************************/
+/*!
+ * @brief Get instance number for CMP module.
+ *
+ * @param base CMP peripheral base address
+ */
+static uint32_t CMP_GetInstance(CMP_Type *base);
+
+/*******************************************************************************
+ * Variables
+ ******************************************************************************/
+/*! @brief Pointers to CMP bases for each instance. */
+static CMP_Type *const s_cmpBases[] = CMP_BASE_PTRS;
+/*! @brief Pointers to CMP clocks for each instance. */
+static const clock_ip_name_t s_cmpClocks[] = CMP_CLOCKS;
+
+/*******************************************************************************
+ * Codes
+ ******************************************************************************/
+static uint32_t CMP_GetInstance(CMP_Type *base)
+{
+ uint32_t instance;
+
+ /* Find the instance index from base address mappings. */
+ for (instance = 0; instance < FSL_FEATURE_SOC_CMP_COUNT; instance++)
+ {
+ if (s_cmpBases[instance] == base)
+ {
+ break;
+ }
+ }
+
+ assert(instance < FSL_FEATURE_SOC_CMP_COUNT);
+
+ return instance;
+}
+
+void CMP_Init(CMP_Type *base, const cmp_config_t *config)
+{
+ assert(NULL != config);
+
+ uint8_t tmp8;
+
+ /* Enable the clock. */
+ CLOCK_EnableClock(s_cmpClocks[CMP_GetInstance(base)]);
+
+ /* Configure. */
+ CMP_Enable(base, false); /* Disable the CMP module during configuring. */
+ /* CMPx_CR1. */
+ tmp8 = base->CR1 & ~(CMP_CR1_PMODE_MASK | CMP_CR1_INV_MASK | CMP_CR1_COS_MASK | CMP_CR1_OPE_MASK);
+ if (config->enableHighSpeed)
+ {
+ tmp8 |= CMP_CR1_PMODE_MASK;
+ }
+ if (config->enableInvertOutput)
+ {
+ tmp8 |= CMP_CR1_INV_MASK;
+ }
+ if (config->useUnfilteredOutput)
+ {
+ tmp8 |= CMP_CR1_COS_MASK;
+ }
+ if (config->enablePinOut)
+ {
+ tmp8 |= CMP_CR1_OPE_MASK;
+ }
+#if defined(FSL_FEATURE_CMP_HAS_TRIGGER_MODE) && FSL_FEATURE_CMP_HAS_TRIGGER_MODE
+ if (config->enableTriggerMode)
+ {
+ tmp8 |= CMP_CR1_TRIGM_MASK;
+ }
+ else
+ {
+ tmp8 &= ~CMP_CR1_TRIGM_MASK;
+ }
+#endif /* FSL_FEATURE_CMP_HAS_TRIGGER_MODE */
+ base->CR1 = tmp8;
+
+ /* CMPx_CR0. */
+ tmp8 = base->CR0 & ~CMP_CR0_HYSTCTR_MASK;
+ tmp8 |= CMP_CR0_HYSTCTR(config->hysteresisMode);
+ base->CR0 = tmp8;
+
+ CMP_Enable(base, config->enableCmp); /* Enable the CMP module after configured or not. */
+}
+
+void CMP_Deinit(CMP_Type *base)
+{
+ /* Disable the CMP module. */
+ CMP_Enable(base, false);
+
+ /* Disable the clock. */
+ CLOCK_DisableClock(s_cmpClocks[CMP_GetInstance(base)]);
+}
+
+void CMP_GetDefaultConfig(cmp_config_t *config)
+{
+ assert(NULL != config);
+
+ config->enableCmp = true; /* Enable the CMP module after initialization. */
+ config->hysteresisMode = kCMP_HysteresisLevel0;
+ config->enableHighSpeed = false;
+ config->enableInvertOutput = false;
+ config->useUnfilteredOutput = false;
+ config->enablePinOut = false;
+#if defined(FSL_FEATURE_CMP_HAS_TRIGGER_MODE) && FSL_FEATURE_CMP_HAS_TRIGGER_MODE
+ config->enableTriggerMode = false;
+#endif /* FSL_FEATURE_CMP_HAS_TRIGGER_MODE */
+}
+
+void CMP_SetInputChannels(CMP_Type *base, uint8_t positiveChannel, uint8_t negativeChannel)
+{
+ uint8_t tmp8 = base->MUXCR;
+
+ tmp8 &= ~(CMP_MUXCR_PSEL_MASK | CMP_MUXCR_MSEL_MASK);
+ tmp8 |= CMP_MUXCR_PSEL(positiveChannel) | CMP_MUXCR_MSEL(negativeChannel);
+ base->MUXCR = tmp8;
+}
+
+#if defined(FSL_FEATURE_CMP_HAS_DMA) && FSL_FEATURE_CMP_HAS_DMA
+void CMP_EnableDMA(CMP_Type *base, bool enable)
+{
+ uint8_t tmp8 = base->SCR & ~(CMP_SCR_CFR_MASK | CMP_SCR_CFF_MASK); /* To avoid change the w1c bits. */
+
+ if (enable)
+ {
+ tmp8 |= CMP_SCR_DMAEN_MASK;
+ }
+ else
+ {
+ tmp8 &= ~CMP_SCR_DMAEN_MASK;
+ }
+ base->SCR = tmp8;
+}
+#endif /* FSL_FEATURE_CMP_HAS_DMA */
+
+void CMP_SetFilterConfig(CMP_Type *base, const cmp_filter_config_t *config)
+{
+ assert(NULL != config);
+
+ uint8_t tmp8;
+
+#if defined(FSL_FEATURE_CMP_HAS_EXTERNAL_SAMPLE_SUPPORT) && FSL_FEATURE_CMP_HAS_EXTERNAL_SAMPLE_SUPPORT
+ /* Choose the clock source for sampling. */
+ if (config->enableSample)
+ {
+ base->CR1 |= CMP_CR1_SE_MASK; /* Choose the external SAMPLE clock. */
+ }
+ else
+ {
+ base->CR1 &= ~CMP_CR1_SE_MASK; /* Choose the internal divided bus clock. */
+ }
+#endif /* FSL_FEATURE_CMP_HAS_EXTERNAL_SAMPLE_SUPPORT */
+ /* Set the filter count. */
+ tmp8 = base->CR0 & ~CMP_CR0_FILTER_CNT_MASK;
+ tmp8 |= CMP_CR0_FILTER_CNT(config->filterCount);
+ base->CR0 = tmp8;
+ /* Set the filter period. It is used as the divider to bus clock. */
+ base->FPR = CMP_FPR_FILT_PER(config->filterPeriod);
+}
+
+void CMP_SetDACConfig(CMP_Type *base, const cmp_dac_config_t *config)
+{
+ uint8_t tmp8 = 0U;
+
+ if (NULL == config)
+ {
+ /* Passing "NULL" as input parameter means no available configuration. So the DAC feature is disabled.*/
+ base->DACCR = 0U;
+ return;
+ }
+ /* CMPx_DACCR. */
+ tmp8 |= CMP_DACCR_DACEN_MASK; /* Enable the internal DAC. */
+ if (kCMP_VrefSourceVin2 == config->referenceVoltageSource)
+ {
+ tmp8 |= CMP_DACCR_VRSEL_MASK;
+ }
+ tmp8 |= CMP_DACCR_VOSEL(config->DACValue);
+
+ base->DACCR = tmp8;
+}
+
+void CMP_EnableInterrupts(CMP_Type *base, uint32_t mask)
+{
+ uint8_t tmp8 = base->SCR & ~(CMP_SCR_CFR_MASK | CMP_SCR_CFF_MASK); /* To avoid change the w1c bits. */
+
+ if (0U != (kCMP_OutputRisingInterruptEnable & mask))
+ {
+ tmp8 |= CMP_SCR_IER_MASK;
+ }
+ if (0U != (kCMP_OutputFallingInterruptEnable & mask))
+ {
+ tmp8 |= CMP_SCR_IEF_MASK;
+ }
+ base->SCR = tmp8;
+}
+
+void CMP_DisableInterrupts(CMP_Type *base, uint32_t mask)
+{
+ uint8_t tmp8 = base->SCR & ~(CMP_SCR_CFR_MASK | CMP_SCR_CFF_MASK); /* To avoid change the w1c bits. */
+
+ if (0U != (kCMP_OutputRisingInterruptEnable & mask))
+ {
+ tmp8 &= ~CMP_SCR_IER_MASK;
+ }
+ if (0U != (kCMP_OutputFallingInterruptEnable & mask))
+ {
+ tmp8 &= ~CMP_SCR_IEF_MASK;
+ }
+ base->SCR = tmp8;
+}
+
+uint32_t CMP_GetStatusFlags(CMP_Type *base)
+{
+ uint32_t ret32 = 0U;
+
+ if (0U != (CMP_SCR_CFR_MASK & base->SCR))
+ {
+ ret32 |= kCMP_OutputRisingEventFlag;
+ }
+ if (0U != (CMP_SCR_CFF_MASK & base->SCR))
+ {
+ ret32 |= kCMP_OutputFallingEventFlag;
+ }
+ if (0U != (CMP_SCR_COUT_MASK & base->SCR))
+ {
+ ret32 |= kCMP_OutputAssertEventFlag;
+ }
+ return ret32;
+}
+
+void CMP_ClearStatusFlags(CMP_Type *base, uint32_t mask)
+{
+ uint8_t tmp8 = base->SCR & ~(CMP_SCR_CFR_MASK | CMP_SCR_CFF_MASK); /* To avoid change the w1c bits. */
+
+ if (0U != (kCMP_OutputRisingEventFlag & mask))
+ {
+ tmp8 |= CMP_SCR_CFR_MASK;
+ }
+ if (0U != (kCMP_OutputFallingEventFlag & mask))
+ {
+ tmp8 |= CMP_SCR_CFF_MASK;
+ }
+ base->SCR = tmp8;
+}
diff --git a/drivers/fsl_cmp.h b/drivers/fsl_cmp.h
new file mode 100644
index 0000000..4c85bba
--- /dev/null
+++ b/drivers/fsl_cmp.h
@@ -0,0 +1,345 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_CMP_H_
+#define _FSL_CMP_H_
+
+#include "fsl_common.h"
+
+/*!
+ * @addtogroup cmp
+ * @{
+ */
+
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+/*! @name Driver version */
+/*@{*/
+/*! @brief CMP driver version 2.0.0. */
+#define FSL_CMP_DRIVER_VERSION (MAKE_VERSION(2, 0, 0))
+/*@}*/
+
+/*!
+* @brief Interrupt enable/disable mask.
+*/
+enum _cmp_interrupt_enable
+{
+ kCMP_OutputRisingInterruptEnable = CMP_SCR_IER_MASK, /*!< Comparator interrupt enable rising. */
+ kCMP_OutputFallingInterruptEnable = CMP_SCR_IEF_MASK, /*!< Comparator interrupt enable falling. */
+};
+
+/*!
+ * @brief Status flags' mask.
+ */
+enum _cmp_status_flags
+{
+ kCMP_OutputRisingEventFlag = CMP_SCR_CFR_MASK, /*!< Rising-edge on compare output has occurred. */
+ kCMP_OutputFallingEventFlag = CMP_SCR_CFF_MASK, /*!< Falling-edge on compare output has occurred. */
+ kCMP_OutputAssertEventFlag = CMP_SCR_COUT_MASK, /*!< Return the current value of the analog comparator output. */
+};
+
+/*!
+ * @brief CMP Hysteresis mode.
+ */
+typedef enum _cmp_hysteresis_mode
+{
+ kCMP_HysteresisLevel0 = 0U, /*!< Hysteresis level 0. */
+ kCMP_HysteresisLevel1 = 1U, /*!< Hysteresis level 1. */
+ kCMP_HysteresisLevel2 = 2U, /*!< Hysteresis level 2. */
+ kCMP_HysteresisLevel3 = 3U, /*!< Hysteresis level 3. */
+} cmp_hysteresis_mode_t;
+
+/*!
+ * @brief CMP Voltage Reference source.
+ */
+typedef enum _cmp_reference_voltage_source
+{
+ kCMP_VrefSourceVin1 = 0U, /*!< Vin1 is selected as resistor ladder network supply reference Vin. */
+ kCMP_VrefSourceVin2 = 1U, /*!< Vin2 is selected as resistor ladder network supply reference Vin. */
+} cmp_reference_voltage_source_t;
+
+/*!
+ * @brief Configuration for the comparator.
+ */
+typedef struct _cmp_config
+{
+ bool enableCmp; /*!< Enable the CMP module. */
+ cmp_hysteresis_mode_t hysteresisMode; /*!< CMP Hysteresis mode. */
+ bool enableHighSpeed; /*!< Enable High-speed comparison mode. */
+ bool enableInvertOutput; /*!< Enable inverted comparator output. */
+ bool useUnfilteredOutput; /*!< Set compare output(COUT) to equal COUTA(true) or COUT(false). */
+ bool enablePinOut; /*!< The comparator output is available on the associated pin. */
+#if defined(FSL_FEATURE_CMP_HAS_TRIGGER_MODE) && FSL_FEATURE_CMP_HAS_TRIGGER_MODE
+ bool enableTriggerMode; /*!< Enable the trigger mode. */
+#endif /* FSL_FEATURE_CMP_HAS_TRIGGER_MODE */
+} cmp_config_t;
+
+/*!
+ * @brief Configuration for the filter.
+ */
+typedef struct _cmp_filter_config
+{
+#if defined(FSL_FEATURE_CMP_HAS_EXTERNAL_SAMPLE_SUPPORT) && FSL_FEATURE_CMP_HAS_EXTERNAL_SAMPLE_SUPPORT
+ bool enableSample; /*!< Using external SAMPLE as sampling clock input, or using divided bus clock. */
+#endif /* FSL_FEATURE_CMP_HAS_EXTERNAL_SAMPLE_SUPPORT */
+ uint8_t filterCount; /*!< Filter Sample Count. Available range is 1-7, 0 would cause the filter disabled.*/
+ uint8_t filterPeriod; /*!< Filter Sample Period. The divider to bus clock. Available range is 0-255. */
+} cmp_filter_config_t;
+
+/*!
+ * @brief Configuration for the internal DAC.
+ */
+typedef struct _cmp_dac_config
+{
+ cmp_reference_voltage_source_t referenceVoltageSource; /*!< Supply voltage reference source. */
+ uint8_t DACValue; /*!< Value for DAC Output Voltage. Available range is 0-63.*/
+} cmp_dac_config_t;
+
+#if defined(__cplusplus)
+extern "C" {
+#endif
+
+/*******************************************************************************
+ * API
+ ******************************************************************************/
+
+/*!
+ * @name Initialization
+ * @{
+ */
+
+/*!
+ * @brief Initializes the CMP.
+ *
+ * This function initializes the CMP module. The operations included are:
+ * - Enabling the clock for CMP module.
+ * - Configuring the comparator.
+ * - Enabling the CMP module.
+ * Note: For some devices, multiple CMP instance share the same clock gate. In this case, to enable the clock for
+ * any instance enables all the CMPs. Check the chip reference manual for the clock assignment of the CMP.
+ *
+ * @param base CMP peripheral base address.
+ * @param config Pointer to configuration structure.
+ */
+void CMP_Init(CMP_Type *base, const cmp_config_t *config);
+
+/*!
+ * @brief De-initializes the CMP module.
+ *
+ * This function de-initializes the CMP module. The operations included are:
+ * - Disabling the CMP module.
+ * - Disabling the clock for CMP module.
+ *
+ * This function disables the clock for the CMP.
+ * Note: For some devices, multiple CMP instance shares the same clock gate. In this case, before disabling the
+ * clock for the CMP, ensure that all the CMP instances are not used.
+ *
+ * @param base CMP peripheral base address.
+ */
+void CMP_Deinit(CMP_Type *base);
+
+/*!
+ * @brief Enables/disables the CMP module.
+ *
+ * @param base CMP peripheral base address.
+ * @param enable Enable the module or not.
+ */
+static inline void CMP_Enable(CMP_Type *base, bool enable)
+{
+ if (enable)
+ {
+ base->CR1 |= CMP_CR1_EN_MASK;
+ }
+ else
+ {
+ base->CR1 &= ~CMP_CR1_EN_MASK;
+ }
+}
+
+/*!
+* @brief Initializes the CMP user configuration structure.
+*
+* This function initializes the user configuration structure to these default values:
+* @code
+* config->enableCmp = true;
+* config->hysteresisMode = kCMP_HysteresisLevel0;
+* config->enableHighSpeed = false;
+* config->enableInvertOutput = false;
+* config->useUnfilteredOutput = false;
+* config->enablePinOut = false;
+* config->enableTriggerMode = false;
+* @endcode
+* @param config Pointer to the configuration structure.
+*/
+void CMP_GetDefaultConfig(cmp_config_t *config);
+
+/*!
+ * @brief Sets the input channels for the comparator.
+ *
+ * This function sets the input channels for the comparator.
+ * Note that two input channels cannot be set as same in the application. When the user selects the same input
+ * from the analog mux to the positive and negative port, the comparator is disabled automatically.
+ *
+ * @param base CMP peripheral base address.
+ * @param positiveChannel Positive side input channel number. Available range is 0-7.
+ * @param negativeChannel Negative side input channel number. Available range is 0-7.
+ */
+void CMP_SetInputChannels(CMP_Type *base, uint8_t positiveChannel, uint8_t negativeChannel);
+
+/* @} */
+
+/*!
+ * @name Advanced Features
+ * @{
+ */
+
+#if defined(FSL_FEATURE_CMP_HAS_DMA) && FSL_FEATURE_CMP_HAS_DMA
+/*!
+ * @brief Enables/disables the DMA request for rising/falling events.
+ *
+ * This function enables/disables the DMA request for rising/falling events. Either event triggers the generation of
+ * the DMA
+ * request from CMP if the DMA feature is enabled. Both events are ignored for generating the DMA request from the CMP
+ * if the
+ * DMA is disabled.
+ *
+ * @param base CMP peripheral base address.
+ * @param enable Enable the feature or not.
+ */
+void CMP_EnableDMA(CMP_Type *base, bool enable);
+#endif /* FSL_FEATURE_CMP_HAS_DMA */
+
+#if defined(FSL_FEATURE_CMP_HAS_WINDOW_MODE) && FSL_FEATURE_CMP_HAS_WINDOW_MODE
+/*!
+ * @brief Enables/disables the window mode.
+ *
+ * @param base CMP peripheral base address.
+ * @param enable Enable the feature or not.
+ */
+static inline void CMP_EnableWindowMode(CMP_Type *base, bool enable)
+{
+ if (enable)
+ {
+ base->CR1 |= CMP_CR1_WE_MASK;
+ }
+ else
+ {
+ base->CR1 &= ~CMP_CR1_WE_MASK;
+ }
+}
+#endif /* FSL_FEATURE_CMP_HAS_WINDOW_MODE */
+
+#if defined(FSL_FEATURE_CMP_HAS_PASS_THROUGH_MODE) && FSL_FEATURE_CMP_HAS_PASS_THROUGH_MODE
+/*!
+ * @brief Enables/disables the pass through mode.
+ *
+ * @param base CMP peripheral base address.
+ * @param enable Enable the feature or not.
+ */
+static inline void CMP_EnablePassThroughMode(CMP_Type *base, bool enable)
+{
+ if (enable)
+ {
+ base->MUXCR |= CMP_MUXCR_PSTM_MASK;
+ }
+ else
+ {
+ base->MUXCR &= ~CMP_MUXCR_PSTM_MASK;
+ }
+}
+#endif /* FSL_FEATURE_CMP_HAS_PASS_THROUGH_MODE */
+
+/*!
+ * @brief Configures the filter.
+ *
+ * @param base CMP peripheral base address.
+ * @param config Pointer to configuration structure.
+ */
+void CMP_SetFilterConfig(CMP_Type *base, const cmp_filter_config_t *config);
+
+/*!
+ * @brief Configures the internal DAC.
+ *
+ * @param base CMP peripheral base address.
+ * @param config Pointer to configuration structure. "NULL" is for disabling the feature.
+ */
+void CMP_SetDACConfig(CMP_Type *base, const cmp_dac_config_t *config);
+
+/*!
+ * @brief Enables the interrupts.
+ *
+ * @param base CMP peripheral base address.
+ * @param mask Mask value for interrupts. See "_cmp_interrupt_enable".
+ */
+void CMP_EnableInterrupts(CMP_Type *base, uint32_t mask);
+
+/*!
+ * @brief Disables the interrupts.
+ *
+ * @param base CMP peripheral base address.
+ * @param mask Mask value for interrupts. See "_cmp_interrupt_enable".
+ */
+void CMP_DisableInterrupts(CMP_Type *base, uint32_t mask);
+
+/* @} */
+
+/*!
+ * @name Results
+ * @{
+ */
+
+/*!
+ * @brief Gets the status flags.
+ *
+ * @param base CMP peripheral base address.
+ *
+ * @return Mask value for the asserted flags. See "_cmp_status_flags".
+ */
+uint32_t CMP_GetStatusFlags(CMP_Type *base);
+
+/*!
+ * @brief Clears the status flags.
+ *
+ * @param base CMP peripheral base address.
+ * @param mask Mask value for the flags. See "_cmp_status_flags".
+ */
+void CMP_ClearStatusFlags(CMP_Type *base, uint32_t mask);
+
+/* @} */
+#if defined(__cplusplus)
+}
+#endif
+/*!
+ * @}
+ */
+#endif /* _FSL_CMP_H_ */
diff --git a/drivers/fsl_cmt.c b/drivers/fsl_cmt.c
new file mode 100644
index 0000000..43b2d3c
--- /dev/null
+++ b/drivers/fsl_cmt.c
@@ -0,0 +1,260 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_cmt.h"
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+/* The standard intermediate frequency (IF). */
+#define CMT_INTERMEDIATEFREQUENCY_8MHZ (8000000U)
+/* CMT data modulate mask. */
+#define CMT_MODULATE_COUNT_WIDTH (8U)
+/* CMT diver 1. */
+#define CMT_CMTDIV_ONE (1)
+/* CMT diver 2. */
+#define CMT_CMTDIV_TWO (2)
+/* CMT diver 4. */
+#define CMT_CMTDIV_FOUR (4)
+/* CMT diver 8. */
+#define CMT_CMTDIV_EIGHT (8)
+/* CMT mode bit mask. */
+#define CMT_MODE_BIT_MASK (CMT_MSC_MCGEN_MASK | CMT_MSC_FSK_MASK | CMT_MSC_BASE_MASK)
+
+/*******************************************************************************
+ * Prototypes
+ ******************************************************************************/
+
+/*!
+ * @brief Get instance number for CMT module.
+ *
+ * @param base CMT peripheral base address.
+ */
+static uint32_t CMT_GetInstance(CMT_Type *base);
+
+/*******************************************************************************
+ * Variables
+ ******************************************************************************/
+
+/*! @brief Pointers to cmt clocks for each instance. */
+static const clock_ip_name_t s_cmtClock[FSL_FEATURE_SOC_CMT_COUNT] = CMT_CLOCKS;
+
+/*! @brief Pointers to cmt bases for each instance. */
+static CMT_Type *const s_cmtBases[] = CMT_BASE_PTRS;
+
+/*! @brief Pointers to cmt IRQ number for each instance. */
+static const IRQn_Type s_cmtIrqs[] = CMT_IRQS;
+
+/*******************************************************************************
+ * Codes
+ ******************************************************************************/
+
+static uint32_t CMT_GetInstance(CMT_Type *base)
+{
+ uint32_t instance;
+
+ /* Find the instance index from base address mappings. */
+ for (instance = 0; instance < FSL_FEATURE_SOC_CMT_COUNT; instance++)
+ {
+ if (s_cmtBases[instance] == base)
+ {
+ break;
+ }
+ }
+
+ assert(instance < FSL_FEATURE_SOC_CMT_COUNT);
+
+ return instance;
+}
+
+void CMT_GetDefaultConfig(cmt_config_t *config)
+{
+ assert(config);
+
+ /* Default infrared output is enabled and set with high active, the divider is set to 1. */
+ config->isInterruptEnabled = false;
+ config->isIroEnabled = true;
+ config->iroPolarity = kCMT_IROActiveHigh;
+ config->divider = kCMT_SecondClkDiv1;
+}
+
+void CMT_Init(CMT_Type *base, const cmt_config_t *config, uint32_t busClock_Hz)
+{
+ assert(config);
+ assert(busClock_Hz >= CMT_INTERMEDIATEFREQUENCY_8MHZ);
+
+ uint8_t divider;
+
+ /* Ungate clock. */
+ CLOCK_EnableClock(s_cmtClock[CMT_GetInstance(base)]);
+
+ /* Sets clock divider. The divider set in pps should be set
+ to make sycClock_Hz/divder = 8MHz */
+ base->PPS = CMT_PPS_PPSDIV(busClock_Hz / CMT_INTERMEDIATEFREQUENCY_8MHZ - 1);
+ divider = base->MSC;
+ divider &= ~CMT_MSC_CMTDIV_MASK;
+ divider |= CMT_MSC_CMTDIV(config->divider);
+ base->MSC = divider;
+
+ /* Set the IRO signal. */
+ base->OC = CMT_OC_CMTPOL(config->iroPolarity) | CMT_OC_IROPEN(config->isIroEnabled);
+
+ /* Set interrupt. */
+ if (config->isInterruptEnabled)
+ {
+ CMT_EnableInterrupts(base, kCMT_EndOfCycleInterruptEnable);
+ EnableIRQ(s_cmtIrqs[CMT_GetInstance(base)]);
+ }
+}
+
+void CMT_Deinit(CMT_Type *base)
+{
+ /*Disable the CMT modulator. */
+ base->MSC = 0;
+
+ /* Disable the interrupt. */
+ CMT_DisableInterrupts(base, kCMT_EndOfCycleInterruptEnable);
+ DisableIRQ(s_cmtIrqs[CMT_GetInstance(base)]);
+
+ /* Gate the clock. */
+ CLOCK_DisableClock(s_cmtClock[CMT_GetInstance(base)]);
+}
+
+void CMT_SetMode(CMT_Type *base, cmt_mode_t mode, cmt_modulate_config_t *modulateConfig)
+{
+ uint8_t mscReg;
+
+ /* Set the mode. */
+ if (mode != kCMT_DirectIROCtl)
+ {
+ assert(modulateConfig);
+
+ /* Set carrier generator. */
+ CMT_SetCarrirGenerateCountOne(base, modulateConfig->highCount1, modulateConfig->lowCount1);
+ if (mode == kCMT_FSKMode)
+ {
+ CMT_SetCarrirGenerateCountTwo(base, modulateConfig->highCount2, modulateConfig->lowCount2);
+ }
+
+ /* Set carrier modulator. */
+ CMT_SetModulateMarkSpace(base, modulateConfig->markCount, modulateConfig->spaceCount);
+ }
+
+ /* Set the CMT mode. */
+ mscReg = base->MSC;
+ mscReg &= ~CMT_MODE_BIT_MASK;
+ mscReg |= mode;
+
+ base->MSC = mscReg;
+}
+
+cmt_mode_t CMT_GetMode(CMT_Type *base)
+{
+ uint8_t mode = base->MSC;
+
+ if (!(mode & CMT_MSC_MCGEN_MASK))
+ { /* Carrier modulator disabled and the IRO signal is in direct software control. */
+ return kCMT_DirectIROCtl;
+ }
+ else
+ {
+ /* Carrier modulator is enabled. */
+ if (mode & CMT_MSC_BASE_MASK)
+ {
+ /* Base band mode. */
+ return kCMT_BasebandMode;
+ }
+ else if (mode & CMT_MSC_FSK_MASK)
+ {
+ /* FSK mode. */
+ return kCMT_FSKMode;
+ }
+ else
+ {
+ /* Time mode. */
+ return kCMT_TimeMode;
+ }
+ }
+}
+
+uint32_t CMT_GetCMTFrequency(CMT_Type *base, uint32_t busClock_Hz)
+{
+ uint32_t frequency;
+ uint32_t divider;
+
+ /* Get intermediate frequency. */
+ frequency = busClock_Hz / ((base->PPS & CMT_PPS_PPSDIV_MASK) + 1);
+
+ /* Get the second divider. */
+ divider = ((base->MSC & CMT_MSC_CMTDIV_MASK) >> CMT_MSC_CMTDIV_SHIFT);
+ /* Get CMT frequency. */
+ switch ((cmt_second_clkdiv_t)divider)
+ {
+ case kCMT_SecondClkDiv1:
+ frequency = frequency / CMT_CMTDIV_ONE;
+ break;
+ case kCMT_SecondClkDiv2:
+ frequency = frequency / CMT_CMTDIV_TWO;
+ break;
+ case kCMT_SecondClkDiv4:
+ frequency = frequency / CMT_CMTDIV_FOUR;
+ break;
+ case kCMT_SecondClkDiv8:
+ frequency = frequency / CMT_CMTDIV_EIGHT;
+ break;
+ default:
+ frequency = frequency / CMT_CMTDIV_ONE;
+ break;
+ }
+
+ return frequency;
+}
+
+void CMT_SetModulateMarkSpace(CMT_Type *base, uint32_t markCount, uint32_t spaceCount)
+{
+ /* Set modulate mark. */
+ base->CMD1 = (markCount >> CMT_MODULATE_COUNT_WIDTH) & CMT_CMD1_MB_MASK;
+ base->CMD2 = (markCount & CMT_CMD2_MB_MASK);
+ /* Set modulate space. */
+ base->CMD3 = (spaceCount >> CMT_MODULATE_COUNT_WIDTH) & CMT_CMD3_SB_MASK;
+ base->CMD4 = spaceCount & CMT_CMD4_SB_MASK;
+}
+
+void CMT_SetIroState(CMT_Type *base, cmt_infrared_output_state_t state)
+{
+ uint8_t ocReg = base->OC;
+
+ ocReg &= ~CMT_OC_IROL_MASK;
+ ocReg |= CMT_OC_IROL(state);
+
+ /* Set the infrared output signal control. */
+ base->OC = ocReg;
+}
diff --git a/drivers/fsl_cmt.h b/drivers/fsl_cmt.h
new file mode 100644
index 0000000..0d57583
--- /dev/null
+++ b/drivers/fsl_cmt.h
@@ -0,0 +1,401 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_CMT_H_
+#define _FSL_CMT_H_
+
+#include "fsl_common.h"
+
+/*!
+ * @addtogroup cmt
+ * @{
+ */
+
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+/*! @name Driver version */
+/*@{*/
+/*! @brief CMT driver version 2.0.1. */
+#define FSL_CMT_DRIVER_VERSION (MAKE_VERSION(2, 0, 1))
+/*@}*/
+
+/*!
+ * @brief The modes of CMT.
+ */
+typedef enum _cmt_mode
+{
+ kCMT_DirectIROCtl = 0x00U, /*!< Carrier modulator is disabled and the IRO signal is directly in software control */
+ kCMT_TimeMode = 0x01U, /*!< Carrier modulator is enabled in time mode. */
+ kCMT_FSKMode = 0x05U, /*!< Carrier modulator is enabled in FSK mode. */
+ kCMT_BasebandMode = 0x09U /*!< Carrier modulator is enabled in baseband mode. */
+} cmt_mode_t;
+
+/*!
+ * @brief The CMT clock divide primary prescaler.
+ * The primary clock divider is used to divider the bus clock to
+ * get the intermediate frequency to approximately equal to 8 MHZ.
+ * When the bus clock is 8 MHZ, set primary prescaler to "kCMT_PrimaryClkDiv1".
+ */
+typedef enum _cmt_primary_clkdiv
+{
+ kCMT_PrimaryClkDiv1 = 0U, /*!< The intermediate frequency is the bus clock divided by 1. */
+ kCMT_PrimaryClkDiv2 = 1U, /*!< The intermediate frequency is the bus clock divided by 2. */
+ kCMT_PrimaryClkDiv3 = 2U, /*!< The intermediate frequency is the bus clock divided by 3. */
+ kCMT_PrimaryClkDiv4 = 3U, /*!< The intermediate frequency is the bus clock divided by 4. */
+ kCMT_PrimaryClkDiv5 = 4U, /*!< The intermediate frequency is the bus clock divided by 5. */
+ kCMT_PrimaryClkDiv6 = 5U, /*!< The intermediate frequency is the bus clock divided by 6. */
+ kCMT_PrimaryClkDiv7 = 6U, /*!< The intermediate frequency is the bus clock divided by 7. */
+ kCMT_PrimaryClkDiv8 = 7U, /*!< The intermediate frequency is the bus clock divided by 8. */
+ kCMT_PrimaryClkDiv9 = 8U, /*!< The intermediate frequency is the bus clock divided by 9. */
+ kCMT_PrimaryClkDiv10 = 9U, /*!< The intermediate frequency is the bus clock divided by 10. */
+ kCMT_PrimaryClkDiv11 = 10U, /*!< The intermediate frequency is the bus clock divided by 11. */
+ kCMT_PrimaryClkDiv12 = 11U, /*!< The intermediate frequency is the bus clock divided by 12. */
+ kCMT_PrimaryClkDiv13 = 12U, /*!< The intermediate frequency is the bus clock divided by 13. */
+ kCMT_PrimaryClkDiv14 = 13U, /*!< The intermediate frequency is the bus clock divided by 14. */
+ kCMT_PrimaryClkDiv15 = 14U, /*!< The intermediate frequency is the bus clock divided by 15. */
+ kCMT_PrimaryClkDiv16 = 15U /*!< The intermediate frequency is the bus clock divided by 16. */
+} cmt_primary_clkdiv_t;
+
+/*!
+ * @brief The CMT clock divide secondary prescaler.
+ * The second prescaler can be used to divide the 8 MHZ CMT clock
+ * by 1, 2, 4, or 8 according to the specification.
+ */
+typedef enum _cmt_second_clkdiv
+{
+ kCMT_SecondClkDiv1 = 0U, /*!< The CMT clock is the intermediate frequency frequency divided by 1. */
+ kCMT_SecondClkDiv2 = 1U, /*!< The CMT clock is the intermediate frequency frequency divided by 2. */
+ kCMT_SecondClkDiv4 = 2U, /*!< The CMT clock is the intermediate frequency frequency divided by 4. */
+ kCMT_SecondClkDiv8 = 3U /*!< The CMT clock is the intermediate frequency frequency divided by 8. */
+} cmt_second_clkdiv_t;
+
+/*!
+ * @brief The CMT infrared output polarity.
+ */
+typedef enum _cmt_infrared_output_polarity
+{
+ kCMT_IROActiveLow = 0U, /*!< The CMT infrared output signal polarity is active-low. */
+ kCMT_IROActiveHigh = 1U /*!< The CMT infrared output signal polarity is active-high. */
+} cmt_infrared_output_polarity_t;
+
+/*!
+ * @brief The CMT infrared output signal state control.
+ */
+typedef enum _cmt_infrared_output_state
+{
+ kCMT_IROCtlLow = 0U, /*!< The CMT Infrared output signal state is controlled to low. */
+ kCMT_IROCtlHigh = 1U /*!< The CMT Infrared output signal state is controlled to high. */
+} cmt_infrared_output_state_t;
+
+/*!
+ * @brief CMT interrupt configuration structure, default settings all disabled.
+ *
+ * This structure contains the settings for all of the CMT interrupt configurations.
+ */
+enum _cmt_interrupt_enable
+{
+ kCMT_EndOfCycleInterruptEnable = CMT_MSC_EOCIE_MASK, /*!< CMT end of cycle interrupt. */
+};
+
+/*!
+ * @brief CMT carrier generator and modulator configuration structure
+ *
+ */
+typedef struct _cmt_modulate_config
+{
+ uint8_t highCount1; /*!< The high time for carrier generator first register. */
+ uint8_t lowCount1; /*!< The low time for carrier generator first register. */
+ uint8_t highCount2; /*!< The high time for carrier generator second register for FSK mode. */
+ uint8_t lowCount2; /*!< The low time for carrier generator second register for FSK mode. */
+ uint16_t markCount; /*!< The mark time for the modulator gate. */
+ uint16_t spaceCount; /*!< The space time for the modulator gate. */
+} cmt_modulate_config_t;
+
+/*! @brief CMT basic configuration structure. */
+typedef struct _cmt_config
+{
+ bool isInterruptEnabled; /*!< Timer interrupt 0-disable, 1-enable. */
+ bool isIroEnabled; /*!< The IRO output 0-disabled, 1-enabled. */
+ cmt_infrared_output_polarity_t iroPolarity; /*!< The IRO polarity. */
+ cmt_second_clkdiv_t divider; /*!< The CMT clock divide prescaler. */
+} cmt_config_t;
+
+/*******************************************************************************
+ * API
+ ******************************************************************************/
+
+#if defined(__cplusplus)
+extern "C" {
+#endif
+
+/*!
+ * @name Initialization and deinitialization
+ * @{
+ */
+
+/*!
+ * @brief Gets the CMT default configuration structure. The purpose
+ * of this API is to get the default configuration structure for the CMT_Init().
+ * Use the initialized structure unchanged in CMT_Init(), or modify
+ * some fields of the structure before calling the CMT_Init().
+ *
+ * @param config The CMT configuration structure pointer.
+ */
+void CMT_GetDefaultConfig(cmt_config_t *config);
+
+/*!
+ * @brief Initializes the CMT module.
+ *
+ * This function ungates the module clock and sets the CMT internal clock,
+ * interrupt, and infrared output signal for the CMT module.
+ *
+ * @param base CMT peripheral base address.
+ * @param config The CMT basic configuration structure.
+ * @param busClock_Hz The CMT module input clock - bus clock frequency.
+ */
+void CMT_Init(CMT_Type *base, const cmt_config_t *config, uint32_t busClock_Hz);
+
+/*!
+ * @brief Disables the CMT module and gate control.
+ *
+ * This function disables CMT modulator, interrupts, and gates the
+ * CMT clock control. CMT_Init must be called to use the CMT again.
+ *
+ * @param base CMT peripheral base address.
+ */
+void CMT_Deinit(CMT_Type *base);
+
+/*! @}*/
+
+/*!
+ * @name Basic Control Operations
+ * @{
+ */
+
+/*!
+ * @brief Selects the mode for CMT.
+ *
+ * @param base CMT peripheral base address.
+ * @param mode The CMT feature mode enumeration. See "cmt_mode_t".
+ * @param modulateConfig The carrier generation and modulator configuration.
+ */
+void CMT_SetMode(CMT_Type *base, cmt_mode_t mode, cmt_modulate_config_t *modulateConfig);
+
+/*!
+ * @brief Gets the mode of the CMT module.
+ *
+ * @param base CMT peripheral base address.
+ * @return The CMT mode.
+ * kCMT_DirectIROCtl Carrier modulator is disabled, the IRO signal is directly in software control.
+ * kCMT_TimeMode Carrier modulator is enabled in time mode.
+ * kCMT_FSKMode Carrier modulator is enabled in FSK mode.
+ * kCMT_BasebandMode Carrier modulator is enabled in baseband mode.
+ */
+cmt_mode_t CMT_GetMode(CMT_Type *base);
+
+/*!
+ * @brief Gets the actual CMT clock frequency.
+ *
+ * @param base CMT peripheral base address.
+ * @param busClock_Hz CMT module input clock - bus clock frequency.
+ * @return The CMT clock frequency.
+ */
+uint32_t CMT_GetCMTFrequency(CMT_Type *base, uint32_t busClock_Hz);
+
+/*!
+ * @brief Sets the primary data set for the CMT carrier generator counter.
+ *
+ * This function sets the high time and low time of the primary data set for the
+ * CMT carrier generator counter to control the period and the duty cycle of the
+ * output carrier signal.
+ * If the CMT clock period is Tcmt, The period of the carrier generator signal equals
+ * (highCount + lowCount) * Tcmt. The duty cycle equals highCount / (highCount + lowCount).
+ *
+ * @param base CMT peripheral base address.
+ * @param highCount The number of CMT clocks for carrier generator signal high time,
+ * integer in the range of 1 ~ 0xFF.
+ * @param lowCount The number of CMT clocks for carrier generator signal low time,
+ * integer in the range of 1 ~ 0xFF.
+ */
+static inline void CMT_SetCarrirGenerateCountOne(CMT_Type *base, uint32_t highCount, uint32_t lowCount)
+{
+ assert(highCount <= CMT_CGH1_PH_MASK);
+ assert(highCount);
+ assert(lowCount <= CMT_CGL1_PL_MASK);
+ assert(lowCount);
+
+ base->CGH1 = highCount;
+ base->CGL1 = lowCount;
+}
+
+/*!
+ * @brief Sets the secondary data set for the CMT carrier generator counter.
+ *
+ * This function is used for FSK mode setting the high time and low time of the secondary
+ * data set CMT carrier generator counter to control the period and the duty cycle
+ * of the output carrier signal.
+ * If the CMT clock period is Tcmt, The period of the carrier generator signal equals
+ * (highCount + lowCount) * Tcmt. The duty cycle equals highCount / (highCount + lowCount).
+ *
+ * @param base CMT peripheral base address.
+ * @param highCount The number of CMT clocks for carrier generator signal high time,
+ * integer in the range of 1 ~ 0xFF.
+ * @param lowCount The number of CMT clocks for carrier generator signal low time,
+ * integer in the range of 1 ~ 0xFF.
+ */
+static inline void CMT_SetCarrirGenerateCountTwo(CMT_Type *base, uint32_t highCount, uint32_t lowCount)
+{
+ assert(highCount <= CMT_CGH2_SH_MASK);
+ assert(highCount);
+ assert(lowCount <= CMT_CGL2_SL_MASK);
+ assert(lowCount);
+
+ base->CGH2 = highCount;
+ base->CGL2 = lowCount;
+}
+
+/*!
+ * @brief Sets the modulation mark and space time period for the CMT modulator.
+ *
+ * This function sets the mark time period of the CMT modulator counter
+ * to control the mark time of the output modulated signal from the carrier generator output signal.
+ * If the CMT clock frequency is Fcmt and the carrier out signal frequency is fcg:
+ * - In Time and Baseband mode: The mark period of the generated signal equals (markCount + 1) / (Fcmt/8).
+ * The space period of the generated signal equals spaceCount / (Fcmt/8).
+ * - In FSK mode: The mark period of the generated signal equals (markCount + 1)/fcg.
+ * The space period of the generated signal equals spaceCount / fcg.
+ *
+ * @param base Base address for current CMT instance.
+ * @param markCount The number of clock period for CMT modulator signal mark period,
+ * in the range of 0 ~ 0xFFFF.
+ * @param spaceCount The number of clock period for CMT modulator signal space period,
+ * in the range of the 0 ~ 0xFFFF.
+ */
+void CMT_SetModulateMarkSpace(CMT_Type *base, uint32_t markCount, uint32_t spaceCount);
+
+/*!
+ * @brief Enables or disables the extended space operation.
+ *
+ * This function is used to make the space period longer
+ * for time, baseband, and FSK modes.
+ *
+ * @param base CMT peripheral base address.
+ * @param enable True enable the extended space, false disable the extended space.
+ */
+static inline void CMT_EnableExtendedSpace(CMT_Type *base, bool enable)
+{
+ if (enable)
+ {
+ base->MSC |= CMT_MSC_EXSPC_MASK;
+ }
+ else
+ {
+ base->MSC &= ~CMT_MSC_EXSPC_MASK;
+ }
+}
+
+/*!
+ * @brief Sets IRO - infrared output signal state.
+ *
+ * Changes the states of the IRO signal when the kCMT_DirectIROMode mode is set
+ * and the IRO signal is enabled.
+ *
+ * @param base CMT peripheral base address.
+ * @param state The control of the IRO signal. See "cmt_infrared_output_state_t"
+ */
+void CMT_SetIroState(CMT_Type *base, cmt_infrared_output_state_t state);
+
+/*!
+ * @brief Enables the CMT interrupt.
+ *
+ * This function enables the CMT interrupts according to the provided maskIf enabled.
+ * The CMT only has the end of the cycle interrupt - an interrupt occurs at the end
+ * of the modulator cycle. This interrupt provides a means for the user
+ * to reload the new mark/space values into the CMT modulator data registers
+ * and verify the modulator mark and space.
+ * For example, to enable the end of cycle, do the following:
+ * @code
+ * CMT_EnableInterrupts(CMT, kCMT_EndOfCycleInterruptEnable);
+ * @endcode
+ * @param base CMT peripheral base address.
+ * @param mask The interrupts to enable. Logical OR of @ref _cmt_interrupt_enable.
+ */
+static inline void CMT_EnableInterrupts(CMT_Type *base, uint32_t mask)
+{
+ base->MSC |= mask;
+}
+
+/*!
+ * @brief Disables the CMT interrupt.
+ *
+ * This function disables the CMT interrupts according to the provided maskIf enabled.
+ * The CMT only has the end of the cycle interrupt.
+ * For example, to disable the end of cycle, do the following:
+ * @code
+ * CMT_DisableInterrupts(CMT, kCMT_EndOfCycleInterruptEnable);
+ * @endcode
+ *
+ * @param base CMT peripheral base address.
+ * @param mask The interrupts to enable. Logical OR of @ref _cmt_interrupt_enable.
+ */
+static inline void CMT_DisableInterrupts(CMT_Type *base, uint32_t mask)
+{
+ base->MSC &= ~mask;
+}
+
+/*!
+ * @brief Gets the end of the cycle status flag.
+ *
+ * The flag is set:
+ * - When the modulator is not currently active and carrier and modulator
+ * are set to start the initial CMT transmission.
+ * - At the end of each modulation cycle when the counter is reloaded and
+ * the carrier and modulator are enabled.
+ * @param base CMT peripheral base address.
+ * @return Current status of the end of cycle status flag
+ * @arg non-zero: End-of-cycle has occurred.
+ * @arg zero: End-of-cycle has not yet occurred since the flag last cleared.
+ */
+static inline uint32_t CMT_GetStatusFlags(CMT_Type *base)
+{
+ return base->MSC & CMT_MSC_EOCF_MASK;
+}
+
+/*! @}*/
+
+#if defined(__cplusplus)
+}
+#endif
+
+/*! @}*/
+
+#endif /* _FSL_CMT_H_*/
diff --git a/drivers/fsl_common.c b/drivers/fsl_common.c
new file mode 100644
index 0000000..de67800
--- /dev/null
+++ b/drivers/fsl_common.c
@@ -0,0 +1,95 @@
+/*
+* Copyright (c) 2015, Freescale Semiconductor, Inc.
+* All rights reserved.
+*
+* 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 Freescale Semiconductor, Inc. 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_common.h"
+#include "fsl_debug_console.h"
+
+#ifndef NDEBUG
+#if (defined(__CC_ARM)) || (defined(__ICCARM__))
+void __aeabi_assert(const char *failedExpr, const char *file, int line)
+{
+ PRINTF("ASSERT ERROR \" %s \": file \"%s\" Line \"%d\" \n", failedExpr, file, line);
+ for (;;)
+ {
+ __asm("bkpt #0");
+ }
+}
+#elif(defined(__GNUC__))
+void __assert_func(const char *file, int line, const char *func, const char *failedExpr)
+{
+ PRINTF("ASSERT ERROR \" %s \": file \"%s\" Line \"%d\" function name \"%s\" \n", failedExpr, file, line, func);
+ for (;;)
+ {
+ __asm("bkpt #0");
+ }
+}
+#endif /* (defined(__CC_ARM)) || (defined (__ICCARM__)) */
+#endif /* NDEBUG */
+
+void InstallIRQHandler(IRQn_Type irq, uint32_t irqHandler)
+{
+/* Addresses for VECTOR_TABLE and VECTOR_RAM come from the linker file */
+#if defined(__CC_ARM)
+ extern uint32_t Image$$VECTOR_ROM$$Base[];
+ extern uint32_t Image$$VECTOR_RAM$$Base[];
+ extern uint32_t Image$$RW_m_data$$Base[];
+
+#define __VECTOR_TABLE Image$$VECTOR_ROM$$Base
+#define __VECTOR_RAM Image$$VECTOR_RAM$$Base
+#define __RAM_VECTOR_TABLE_SIZE (((uint32_t)Image$$RW_m_data$$Base - (uint32_t)Image$$VECTOR_RAM$$Base))
+#elif defined(__ICCARM__)
+ extern uint32_t __RAM_VECTOR_TABLE_SIZE[];
+ extern uint32_t __VECTOR_TABLE[];
+ extern uint32_t __VECTOR_RAM[];
+#elif defined(__GNUC__)
+ extern uint32_t __VECTOR_TABLE[];
+ extern uint32_t __VECTOR_RAM[];
+ extern uint32_t __RAM_VECTOR_TABLE_SIZE_BYTES[];
+ uint32_t __RAM_VECTOR_TABLE_SIZE = (uint32_t)(__RAM_VECTOR_TABLE_SIZE_BYTES);
+#endif /* defined(__CC_ARM) */
+ uint32_t n;
+
+ __disable_irq();
+ if (SCB->VTOR != (uint32_t)__VECTOR_RAM)
+ {
+ /* Copy the vector table from ROM to RAM */
+ for (n = 0; n < ((uint32_t)__RAM_VECTOR_TABLE_SIZE) / sizeof(uint32_t); n++)
+ {
+ __VECTOR_RAM[n] = __VECTOR_TABLE[n];
+ }
+ /* Point the VTOR to the position of vector table */
+ SCB->VTOR = (uint32_t)__VECTOR_RAM;
+ }
+
+ /* make sure the __VECTOR_RAM is noncachable */
+ __VECTOR_RAM[irq + 16] = irqHandler;
+
+ __enable_irq();
+}
diff --git a/drivers/fsl_common.h b/drivers/fsl_common.h
new file mode 100644
index 0000000..a843078
--- /dev/null
+++ b/drivers/fsl_common.h
@@ -0,0 +1,254 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_COMMON_H_
+#define _FSL_COMMON_H_
+
+#include <assert.h>
+#include <stdbool.h>
+#include <stdint.h>
+#include <string.h>
+#include "fsl_device_registers.h"
+
+/*!
+ * @addtogroup ksdk_common
+ * @{
+ */
+
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+/*! @brief Construct a status code value from a group and code number. */
+#define MAKE_STATUS(group, code) ((((group)*100) + (code)))
+
+/*! @brief Construct the version number for drivers. */
+#define MAKE_VERSION(major, minor, bugfix) (((major) << 16) | ((minor) << 8) | (bugfix))
+
+/* Debug console type definition. */
+#define DEBUG_CONSOLE_DEVICE_TYPE_NONE 0U /*!< No debug console. */
+#define DEBUG_CONSOLE_DEVICE_TYPE_UART 1U /*!< Debug console base on UART. */
+#define DEBUG_CONSOLE_DEVICE_TYPE_LPUART 2U /*!< Debug console base on LPUART. */
+#define DEBUG_CONSOLE_DEVICE_TYPE_LPSCI 3U /*!< Debug console base on LPSCI. */
+#define DEBUG_CONSOLE_DEVICE_TYPE_USBCDC 4U /*!< Debug console base on USBCDC. */
+
+/*! @brief Status group numbers. */
+enum _status_groups
+{
+ kStatusGroup_Generic = 0, /*!< Group number for generic status codes. */
+ kStatusGroup_FLASH = 1, /*!< Group number for FLASH status codes. */
+ kStatusGroup_LPSPI = 4, /*!< Group number for LPSPI status codes. */
+ kStatusGroup_FLEXIO_SPI = 5, /*!< Group number for FLEXIO SPI status codes. */
+ kStatusGroup_DSPI = 6, /*!< Group number for DSPI status codes. */
+ kStatusGroup_FLEXIO_UART = 7, /*!< Group number for FLEXIO UART status codes. */
+ kStatusGroup_FLEXIO_I2C = 8, /*!< Group number for FLEXIO I2C status codes. */
+ kStatusGroup_LPI2C = 9, /*!< Group number for LPI2C status codes. */
+ kStatusGroup_UART = 10, /*!< Group number for UART status codes. */
+ kStatusGroup_I2C = 11, /*!< Group number for UART status codes. */
+ kStatusGroup_LPSCI = 12, /*!< Group number for LPSCI status codes. */
+ kStatusGroup_LPUART = 13, /*!< Group number for LPUART status codes. */
+ kStatusGroup_SPI = 14, /*!< Group number for SPI status code.*/
+ kStatusGroup_XRDC = 15, /*!< Group number for XRDC status code.*/
+ kStatusGroup_SEMA42 = 16, /*!< Group number for SEMA42 status code.*/
+ kStatusGroup_SDHC = 17, /*!< Group number for SDHC status code */
+ kStatusGroup_SDMMC = 18, /*!< Group number for SDMMC status code */
+ kStatusGroup_SAI = 19, /*!< Group number for SAI status code */
+ kStatusGroup_MCG = 20, /*!< Group number for MCG status codes. */
+ kStatusGroup_SCG = 21, /*!< Group number for SCG status codes. */
+ kStatusGroup_SDSPI = 22, /*!< Group number for SDSPI status codes. */
+ kStatusGroup_FLEXIO_I2S = 23, /*!< Group number for FLEXIO I2S status codes */
+ kStatusGroup_SDRAMC = 35, /*!< Group number for SDRAMC status codes. */
+ kStatusGroup_POWER = 39, /*!< Group number for POWER status codes. */
+ kStatusGroup_ENET = 40, /*!< Group number for ENET status codes. */
+ kStatusGroup_PHY = 41, /*!< Group number for PHY status codes. */
+ kStatusGroup_TRGMUX = 42, /*!< Group number for TRGMUX status codes. */
+ kStatusGroup_SMARTCARD = 43, /*!< Group number for SMARTCARD status codes. */
+ kStatusGroup_LMEM = 44, /*!< Group number for LMEM status codes. */
+ kStatusGroup_QSPI = 45, /*!< Group number for QSPI status codes. */
+ kStatusGroup_DMA = 50, /*!< Group number for DMA status codes. */
+ kStatusGroup_EDMA = 51, /*!< Group number for EDMA status codes. */
+ kStatusGroup_DMAMGR = 52, /*!< Group number for DMAMGR status codes. */
+ kStatusGroup_FLEXCAN = 53, /*!< Group number for FlexCAN status codes. */
+ kStatusGroup_LTC = 54, /*!< Group number for LTC status codes. */
+ kStatusGroup_FLEXIO_CAMERA = 55, /*!< Group number for FLEXIO CAMERA status codes. */
+ kStatusGroup_NOTIFIER = 98, /*!< Group number for NOTIFIER status codes. */
+ kStatusGroup_DebugConsole = 99, /*!< Group number for debug console status codes. */
+ kStatusGroup_ApplicationRangeStart = 100, /*!< Starting number for application groups. */
+};
+
+/*! @brief Generic status return codes. */
+enum _generic_status
+{
+ kStatus_Success = MAKE_STATUS(kStatusGroup_Generic, 0),
+ kStatus_Fail = MAKE_STATUS(kStatusGroup_Generic, 1),
+ kStatus_ReadOnly = MAKE_STATUS(kStatusGroup_Generic, 2),
+ kStatus_OutOfRange = MAKE_STATUS(kStatusGroup_Generic, 3),
+ kStatus_InvalidArgument = MAKE_STATUS(kStatusGroup_Generic, 4),
+ kStatus_Timeout = MAKE_STATUS(kStatusGroup_Generic, 5),
+ kStatus_NoTransferInProgress = MAKE_STATUS(kStatusGroup_Generic, 6),
+};
+
+/*! @brief Type used for all status and error return values. */
+typedef int32_t status_t;
+
+/*
+ * The fsl_clock.h is included here because it needs MAKE_VERSION/MAKE_STATUS/status_t
+ * defined in previous of this file.
+ */
+#include "fsl_clock.h"
+
+/*! @name Min/max macros */
+/* @{ */
+#if !defined(MIN)
+#define MIN(a, b) ((a) < (b) ? (a) : (b))
+#endif
+
+#if !defined(MAX)
+#define MAX(a, b) ((a) > (b) ? (a) : (b))
+#endif
+/* @} */
+
+/*! @brief Computes the number of elements in an array. */
+#define ARRAY_SIZE(x) (sizeof(x) / sizeof((x)[0]))
+
+/*! @name UINT16_MAX/UINT32_MAX value */
+/* @{ */
+#if !defined(UINT16_MAX)
+#define UINT16_MAX ((uint16_t)-1)
+#endif
+
+#if !defined(UINT32_MAX)
+#define UINT32_MAX ((uint32_t)-1)
+#endif
+/* @} */
+
+/*! @name Timer utilities */
+/* @{ */
+/*! Macro to convert a microsecond period to raw count value */
+#define USEC_TO_COUNT(us, clockFreqInHz) (uint64_t)((uint64_t)us * clockFreqInHz / 1000000U)
+/*! Macro to convert a raw count value to microsecond */
+#define COUNT_TO_USEC(count, clockFreqInHz) (uint64_t)((uint64_t)count * 1000000U / clockFreqInHz)
+
+/*! Macro to convert a millisecond period to raw count value */
+#define MSEC_TO_COUNT(ms, clockFreqInHz) (uint64_t)((uint64_t)ms * clockFreqInHz / 1000U)
+/*! Macro to convert a raw count value to millisecond */
+#define COUNT_TO_MSEC(count, clockFreqInHz) (uint64_t)((uint64_t)count * 1000U / clockFreqInHz)
+/* @} */
+
+/*******************************************************************************
+ * API
+ ******************************************************************************/
+
+#if defined(__cplusplus)
+extern "C" {
+#endif
+
+/*!
+ * @brief Enable specific interrupt.
+ *
+ * Enable the interrupt not routed from intmux.
+ *
+ * @param interrupt The IRQ number.
+ */
+static inline void EnableIRQ(IRQn_Type interrupt)
+{
+#if defined(FSL_FEATURE_SOC_INTMUX_COUNT) && (FSL_FEATURE_SOC_INTMUX_COUNT > 0)
+ if (interrupt < FSL_FEATURE_INTMUX_IRQ_START_INDEX)
+#endif
+ {
+ NVIC_EnableIRQ(interrupt);
+ }
+}
+
+/*!
+ * @brief Disable specific interrupt.
+ *
+ * Disable the interrupt not routed from intmux.
+ *
+ * @param interrupt The IRQ number.
+ */
+static inline void DisableIRQ(IRQn_Type interrupt)
+{
+#if defined(FSL_FEATURE_SOC_INTMUX_COUNT) && (FSL_FEATURE_SOC_INTMUX_COUNT > 0)
+ if (interrupt < FSL_FEATURE_INTMUX_IRQ_START_INDEX)
+#endif
+ {
+ NVIC_DisableIRQ(interrupt);
+ }
+}
+
+/*!
+ * @brief Disable the global IRQ
+ *
+ * Disable the global interrupt and return the current primask register. User is required to provided the primask
+ * register for the EnableGlobalIRQ().
+ *
+ * @return Current primask value.
+ */
+static inline uint32_t DisableGlobalIRQ(void)
+{
+ uint32_t regPrimask = __get_PRIMASK();
+
+ __disable_irq();
+
+ return regPrimask;
+}
+
+/*!
+ * @brief Enaable the global IRQ
+ *
+ * Set the primask register with the provided primask value but not just enable the primask. The idea is for the
+ * convinience of integration of RTOS. some RTOS get its own management mechanism of primask. User is required to
+ * use the EnableGlobalIRQ() and DisableGlobalIRQ() in pair.
+ *
+ * @param primask value of primask register to be restored. The primask value is supposed to be provided by the
+ * DisableGlobalIRQ().
+ */
+static inline void EnableGlobalIRQ(uint32_t primask)
+{
+ __set_PRIMASK(primask);
+}
+
+/*!
+ * @brief install IRQ handler
+ *
+ * @param irq IRQ number
+ * @param irqHandler IRQ handler address
+ */
+void InstallIRQHandler(IRQn_Type irq, uint32_t irqHandler);
+
+#if defined(__cplusplus)
+}
+#endif
+
+/*! @} */
+
+#endif /* _FSL_COMMON_H_ */
diff --git a/drivers/fsl_crc.c b/drivers/fsl_crc.c
new file mode 100644
index 0000000..de86e32
--- /dev/null
+++ b/drivers/fsl_crc.c
@@ -0,0 +1,280 @@
+/*
+ * Copyright (c) 2015-2016, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_crc.h"
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+/*! @internal @brief Has data register with name CRC. */
+#if defined(FSL_FEATURE_CRC_HAS_CRC_REG) && FSL_FEATURE_CRC_HAS_CRC_REG
+#define DATA CRC
+#define DATALL CRCLL
+#endif
+
+#if defined(CRC_DRIVER_USE_CRC16_CCIT_FALSE_AS_DEFAULT) && CRC_DRIVER_USE_CRC16_CCIT_FALSE_AS_DEFAULT
+/* @brief Default user configuration structure for CRC-16-CCITT */
+#define CRC_DRIVER_DEFAULT_POLYNOMIAL 0x1021U
+/*< CRC-16-CCIT polynomial x**16 + x**12 + x**5 + x**0 */
+#define CRC_DRIVER_DEFAULT_SEED 0xFFFFU
+/*< Default initial checksum */
+#define CRC_DRIVER_DEFAULT_REFLECT_IN false
+/*< Default is no transpose */
+#define CRC_DRIVER_DEFAULT_REFLECT_OUT false
+/*< Default is transpose bytes */
+#define CRC_DRIVER_DEFAULT_COMPLEMENT_CHECKSUM false
+/*< Default is without complement of CRC data register read data */
+#define CRC_DRIVER_DEFAULT_CRC_BITS kCrcBits16
+/*< Default is 16-bit CRC protocol */
+#define CRC_DRIVER_DEFAULT_CRC_RESULT kCrcFinalChecksum
+/*< Default is resutl type is final checksum */
+#endif /* CRC_DRIVER_USE_CRC16_CCIT_FALSE_AS_DEFAULT */
+
+/*! @brief CRC type of transpose of read write data */
+typedef enum _crc_transpose_type
+{
+ kCrcTransposeNone = 0U, /*! No transpose */
+ kCrcTransposeBits = 1U, /*! Tranpose bits in bytes */
+ kCrcTransposeBitsAndBytes = 2U, /*! Transpose bytes and bits in bytes */
+ kCrcTransposeBytes = 3U, /*! Transpose bytes */
+} crc_transpose_type_t;
+
+/*!
+* @brief CRC module configuration.
+*
+* This structure holds the configuration for the CRC module.
+*/
+typedef struct _crc_module_config
+{
+ uint32_t polynomial; /*!< CRC Polynomial, MSBit first.@n
+ Example polynomial: 0x1021 = 1_0000_0010_0001 = x^12+x^5+1 */
+ uint32_t seed; /*!< Starting checksum value */
+ crc_transpose_type_t readTranspose; /*!< Type of transpose when reading CRC result. */
+ crc_transpose_type_t writeTranspose; /*!< Type of transpose when writing CRC input data. */
+ bool complementChecksum; /*!< True if the result shall be complement of the actual checksum. */
+ crc_bits_t crcBits; /*!< Selects 16- or 32- bit CRC protocol. */
+} crc_module_config_t;
+
+/*******************************************************************************
+ * Code
+ ******************************************************************************/
+
+/*!
+ * @brief Returns transpose type for CRC protocol reflect in parameter.
+ *
+ * This functions helps to set writeTranspose member of crc_config_t structure. Reflect in is CRC protocol parameter.
+ *
+ * @param enable True or false for the selected CRC protocol Reflect In (refin) parameter.
+ */
+static inline crc_transpose_type_t crc_GetTransposeTypeFromReflectIn(bool enable)
+{
+ return ((enable) ? kCrcTransposeBitsAndBytes : kCrcTransposeBytes);
+}
+
+/*!
+ * @brief Returns transpose type for CRC protocol reflect out parameter.
+ *
+ * This functions helps to set readTranspose member of crc_config_t structure. Reflect out is CRC protocol parameter.
+ *
+ * @param enable True or false for the selected CRC protocol Reflect Out (refout) parameter.
+ */
+static inline crc_transpose_type_t crc_GetTransposeTypeFromReflectOut(bool enable)
+{
+ return ((enable) ? kCrcTransposeBitsAndBytes : kCrcTransposeNone);
+}
+
+/*!
+ * @brief Starts checksum computation.
+ *
+ * Configures the CRC module for the specified CRC protocol. @n
+ * Starts the checksum computation by writing the seed value
+ *
+ * @param base CRC peripheral address.
+ * @param config Pointer to protocol configuration structure.
+ */
+static void crc_ConfigureAndStart(CRC_Type *base, const crc_module_config_t *config)
+{
+ uint32_t crcControl;
+
+ /* pre-compute value for CRC control registger based on user configuraton without WAS field */
+ crcControl = 0 | CRC_CTRL_TOT(config->writeTranspose) | CRC_CTRL_TOTR(config->readTranspose) |
+ CRC_CTRL_FXOR(config->complementChecksum) | CRC_CTRL_TCRC(config->crcBits);
+
+ /* make sure the control register is clear - WAS is deasserted, and protocol is set */
+ base->CTRL = crcControl;
+
+ /* write polynomial register */
+ base->GPOLY = config->polynomial;
+
+ /* write pre-computed control register value along with WAS to start checksum computation */
+ base->CTRL = crcControl | CRC_CTRL_WAS(true);
+
+ /* write seed (initial checksum) */
+ base->DATA = config->seed;
+
+ /* deassert WAS by writing pre-computed CRC control register value */
+ base->CTRL = crcControl;
+}
+
+/*!
+ * @brief Starts final checksum computation.
+ *
+ * Configures the CRC module for the specified CRC protocol. @n
+ * Starts final checksum computation by writing the seed value.
+ * @note CRC_Get16bitResult() or CRC_Get32bitResult() return final checksum
+ * (output reflection and xor functions are applied).
+ *
+ * @param base CRC peripheral address.
+ * @param protocolConfig Pointer to protocol configuration structure.
+ */
+static void crc_SetProtocolConfig(CRC_Type *base, const crc_config_t *protocolConfig)
+{
+ crc_module_config_t moduleConfig;
+ /* convert protocol to CRC peripheral module configuration, prepare for final checksum */
+ moduleConfig.polynomial = protocolConfig->polynomial;
+ moduleConfig.seed = protocolConfig->seed;
+ moduleConfig.readTranspose = crc_GetTransposeTypeFromReflectOut(protocolConfig->reflectOut);
+ moduleConfig.writeTranspose = crc_GetTransposeTypeFromReflectIn(protocolConfig->reflectIn);
+ moduleConfig.complementChecksum = protocolConfig->complementChecksum;
+ moduleConfig.crcBits = protocolConfig->crcBits;
+
+ crc_ConfigureAndStart(base, &moduleConfig);
+}
+
+/*!
+ * @brief Starts intermediate checksum computation.
+ *
+ * Configures the CRC module for the specified CRC protocol. @n
+ * Starts intermediate checksum computation by writing the seed value.
+ * @note CRC_Get16bitResult() or CRC_Get32bitResult() return intermediate checksum (raw data register value).
+ *
+ * @param base CRC peripheral address.
+ * @param protocolConfig Pointer to protocol configuration structure.
+ */
+static void crc_SetRawProtocolConfig(CRC_Type *base, const crc_config_t *protocolConfig)
+{
+ crc_module_config_t moduleConfig;
+ /* convert protocol to CRC peripheral module configuration, prepare for intermediate checksum */
+ moduleConfig.polynomial = protocolConfig->polynomial;
+ moduleConfig.seed = protocolConfig->seed;
+ moduleConfig.readTranspose =
+ kCrcTransposeNone; /* intermediate checksum does no transpose of data register read value */
+ moduleConfig.writeTranspose = crc_GetTransposeTypeFromReflectIn(protocolConfig->reflectIn);
+ moduleConfig.complementChecksum = false; /* intermediate checksum does no xor of data register read value */
+ moduleConfig.crcBits = protocolConfig->crcBits;
+
+ crc_ConfigureAndStart(base, &moduleConfig);
+}
+
+void CRC_Init(CRC_Type *base, const crc_config_t *config)
+{
+ /* ungate clock */
+ CLOCK_EnableClock(kCLOCK_Crc0);
+ /* configure CRC module and write the seed */
+ if (config->crcResult == kCrcFinalChecksum)
+ {
+ crc_SetProtocolConfig(base, config);
+ }
+ else
+ {
+ crc_SetRawProtocolConfig(base, config);
+ }
+}
+
+void CRC_GetDefaultConfig(crc_config_t *config)
+{
+ static const crc_config_t crc16ccit = {
+ CRC_DRIVER_DEFAULT_POLYNOMIAL, CRC_DRIVER_DEFAULT_SEED,
+ CRC_DRIVER_DEFAULT_REFLECT_IN, CRC_DRIVER_DEFAULT_REFLECT_OUT,
+ CRC_DRIVER_DEFAULT_COMPLEMENT_CHECKSUM, CRC_DRIVER_DEFAULT_CRC_BITS,
+ CRC_DRIVER_DEFAULT_CRC_RESULT,
+ };
+
+ *config = crc16ccit;
+}
+
+void CRC_WriteData(CRC_Type *base, const uint8_t *data, size_t dataSize)
+{
+ const uint32_t *data32;
+
+ /* 8-bit reads and writes till source address is aligned 4 bytes */
+ while ((dataSize) && ((uint32_t)data & 3U))
+ {
+ base->ACCESS8BIT.DATALL = *data;
+ data++;
+ dataSize--;
+ }
+
+ /* use 32-bit reads and writes as long as possible */
+ data32 = (const uint32_t *)data;
+ while (dataSize >= sizeof(uint32_t))
+ {
+ base->DATA = *data32;
+ data32++;
+ dataSize -= sizeof(uint32_t);
+ }
+
+ data = (const uint8_t *)data32;
+
+ /* 8-bit reads and writes till end of data buffer */
+ while (dataSize)
+ {
+ base->ACCESS8BIT.DATALL = *data;
+ data++;
+ dataSize--;
+ }
+}
+
+uint32_t CRC_Get32bitResult(CRC_Type *base)
+{
+ return base->DATA;
+}
+
+uint16_t CRC_Get16bitResult(CRC_Type *base)
+{
+ uint32_t retval;
+ uint32_t totr; /* type of transpose read bitfield */
+
+ retval = base->DATA;
+ totr = (base->CTRL & CRC_CTRL_TOTR_MASK) >> CRC_CTRL_TOTR_SHIFT;
+
+ /* check transpose type to get 16-bit out of 32-bit register */
+ if (totr >= 2U)
+ {
+ /* transpose of bytes for read is set, the result CRC is in CRC_DATA[HU:HL] */
+ retval &= 0xFFFF0000U;
+ retval = retval >> 16U;
+ }
+ else
+ {
+ /* no transpose of bytes for read, the result CRC is in CRC_DATA[LU:LL] */
+ retval &= 0x0000FFFFU;
+ }
+ return (uint16_t)retval;
+}
diff --git a/drivers/fsl_crc.h b/drivers/fsl_crc.h
new file mode 100644
index 0000000..9d76731
--- /dev/null
+++ b/drivers/fsl_crc.h
@@ -0,0 +1,192 @@
+/*
+ * Copyright (c) 2015-2016, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_CRC_H_
+#define _FSL_CRC_H_
+
+#include "fsl_common.h"
+
+/*!
+ * @addtogroup crc
+ * @{
+ */
+
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+/*! @name Driver version */
+/*@{*/
+/*! @brief CRC driver version. Version 2.0.1.
+ *
+ * Current version: 2.0.1
+ *
+ * Change log:
+ * - Version 2.0.1
+ * - move DATA and DATALL macro definition from header file to source file
+ */
+#define FSL_CRC_DRIVER_VERSION (MAKE_VERSION(2, 0, 1))
+/*@}*/
+
+#ifndef CRC_DRIVER_CUSTOM_DEFAULTS
+/*! @brief Default configuration structure filled by CRC_GetDefaultConfig(). Use CRC16-CCIT-FALSE as defeault. */
+#define CRC_DRIVER_USE_CRC16_CCIT_FALSE_AS_DEFAULT 1
+#endif
+
+/*! @brief CRC bit width */
+typedef enum _crc_bits
+{
+ kCrcBits16 = 0U, /*!< Generate 16-bit CRC code */
+ kCrcBits32 = 1U /*!< Generate 32-bit CRC code */
+} crc_bits_t;
+
+/*! @brief CRC result type */
+typedef enum _crc_result
+{
+ kCrcFinalChecksum = 0U, /*!< CRC data register read value is the final checksum.
+ Reflect out and final xor protocol features are applied. */
+ kCrcIntermediateChecksum = 1U /*!< CRC data register read value is intermediate checksum (raw value).
+ Reflect out and final xor protocol feature are not applied.
+ Intermediate checksum can be used as a seed for CRC_Init()
+ to continue adding data to this checksum. */
+} crc_result_t;
+
+/*!
+* @brief CRC protocol configuration.
+*
+* This structure holds the configuration for the CRC protocol.
+*
+*/
+typedef struct _crc_config
+{
+ uint32_t polynomial; /*!< CRC Polynomial, MSBit first.
+ Example polynomial: 0x1021 = 1_0000_0010_0001 = x^12+x^5+1 */
+ uint32_t seed; /*!< Starting checksum value */
+ bool reflectIn; /*!< Reflect bits on input. */
+ bool reflectOut; /*!< Reflect bits on output. */
+ bool complementChecksum; /*!< True if the result shall be complement of the actual checksum. */
+ crc_bits_t crcBits; /*!< Selects 16- or 32- bit CRC protocol. */
+ crc_result_t crcResult; /*!< Selects final or intermediate checksum return from CRC_Get16bitResult() or
+ CRC_Get32bitResult() */
+} crc_config_t;
+
+/*******************************************************************************
+ * API
+ ******************************************************************************/
+#if defined(__cplusplus)
+extern "C" {
+#endif
+
+/*!
+ * @brief Enables and configures the CRC peripheral module.
+ *
+ * This functions enables the clock gate in the Kinetis SIM module for the CRC peripheral.
+ * It also configures the CRC module and starts checksum computation by writing the seed.
+ *
+ * @param base CRC peripheral address.
+ * @param config CRC module configuration structure
+ */
+void CRC_Init(CRC_Type *base, const crc_config_t *config);
+
+/*!
+ * @brief Disables the CRC peripheral module.
+ *
+ * This functions disables the clock gate in the Kinetis SIM module for the CRC peripheral.
+ *
+ * @param base CRC peripheral address.
+ */
+static inline void CRC_Deinit(CRC_Type *base)
+{
+ /* gate clock */
+ CLOCK_DisableClock(kCLOCK_Crc0);
+}
+
+/*!
+ * @brief Loads default values to CRC protocol configuration structure.
+ *
+ * Loads default values to CRC protocol configuration structure. The default values are:
+ * @code
+ * config->polynomial = 0x1021;
+ * config->seed = 0xFFFF;
+ * config->reflectIn = false;
+ * config->reflectOut = false;
+ * config->complementChecksum = false;
+ * config->crcBits = kCrcBits16;
+ * config->crcResult = kCrcFinalChecksum;
+ * @endcode
+ *
+ * @param config CRC protocol configuration structure
+ */
+void CRC_GetDefaultConfig(crc_config_t *config);
+
+/*!
+ * @brief Writes data to the CRC module.
+ *
+ * Writes input data buffer bytes to CRC data register.
+ * The configured type of transpose is applied.
+ *
+ * @param base CRC peripheral address.
+ * @param data Input data stream, MSByte in data[0].
+ * @param dataSize Size in bytes of the input data buffer.
+ */
+void CRC_WriteData(CRC_Type *base, const uint8_t *data, size_t dataSize);
+
+/*!
+ * @brief Reads 32-bit checksum from the CRC module.
+ *
+ * Reads CRC data register (intermediate or final checksum).
+ * The configured type of transpose and complement are applied.
+ *
+ * @param base CRC peripheral address.
+ * @return intermediate or final 32-bit checksum, after configured transpose and complement operations.
+ */
+uint32_t CRC_Get32bitResult(CRC_Type *base);
+
+/*!
+ * @brief Reads 16-bit checksum from the CRC module.
+ *
+ * Reads CRC data register (intermediate or final checksum).
+ * The configured type of transpose and complement are applied.
+ *
+ * @param base CRC peripheral address.
+ * @return intermediate or final 16-bit checksum, after configured transpose and complement operations.
+ */
+uint16_t CRC_Get16bitResult(CRC_Type *base);
+
+#if defined(__cplusplus)
+}
+#endif
+
+/*!
+ *@}
+ */
+
+#endif /* _FSL_CRC_H_ */
diff --git a/drivers/fsl_dac.c b/drivers/fsl_dac.c
new file mode 100644
index 0000000..55e5517
--- /dev/null
+++ b/drivers/fsl_dac.c
@@ -0,0 +1,214 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_dac.h"
+
+/*******************************************************************************
+ * Prototypes
+ ******************************************************************************/
+/*!
+ * @brief Get instance number for DAC module.
+ *
+ * @param base DAC peripheral base address
+ */
+static uint32_t DAC_GetInstance(DAC_Type *base);
+
+/*******************************************************************************
+ * Variables
+ ******************************************************************************/
+/*! @brief Pointers to DAC bases for each instance. */
+static DAC_Type *const s_dacBases[] = DAC_BASE_PTRS;
+/*! @brief Pointers to DAC clocks for each instance. */
+static const clock_ip_name_t s_dacClocks[] = DAC_CLOCKS;
+
+/*******************************************************************************
+ * Codes
+ ******************************************************************************/
+static uint32_t DAC_GetInstance(DAC_Type *base)
+{
+ uint32_t instance;
+
+ /* Find the instance index from base address mappings. */
+ for (instance = 0; instance < FSL_FEATURE_SOC_DAC_COUNT; instance++)
+ {
+ if (s_dacBases[instance] == base)
+ {
+ break;
+ }
+ }
+
+ assert(instance < FSL_FEATURE_SOC_DAC_COUNT);
+
+ return instance;
+}
+
+void DAC_Init(DAC_Type *base, const dac_config_t *config)
+{
+ assert(NULL != config);
+
+ uint8_t tmp8;
+
+ /* Enable the clock. */
+ CLOCK_EnableClock(s_dacClocks[DAC_GetInstance(base)]);
+
+ /* Configure. */
+ /* DACx_C0. */
+ tmp8 = base->C0 & ~(DAC_C0_DACRFS_MASK | DAC_C0_LPEN_MASK);
+ if (kDAC_ReferenceVoltageSourceVref2 == config->referenceVoltageSource)
+ {
+ tmp8 |= DAC_C0_DACRFS_MASK;
+ }
+ if (config->enableLowPowerMode)
+ {
+ tmp8 |= DAC_C0_LPEN_MASK;
+ }
+ base->C0 = tmp8;
+
+ /* DAC_Enable(base, true); */
+ /* Tip: The DAC output can be enabled till then after user sets their own available data in application. */
+}
+
+void DAC_Deinit(DAC_Type *base)
+{
+ DAC_Enable(base, false);
+
+ /* Disable the clock. */
+ CLOCK_DisableClock(s_dacClocks[DAC_GetInstance(base)]);
+}
+
+void DAC_GetDefaultConfig(dac_config_t *config)
+{
+ assert(NULL != config);
+
+ config->referenceVoltageSource = kDAC_ReferenceVoltageSourceVref2;
+ config->enableLowPowerMode = false;
+}
+
+void DAC_SetBufferConfig(DAC_Type *base, const dac_buffer_config_t *config)
+{
+ assert(NULL != config);
+
+ uint8_t tmp8;
+
+ /* DACx_C0. */
+ tmp8 = base->C0 & ~(DAC_C0_DACTRGSEL_MASK);
+ if (kDAC_BufferTriggerBySoftwareMode == config->triggerMode)
+ {
+ tmp8 |= DAC_C0_DACTRGSEL_MASK;
+ }
+ base->C0 = tmp8;
+
+ /* DACx_C1. */
+ tmp8 = base->C1 &
+ ~(
+#if defined(FSL_FEATURE_DAC_HAS_WATERMARK_SELECTION) && FSL_FEATURE_DAC_HAS_WATERMARK_SELECTION
+ DAC_C1_DACBFWM_MASK |
+#endif /* FSL_FEATURE_DAC_HAS_WATERMARK_SELECTION */
+ DAC_C1_DACBFMD_MASK);
+#if defined(FSL_FEATURE_DAC_HAS_WATERMARK_SELECTION) && FSL_FEATURE_DAC_HAS_WATERMARK_SELECTION
+ tmp8 |= DAC_C1_DACBFWM(config->watermark);
+#endif /* FSL_FEATURE_DAC_HAS_WATERMARK_SELECTION */
+ tmp8 |= DAC_C1_DACBFMD(config->workMode);
+ base->C1 = tmp8;
+
+ /* DACx_C2. */
+ tmp8 = base->C2 & ~DAC_C2_DACBFUP_MASK;
+ tmp8 |= DAC_C2_DACBFUP(config->upperLimit);
+ base->C2 = tmp8;
+}
+
+void DAC_GetDefaultBufferConfig(dac_buffer_config_t *config)
+{
+ assert(NULL != config);
+
+ config->triggerMode = kDAC_BufferTriggerBySoftwareMode;
+#if defined(FSL_FEATURE_DAC_HAS_WATERMARK_SELECTION) && FSL_FEATURE_DAC_HAS_WATERMARK_SELECTION
+ config->watermark = kDAC_BufferWatermark1Word;
+#endif /* FSL_FEATURE_DAC_HAS_WATERMARK_SELECTION */
+ config->workMode = kDAC_BufferWorkAsNormalMode;
+ config->upperLimit = DAC_DATL_COUNT - 1U;
+}
+
+void DAC_SetBufferValue(DAC_Type *base, uint8_t index, uint16_t value)
+{
+ assert(index < DAC_DATL_COUNT);
+
+ base->DAT[index].DATL = (uint8_t)(0xFFU & value); /* Low 8-bit. */
+ base->DAT[index].DATH = (uint8_t)((0xF00U & value) >> 8); /* High 4-bit. */
+}
+
+void DAC_SetBufferReadPointer(DAC_Type *base, uint8_t index)
+{
+ assert(index < DAC_DATL_COUNT);
+
+ uint8_t tmp8 = base->C2 & ~DAC_C2_DACBFRP_MASK;
+
+ tmp8 |= DAC_C2_DACBFRP(index);
+ base->C2 = tmp8;
+}
+
+void DAC_EnableBufferInterrupts(DAC_Type *base, uint32_t mask)
+{
+ mask &= (
+#if defined(FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION) && FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION
+ DAC_C0_DACBWIEN_MASK |
+#endif /* FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION */
+ DAC_C0_DACBTIEN_MASK | DAC_C0_DACBBIEN_MASK);
+ base->C0 |= ((uint8_t)mask); /* Write 1 to enable. */
+}
+
+void DAC_DisableBufferInterrupts(DAC_Type *base, uint32_t mask)
+{
+ mask &= (
+#if defined(FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION) && FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION
+ DAC_C0_DACBWIEN_MASK |
+#endif /* FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION */
+ DAC_C0_DACBTIEN_MASK | DAC_C0_DACBBIEN_MASK);
+ base->C0 &= (uint8_t)(~((uint8_t)mask)); /* Write 0 to disable. */
+}
+
+uint32_t DAC_GetBufferStatusFlags(DAC_Type *base)
+{
+ return (uint32_t)(base->SR & (
+#if defined(FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION) && FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION
+ DAC_SR_DACBFWMF_MASK |
+#endif /* FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION */
+ DAC_SR_DACBFRPTF_MASK | DAC_SR_DACBFRPBF_MASK));
+}
+
+void DAC_ClearBufferStatusFlags(DAC_Type *base, uint32_t mask)
+{
+ mask &= (
+#if defined(FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION) && FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION
+ DAC_SR_DACBFWMF_MASK |
+#endif /* FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION */
+ DAC_SR_DACBFRPTF_MASK | DAC_SR_DACBFRPBF_MASK);
+ base->SR &= (uint8_t)(~((uint8_t)mask)); /* Write 0 to clear flags. */
+}
diff --git a/drivers/fsl_dac.h b/drivers/fsl_dac.h
new file mode 100644
index 0000000..925ca19
--- /dev/null
+++ b/drivers/fsl_dac.h
@@ -0,0 +1,378 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_DAC_H_
+#define _FSL_DAC_H_
+
+#include "fsl_common.h"
+
+/*!
+ * @addtogroup dac
+ * @{
+ */
+
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+/*! @name Driver version */
+/*@{*/
+/*! @brief DAC driver version 2.0.1. */
+#define FSL_DAC_DRIVER_VERSION (MAKE_VERSION(2, 0, 1))
+/*@}*/
+
+/*!
+ * @brief DAC buffer flags.
+ */
+enum _dac_buffer_status_flags
+{
+#if defined(FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION) && FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION
+ kDAC_BufferWatermarkFlag = DAC_SR_DACBFWMF_MASK, /*!< DAC Buffer Watermark Flag. */
+#endif /* FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION */
+ kDAC_BufferReadPointerTopPositionFlag = DAC_SR_DACBFRPTF_MASK, /*!< DAC Buffer Read Pointer Top Position Flag. */
+ kDAC_BufferReadPointerBottomPositionFlag = DAC_SR_DACBFRPBF_MASK, /*!< DAC Buffer Read Pointer Bottom Position
+ Flag. */
+};
+
+/*!
+ * @brief DAC buffer interrupts.
+ */
+enum _dac_buffer_interrupt_enable
+{
+#if defined(FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION) && FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION
+ kDAC_BufferWatermarkInterruptEnable = DAC_C0_DACBWIEN_MASK, /*!< DAC Buffer Watermark Interrupt Enable. */
+#endif /* FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION */
+ kDAC_BufferReadPointerTopInterruptEnable = DAC_C0_DACBTIEN_MASK, /*!< DAC Buffer Read Pointer Top Flag Interrupt
+ Enable. */
+ kDAC_BufferReadPointerBottomInterruptEnable = DAC_C0_DACBBIEN_MASK, /*!< DAC Buffer Read Pointer Bottom Flag
+ Interrupt Enable */
+};
+
+/*!
+ * @brief DAC reference voltage source.
+ */
+typedef enum _dac_reference_voltage_source
+{
+ kDAC_ReferenceVoltageSourceVref1 = 0U, /*!< The DAC selects DACREF_1 as the reference voltage. */
+ kDAC_ReferenceVoltageSourceVref2 = 1U, /*!< The DAC selects DACREF_2 as the reference voltage. */
+} dac_reference_voltage_source_t;
+
+/*!
+ * @brief DAC buffer trigger mode.
+ */
+typedef enum _dac_buffer_trigger_mode
+{
+ kDAC_BufferTriggerByHardwareMode = 0U, /*!< The DAC hardware trigger is selected. */
+ kDAC_BufferTriggerBySoftwareMode = 1U, /*!< The DAC software trigger is selected. */
+} dac_buffer_trigger_mode_t;
+
+#if defined(FSL_FEATURE_DAC_HAS_WATERMARK_SELECTION) && FSL_FEATURE_DAC_HAS_WATERMARK_SELECTION
+/*!
+ * @brief DAC buffer watermark.
+ */
+typedef enum _dac_buffer_watermark
+{
+#if defined(FSL_FEATURE_DAC_HAS_WATERMARK_1_WORD) && FSL_FEATURE_DAC_HAS_WATERMARK_1_WORD
+ kDAC_BufferWatermark1Word = 0U, /*!< 1 word away from the upper limit. */
+#endif /* FSL_FEATURE_DAC_HAS_WATERMARK_1_WORD */
+#if defined(FSL_FEATURE_DAC_HAS_WATERMARK_2_WORDS) && FSL_FEATURE_DAC_HAS_WATERMARK_2_WORDS
+ kDAC_BufferWatermark2Word = 1U, /*!< 2 words away from the upper limit. */
+#endif /* FSL_FEATURE_DAC_HAS_WATERMARK_2_WORDS */
+#if defined(FSL_FEATURE_DAC_HAS_WATERMARK_3_WORDS) && FSL_FEATURE_DAC_HAS_WATERMARK_3_WORDS
+ kDAC_BufferWatermark3Word = 2U, /*!< 3 words away from the upper limit. */
+#endif /* FSL_FEATURE_DAC_HAS_WATERMARK_3_WORDS */
+#if defined(FSL_FEATURE_DAC_HAS_WATERMARK_4_WORDS) && FSL_FEATURE_DAC_HAS_WATERMARK_4_WORDS
+ kDAC_BufferWatermark4Word = 3U, /*!< 4 words away from the upper limit. */
+#endif /* FSL_FEATURE_DAC_HAS_WATERMARK_4_WORDS */
+} dac_buffer_watermark_t;
+#endif /* FSL_FEATURE_DAC_HAS_WATERMARK_SELECTION */
+
+/*!
+ * @brief DAC buffer work mode.
+ */
+typedef enum _dac_buffer_work_mode
+{
+ kDAC_BufferWorkAsNormalMode = 0U, /*!< Normal mode. */
+#if defined(FSL_FEATURE_DAC_HAS_BUFFER_SWING_MODE) && FSL_FEATURE_DAC_HAS_BUFFER_SWING_MODE
+ kDAC_BufferWorkAsSwingMode, /*!< Swing mode. */
+#endif /* FSL_FEATURE_DAC_HAS_BUFFER_SWING_MODE */
+ kDAC_BufferWorkAsOneTimeScanMode, /*!< One-Time Scan mode. */
+#if defined(FSL_FEATURE_DAC_HAS_BUFFER_FIFO_MODE) && FSL_FEATURE_DAC_HAS_BUFFER_FIFO_MODE
+ kDAC_BufferWorkAsFIFOMode, /*!< FIFO mode. */
+#endif /* FSL_FEATURE_DAC_HAS_BUFFER_FIFO_MODE */
+} dac_buffer_work_mode_t;
+
+/*!
+ * @brief DAC module configuration.
+ */
+typedef struct _dac_config
+{
+ dac_reference_voltage_source_t referenceVoltageSource; /*!< Select the DAC reference voltage source. */
+ bool enableLowPowerMode; /*!< Enable the low-power mode. */
+} dac_config_t;
+
+/*!
+ * @brief DAC buffer configuration.
+ */
+typedef struct _dac_buffer_config
+{
+ dac_buffer_trigger_mode_t triggerMode; /*!< Select the buffer's trigger mode. */
+#if defined(FSL_FEATURE_DAC_HAS_WATERMARK_SELECTION) && FSL_FEATURE_DAC_HAS_WATERMARK_SELECTION
+ dac_buffer_watermark_t watermark; /*!< Select the buffer's watermark. */
+#endif /* FSL_FEATURE_DAC_HAS_WATERMARK_SELECTION */
+ dac_buffer_work_mode_t workMode; /*!< Select the buffer's work mode. */
+ uint8_t upperLimit; /*!< Set the upper limit for buffer index.
+ Normally, 0-15 is available for buffer with 16 item. */
+} dac_buffer_config_t;
+
+/*******************************************************************************
+ * API
+ ******************************************************************************/
+#if defined(__cplusplus)
+extern "C" {
+#endif
+
+/*!
+ * @name Initialization
+ * @{
+ */
+
+/*!
+ * @brief Initializes the DAC module.
+ *
+ * This function initializes the DAC module, including:
+ * - Enabling the clock for DAC module.
+ * - Configuring the DAC converter with a user configuration.
+ * - Enabling the DAC module.
+ *
+ * @param base DAC peripheral base address.
+ * @param config Pointer to the configuration structure. See "dac_config_t".
+ */
+void DAC_Init(DAC_Type *base, const dac_config_t *config);
+
+/*!
+ * @brief De-initializes the DAC module.
+ *
+ * This function de-initializes the DAC module, including:
+ * - Disabling the DAC module.
+ * - Disabling the clock for the DAC module.
+ *
+ * @param base DAC peripheral base address.
+ */
+void DAC_Deinit(DAC_Type *base);
+
+/*!
+ * @brief Initializes the DAC user configuration structure.
+ *
+ * This function initializes the user configuration structure to a default value. The default values are:
+ * @code
+ * config->referenceVoltageSource = kDAC_ReferenceVoltageSourceVref2;
+ * config->enableLowPowerMode = false;
+ * @endcode
+ * @param config Pointer to the configuration structure. See "dac_config_t".
+ */
+void DAC_GetDefaultConfig(dac_config_t *config);
+
+/*!
+ * @brief Enables the DAC module.
+ *
+ * @param base DAC peripheral base address.
+ * @param enable Enables/disables the feature.
+ */
+static inline void DAC_Enable(DAC_Type *base, bool enable)
+{
+ if (enable)
+ {
+ base->C0 |= DAC_C0_DACEN_MASK;
+ }
+ else
+ {
+ base->C0 &= ~DAC_C0_DACEN_MASK;
+ }
+}
+
+/* @} */
+
+/*!
+ * @name Buffer
+ * @{
+ */
+
+/*!
+ * @brief Enables the DAC buffer.
+ *
+ * @param base DAC peripheral base address.
+ * @param enable Enables/disables the feature.
+ */
+static inline void DAC_EnableBuffer(DAC_Type *base, bool enable)
+{
+ if (enable)
+ {
+ base->C1 |= DAC_C1_DACBFEN_MASK;
+ }
+ else
+ {
+ base->C1 &= ~DAC_C1_DACBFEN_MASK;
+ }
+}
+
+/*!
+ * @brief Configures the CMP buffer.
+ *
+ * @param base DAC peripheral base address.
+ * @param config Pointer to the configuration structure. See "dac_buffer_config_t".
+ */
+void DAC_SetBufferConfig(DAC_Type *base, const dac_buffer_config_t *config);
+
+/*!
+ * @brief Initializes the DAC buffer configuration structure.
+ *
+ * This function initializes the DAC buffer configuration structure to a default value. The default values are:
+ * @code
+ * config->triggerMode = kDAC_BufferTriggerBySoftwareMode;
+ * config->watermark = kDAC_BufferWatermark1Word;
+ * config->workMode = kDAC_BufferWorkAsNormalMode;
+ * config->upperLimit = DAC_DATL_COUNT - 1U;
+ * @endcode
+ * @param config Pointer to the configuration structure. See "dac_buffer_config_t".
+ */
+void DAC_GetDefaultBufferConfig(dac_buffer_config_t *config);
+
+/*!
+ * @brief Enables the DMA for DAC buffer.
+ *
+ * @param base DAC peripheral base address.
+ * @param enable Enables/disables the feature.
+ */
+static inline void DAC_EnableBufferDMA(DAC_Type *base, bool enable)
+{
+ if (enable)
+ {
+ base->C1 |= DAC_C1_DMAEN_MASK;
+ }
+ else
+ {
+ base->C1 &= ~DAC_C1_DMAEN_MASK;
+ }
+}
+
+/*!
+ * @brief Sets the value for items in the buffer.
+ *
+ * @param base DAC peripheral base address.
+ * @param index Setting index for items in the buffer. The available index should not exceed the size of the DAC buffer.
+ * @param value Setting value for items in the buffer. 12-bits are available.
+ */
+void DAC_SetBufferValue(DAC_Type *base, uint8_t index, uint16_t value);
+
+/*!
+ * @brief Triggers the buffer by software and updates the read pointer of the DAC buffer.
+ *
+ * This function triggers the function by software. The read pointer of the DAC buffer is updated with one step
+ * after this function is called. Changing the read pointer depends on the buffer's work mode.
+ *
+ * @param base DAC peripheral base address.
+ */
+static inline void DAC_DoSoftwareTriggerBuffer(DAC_Type *base)
+{
+ base->C0 |= DAC_C0_DACSWTRG_MASK;
+}
+
+/*!
+ * @brief Gets the current read pointer of the DAC buffer.
+ *
+ * This function gets the current read pointer of the DAC buffer.
+ * The current output value depends on the item indexed by the read pointer. It is updated
+ * by software trigger or hardware trigger.
+ *
+ * @param base DAC peripheral base address.
+ *
+ * @return Current read pointer of DAC buffer.
+ */
+static inline uint8_t DAC_GetBufferReadPointer(DAC_Type *base)
+{
+ return ((base->C2 & DAC_C2_DACBFRP_MASK) >> DAC_C2_DACBFRP_SHIFT);
+}
+
+/*!
+ * @brief Sets the current read pointer of the DAC buffer.
+ *
+ * This function sets the current read pointer of the DAC buffer.
+ * The current output value depends on the item indexed by the read pointer. It is updated by
+ * software trigger or hardware trigger. After the read pointer changes, the DAC output value also changes.
+ *
+ * @param base DAC peripheral base address.
+ * @param index Setting index value for the pointer.
+ */
+void DAC_SetBufferReadPointer(DAC_Type *base, uint8_t index);
+
+/*!
+ * @brief Enables interrupts for the DAC buffer.
+ *
+ * @param base DAC peripheral base address.
+ * @param mask Mask value for interrupts. See "_dac_buffer_interrupt_enable".
+ */
+void DAC_EnableBufferInterrupts(DAC_Type *base, uint32_t mask);
+
+/*!
+ * @brief Disables interrupts for the DAC buffer.
+ *
+ * @param base DAC peripheral base address.
+ * @param mask Mask value for interrupts. See "_dac_buffer_interrupt_enable".
+ */
+void DAC_DisableBufferInterrupts(DAC_Type *base, uint32_t mask);
+
+/*!
+ * @brief Gets the flags of events for the DAC buffer.
+ *
+ * @param base DAC peripheral base address.
+ *
+ * @return Mask value for the asserted flags. See "_dac_buffer_status_flags".
+ */
+uint32_t DAC_GetBufferStatusFlags(DAC_Type *base);
+
+/*!
+ * @brief Clears the flags of events for the DAC buffer.
+ *
+ * @param base DAC peripheral base address.
+ * @param mask Mask value for flags. See "_dac_buffer_status_flags_t".
+ */
+void DAC_ClearBufferStatusFlags(DAC_Type *base, uint32_t mask);
+
+/* @} */
+
+#if defined(__cplusplus)
+}
+#endif
+/*!
+ * @}
+ */
+#endif /* _FSL_DAC_H_ */
diff --git a/drivers/fsl_dmamux.c b/drivers/fsl_dmamux.c
new file mode 100644
index 0000000..a288b9f
--- /dev/null
+++ b/drivers/fsl_dmamux.c
@@ -0,0 +1,87 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_dmamux.h"
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+/*******************************************************************************
+ * Prototypes
+ ******************************************************************************/
+
+/*!
+ * @brief Get instance number for DMAMUX.
+ *
+ * @param base DMAMUX peripheral base address.
+ */
+static uint32_t DMAMUX_GetInstance(DMAMUX_Type *base);
+
+/*******************************************************************************
+ * Variables
+ ******************************************************************************/
+
+/*! @brief Array to map DMAMUX instance number to base pointer. */
+static DMAMUX_Type *const s_dmamuxBases[] = DMAMUX_BASE_PTRS;
+
+/*! @brief Array to map DMAMUX instance number to clock name. */
+static const clock_ip_name_t s_dmamuxClockName[] = DMAMUX_CLOCKS;
+
+/*******************************************************************************
+ * Code
+ ******************************************************************************/
+static uint32_t DMAMUX_GetInstance(DMAMUX_Type *base)
+{
+ uint32_t instance;
+
+ /* Find the instance index from base address mappings. */
+ for (instance = 0; instance < FSL_FEATURE_SOC_DMAMUX_COUNT; instance++)
+ {
+ if (s_dmamuxBases[instance] == base)
+ {
+ break;
+ }
+ }
+
+ assert(instance < FSL_FEATURE_SOC_DMAMUX_COUNT);
+
+ return instance;
+}
+
+void DMAMUX_Init(DMAMUX_Type *base)
+{
+ CLOCK_EnableClock(s_dmamuxClockName[DMAMUX_GetInstance(base)]);
+}
+
+void DMAMUX_Deinit(DMAMUX_Type *base)
+{
+ CLOCK_DisableClock(s_dmamuxClockName[DMAMUX_GetInstance(base)]);
+}
diff --git a/drivers/fsl_dmamux.h b/drivers/fsl_dmamux.h
new file mode 100644
index 0000000..5dce562
--- /dev/null
+++ b/drivers/fsl_dmamux.h
@@ -0,0 +1,175 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_DMAMUX_H_
+#define _FSL_DMAMUX_H_
+
+#include "fsl_common.h"
+
+/*!
+ * @addtogroup dmamux
+ * @{
+ */
+
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+/*! @name Driver version */
+/*@{*/
+/*! @brief DMAMUX driver version 2.0.1. */
+#define FSL_DMAMUX_DRIVER_VERSION (MAKE_VERSION(2, 0, 1))
+/*@}*/
+
+/*******************************************************************************
+ * API
+ ******************************************************************************/
+
+#if defined(__cplusplus)
+extern "C" {
+#endif /* __cplusplus */
+
+/*!
+ * @name DMAMUX Initialize and De-initialize
+ * @{
+ */
+
+/*!
+ * @brief Initializes DMAMUX peripheral.
+ *
+ * This function ungate the DMAMUX clock.
+ *
+ * @param base DMAMUX peripheral base address.
+ *
+ */
+void DMAMUX_Init(DMAMUX_Type *base);
+
+/*!
+ * @brief Deinitializes DMAMUX peripheral.
+ *
+ * This function gate the DMAMUX clock.
+ *
+ * @param base DMAMUX peripheral base address.
+ */
+void DMAMUX_Deinit(DMAMUX_Type *base);
+
+/* @} */
+/*!
+ * @name DMAMUX Channel Operation
+ * @{
+ */
+
+/*!
+ * @brief Enable DMAMUX channel.
+ *
+ * This function enable DMAMUX channel to work.
+ *
+ * @param base DMAMUX peripheral base address.
+ * @param channel DMAMUX channel number.
+ */
+static inline void DMAMUX_EnableChannel(DMAMUX_Type *base, uint32_t channel)
+{
+ assert(channel < FSL_FEATURE_DMAMUX_MODULE_CHANNEL);
+
+ base->CHCFG[channel] |= DMAMUX_CHCFG_ENBL_MASK;
+}
+
+/*!
+ * @brief Disable DMAMUX channel.
+ *
+ * This function disable DMAMUX channel.
+ *
+ * @note User must disable DMAMUX channel before configuring it.
+ * @param base DMAMUX peripheral base address.
+ * @param channel DMAMUX channel number.
+ */
+static inline void DMAMUX_DisableChannel(DMAMUX_Type *base, uint32_t channel)
+{
+ assert(channel < FSL_FEATURE_DMAMUX_MODULE_CHANNEL);
+
+ base->CHCFG[channel] &= ~DMAMUX_CHCFG_ENBL_MASK;
+}
+
+/*!
+ * @brief Configure DMAMUX channel source.
+ *
+ * @param base DMAMUX peripheral base address.
+ * @param channel DMAMUX channel number.
+ * @param source Channel source which is used to trigger DMA transfer.
+ */
+static inline void DMAMUX_SetSource(DMAMUX_Type *base, uint32_t channel, uint32_t source)
+{
+ assert(channel < FSL_FEATURE_DMAMUX_MODULE_CHANNEL);
+
+ base->CHCFG[channel] = ((base->CHCFG[channel] & ~DMAMUX_CHCFG_SOURCE_MASK) | DMAMUX_CHCFG_SOURCE(source));
+}
+
+#if defined(FSL_FEATURE_DMAMUX_HAS_TRIG) && FSL_FEATURE_DMAMUX_HAS_TRIG > 0U
+/*!
+ * @brief Enable DMAMUX period trigger.
+ *
+ * This function enable DMAMUX period trigger feature.
+ *
+ * @param base DMAMUX peripheral base address.
+ * @param channel DMAMUX channel number.
+ */
+static inline void DMAMUX_EnablePeriodTrigger(DMAMUX_Type *base, uint32_t channel)
+{
+ assert(channel < FSL_FEATURE_DMAMUX_MODULE_CHANNEL);
+
+ base->CHCFG[channel] |= DMAMUX_CHCFG_TRIG_MASK;
+}
+
+/*!
+ * @brief Disable DMAMUX period trigger.
+ *
+ * This function disable DMAMUX period trigger.
+ *
+ * @param base DMAMUX peripheral base address.
+ * @param channel DMAMUX channel number.
+ */
+static inline void DMAMUX_DisablePeriodTrigger(DMAMUX_Type *base, uint32_t channel)
+{
+ assert(channel < FSL_FEATURE_DMAMUX_MODULE_CHANNEL);
+
+ base->CHCFG[channel] &= ~DMAMUX_CHCFG_TRIG_MASK;
+}
+#endif /* FSL_FEATURE_DMAMUX_HAS_TRIG */
+
+/* @} */
+
+#if defined(__cplusplus)
+}
+#endif /* __cplusplus */
+
+/* @} */
+
+#endif /* _FSL_DMAMUX_H_ */
diff --git a/drivers/fsl_dspi.c b/drivers/fsl_dspi.c
new file mode 100644
index 0000000..b2f28ed
--- /dev/null
+++ b/drivers/fsl_dspi.c
@@ -0,0 +1,1661 @@
+/*
+* Copyright (c) 2015, Freescale Semiconductor, Inc.
+* All rights reserved.
+*
+* 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 Freescale Semiconductor, Inc. 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_dspi.h"
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+/*! @brief Typedef for master interrupt handler. */
+typedef void (*dspi_master_isr_t)(SPI_Type *base, dspi_master_handle_t *handle);
+
+/*! @brief Typedef for slave interrupt handler. */
+typedef void (*dspi_slave_isr_t)(SPI_Type *base, dspi_slave_handle_t *handle);
+
+/*******************************************************************************
+ * Prototypes
+ ******************************************************************************/
+/*!
+ * @brief Get instance number for DSPI module.
+ *
+ * @param base DSPI peripheral base address.
+ */
+uint32_t DSPI_GetInstance(SPI_Type *base);
+
+/*!
+ * @brief Configures the DSPI peripheral chip select polarity.
+ *
+ * This function takes in the desired peripheral chip select (Pcs) and it's corresponding desired polarity and
+ * configures the Pcs signal to operate with the desired characteristic.
+ *
+ * @param base DSPI peripheral address.
+ * @param pcs The particular peripheral chip select (parameter value is of type dspi_which_pcs_t) for which we wish to
+ * apply the active high or active low characteristic.
+ * @param activeLowOrHigh The setting for either "active high, inactive low (0)" or "active low, inactive high(1)" of
+ * type dspi_pcs_polarity_config_t.
+ */
+static void DSPI_SetOnePcsPolarity(SPI_Type *base, dspi_which_pcs_t pcs, dspi_pcs_polarity_config_t activeLowOrHigh);
+
+/*!
+ * @brief Master fill up the TX FIFO with data.
+ * This is not a public API as it is called from other driver functions.
+ */
+static void DSPI_MasterTransferFillUpTxFifo(SPI_Type *base, dspi_master_handle_t *handle);
+
+/*!
+ * @brief Master finish up a transfer.
+ * It would call back if there is callback function and set the state to idle.
+ * This is not a public API as it is called from other driver functions.
+ */
+static void DSPI_MasterTransferComplete(SPI_Type *base, dspi_master_handle_t *handle);
+
+/*!
+ * @brief Slave fill up the TX FIFO with data.
+ * This is not a public API as it is called from other driver functions.
+ */
+static void DSPI_SlaveTransferFillUpTxFifo(SPI_Type *base, dspi_slave_handle_t *handle);
+
+/*!
+ * @brief Slave finish up a transfer.
+ * It would call back if there is callback function and set the state to idle.
+ * This is not a public API as it is called from other driver functions.
+ */
+static void DSPI_SlaveTransferComplete(SPI_Type *base, dspi_slave_handle_t *handle);
+
+/*!
+ * @brief DSPI common interrupt handler.
+ *
+ * @param base DSPI peripheral address.
+ * @param handle pointer to g_dspiHandle which stores the transfer state.
+ */
+static void DSPI_CommonIRQHandler(SPI_Type *base, void *param);
+
+/*!
+ * @brief Master prepare the transfer.
+ * Basically it set up dspi_master_handle .
+ * This is not a public API as it is called from other driver functions. fsl_dspi_edma.c also call this function.
+ */
+static void DSPI_MasterTransferPrepare(SPI_Type *base, dspi_master_handle_t *handle, dspi_transfer_t *transfer);
+
+/*******************************************************************************
+ * Variables
+ ******************************************************************************/
+
+/* Defines constant value arrays for the baud rate pre-scalar and scalar divider values.*/
+static const uint32_t s_baudratePrescaler[] = {2, 3, 5, 7};
+static const uint32_t s_baudrateScaler[] = {2, 4, 6, 8, 16, 32, 64, 128,
+ 256, 512, 1024, 2048, 4096, 8192, 16384, 32768};
+
+static const uint32_t s_delayPrescaler[] = {1, 3, 5, 7};
+static const uint32_t s_delayScaler[] = {2, 4, 8, 16, 32, 64, 128, 256,
+ 512, 1024, 2048, 4096, 8192, 16384, 32768, 65536};
+
+/*! @brief Pointers to dspi bases for each instance. */
+static SPI_Type *const s_dspiBases[] = SPI_BASE_PTRS;
+
+/*! @brief Pointers to dspi IRQ number for each instance. */
+static IRQn_Type const s_dspiIRQ[] = SPI_IRQS;
+
+/*! @brief Pointers to dspi clocks for each instance. */
+static clock_ip_name_t const s_dspiClock[] = DSPI_CLOCKS;
+
+/*! @brief Pointers to dspi handles for each instance. */
+static void *g_dspiHandle[FSL_FEATURE_SOC_DSPI_COUNT];
+
+/*! @brief Pointer to master IRQ handler for each instance. */
+static dspi_master_isr_t s_dspiMasterIsr;
+
+/*! @brief Pointer to slave IRQ handler for each instance. */
+static dspi_slave_isr_t s_dspiSlaveIsr;
+
+/**********************************************************************************************************************
+* Code
+*********************************************************************************************************************/
+uint32_t DSPI_GetInstance(SPI_Type *base)
+{
+ uint32_t instance;
+
+ /* Find the instance index from base address mappings. */
+ for (instance = 0; instance < FSL_FEATURE_SOC_DSPI_COUNT; instance++)
+ {
+ if (s_dspiBases[instance] == base)
+ {
+ break;
+ }
+ }
+
+ assert(instance < FSL_FEATURE_SOC_DSPI_COUNT);
+
+ return instance;
+}
+
+void DSPI_MasterInit(SPI_Type *base, const dspi_master_config_t *masterConfig, uint32_t srcClock_Hz)
+{
+ uint32_t temp;
+ /* enable DSPI clock */
+ CLOCK_EnableClock(s_dspiClock[DSPI_GetInstance(base)]);
+
+ DSPI_Enable(base, true);
+ DSPI_StopTransfer(base);
+
+ DSPI_SetMasterSlaveMode(base, kDSPI_Master);
+
+ temp = base->MCR & (~(SPI_MCR_CONT_SCKE_MASK | SPI_MCR_MTFE_MASK | SPI_MCR_ROOE_MASK | SPI_MCR_SMPL_PT_MASK |
+ SPI_MCR_DIS_TXF_MASK | SPI_MCR_DIS_RXF_MASK));
+
+ base->MCR = temp | SPI_MCR_CONT_SCKE(masterConfig->enableContinuousSCK) |
+ SPI_MCR_MTFE(masterConfig->enableModifiedTimingFormat) |
+ SPI_MCR_ROOE(masterConfig->enableRxFifoOverWrite) | SPI_MCR_SMPL_PT(masterConfig->samplePoint) |
+ SPI_MCR_DIS_TXF(false) | SPI_MCR_DIS_RXF(false);
+
+ DSPI_SetOnePcsPolarity(base, masterConfig->whichPcs, masterConfig->pcsActiveHighOrLow);
+
+ if (0 == DSPI_MasterSetBaudRate(base, masterConfig->whichCtar, masterConfig->ctarConfig.baudRate, srcClock_Hz))
+ {
+ assert(false);
+ }
+
+ temp = base->CTAR[masterConfig->whichCtar] &
+ ~(SPI_CTAR_FMSZ_MASK | SPI_CTAR_CPOL_MASK | SPI_CTAR_CPHA_MASK | SPI_CTAR_LSBFE_MASK);
+
+ base->CTAR[masterConfig->whichCtar] =
+ temp | SPI_CTAR_FMSZ(masterConfig->ctarConfig.bitsPerFrame - 1) | SPI_CTAR_CPOL(masterConfig->ctarConfig.cpol) |
+ SPI_CTAR_CPHA(masterConfig->ctarConfig.cpha) | SPI_CTAR_LSBFE(masterConfig->ctarConfig.direction);
+
+ DSPI_MasterSetDelayTimes(base, masterConfig->whichCtar, kDSPI_PcsToSck, srcClock_Hz,
+ masterConfig->ctarConfig.pcsToSckDelayInNanoSec);
+ DSPI_MasterSetDelayTimes(base, masterConfig->whichCtar, kDSPI_LastSckToPcs, srcClock_Hz,
+ masterConfig->ctarConfig.lastSckToPcsDelayInNanoSec);
+ DSPI_MasterSetDelayTimes(base, masterConfig->whichCtar, kDSPI_BetweenTransfer, srcClock_Hz,
+ masterConfig->ctarConfig.betweenTransferDelayInNanoSec);
+
+ DSPI_StartTransfer(base);
+}
+
+void DSPI_MasterGetDefaultConfig(dspi_master_config_t *masterConfig)
+{
+ masterConfig->whichCtar = kDSPI_Ctar0;
+ masterConfig->ctarConfig.baudRate = 500000;
+ masterConfig->ctarConfig.bitsPerFrame = 8;
+ masterConfig->ctarConfig.cpol = kDSPI_ClockPolarityActiveHigh;
+ masterConfig->ctarConfig.cpha = kDSPI_ClockPhaseFirstEdge;
+ masterConfig->ctarConfig.direction = kDSPI_MsbFirst;
+
+ masterConfig->ctarConfig.pcsToSckDelayInNanoSec = 1000;
+ masterConfig->ctarConfig.lastSckToPcsDelayInNanoSec = 1000;
+ masterConfig->ctarConfig.betweenTransferDelayInNanoSec = 1000;
+
+ masterConfig->whichPcs = kDSPI_Pcs0;
+ masterConfig->pcsActiveHighOrLow = kDSPI_PcsActiveLow;
+
+ masterConfig->enableContinuousSCK = false;
+ masterConfig->enableRxFifoOverWrite = false;
+ masterConfig->enableModifiedTimingFormat = false;
+ masterConfig->samplePoint = kDSPI_SckToSin0Clock;
+}
+
+void DSPI_SlaveInit(SPI_Type *base, const dspi_slave_config_t *slaveConfig)
+{
+ uint32_t temp = 0;
+
+ /* enable DSPI clock */
+ CLOCK_EnableClock(s_dspiClock[DSPI_GetInstance(base)]);
+
+ DSPI_Enable(base, true);
+ DSPI_StopTransfer(base);
+
+ DSPI_SetMasterSlaveMode(base, kDSPI_Slave);
+
+ temp = base->MCR & (~(SPI_MCR_CONT_SCKE_MASK | SPI_MCR_MTFE_MASK | SPI_MCR_ROOE_MASK | SPI_MCR_SMPL_PT_MASK |
+ SPI_MCR_DIS_TXF_MASK | SPI_MCR_DIS_RXF_MASK));
+
+ base->MCR = temp | SPI_MCR_CONT_SCKE(slaveConfig->enableContinuousSCK) |
+ SPI_MCR_MTFE(slaveConfig->enableModifiedTimingFormat) |
+ SPI_MCR_ROOE(slaveConfig->enableRxFifoOverWrite) | SPI_MCR_SMPL_PT(slaveConfig->samplePoint) |
+ SPI_MCR_DIS_TXF(false) | SPI_MCR_DIS_RXF(false);
+
+ DSPI_SetOnePcsPolarity(base, kDSPI_Pcs0, kDSPI_PcsActiveLow);
+
+ temp = base->CTAR[slaveConfig->whichCtar] &
+ ~(SPI_CTAR_FMSZ_MASK | SPI_CTAR_CPOL_MASK | SPI_CTAR_CPHA_MASK | SPI_CTAR_LSBFE_MASK);
+
+ base->CTAR[slaveConfig->whichCtar] = temp | SPI_CTAR_SLAVE_FMSZ(slaveConfig->ctarConfig.bitsPerFrame - 1) |
+ SPI_CTAR_SLAVE_CPOL(slaveConfig->ctarConfig.cpol) |
+ SPI_CTAR_SLAVE_CPHA(slaveConfig->ctarConfig.cpha);
+
+ DSPI_StartTransfer(base);
+}
+
+void DSPI_SlaveGetDefaultConfig(dspi_slave_config_t *slaveConfig)
+{
+ slaveConfig->whichCtar = kDSPI_Ctar0;
+ slaveConfig->ctarConfig.bitsPerFrame = 8;
+ slaveConfig->ctarConfig.cpol = kDSPI_ClockPolarityActiveHigh;
+ slaveConfig->ctarConfig.cpha = kDSPI_ClockPhaseFirstEdge;
+
+ slaveConfig->enableContinuousSCK = false;
+ slaveConfig->enableRxFifoOverWrite = false;
+ slaveConfig->enableModifiedTimingFormat = false;
+ slaveConfig->samplePoint = kDSPI_SckToSin0Clock;
+}
+
+void DSPI_Deinit(SPI_Type *base)
+{
+ DSPI_StopTransfer(base);
+ DSPI_Enable(base, false);
+
+ /* disable DSPI clock */
+ CLOCK_DisableClock(s_dspiClock[DSPI_GetInstance(base)]);
+}
+
+static void DSPI_SetOnePcsPolarity(SPI_Type *base, dspi_which_pcs_t pcs, dspi_pcs_polarity_config_t activeLowOrHigh)
+{
+ uint32_t temp;
+
+ temp = base->MCR;
+
+ if (activeLowOrHigh == kDSPI_PcsActiveLow)
+ {
+ temp |= SPI_MCR_PCSIS(pcs);
+ }
+ else
+ {
+ temp &= ~SPI_MCR_PCSIS(pcs);
+ }
+
+ base->MCR = temp;
+}
+
+uint32_t DSPI_MasterSetBaudRate(SPI_Type *base,
+ dspi_ctar_selection_t whichCtar,
+ uint32_t baudRate_Bps,
+ uint32_t srcClock_Hz)
+{
+ /* for master mode configuration, if slave mode detected, return 0*/
+ if (!DSPI_IsMaster(base))
+ {
+ return 0;
+ }
+ uint32_t temp;
+ uint32_t prescaler, bestPrescaler;
+ uint32_t scaler, bestScaler;
+ uint32_t dbr, bestDbr;
+ uint32_t realBaudrate, bestBaudrate;
+ uint32_t diff, min_diff;
+ uint32_t baudrate = baudRate_Bps;
+
+ /* find combination of prescaler and scaler resulting in baudrate closest to the requested value */
+ min_diff = 0xFFFFFFFFU;
+ bestPrescaler = 0;
+ bestScaler = 0;
+ bestDbr = 1;
+ bestBaudrate = 0; /* required to avoid compilation warning */
+
+ /* In all for loops, if min_diff = 0, the exit for loop*/
+ for (prescaler = 0; (prescaler < 4) && min_diff; prescaler++)
+ {
+ for (scaler = 0; (scaler < 16) && min_diff; scaler++)
+ {
+ for (dbr = 1; (dbr < 3) && min_diff; dbr++)
+ {
+ realBaudrate = ((srcClock_Hz * dbr) / (s_baudratePrescaler[prescaler] * (s_baudrateScaler[scaler])));
+
+ /* calculate the baud rate difference based on the conditional statement that states that the calculated
+ * baud rate must not exceed the desired baud rate.
+ */
+ if (baudrate >= realBaudrate)
+ {
+ diff = baudrate - realBaudrate;
+ if (min_diff > diff)
+ {
+ /* a better match found */
+ min_diff = diff;
+ bestPrescaler = prescaler;
+ bestScaler = scaler;
+ bestBaudrate = realBaudrate;
+ bestDbr = dbr;
+ }
+ }
+ }
+ }
+ }
+
+ /* write the best dbr, prescalar, and baud rate scalar to the CTAR */
+ temp = base->CTAR[whichCtar] & ~(SPI_CTAR_DBR_MASK | SPI_CTAR_PBR_MASK | SPI_CTAR_BR_MASK);
+
+ base->CTAR[whichCtar] = temp | ((bestDbr - 1) << SPI_CTAR_DBR_SHIFT) | (bestPrescaler << SPI_CTAR_PBR_SHIFT) |
+ (bestScaler << SPI_CTAR_BR_SHIFT);
+
+ /* return the actual calculated baud rate */
+ return bestBaudrate;
+}
+
+void DSPI_MasterSetDelayScaler(
+ SPI_Type *base, dspi_ctar_selection_t whichCtar, uint32_t prescaler, uint32_t scaler, dspi_delay_type_t whichDelay)
+{
+ /* these settings are only relevant in master mode */
+ if (DSPI_IsMaster(base))
+ {
+ switch (whichDelay)
+ {
+ case kDSPI_PcsToSck:
+ base->CTAR[whichCtar] = (base->CTAR[whichCtar] & (~SPI_CTAR_PCSSCK_MASK) & (~SPI_CTAR_CSSCK_MASK)) |
+ SPI_CTAR_PCSSCK(prescaler) | SPI_CTAR_CSSCK(scaler);
+ break;
+ case kDSPI_LastSckToPcs:
+ base->CTAR[whichCtar] = (base->CTAR[whichCtar] & (~SPI_CTAR_PASC_MASK) & (~SPI_CTAR_ASC_MASK)) |
+ SPI_CTAR_PASC(prescaler) | SPI_CTAR_ASC(scaler);
+ break;
+ case kDSPI_BetweenTransfer:
+ base->CTAR[whichCtar] = (base->CTAR[whichCtar] & (~SPI_CTAR_PDT_MASK) & (~SPI_CTAR_DT_MASK)) |
+ SPI_CTAR_PDT(prescaler) | SPI_CTAR_DT(scaler);
+ break;
+ default:
+ break;
+ }
+ }
+}
+
+uint32_t DSPI_MasterSetDelayTimes(SPI_Type *base,
+ dspi_ctar_selection_t whichCtar,
+ dspi_delay_type_t whichDelay,
+ uint32_t srcClock_Hz,
+ uint32_t delayTimeInNanoSec)
+{
+ /* for master mode configuration, if slave mode detected, return 0 */
+ if (!DSPI_IsMaster(base))
+ {
+ return 0;
+ }
+
+ uint32_t prescaler, bestPrescaler;
+ uint32_t scaler, bestScaler;
+ uint32_t realDelay, bestDelay;
+ uint32_t diff, min_diff;
+ uint32_t initialDelayNanoSec;
+
+ /* find combination of prescaler and scaler resulting in the delay closest to the
+ * requested value
+ */
+ min_diff = 0xFFFFFFFFU;
+ /* Initialize prescaler and scaler to their max values to generate the max delay */
+ bestPrescaler = 0x3;
+ bestScaler = 0xF;
+ bestDelay = (((1000000000U * 4) / srcClock_Hz) * s_delayPrescaler[bestPrescaler] * s_delayScaler[bestScaler]) / 4;
+
+ /* First calculate the initial, default delay */
+ initialDelayNanoSec = 1000000000U / srcClock_Hz * 2;
+
+ /* If the initial, default delay is already greater than the desired delay, then
+ * set the delays to their initial value (0) and return the delay. In other words,
+ * there is no way to decrease the delay value further.
+ */
+ if (initialDelayNanoSec >= delayTimeInNanoSec)
+ {
+ DSPI_MasterSetDelayScaler(base, whichCtar, 0, 0, whichDelay);
+ return initialDelayNanoSec;
+ }
+
+ /* In all for loops, if min_diff = 0, the exit for loop */
+ for (prescaler = 0; (prescaler < 4) && min_diff; prescaler++)
+ {
+ for (scaler = 0; (scaler < 16) && min_diff; scaler++)
+ {
+ realDelay = ((4000000000U / srcClock_Hz) * s_delayPrescaler[prescaler] * s_delayScaler[scaler]) / 4;
+
+ /* calculate the delay difference based on the conditional statement
+ * that states that the calculated delay must not be less then the desired delay
+ */
+ if (realDelay >= delayTimeInNanoSec)
+ {
+ diff = realDelay - delayTimeInNanoSec;
+ if (min_diff > diff)
+ {
+ /* a better match found */
+ min_diff = diff;
+ bestPrescaler = prescaler;
+ bestScaler = scaler;
+ bestDelay = realDelay;
+ }
+ }
+ }
+ }
+
+ /* write the best dbr, prescalar, and baud rate scalar to the CTAR */
+ DSPI_MasterSetDelayScaler(base, whichCtar, bestPrescaler, bestScaler, whichDelay);
+
+ /* return the actual calculated baud rate */
+ return bestDelay;
+}
+
+void DSPI_GetDefaultDataCommandConfig(dspi_command_data_config_t *command)
+{
+ command->isPcsContinuous = false;
+ command->whichCtar = kDSPI_Ctar0;
+ command->whichPcs = kDSPI_Pcs0;
+ command->isEndOfQueue = false;
+ command->clearTransferCount = false;
+}
+
+void DSPI_MasterWriteDataBlocking(SPI_Type *base, dspi_command_data_config_t *command, uint16_t data)
+{
+ /* First, clear Transmit Complete Flag (TCF) */
+ DSPI_ClearStatusFlags(base, kDSPI_TxCompleteFlag);
+
+ while (!(DSPI_GetStatusFlags(base) & kDSPI_TxFifoFillRequestFlag))
+ {
+ DSPI_ClearStatusFlags(base, kDSPI_TxFifoFillRequestFlag);
+ }
+
+ base->PUSHR = SPI_PUSHR_CONT(command->isPcsContinuous) | SPI_PUSHR_CTAS(command->whichCtar) |
+ SPI_PUSHR_PCS(command->whichPcs) | SPI_PUSHR_EOQ(command->isEndOfQueue) |
+ SPI_PUSHR_CTCNT(command->clearTransferCount) | SPI_PUSHR_TXDATA(data);
+ DSPI_ClearStatusFlags(base, kDSPI_TxFifoFillRequestFlag);
+
+ /* Wait till TCF sets */
+ while (!(DSPI_GetStatusFlags(base) & kDSPI_TxCompleteFlag))
+ {
+ }
+}
+
+void DSPI_MasterWriteCommandDataBlocking(SPI_Type *base, uint32_t data)
+{
+ /* First, clear Transmit Complete Flag (TCF) */
+ DSPI_ClearStatusFlags(base, kDSPI_TxCompleteFlag);
+
+ while (!(DSPI_GetStatusFlags(base) & kDSPI_TxFifoFillRequestFlag))
+ {
+ DSPI_ClearStatusFlags(base, kDSPI_TxFifoFillRequestFlag);
+ }
+
+ base->PUSHR = data;
+
+ DSPI_ClearStatusFlags(base, kDSPI_TxFifoFillRequestFlag);
+
+ /* Wait till TCF sets */
+ while (!(DSPI_GetStatusFlags(base) & kDSPI_TxCompleteFlag))
+ {
+ }
+}
+
+void DSPI_SlaveWriteDataBlocking(SPI_Type *base, uint32_t data)
+{
+ /* First, clear Transmit Complete Flag (TCF) */
+ DSPI_ClearStatusFlags(base, kDSPI_TxCompleteFlag);
+
+ while (!(DSPI_GetStatusFlags(base) & kDSPI_TxFifoFillRequestFlag))
+ {
+ DSPI_ClearStatusFlags(base, kDSPI_TxFifoFillRequestFlag);
+ }
+
+ base->PUSHR_SLAVE = data;
+
+ DSPI_ClearStatusFlags(base, kDSPI_TxFifoFillRequestFlag);
+
+ /* Wait till TCF sets */
+ while (!(DSPI_GetStatusFlags(base) & kDSPI_TxCompleteFlag))
+ {
+ }
+}
+
+void DSPI_EnableInterrupts(SPI_Type *base, uint32_t mask)
+{
+ if (mask & SPI_RSER_TFFF_RE_MASK)
+ {
+ base->RSER &= ~SPI_RSER_TFFF_DIRS_MASK;
+ }
+ if (mask & SPI_RSER_RFDF_RE_MASK)
+ {
+ base->RSER &= ~SPI_RSER_RFDF_DIRS_MASK;
+ }
+ base->RSER |= mask;
+}
+
+/*Transactional APIs -- Master*/
+
+void DSPI_MasterTransferCreateHandle(SPI_Type *base,
+ dspi_master_handle_t *handle,
+ dspi_master_transfer_callback_t callback,
+ void *userData)
+{
+ assert(handle);
+
+ /* Zero the handle. */
+ memset(handle, 0, sizeof(*handle));
+
+ g_dspiHandle[DSPI_GetInstance(base)] = handle;
+
+ handle->callback = callback;
+ handle->userData = userData;
+}
+
+status_t DSPI_MasterTransferBlocking(SPI_Type *base, dspi_transfer_t *transfer)
+{
+ assert(transfer);
+
+ uint16_t wordToSend = 0;
+ uint16_t wordReceived = 0;
+ uint8_t dummyData = DSPI_DUMMY_DATA;
+ uint8_t bitsPerFrame;
+
+ uint32_t command;
+ uint32_t lastCommand;
+
+ uint8_t *txData;
+ uint8_t *rxData;
+ uint32_t remainingSendByteCount;
+ uint32_t remainingReceiveByteCount;
+
+ uint32_t fifoSize;
+ dspi_command_data_config_t commandStruct;
+
+ /* If the transfer count is zero, then return immediately.*/
+ if (transfer->dataSize == 0)
+ {
+ return kStatus_InvalidArgument;
+ }
+
+ DSPI_StopTransfer(base);
+ DSPI_DisableInterrupts(base, kDSPI_AllInterruptEnable);
+ DSPI_FlushFifo(base, true, true);
+ DSPI_ClearStatusFlags(base, kDSPI_AllStatusFlag);
+
+ /*Calculate the command and lastCommand*/
+ commandStruct.whichPcs =
+ (dspi_which_pcs_t)(1U << ((transfer->configFlags & DSPI_MASTER_PCS_MASK) >> DSPI_MASTER_PCS_SHIFT));
+ commandStruct.isEndOfQueue = false;
+ commandStruct.clearTransferCount = false;
+ commandStruct.whichCtar =
+ (dspi_ctar_selection_t)((transfer->configFlags & DSPI_MASTER_CTAR_MASK) >> DSPI_MASTER_CTAR_SHIFT);
+ commandStruct.isPcsContinuous = (bool)(transfer->configFlags & kDSPI_MasterPcsContinuous);
+
+ command = DSPI_MasterGetFormattedCommand(&(commandStruct));
+
+ commandStruct.isEndOfQueue = true;
+ commandStruct.isPcsContinuous = (bool)(transfer->configFlags & kDSPI_MasterActiveAfterTransfer);
+ lastCommand = DSPI_MasterGetFormattedCommand(&(commandStruct));
+
+ /*Calculate the bitsPerFrame*/
+ bitsPerFrame = ((base->CTAR[commandStruct.whichCtar] & SPI_CTAR_FMSZ_MASK) >> SPI_CTAR_FMSZ_SHIFT) + 1;
+
+ txData = transfer->txData;
+ rxData = transfer->rxData;
+ remainingSendByteCount = transfer->dataSize;
+ remainingReceiveByteCount = transfer->dataSize;
+
+ if ((base->MCR & SPI_MCR_DIS_RXF_MASK) || (base->MCR & SPI_MCR_DIS_TXF_MASK))
+ {
+ fifoSize = 1;
+ }
+ else
+ {
+ fifoSize = FSL_FEATURE_DSPI_FIFO_SIZEn(base);
+ }
+
+ DSPI_StartTransfer(base);
+
+ if (bitsPerFrame <= 8)
+ {
+ while (remainingSendByteCount > 0)
+ {
+ if (remainingSendByteCount == 1)
+ {
+ while ((remainingReceiveByteCount - remainingSendByteCount) >= fifoSize)
+ {
+ if (DSPI_GetStatusFlags(base) & kDSPI_RxFifoDrainRequestFlag)
+ {
+ if (rxData != NULL)
+ {
+ *(rxData) = DSPI_ReadData(base);
+ rxData++;
+ }
+ else
+ {
+ DSPI_ReadData(base);
+ }
+ remainingReceiveByteCount--;
+
+ DSPI_ClearStatusFlags(base, kDSPI_RxFifoDrainRequestFlag);
+ }
+ }
+
+ while (!(DSPI_GetStatusFlags(base) & kDSPI_TxFifoFillRequestFlag))
+ {
+ DSPI_ClearStatusFlags(base, kDSPI_TxFifoFillRequestFlag);
+ }
+
+ if (txData != NULL)
+ {
+ base->PUSHR = (*txData) | (lastCommand);
+ txData++;
+ }
+ else
+ {
+ base->PUSHR = (lastCommand) | (dummyData);
+ }
+ DSPI_ClearStatusFlags(base, kDSPI_TxFifoFillRequestFlag);
+ remainingSendByteCount--;
+
+ while (remainingReceiveByteCount > 0)
+ {
+ if (DSPI_GetStatusFlags(base) & kDSPI_RxFifoDrainRequestFlag)
+ {
+ if (rxData != NULL)
+ {
+ /* Read data from POPR*/
+ *(rxData) = DSPI_ReadData(base);
+ rxData++;
+ }
+ else
+ {
+ DSPI_ReadData(base);
+ }
+ remainingReceiveByteCount--;
+
+ DSPI_ClearStatusFlags(base, kDSPI_RxFifoDrainRequestFlag);
+ }
+ }
+ }
+ else
+ {
+ /*Wait until Tx Fifo is not full*/
+ while (!(DSPI_GetStatusFlags(base) & kDSPI_TxFifoFillRequestFlag))
+ {
+ DSPI_ClearStatusFlags(base, kDSPI_TxFifoFillRequestFlag);
+ }
+ if (txData != NULL)
+ {
+ base->PUSHR = command | (uint16_t)(*txData);
+ txData++;
+ }
+ else
+ {
+ base->PUSHR = command | dummyData;
+ }
+ remainingSendByteCount--;
+
+ DSPI_ClearStatusFlags(base, kDSPI_TxFifoFillRequestFlag);
+
+ if (DSPI_GetStatusFlags(base) & kDSPI_RxFifoDrainRequestFlag)
+ {
+ if (rxData != NULL)
+ {
+ *(rxData) = DSPI_ReadData(base);
+ rxData++;
+ }
+ else
+ {
+ DSPI_ReadData(base);
+ }
+ remainingReceiveByteCount--;
+
+ DSPI_ClearStatusFlags(base, kDSPI_RxFifoDrainRequestFlag);
+ }
+ }
+ }
+ }
+ else
+ {
+ while (remainingSendByteCount > 0)
+ {
+ if (remainingSendByteCount <= 2)
+ {
+ while (((remainingReceiveByteCount - remainingSendByteCount) / 2) >= fifoSize)
+ {
+ if (DSPI_GetStatusFlags(base) & kDSPI_RxFifoDrainRequestFlag)
+ {
+ wordReceived = DSPI_ReadData(base);
+
+ if (rxData != NULL)
+ {
+ *rxData = wordReceived;
+ ++rxData;
+ *rxData = wordReceived >> 8;
+ ++rxData;
+ }
+ remainingReceiveByteCount -= 2;
+
+ DSPI_ClearStatusFlags(base, kDSPI_RxFifoDrainRequestFlag);
+ }
+ }
+
+ while (!(DSPI_GetStatusFlags(base) & kDSPI_TxFifoFillRequestFlag))
+ {
+ DSPI_ClearStatusFlags(base, kDSPI_TxFifoFillRequestFlag);
+ }
+
+ if (txData != NULL)
+ {
+ wordToSend = *(txData);
+ ++txData;
+
+ if (remainingSendByteCount > 1)
+ {
+ wordToSend |= (unsigned)(*(txData)) << 8U;
+ ++txData;
+ }
+ }
+ else
+ {
+ wordToSend = dummyData;
+ }
+
+ base->PUSHR = lastCommand | wordToSend;
+
+ DSPI_ClearStatusFlags(base, kDSPI_TxFifoFillRequestFlag);
+ remainingSendByteCount = 0;
+
+ while (remainingReceiveByteCount > 0)
+ {
+ if (DSPI_GetStatusFlags(base) & kDSPI_RxFifoDrainRequestFlag)
+ {
+ wordReceived = DSPI_ReadData(base);
+
+ if (remainingReceiveByteCount != 1)
+ {
+ if (rxData != NULL)
+ {
+ *(rxData) = wordReceived;
+ ++rxData;
+ *(rxData) = wordReceived >> 8;
+ ++rxData;
+ }
+ remainingReceiveByteCount -= 2;
+ }
+ else
+ {
+ if (rxData != NULL)
+ {
+ *(rxData) = wordReceived;
+ ++rxData;
+ }
+ remainingReceiveByteCount--;
+ }
+ DSPI_ClearStatusFlags(base, kDSPI_RxFifoDrainRequestFlag);
+ }
+ }
+ }
+ else
+ {
+ /*Wait until Tx Fifo is not full*/
+ while (!(DSPI_GetStatusFlags(base) & kDSPI_TxFifoFillRequestFlag))
+ {
+ DSPI_ClearStatusFlags(base, kDSPI_TxFifoFillRequestFlag);
+ }
+
+ if (txData != NULL)
+ {
+ wordToSend = *(txData);
+ ++txData;
+ wordToSend |= (unsigned)(*(txData)) << 8U;
+ ++txData;
+ }
+ else
+ {
+ wordToSend = dummyData;
+ }
+ base->PUSHR = command | wordToSend;
+ remainingSendByteCount -= 2;
+
+ DSPI_ClearStatusFlags(base, kDSPI_TxFifoFillRequestFlag);
+
+ if (DSPI_GetStatusFlags(base) & kDSPI_RxFifoDrainRequestFlag)
+ {
+ wordReceived = DSPI_ReadData(base);
+
+ if (rxData != NULL)
+ {
+ *rxData = wordReceived;
+ ++rxData;
+ *rxData = wordReceived >> 8;
+ ++rxData;
+ }
+ remainingReceiveByteCount -= 2;
+
+ DSPI_ClearStatusFlags(base, kDSPI_RxFifoDrainRequestFlag);
+ }
+ }
+ }
+ }
+
+ return kStatus_Success;
+}
+
+static void DSPI_MasterTransferPrepare(SPI_Type *base, dspi_master_handle_t *handle, dspi_transfer_t *transfer)
+{
+ dspi_command_data_config_t commandStruct;
+
+ DSPI_StopTransfer(base);
+ DSPI_FlushFifo(base, true, true);
+ DSPI_ClearStatusFlags(base, kDSPI_AllStatusFlag);
+
+ commandStruct.whichPcs =
+ (dspi_which_pcs_t)(1U << ((transfer->configFlags & DSPI_MASTER_PCS_MASK) >> DSPI_MASTER_PCS_SHIFT));
+ commandStruct.isEndOfQueue = false;
+ commandStruct.clearTransferCount = false;
+ commandStruct.whichCtar =
+ (dspi_ctar_selection_t)((transfer->configFlags & DSPI_MASTER_CTAR_MASK) >> DSPI_MASTER_CTAR_SHIFT);
+ commandStruct.isPcsContinuous = (bool)(transfer->configFlags & kDSPI_MasterPcsContinuous);
+ handle->command = DSPI_MasterGetFormattedCommand(&(commandStruct));
+
+ commandStruct.isEndOfQueue = true;
+ commandStruct.isPcsContinuous = (bool)(transfer->configFlags & kDSPI_MasterActiveAfterTransfer);
+ handle->lastCommand = DSPI_MasterGetFormattedCommand(&(commandStruct));
+
+ handle->bitsPerFrame = ((base->CTAR[commandStruct.whichCtar] & SPI_CTAR_FMSZ_MASK) >> SPI_CTAR_FMSZ_SHIFT) + 1;
+
+ if ((base->MCR & SPI_MCR_DIS_RXF_MASK) || (base->MCR & SPI_MCR_DIS_TXF_MASK))
+ {
+ handle->fifoSize = 1;
+ }
+ else
+ {
+ handle->fifoSize = FSL_FEATURE_DSPI_FIFO_SIZEn(base);
+ }
+ handle->txData = transfer->txData;
+ handle->rxData = transfer->rxData;
+ handle->remainingSendByteCount = transfer->dataSize;
+ handle->remainingReceiveByteCount = transfer->dataSize;
+ handle->totalByteCount = transfer->dataSize;
+}
+
+status_t DSPI_MasterTransferNonBlocking(SPI_Type *base, dspi_master_handle_t *handle, dspi_transfer_t *transfer)
+{
+ assert(handle && transfer);
+
+ /* If the transfer count is zero, then return immediately.*/
+ if (transfer->dataSize == 0)
+ {
+ return kStatus_InvalidArgument;
+ }
+
+ /* Check that we're not busy.*/
+ if (handle->state == kDSPI_Busy)
+ {
+ return kStatus_DSPI_Busy;
+ }
+
+ handle->state = kDSPI_Busy;
+
+ DSPI_MasterTransferPrepare(base, handle, transfer);
+ DSPI_StartTransfer(base);
+
+ /* Enable the NVIC for DSPI peripheral. */
+ EnableIRQ(s_dspiIRQ[DSPI_GetInstance(base)]);
+
+ DSPI_MasterTransferFillUpTxFifo(base, handle);
+
+ /* RX FIFO Drain request: RFDF_RE to enable RFDF interrupt
+ * Since SPI is a synchronous interface, we only need to enable the RX interrupt.
+ * The IRQ handler will get the status of RX and TX interrupt flags.
+ */
+ s_dspiMasterIsr = DSPI_MasterTransferHandleIRQ;
+
+ DSPI_EnableInterrupts(base, kDSPI_RxFifoDrainRequestInterruptEnable);
+
+ return kStatus_Success;
+}
+
+status_t DSPI_MasterTransferGetCount(SPI_Type *base, dspi_master_handle_t *handle, size_t *count)
+{
+ assert(handle);
+
+ if (!count)
+ {
+ return kStatus_InvalidArgument;
+ }
+
+ /* Catch when there is not an active transfer. */
+ if (handle->state != kDSPI_Busy)
+ {
+ *count = 0;
+ return kStatus_NoTransferInProgress;
+ }
+
+ *count = handle->totalByteCount - handle->remainingReceiveByteCount;
+ return kStatus_Success;
+}
+
+static void DSPI_MasterTransferComplete(SPI_Type *base, dspi_master_handle_t *handle)
+{
+ /* Disable interrupt requests*/
+ DSPI_DisableInterrupts(base, kDSPI_RxFifoDrainRequestInterruptEnable | kDSPI_TxFifoFillRequestInterruptEnable);
+
+ status_t status = 0;
+ if (handle->state == kDSPI_Error)
+ {
+ status = kStatus_DSPI_Error;
+ }
+ else
+ {
+ status = kStatus_Success;
+ }
+
+ if (handle->callback)
+ {
+ handle->callback(base, handle, status, handle->userData);
+ }
+
+ /* The transfer is complete.*/
+ handle->state = kDSPI_Idle;
+}
+
+static void DSPI_MasterTransferFillUpTxFifo(SPI_Type *base, dspi_master_handle_t *handle)
+{
+ uint16_t wordToSend = 0;
+ uint8_t dummyData = DSPI_DUMMY_DATA;
+
+ /* If bits/frame is greater than one byte */
+ if (handle->bitsPerFrame > 8)
+ {
+ /* Fill the fifo until it is full or until the send word count is 0 or until the difference
+ * between the remainingReceiveByteCount and remainingSendByteCount equals the FIFO depth.
+ * The reason for checking the difference is to ensure we only send as much as the
+ * RX FIFO can receive.
+ * For this case where bitsPerFrame > 8, each entry in the FIFO contains 2 bytes of the
+ * send data, hence the difference between the remainingReceiveByteCount and
+ * remainingSendByteCount must be divided by 2 to convert this difference into a
+ * 16-bit (2 byte) value.
+ */
+ while ((DSPI_GetStatusFlags(base) & kDSPI_TxFifoFillRequestFlag) &&
+ ((handle->remainingReceiveByteCount - handle->remainingSendByteCount) / 2 < handle->fifoSize))
+ {
+ if (handle->remainingSendByteCount <= 2)
+ {
+ if (handle->txData)
+ {
+ if (handle->remainingSendByteCount == 1)
+ {
+ wordToSend = *(handle->txData);
+ }
+ else
+ {
+ wordToSend = *(handle->txData);
+ ++handle->txData; /* increment to next data byte */
+ wordToSend |= (unsigned)(*(handle->txData)) << 8U;
+ }
+ }
+ else
+ {
+ wordToSend = dummyData;
+ }
+ handle->remainingSendByteCount = 0;
+ base->PUSHR = handle->lastCommand | wordToSend;
+ }
+ /* For all words except the last word */
+ else
+ {
+ if (handle->txData)
+ {
+ wordToSend = *(handle->txData);
+ ++handle->txData; /* increment to next data byte */
+ wordToSend |= (unsigned)(*(handle->txData)) << 8U;
+ ++handle->txData; /* increment to next data byte */
+ }
+ else
+ {
+ wordToSend = dummyData;
+ }
+ handle->remainingSendByteCount -= 2; /* decrement remainingSendByteCount by 2 */
+ base->PUSHR = handle->command | wordToSend;
+ }
+
+ /* Try to clear the TFFF; if the TX FIFO is full this will clear */
+ DSPI_ClearStatusFlags(base, kDSPI_TxFifoFillRequestFlag);
+
+ /* exit loop if send count is zero, else update local variables for next loop */
+ if (handle->remainingSendByteCount == 0)
+ {
+ break;
+ }
+ } /* End of TX FIFO fill while loop */
+ }
+ /* Optimized for bits/frame less than or equal to one byte. */
+ else
+ {
+ /* Fill the fifo until it is full or until the send word count is 0 or until the difference
+ * between the remainingReceiveByteCount and remainingSendByteCount equals the FIFO depth.
+ * The reason for checking the difference is to ensure we only send as much as the
+ * RX FIFO can receive.
+ */
+ while ((DSPI_GetStatusFlags(base) & kDSPI_TxFifoFillRequestFlag) &&
+ ((handle->remainingReceiveByteCount - handle->remainingSendByteCount) < handle->fifoSize))
+ {
+ if (handle->txData)
+ {
+ wordToSend = *(handle->txData);
+ ++handle->txData;
+ }
+ else
+ {
+ wordToSend = dummyData;
+ }
+
+ if (handle->remainingSendByteCount == 1)
+ {
+ base->PUSHR = handle->lastCommand | wordToSend;
+ }
+ else
+ {
+ base->PUSHR = handle->command | wordToSend;
+ }
+
+ /* Try to clear the TFFF; if the TX FIFO is full this will clear */
+ DSPI_ClearStatusFlags(base, kDSPI_TxFifoFillRequestFlag);
+
+ --handle->remainingSendByteCount;
+
+ /* exit loop if send count is zero, else update local variables for next loop */
+ if (handle->remainingSendByteCount == 0)
+ {
+ break;
+ }
+ }
+ }
+}
+
+void DSPI_MasterTransferAbort(SPI_Type *base, dspi_master_handle_t *handle)
+{
+ DSPI_StopTransfer(base);
+
+ /* Disable interrupt requests*/
+ DSPI_DisableInterrupts(base, kDSPI_RxFifoDrainRequestInterruptEnable | kDSPI_TxFifoFillRequestInterruptEnable);
+
+ handle->state = kDSPI_Idle;
+}
+
+void DSPI_MasterTransferHandleIRQ(SPI_Type *base, dspi_master_handle_t *handle)
+{
+ /* RECEIVE IRQ handler: Check read buffer only if there are remaining bytes to read. */
+ if (handle->remainingReceiveByteCount)
+ {
+ /* Check read buffer.*/
+ uint16_t wordReceived; /* Maximum supported data bit length in master mode is 16-bits */
+
+ /* If bits/frame is greater than one byte */
+ if (handle->bitsPerFrame > 8)
+ {
+ while (DSPI_GetStatusFlags(base) & kDSPI_RxFifoDrainRequestFlag)
+ {
+ wordReceived = DSPI_ReadData(base);
+ /* clear the rx fifo drain request, needed for non-DMA applications as this flag
+ * will remain set even if the rx fifo is empty. By manually clearing this flag, it
+ * either remain clear if no more data is in the fifo, or it will set if there is
+ * more data in the fifo.
+ */
+ DSPI_ClearStatusFlags(base, kDSPI_RxFifoDrainRequestFlag);
+
+ /* Store read bytes into rx buffer only if a buffer pointer was provided */
+ if (handle->rxData)
+ {
+ /* For the last word received, if there is an extra byte due to the odd transfer
+ * byte count, only save the the last byte and discard the upper byte
+ */
+ if (handle->remainingReceiveByteCount == 1)
+ {
+ *handle->rxData = wordReceived; /* Write first data byte */
+ --handle->remainingReceiveByteCount;
+ }
+ else
+ {
+ *handle->rxData = wordReceived; /* Write first data byte */
+ ++handle->rxData; /* increment to next data byte */
+ *handle->rxData = wordReceived >> 8; /* Write second data byte */
+ ++handle->rxData; /* increment to next data byte */
+ handle->remainingReceiveByteCount -= 2;
+ }
+ }
+ else
+ {
+ if (handle->remainingReceiveByteCount == 1)
+ {
+ --handle->remainingReceiveByteCount;
+ }
+ else
+ {
+ handle->remainingReceiveByteCount -= 2;
+ }
+ }
+ if (handle->remainingReceiveByteCount == 0)
+ {
+ break;
+ }
+ } /* End of RX FIFO drain while loop */
+ }
+ /* Optimized for bits/frame less than or equal to one byte. */
+ else
+ {
+ while (DSPI_GetStatusFlags(base) & kDSPI_RxFifoDrainRequestFlag)
+ {
+ wordReceived = DSPI_ReadData(base);
+ /* clear the rx fifo drain request, needed for non-DMA applications as this flag
+ * will remain set even if the rx fifo is empty. By manually clearing this flag, it
+ * either remain clear if no more data is in the fifo, or it will set if there is
+ * more data in the fifo.
+ */
+ DSPI_ClearStatusFlags(base, kDSPI_RxFifoDrainRequestFlag);
+
+ /* Store read bytes into rx buffer only if a buffer pointer was provided */
+ if (handle->rxData)
+ {
+ *handle->rxData = wordReceived;
+ ++handle->rxData;
+ }
+
+ --handle->remainingReceiveByteCount;
+
+ if (handle->remainingReceiveByteCount == 0)
+ {
+ break;
+ }
+ } /* End of RX FIFO drain while loop */
+ }
+ }
+
+ /* Check write buffer. We always have to send a word in order to keep the transfer
+ * moving. So if the caller didn't provide a send buffer, we just send a zero.
+ */
+ if (handle->remainingSendByteCount)
+ {
+ DSPI_MasterTransferFillUpTxFifo(base, handle);
+ }
+
+ /* Check if we're done with this transfer.*/
+ if ((handle->remainingSendByteCount == 0) && (handle->remainingReceiveByteCount == 0))
+ {
+ /* Complete the transfer and disable the interrupts */
+ DSPI_MasterTransferComplete(base, handle);
+ }
+}
+
+/*Transactional APIs -- Slave*/
+void DSPI_SlaveTransferCreateHandle(SPI_Type *base,
+ dspi_slave_handle_t *handle,
+ dspi_slave_transfer_callback_t callback,
+ void *userData)
+{
+ assert(handle);
+
+ /* Zero the handle. */
+ memset(handle, 0, sizeof(*handle));
+
+ g_dspiHandle[DSPI_GetInstance(base)] = handle;
+
+ handle->callback = callback;
+ handle->userData = userData;
+}
+
+status_t DSPI_SlaveTransferNonBlocking(SPI_Type *base, dspi_slave_handle_t *handle, dspi_transfer_t *transfer)
+{
+ assert(handle && transfer);
+
+ /* If receive length is zero */
+ if (transfer->dataSize == 0)
+ {
+ return kStatus_InvalidArgument;
+ }
+
+ /* If both send buffer and receive buffer is null */
+ if ((!(transfer->txData)) && (!(transfer->rxData)))
+ {
+ return kStatus_InvalidArgument;
+ }
+
+ /* Check that we're not busy.*/
+ if (handle->state == kDSPI_Busy)
+ {
+ return kStatus_DSPI_Busy;
+ }
+ handle->state = kDSPI_Busy;
+
+ /* Enable the NVIC for DSPI peripheral. */
+ EnableIRQ(s_dspiIRQ[DSPI_GetInstance(base)]);
+
+ /* Store transfer information */
+ handle->txData = transfer->txData;
+ handle->rxData = transfer->rxData;
+ handle->remainingSendByteCount = transfer->dataSize;
+ handle->remainingReceiveByteCount = transfer->dataSize;
+ handle->totalByteCount = transfer->dataSize;
+
+ handle->errorCount = 0;
+
+ uint8_t whichCtar = (transfer->configFlags & DSPI_SLAVE_CTAR_MASK) >> DSPI_SLAVE_CTAR_SHIFT;
+ handle->bitsPerFrame =
+ (((base->CTAR_SLAVE[whichCtar]) & SPI_CTAR_SLAVE_FMSZ_MASK) >> SPI_CTAR_SLAVE_FMSZ_SHIFT) + 1;
+
+ DSPI_StopTransfer(base);
+
+ DSPI_FlushFifo(base, true, true);
+ DSPI_ClearStatusFlags(base, kDSPI_AllStatusFlag);
+
+ DSPI_StartTransfer(base);
+
+ /* Prepare data to transmit */
+ DSPI_SlaveTransferFillUpTxFifo(base, handle);
+
+ s_dspiSlaveIsr = DSPI_SlaveTransferHandleIRQ;
+
+ /* Enable RX FIFO drain request, the slave only use this interrupt */
+ DSPI_EnableInterrupts(base, kDSPI_RxFifoDrainRequestInterruptEnable);
+
+ if (handle->rxData)
+ {
+ /* RX FIFO overflow request enable */
+ DSPI_EnableInterrupts(base, kDSPI_RxFifoOverflowInterruptEnable);
+ }
+ if (handle->txData)
+ {
+ /* TX FIFO underflow request enable */
+ DSPI_EnableInterrupts(base, kDSPI_TxFifoUnderflowInterruptEnable);
+ }
+
+ return kStatus_Success;
+}
+
+status_t DSPI_SlaveTransferGetCount(SPI_Type *base, dspi_slave_handle_t *handle, size_t *count)
+{
+ assert(handle);
+
+ if (!count)
+ {
+ return kStatus_InvalidArgument;
+ }
+
+ /* Catch when there is not an active transfer. */
+ if (handle->state != kDSPI_Busy)
+ {
+ *count = 0;
+ return kStatus_NoTransferInProgress;
+ }
+
+ *count = handle->totalByteCount - handle->remainingReceiveByteCount;
+ return kStatus_Success;
+}
+
+static void DSPI_SlaveTransferFillUpTxFifo(SPI_Type *base, dspi_slave_handle_t *handle)
+{
+ uint16_t transmitData = 0;
+ uint8_t dummyPattern = DSPI_DUMMY_DATA;
+
+ /* Service the transmitter, if transmit buffer provided, transmit the data,
+ * else transmit dummy pattern
+ */
+ while (DSPI_GetStatusFlags(base) & kDSPI_TxFifoFillRequestFlag)
+ {
+ /* Transmit data */
+ if (handle->remainingSendByteCount > 0)
+ {
+ /* Have data to transmit, update the transmit data and push to FIFO */
+ if (handle->bitsPerFrame <= 8)
+ {
+ /* bits/frame is 1 byte */
+ if (handle->txData)
+ {
+ /* Update transmit data and transmit pointer */
+ transmitData = *handle->txData;
+ handle->txData++;
+ }
+ else
+ {
+ transmitData = dummyPattern;
+ }
+
+ /* Decrease remaining dataSize */
+ --handle->remainingSendByteCount;
+ }
+ /* bits/frame is 2 bytes */
+ else
+ {
+ /* With multibytes per frame transmission, the transmit frame contains data from
+ * transmit buffer until sent dataSize matches user request. Other bytes will set to
+ * dummy pattern value.
+ */
+ if (handle->txData)
+ {
+ /* Update first byte of transmit data and transmit pointer */
+ transmitData = *handle->txData;
+ handle->txData++;
+
+ if (handle->remainingSendByteCount == 1)
+ {
+ /* Decrease remaining dataSize */
+ --handle->remainingSendByteCount;
+ /* Update second byte of transmit data to second byte of dummy pattern */
+ transmitData = transmitData | (uint16_t)(((uint16_t)dummyPattern) << 8);
+ }
+ else
+ {
+ /* Update second byte of transmit data and transmit pointer */
+ transmitData = transmitData | (uint16_t)((uint16_t)(*handle->txData) << 8);
+ handle->txData++;
+ handle->remainingSendByteCount -= 2;
+ }
+ }
+ else
+ {
+ if (handle->remainingSendByteCount == 1)
+ {
+ --handle->remainingSendByteCount;
+ }
+ else
+ {
+ handle->remainingSendByteCount -= 2;
+ }
+ transmitData = (uint16_t)((uint16_t)(dummyPattern) << 8) | dummyPattern;
+ }
+ }
+ }
+ else
+ {
+ break;
+ }
+
+ /* Write the data to the DSPI data register */
+ base->PUSHR_SLAVE = transmitData;
+
+ /* Try to clear TFFF by writing a one to it; it will not clear if TX FIFO not full */
+ DSPI_ClearStatusFlags(base, kDSPI_TxFifoFillRequestFlag);
+ }
+}
+
+static void DSPI_SlaveTransferComplete(SPI_Type *base, dspi_slave_handle_t *handle)
+{
+ /* Disable interrupt requests */
+ DSPI_DisableInterrupts(base, kDSPI_TxFifoUnderflowInterruptEnable | kDSPI_TxFifoFillRequestInterruptEnable |
+ kDSPI_RxFifoOverflowInterruptEnable | kDSPI_RxFifoDrainRequestInterruptEnable);
+
+ /* The transfer is complete. */
+ handle->txData = NULL;
+ handle->rxData = NULL;
+ handle->remainingReceiveByteCount = 0;
+ handle->remainingSendByteCount = 0;
+
+ status_t status = 0;
+ if (handle->state == kDSPI_Error)
+ {
+ status = kStatus_DSPI_Error;
+ }
+ else
+ {
+ status = kStatus_Success;
+ }
+
+ if (handle->callback)
+ {
+ handle->callback(base, handle, status, handle->userData);
+ }
+
+ handle->state = kDSPI_Idle;
+}
+
+void DSPI_SlaveTransferAbort(SPI_Type *base, dspi_slave_handle_t *handle)
+{
+ DSPI_StopTransfer(base);
+
+ /* Disable interrupt requests */
+ DSPI_DisableInterrupts(base, kDSPI_TxFifoUnderflowInterruptEnable | kDSPI_TxFifoFillRequestInterruptEnable |
+ kDSPI_RxFifoOverflowInterruptEnable | kDSPI_RxFifoDrainRequestInterruptEnable);
+
+ handle->state = kDSPI_Idle;
+ handle->remainingSendByteCount = 0;
+ handle->remainingReceiveByteCount = 0;
+}
+
+void DSPI_SlaveTransferHandleIRQ(SPI_Type *base, dspi_slave_handle_t *handle)
+{
+ uint8_t dummyPattern = DSPI_DUMMY_DATA;
+ uint32_t dataReceived;
+ uint32_t dataSend = 0;
+
+ /* Because SPI protocol is synchronous, the number of bytes that that slave received from the
+ * master is the actual number of bytes that the slave transmitted to the master. So we only
+ * monitor the received dataSize to know when the transfer is complete.
+ */
+ if (handle->remainingReceiveByteCount > 0)
+ {
+ while (DSPI_GetStatusFlags(base) & kDSPI_RxFifoDrainRequestFlag)
+ {
+ /* Have received data in the buffer. */
+ dataReceived = base->POPR;
+ /*Clear the rx fifo drain request, needed for non-DMA applications as this flag
+ * will remain set even if the rx fifo is empty. By manually clearing this flag, it
+ * either remain clear if no more data is in the fifo, or it will set if there is
+ * more data in the fifo.
+ */
+ DSPI_ClearStatusFlags(base, kDSPI_RxFifoDrainRequestFlag);
+
+ /* If bits/frame is one byte */
+ if (handle->bitsPerFrame <= 8)
+ {
+ if (handle->rxData)
+ {
+ /* Receive buffer is not null, store data into it */
+ *handle->rxData = dataReceived;
+ ++handle->rxData;
+ }
+ /* Descrease remaining receive byte count */
+ --handle->remainingReceiveByteCount;
+
+ if (handle->remainingSendByteCount > 0)
+ {
+ if (handle->txData)
+ {
+ dataSend = *handle->txData;
+ ++handle->txData;
+ }
+ else
+ {
+ dataSend = dummyPattern;
+ }
+
+ --handle->remainingSendByteCount;
+ /* Write the data to the DSPI data register */
+ base->PUSHR_SLAVE = dataSend;
+ }
+ }
+ else /* If bits/frame is 2 bytes */
+ {
+ /* With multibytes frame receiving, we only receive till the received dataSize
+ * matches user request. Other bytes will be ignored.
+ */
+ if (handle->rxData)
+ {
+ /* Receive buffer is not null, store first byte into it */
+ *handle->rxData = dataReceived;
+ ++handle->rxData;
+
+ if (handle->remainingReceiveByteCount == 1)
+ {
+ /* Decrease remaining receive byte count */
+ --handle->remainingReceiveByteCount;
+ }
+ else
+ {
+ /* Receive buffer is not null, store second byte into it */
+ *handle->rxData = dataReceived >> 8;
+ ++handle->rxData;
+ handle->remainingReceiveByteCount -= 2;
+ }
+ }
+ /* If no handle->rxData*/
+ else
+ {
+ if (handle->remainingReceiveByteCount == 1)
+ {
+ /* Decrease remaining receive byte count */
+ --handle->remainingReceiveByteCount;
+ }
+ else
+ {
+ handle->remainingReceiveByteCount -= 2;
+ }
+ }
+
+ if (handle->remainingSendByteCount > 0)
+ {
+ if (handle->txData)
+ {
+ dataSend = *handle->txData;
+ ++handle->txData;
+
+ if (handle->remainingSendByteCount == 1)
+ {
+ --handle->remainingSendByteCount;
+ dataSend |= (uint16_t)((uint16_t)(dummyPattern) << 8);
+ }
+ else
+ {
+ dataSend |= (uint32_t)(*handle->txData) << 8;
+ ++handle->txData;
+ handle->remainingSendByteCount -= 2;
+ }
+ }
+ /* If no handle->txData*/
+ else
+ {
+ if (handle->remainingSendByteCount == 1)
+ {
+ --handle->remainingSendByteCount;
+ }
+ else
+ {
+ handle->remainingSendByteCount -= 2;
+ }
+ dataSend = (uint16_t)((uint16_t)(dummyPattern) << 8) | dummyPattern;
+ }
+ /* Write the data to the DSPI data register */
+ base->PUSHR_SLAVE = dataSend;
+ }
+ }
+ /* Try to clear TFFF by writing a one to it; it will not clear if TX FIFO not full */
+ DSPI_ClearStatusFlags(base, kDSPI_TxFifoFillRequestFlag);
+
+ if (handle->remainingReceiveByteCount == 0)
+ {
+ break;
+ }
+ }
+ }
+ /* Check if remaining receive byte count matches user request */
+ if ((handle->remainingReceiveByteCount == 0) || (handle->state == kDSPI_Error))
+ {
+ /* Other cases, stop the transfer. */
+ DSPI_SlaveTransferComplete(base, handle);
+ return;
+ }
+
+ /* Catch tx fifo underflow conditions, service only if tx under flow interrupt enabled */
+ if ((DSPI_GetStatusFlags(base) & kDSPI_TxFifoUnderflowFlag) && (base->RSER & SPI_RSER_TFUF_RE_MASK))
+ {
+ DSPI_ClearStatusFlags(base, kDSPI_TxFifoUnderflowFlag);
+ /* Change state to error and clear flag */
+ if (handle->txData)
+ {
+ handle->state = kDSPI_Error;
+ }
+ handle->errorCount++;
+ }
+ /* Catch rx fifo overflow conditions, service only if rx over flow interrupt enabled */
+ if ((DSPI_GetStatusFlags(base) & kDSPI_RxFifoOverflowFlag) && (base->RSER & SPI_RSER_RFOF_RE_MASK))
+ {
+ DSPI_ClearStatusFlags(base, kDSPI_RxFifoOverflowFlag);
+ /* Change state to error and clear flag */
+ if (handle->txData)
+ {
+ handle->state = kDSPI_Error;
+ }
+ handle->errorCount++;
+ }
+}
+
+static void DSPI_CommonIRQHandler(SPI_Type *base, void *param)
+{
+ if (DSPI_IsMaster(base))
+ {
+ s_dspiMasterIsr(base, (dspi_master_handle_t *)param);
+ }
+ else
+ {
+ s_dspiSlaveIsr(base, (dspi_slave_handle_t *)param);
+ }
+}
+
+#if (FSL_FEATURE_SOC_DSPI_COUNT > 0)
+void SPI0_DriverIRQHandler(void)
+{
+ assert(g_dspiHandle[0]);
+ DSPI_CommonIRQHandler(SPI0, g_dspiHandle[0]);
+}
+#endif
+
+#if (FSL_FEATURE_SOC_DSPI_COUNT > 1)
+void SPI1_DriverIRQHandler(void)
+{
+ assert(g_dspiHandle[1]);
+ DSPI_CommonIRQHandler(SPI1, g_dspiHandle[1]);
+}
+#endif
+
+#if (FSL_FEATURE_SOC_DSPI_COUNT > 2)
+void SPI2_DriverIRQHandler(void)
+{
+ assert(g_dspiHandle[2]);
+ DSPI_CommonIRQHandler(SPI2, g_dspiHandle[2]);
+}
+#endif
+
+#if (FSL_FEATURE_SOC_DSPI_COUNT > 3)
+void SPI3_DriverIRQHandler(void)
+{
+ assert(g_dspiHandle[3]);
+ DSPI_CommonIRQHandler(SPI3, g_dspiHandle[3]);
+}
+#endif
+
+#if (FSL_FEATURE_SOC_DSPI_COUNT > 4)
+void SPI4_DriverIRQHandler(void)
+{
+ assert(g_dspiHandle[4]);
+ DSPI_CommonIRQHandler(SPI4, g_dspiHandle[4]);
+}
+#endif
+
+#if (FSL_FEATURE_SOC_DSPI_COUNT > 5)
+void SPI5_DriverIRQHandler(void)
+{
+ assert(g_dspiHandle[5]);
+ DSPI_CommonIRQHandler(SPI5, g_dspiHandle[5]);
+}
+#endif
+
+#if (FSL_FEATURE_SOC_DSPI_COUNT > 6)
+#error "Should write the SPIx_DriverIRQHandler function that instance greater than 5 !"
+#endif
diff --git a/drivers/fsl_dspi.h b/drivers/fsl_dspi.h
new file mode 100644
index 0000000..dfbeb3e
--- /dev/null
+++ b/drivers/fsl_dspi.h
@@ -0,0 +1,1181 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_DSPI_H_
+#define _FSL_DSPI_H_
+
+#include "fsl_common.h"
+
+/*!
+ * @addtogroup dspi_driver
+ * @{
+ */
+
+
+/**********************************************************************************************************************
+ * Definitions
+ *********************************************************************************************************************/
+
+/*! @name Driver version */
+/*@{*/
+/*! @brief DSPI driver version 2.1.1. */
+#define FSL_DSPI_DRIVER_VERSION (MAKE_VERSION(2, 1, 1))
+/*@}*/
+
+/*! @brief DSPI dummy data if no Tx data.*/
+#define DSPI_DUMMY_DATA (0x00U) /*!< Dummy data used for tx if there is not txData. */
+
+/*! @brief Status for the DSPI driver.*/
+enum _dspi_status
+{
+ kStatus_DSPI_Busy = MAKE_STATUS(kStatusGroup_DSPI, 0), /*!< DSPI transfer is busy.*/
+ kStatus_DSPI_Error = MAKE_STATUS(kStatusGroup_DSPI, 1), /*!< DSPI driver error. */
+ kStatus_DSPI_Idle = MAKE_STATUS(kStatusGroup_DSPI, 2), /*!< DSPI is idle.*/
+ kStatus_DSPI_OutOfRange = MAKE_STATUS(kStatusGroup_DSPI, 3) /*!< DSPI transfer out Of range. */
+};
+
+/*! @brief DSPI status flags in SPIx_SR register.*/
+enum _dspi_flags
+{
+ kDSPI_TxCompleteFlag = SPI_SR_TCF_MASK, /*!< Transfer Complete Flag. */
+ kDSPI_EndOfQueueFlag = SPI_SR_EOQF_MASK, /*!< End of Queue Flag.*/
+ kDSPI_TxFifoUnderflowFlag = SPI_SR_TFUF_MASK, /*!< Transmit FIFO Underflow Flag.*/
+ kDSPI_TxFifoFillRequestFlag = SPI_SR_TFFF_MASK, /*!< Transmit FIFO Fill Flag.*/
+ kDSPI_RxFifoOverflowFlag = SPI_SR_RFOF_MASK, /*!< Receive FIFO Overflow Flag.*/
+ kDSPI_RxFifoDrainRequestFlag = SPI_SR_RFDF_MASK, /*!< Receive FIFO Drain Flag.*/
+ kDSPI_TxAndRxStatusFlag = SPI_SR_TXRXS_MASK, /*!< The module is in Stopped/Running state.*/
+ kDSPI_AllStatusFlag = SPI_SR_TCF_MASK | SPI_SR_EOQF_MASK | SPI_SR_TFUF_MASK | SPI_SR_TFFF_MASK | SPI_SR_RFOF_MASK |
+ SPI_SR_RFDF_MASK | SPI_SR_TXRXS_MASK /*!< All status above.*/
+};
+
+/*! @brief DSPI interrupt source.*/
+enum _dspi_interrupt_enable
+{
+ kDSPI_TxCompleteInterruptEnable = SPI_RSER_TCF_RE_MASK, /*!< TCF interrupt enable.*/
+ kDSPI_EndOfQueueInterruptEnable = SPI_RSER_EOQF_RE_MASK, /*!< EOQF interrupt enable.*/
+ kDSPI_TxFifoUnderflowInterruptEnable = SPI_RSER_TFUF_RE_MASK, /*!< TFUF interrupt enable.*/
+ kDSPI_TxFifoFillRequestInterruptEnable = SPI_RSER_TFFF_RE_MASK, /*!< TFFF interrupt enable, DMA disable.*/
+ kDSPI_RxFifoOverflowInterruptEnable = SPI_RSER_RFOF_RE_MASK, /*!< RFOF interrupt enable.*/
+ kDSPI_RxFifoDrainRequestInterruptEnable = SPI_RSER_RFDF_RE_MASK, /*!< RFDF interrupt enable, DMA disable.*/
+ kDSPI_AllInterruptEnable = SPI_RSER_TCF_RE_MASK | SPI_RSER_EOQF_RE_MASK | SPI_RSER_TFUF_RE_MASK |
+ SPI_RSER_TFFF_RE_MASK | SPI_RSER_RFOF_RE_MASK | SPI_RSER_RFDF_RE_MASK
+ /*!< All above interrupts enable.*/
+};
+
+/*! @brief DSPI DMA source.*/
+enum _dspi_dma_enable
+{
+ kDSPI_TxDmaEnable = (SPI_RSER_TFFF_RE_MASK | SPI_RSER_TFFF_DIRS_MASK), /*!< TFFF flag generates DMA requests.
+ No Tx interrupt request. */
+ kDSPI_RxDmaEnable = (SPI_RSER_RFDF_RE_MASK | SPI_RSER_RFDF_DIRS_MASK) /*!< RFDF flag generates DMA requests.
+ No Rx interrupt request. */
+};
+
+/*! @brief DSPI master or slave mode configuration.*/
+typedef enum _dspi_master_slave_mode
+{
+ kDSPI_Master = 1U, /*!< DSPI peripheral operates in master mode.*/
+ kDSPI_Slave = 0U /*!< DSPI peripheral operates in slave mode.*/
+} dspi_master_slave_mode_t;
+
+/*!
+ * @brief DSPI Sample Point: Controls when the DSPI master samples SIN in Modified Transfer Format. This field is valid
+ * only when CPHA bit in CTAR register is 0.
+ */
+typedef enum _dspi_master_sample_point
+{
+ kDSPI_SckToSin0Clock = 0U, /*!< 0 system clocks between SCK edge and SIN sample.*/
+ kDSPI_SckToSin1Clock = 1U, /*!< 1 system clock between SCK edge and SIN sample.*/
+ kDSPI_SckToSin2Clock = 2U /*!< 2 system clocks between SCK edge and SIN sample.*/
+} dspi_master_sample_point_t;
+
+/*! @brief DSPI Peripheral Chip Select (Pcs) configuration (which Pcs to configure).*/
+typedef enum _dspi_which_pcs_config
+{
+ kDSPI_Pcs0 = 1U << 0, /*!< Pcs[0] */
+ kDSPI_Pcs1 = 1U << 1, /*!< Pcs[1] */
+ kDSPI_Pcs2 = 1U << 2, /*!< Pcs[2] */
+ kDSPI_Pcs3 = 1U << 3, /*!< Pcs[3] */
+ kDSPI_Pcs4 = 1U << 4, /*!< Pcs[4] */
+ kDSPI_Pcs5 = 1U << 5 /*!< Pcs[5] */
+} dspi_which_pcs_t;
+
+/*! @brief DSPI Peripheral Chip Select (Pcs) Polarity configuration.*/
+typedef enum _dspi_pcs_polarity_config
+{
+ kDSPI_PcsActiveHigh = 0U, /*!< Pcs Active High (idles low). */
+ kDSPI_PcsActiveLow = 1U /*!< Pcs Active Low (idles high). */
+} dspi_pcs_polarity_config_t;
+
+/*! @brief DSPI Peripheral Chip Select (Pcs) Polarity.*/
+enum _dspi_pcs_polarity
+{
+ kDSPI_Pcs0ActiveLow = 1U << 0, /*!< Pcs0 Active Low (idles high). */
+ kDSPI_Pcs1ActiveLow = 1U << 1, /*!< Pcs1 Active Low (idles high). */
+ kDSPI_Pcs2ActiveLow = 1U << 2, /*!< Pcs2 Active Low (idles high). */
+ kDSPI_Pcs3ActiveLow = 1U << 3, /*!< Pcs3 Active Low (idles high). */
+ kDSPI_Pcs4ActiveLow = 1U << 4, /*!< Pcs4 Active Low (idles high). */
+ kDSPI_Pcs5ActiveLow = 1U << 5, /*!< Pcs5 Active Low (idles high). */
+ kDSPI_PcsAllActiveLow = 0xFFU /*!< Pcs0 to Pcs5 Active Low (idles high). */
+};
+
+/*! @brief DSPI clock polarity configuration for a given CTAR.*/
+typedef enum _dspi_clock_polarity
+{
+ kDSPI_ClockPolarityActiveHigh = 0U, /*!< CPOL=0. Active-high DSPI clock (idles low).*/
+ kDSPI_ClockPolarityActiveLow = 1U /*!< CPOL=1. Active-low DSPI clock (idles high).*/
+} dspi_clock_polarity_t;
+
+/*! @brief DSPI clock phase configuration for a given CTAR.*/
+typedef enum _dspi_clock_phase
+{
+ kDSPI_ClockPhaseFirstEdge = 0U, /*!< CPHA=0. Data is captured on the leading edge of the SCK and changed on the
+ following edge.*/
+ kDSPI_ClockPhaseSecondEdge = 1U /*!< CPHA=1. Data is changed on the leading edge of the SCK and captured on the
+ following edge.*/
+} dspi_clock_phase_t;
+
+/*! @brief DSPI data shifter direction options for a given CTAR.*/
+typedef enum _dspi_shift_direction
+{
+ kDSPI_MsbFirst = 0U, /*!< Data transfers start with most significant bit.*/
+ kDSPI_LsbFirst = 1U /*!< Data transfers start with least significant bit.*/
+} dspi_shift_direction_t;
+
+/*! @brief DSPI delay type selection.*/
+typedef enum _dspi_delay_type
+{
+ kDSPI_PcsToSck = 1U, /*!< Pcs-to-SCK delay. */
+ kDSPI_LastSckToPcs, /*!< Last SCK edge to Pcs delay. */
+ kDSPI_BetweenTransfer /*!< Delay between transfers. */
+} dspi_delay_type_t;
+
+/*! @brief DSPI Clock and Transfer Attributes Register (CTAR) selection.*/
+typedef enum _dspi_ctar_selection
+{
+ kDSPI_Ctar0 = 0U, /*!< CTAR0 selection option for master or slave mode, note that CTAR0 and CTAR0_SLAVE are the
+ same register address. */
+ kDSPI_Ctar1 = 1U, /*!< CTAR1 selection option for master mode only. */
+ kDSPI_Ctar2 = 2U, /*!< CTAR2 selection option for master mode only , note that some device do not support CTAR2. */
+ kDSPI_Ctar3 = 3U, /*!< CTAR3 selection option for master mode only , note that some device do not support CTAR3. */
+ kDSPI_Ctar4 = 4U, /*!< CTAR4 selection option for master mode only , note that some device do not support CTAR4. */
+ kDSPI_Ctar5 = 5U, /*!< CTAR5 selection option for master mode only , note that some device do not support CTAR5. */
+ kDSPI_Ctar6 = 6U, /*!< CTAR6 selection option for master mode only , note that some device do not support CTAR6. */
+ kDSPI_Ctar7 = 7U /*!< CTAR7 selection option for master mode only , note that some device do not support CTAR7. */
+} dspi_ctar_selection_t;
+
+#define DSPI_MASTER_CTAR_SHIFT (0U) /*!< DSPI master CTAR shift macro , internal used. */
+#define DSPI_MASTER_CTAR_MASK (0x0FU) /*!< DSPI master CTAR mask macro , internal used. */
+#define DSPI_MASTER_PCS_SHIFT (4U) /*!< DSPI master PCS shift macro , internal used. */
+#define DSPI_MASTER_PCS_MASK (0xF0U) /*!< DSPI master PCS mask macro , internal used. */
+/*! @brief Can use this enumeration for DSPI master transfer configFlags. */
+enum _dspi_transfer_config_flag_for_master
+{
+ kDSPI_MasterCtar0 = 0U << DSPI_MASTER_CTAR_SHIFT, /*!< DSPI master transfer use CTAR0 setting. */
+ kDSPI_MasterCtar1 = 1U << DSPI_MASTER_CTAR_SHIFT, /*!< DSPI master transfer use CTAR1 setting. */
+ kDSPI_MasterCtar2 = 2U << DSPI_MASTER_CTAR_SHIFT, /*!< DSPI master transfer use CTAR2 setting. */
+ kDSPI_MasterCtar3 = 3U << DSPI_MASTER_CTAR_SHIFT, /*!< DSPI master transfer use CTAR3 setting. */
+ kDSPI_MasterCtar4 = 4U << DSPI_MASTER_CTAR_SHIFT, /*!< DSPI master transfer use CTAR4 setting. */
+ kDSPI_MasterCtar5 = 5U << DSPI_MASTER_CTAR_SHIFT, /*!< DSPI master transfer use CTAR5 setting. */
+ kDSPI_MasterCtar6 = 6U << DSPI_MASTER_CTAR_SHIFT, /*!< DSPI master transfer use CTAR6 setting. */
+ kDSPI_MasterCtar7 = 7U << DSPI_MASTER_CTAR_SHIFT, /*!< DSPI master transfer use CTAR7 setting. */
+
+ kDSPI_MasterPcs0 = 0U << DSPI_MASTER_PCS_SHIFT, /*!< DSPI master transfer use PCS0 signal. */
+ kDSPI_MasterPcs1 = 1U << DSPI_MASTER_PCS_SHIFT, /*!< DSPI master transfer use PCS1 signal. */
+ kDSPI_MasterPcs2 = 2U << DSPI_MASTER_PCS_SHIFT, /*!< DSPI master transfer use PCS2 signal.*/
+ kDSPI_MasterPcs3 = 3U << DSPI_MASTER_PCS_SHIFT, /*!< DSPI master transfer use PCS3 signal. */
+ kDSPI_MasterPcs4 = 4U << DSPI_MASTER_PCS_SHIFT, /*!< DSPI master transfer use PCS4 signal. */
+ kDSPI_MasterPcs5 = 5U << DSPI_MASTER_PCS_SHIFT, /*!< DSPI master transfer use PCS5 signal. */
+
+ kDSPI_MasterPcsContinuous = 1U << 20, /*!< Is PCS signal continuous. */
+ kDSPI_MasterActiveAfterTransfer = 1U << 21, /*!< Is PCS signal active after last frame transfer.*/
+};
+
+#define DSPI_SLAVE_CTAR_SHIFT (0U) /*!< DSPI slave CTAR shift macro , internal used. */
+#define DSPI_SLAVE_CTAR_MASK (0x07U) /*!< DSPI slave CTAR mask macro , internal used. */
+/*! @brief Can use this enum for DSPI slave transfer configFlags. */
+enum _dspi_transfer_config_flag_for_slave
+{
+ kDSPI_SlaveCtar0 = 0U << DSPI_SLAVE_CTAR_SHIFT, /*!< DSPI slave transfer use CTAR0 setting. */
+ /*!< DSPI slave can only use PCS0. */
+};
+
+/*! @brief DSPI transfer state, which is used for DSPI transactional API state machine. */
+enum _dspi_transfer_state
+{
+ kDSPI_Idle = 0x0U, /*!< Nothing in the transmitter/receiver. */
+ kDSPI_Busy, /*!< Transfer queue is not finished. */
+ kDSPI_Error /*!< Transfer error. */
+};
+
+/*! @brief DSPI master command date configuration used for SPIx_PUSHR.*/
+typedef struct _dspi_command_data_config
+{
+ bool isPcsContinuous; /*!< Option to enable the continuous assertion of chip select between transfers.*/
+ dspi_ctar_selection_t whichCtar; /*!< The desired Clock and Transfer Attributes
+ Register (CTAR) to use for CTAS.*/
+ dspi_which_pcs_t whichPcs; /*!< The desired PCS signal to use for the data transfer.*/
+ bool isEndOfQueue; /*!< Signals that the current transfer is the last in the queue.*/
+ bool clearTransferCount; /*!< Clears SPI Transfer Counter (SPI_TCNT) before transmission starts.*/
+} dspi_command_data_config_t;
+
+/*! @brief DSPI master ctar configuration structure.*/
+typedef struct _dspi_master_ctar_config
+{
+ uint32_t baudRate; /*!< Baud Rate for DSPI. */
+ uint32_t bitsPerFrame; /*!< Bits per frame, minimum 4, maximum 16.*/
+ dspi_clock_polarity_t cpol; /*!< Clock polarity. */
+ dspi_clock_phase_t cpha; /*!< Clock phase. */
+ dspi_shift_direction_t direction; /*!< MSB or LSB data shift direction. */
+
+ uint32_t pcsToSckDelayInNanoSec; /*!< PCS to SCK delay time with nanosecond , set to 0 sets the minimum
+ delay. It sets the boundary value if out of range that can be set.*/
+ uint32_t lastSckToPcsDelayInNanoSec; /*!< Last SCK to PCS delay time with nanosecond , set to 0 sets the
+ minimum delay.It sets the boundary value if out of range that can be
+ set.*/
+ uint32_t betweenTransferDelayInNanoSec; /*!< After SCK delay time with nanosecond , set to 0 sets the minimum
+ delay.It sets the boundary value if out of range that can be set.*/
+} dspi_master_ctar_config_t;
+
+/*! @brief DSPI master configuration structure.*/
+typedef struct _dspi_master_config
+{
+ dspi_ctar_selection_t whichCtar; /*!< Desired CTAR to use. */
+ dspi_master_ctar_config_t ctarConfig; /*!< Set the ctarConfig to the desired CTAR. */
+
+ dspi_which_pcs_t whichPcs; /*!< Desired Peripheral Chip Select (pcs). */
+ dspi_pcs_polarity_config_t pcsActiveHighOrLow; /*!< Desired PCS active high or low. */
+
+ bool enableContinuousSCK; /*!< CONT_SCKE, continuous SCK enable . Note that continuous SCK is only
+ supported for CPHA = 1.*/
+ bool enableRxFifoOverWrite; /*!< ROOE, Receive FIFO overflow overwrite enable. ROOE = 0, the incoming
+ data is ignored, the data from the transfer that generated the overflow
+ is either ignored. ROOE = 1, the incoming data is shifted in to the
+ shift to the shift register. */
+
+ bool enableModifiedTimingFormat; /*!< Enables a modified transfer format to be used if it's true.*/
+ dspi_master_sample_point_t samplePoint; /*!< Controls when the module master samples SIN in Modified Transfer
+ Format. It's valid only when CPHA=0. */
+} dspi_master_config_t;
+
+/*! @brief DSPI slave ctar configuration structure.*/
+typedef struct _dspi_slave_ctar_config
+{
+ uint32_t bitsPerFrame; /*!< Bits per frame, minimum 4, maximum 16.*/
+ dspi_clock_polarity_t cpol; /*!< Clock polarity. */
+ dspi_clock_phase_t cpha; /*!< Clock phase. */
+ /*!< Slave only supports MSB , does not support LSB.*/
+} dspi_slave_ctar_config_t;
+
+/*! @brief DSPI slave configuration structure.*/
+typedef struct _dspi_slave_config
+{
+ dspi_ctar_selection_t whichCtar; /*!< Desired CTAR to use. */
+ dspi_slave_ctar_config_t ctarConfig; /*!< Set the ctarConfig to the desired CTAR. */
+
+ bool enableContinuousSCK; /*!< CONT_SCKE, continuous SCK enable. Note that continuous SCK is only
+ supported for CPHA = 1.*/
+ bool enableRxFifoOverWrite; /*!< ROOE, Receive FIFO overflow overwrite enable. ROOE = 0, the incoming
+ data is ignored, the data from the transfer that generated the overflow
+ is either ignored. ROOE = 1, the incoming data is shifted in to the
+ shift to the shift register. */
+ bool enableModifiedTimingFormat; /*!< Enables a modified transfer format to be used if it's true.*/
+ dspi_master_sample_point_t samplePoint; /*!< Controls when the module master samples SIN in Modified Transfer
+ Format. It's valid only when CPHA=0. */
+} dspi_slave_config_t;
+
+/*!
+* @brief Forward declaration of the _dspi_master_handle typedefs.
+*/
+typedef struct _dspi_master_handle dspi_master_handle_t;
+
+/*!
+* @brief Forward declaration of the _dspi_slave_handle typedefs.
+*/
+typedef struct _dspi_slave_handle dspi_slave_handle_t;
+
+/*!
+ * @brief Completion callback function pointer type.
+ *
+ * @param base DSPI peripheral address.
+ * @param handle Pointer to the handle for the DSPI master.
+ * @param status Success or error code describing whether the transfer completed.
+ * @param userData Arbitrary pointer-dataSized value passed from the application.
+ */
+typedef void (*dspi_master_transfer_callback_t)(SPI_Type *base,
+ dspi_master_handle_t *handle,
+ status_t status,
+ void *userData);
+/*!
+ * @brief Completion callback function pointer type.
+ *
+ * @param base DSPI peripheral address.
+ * @param handle Pointer to the handle for the DSPI slave.
+ * @param status Success or error code describing whether the transfer completed.
+ * @param userData Arbitrary pointer-dataSized value passed from the application.
+ */
+typedef void (*dspi_slave_transfer_callback_t)(SPI_Type *base,
+ dspi_slave_handle_t *handle,
+ status_t status,
+ void *userData);
+
+/*! @brief DSPI master/slave transfer structure.*/
+typedef struct _dspi_transfer
+{
+ uint8_t *txData; /*!< Send buffer. */
+ uint8_t *rxData; /*!< Receive buffer. */
+ volatile size_t dataSize; /*!< Transfer bytes. */
+
+ uint32_t
+ configFlags; /*!< Transfer transfer configuration flags , set from _dspi_transfer_config_flag_for_master if the
+ transfer is used for master or _dspi_transfer_config_flag_for_slave enumeration if the transfer
+ is used for slave.*/
+} dspi_transfer_t;
+
+/*! @brief DSPI master transfer handle structure used for transactional API. */
+struct _dspi_master_handle
+{
+ uint32_t bitsPerFrame; /*!< Desired number of bits per frame. */
+ volatile uint32_t command; /*!< Desired data command. */
+ volatile uint32_t lastCommand; /*!< Desired last data command. */
+
+ uint8_t fifoSize; /*!< FIFO dataSize. */
+
+ volatile bool isPcsActiveAfterTransfer; /*!< Is PCS signal keep active after the last frame transfer.*/
+ volatile bool isThereExtraByte; /*!< Is there extra byte.*/
+
+ uint8_t *volatile txData; /*!< Send buffer. */
+ uint8_t *volatile rxData; /*!< Receive buffer. */
+ volatile size_t remainingSendByteCount; /*!< Number of bytes remaining to send.*/
+ volatile size_t remainingReceiveByteCount; /*!< Number of bytes remaining to receive.*/
+ size_t totalByteCount; /*!< Number of transfer bytes*/
+
+ volatile uint8_t state; /*!< DSPI transfer state , _dspi_transfer_state.*/
+
+ dspi_master_transfer_callback_t callback; /*!< Completion callback. */
+ void *userData; /*!< Callback user data. */
+};
+
+/*! @brief DSPI slave transfer handle structure used for transactional API. */
+struct _dspi_slave_handle
+{
+ uint32_t bitsPerFrame; /*!< Desired number of bits per frame. */
+ volatile bool isThereExtraByte; /*!< Is there extra byte.*/
+
+ uint8_t *volatile txData; /*!< Send buffer. */
+ uint8_t *volatile rxData; /*!< Receive buffer. */
+ volatile size_t remainingSendByteCount; /*!< Number of bytes remaining to send.*/
+ volatile size_t remainingReceiveByteCount; /*!< Number of bytes remaining to receive.*/
+ size_t totalByteCount; /*!< Number of transfer bytes*/
+
+ volatile uint8_t state; /*!< DSPI transfer state.*/
+
+ volatile uint32_t errorCount; /*!< Error count for slave transfer.*/
+
+ dspi_slave_transfer_callback_t callback; /*!< Completion callback. */
+ void *userData; /*!< Callback user data. */
+};
+
+/**********************************************************************************************************************
+ * API
+ *********************************************************************************************************************/
+#if defined(__cplusplus)
+extern "C" {
+#endif /*_cplusplus*/
+
+/*!
+ * @name Initialization and deinitialization
+ * @{
+ */
+
+/*!
+ * @brief Initializes the DSPI master.
+ *
+ * This function initializes the DSPI master configuration. An example use case is as follows:
+ * @code
+ * dspi_master_config_t masterConfig;
+ * masterConfig.whichCtar = kDSPI_Ctar0;
+ * masterConfig.ctarConfig.baudRate = 500000000;
+ * masterConfig.ctarConfig.bitsPerFrame = 8;
+ * masterConfig.ctarConfig.cpol = kDSPI_ClockPolarityActiveHigh;
+ * masterConfig.ctarConfig.cpha = kDSPI_ClockPhaseFirstEdge;
+ * masterConfig.ctarConfig.direction = kDSPI_MsbFirst;
+ * masterConfig.ctarConfig.pcsToSckDelayInNanoSec = 1000000000 / masterConfig.ctarConfig.baudRate ;
+ * masterConfig.ctarConfig.lastSckToPcsDelayInNanoSec = 1000000000 / masterConfig.ctarConfig.baudRate ;
+ * masterConfig.ctarConfig.betweenTransferDelayInNanoSec = 1000000000 / masterConfig.ctarConfig.baudRate ;
+ * masterConfig.whichPcs = kDSPI_Pcs0;
+ * masterConfig.pcsActiveHighOrLow = kDSPI_PcsActiveLow;
+ * masterConfig.enableContinuousSCK = false;
+ * masterConfig.enableRxFifoOverWrite = false;
+ * masterConfig.enableModifiedTimingFormat = false;
+ * masterConfig.samplePoint = kDSPI_SckToSin0Clock;
+ * DSPI_MasterInit(base, &masterConfig, srcClock_Hz);
+ * @endcode
+ *
+ * @param base DSPI peripheral address.
+ * @param masterConfig Pointer to structure dspi_master_config_t.
+ * @param srcClock_Hz Module source input clock in Hertz
+ */
+void DSPI_MasterInit(SPI_Type *base, const dspi_master_config_t *masterConfig, uint32_t srcClock_Hz);
+
+/*!
+ * @brief Sets the dspi_master_config_t structure to default values.
+ *
+ * The purpose of this API is to get the configuration structure initialized for the DSPI_MasterInit().
+ * User may use the initialized structure unchanged in DSPI_MasterInit() or modify the structure
+ * before calling DSPI_MasterInit().
+ * Example:
+ * @code
+ * dspi_master_config_t masterConfig;
+ * DSPI_MasterGetDefaultConfig(&masterConfig);
+ * @endcode
+ * @param masterConfig pointer to dspi_master_config_t structure
+ */
+void DSPI_MasterGetDefaultConfig(dspi_master_config_t *masterConfig);
+
+/*!
+ * @brief DSPI slave configuration.
+ *
+ * This function initializes the DSPI slave configuration. An example use case is as follows:
+ * @code
+ * dspi_slave_config_t slaveConfig;
+ * slaveConfig->whichCtar = kDSPI_Ctar0;
+ * slaveConfig->ctarConfig.bitsPerFrame = 8;
+ * slaveConfig->ctarConfig.cpol = kDSPI_ClockPolarityActiveHigh;
+ * slaveConfig->ctarConfig.cpha = kDSPI_ClockPhaseFirstEdge;
+ * slaveConfig->enableContinuousSCK = false;
+ * slaveConfig->enableRxFifoOverWrite = false;
+ * slaveConfig->enableModifiedTimingFormat = false;
+ * slaveConfig->samplePoint = kDSPI_SckToSin0Clock;
+ * DSPI_SlaveInit(base, &slaveConfig);
+ * @endcode
+ *
+ * @param base DSPI peripheral address.
+ * @param slaveConfig Pointer to structure dspi_master_config_t.
+ */
+void DSPI_SlaveInit(SPI_Type *base, const dspi_slave_config_t *slaveConfig);
+
+/*!
+ * @brief Sets the dspi_slave_config_t structure to default values.
+ *
+ * The purpose of this API is to get the configuration structure initialized for the DSPI_SlaveInit().
+ * User may use the initialized structure unchanged in DSPI_SlaveInit(), or modify the structure
+ * before calling DSPI_SlaveInit().
+ * Example:
+ * @code
+ * dspi_slave_config_t slaveConfig;
+ * DSPI_SlaveGetDefaultConfig(&slaveConfig);
+ * @endcode
+ * @param slaveConfig pointer to dspi_slave_config_t structure.
+ */
+void DSPI_SlaveGetDefaultConfig(dspi_slave_config_t *slaveConfig);
+
+/*!
+ * @brief De-initializes the DSPI peripheral. Call this API to disable the DSPI clock.
+ * @param base DSPI peripheral address.
+ */
+void DSPI_Deinit(SPI_Type *base);
+
+/*!
+ * @brief Enables the DSPI peripheral and sets the MCR MDIS to 0.
+ *
+ * @param base DSPI peripheral address.
+ * @param enable pass true to enable module, false to disable module.
+ */
+static inline void DSPI_Enable(SPI_Type *base, bool enable)
+{
+ if (enable)
+ {
+ base->MCR &= ~SPI_MCR_MDIS_MASK;
+ }
+ else
+ {
+ base->MCR |= SPI_MCR_MDIS_MASK;
+ }
+}
+
+/*!
+ *@}
+*/
+
+/*!
+ * @name Status
+ * @{
+ */
+
+/*!
+ * @brief Gets the DSPI status flag state.
+ * @param base DSPI peripheral address.
+ * @return The DSPI status(in SR register).
+ */
+static inline uint32_t DSPI_GetStatusFlags(SPI_Type *base)
+{
+ return (base->SR);
+}
+
+/*!
+ * @brief Clears the DSPI status flag.
+ *
+ * This function clears the desired status bit by using a write-1-to-clear. The user passes in the base and the
+ * desired status bit to clear. The list of status bits is defined in the dspi_status_and_interrupt_request_t. The
+ * function uses these bit positions in its algorithm to clear the desired flag state.
+ * Example usage:
+ * @code
+ * DSPI_ClearStatusFlags(base, kDSPI_TxCompleteFlag|kDSPI_EndOfQueueFlag);
+ * @endcode
+ *
+ * @param base DSPI peripheral address.
+ * @param statusFlags The status flag , used from type dspi_flags.
+ */
+static inline void DSPI_ClearStatusFlags(SPI_Type *base, uint32_t statusFlags)
+{
+ base->SR = statusFlags; /*!< The status flags are cleared by writing 1 (w1c).*/
+}
+
+/*!
+ *@}
+*/
+
+/*!
+ * @name Interrupts
+ * @{
+ */
+
+/*!
+ * @brief Enables the DSPI interrupts.
+ *
+ * This function configures the various interrupt masks of the DSPI. The parameters are base and an interrupt mask.
+ * Note, for Tx Fill and Rx FIFO drain requests, enable the interrupt request and disable the DMA request.
+ *
+ * @code
+ * DSPI_EnableInterrupts(base, kDSPI_TxCompleteInterruptEnable | kDSPI_EndOfQueueInterruptEnable );
+ * @endcode
+ *
+ * @param base DSPI peripheral address.
+ * @param mask The interrupt mask, can use the enum _dspi_interrupt_enable.
+ */
+void DSPI_EnableInterrupts(SPI_Type *base, uint32_t mask);
+
+/*!
+ * @brief Disables the DSPI interrupts.
+ *
+ * @code
+ * DSPI_DisableInterrupts(base, kDSPI_TxCompleteInterruptEnable | kDSPI_EndOfQueueInterruptEnable );
+ * @endcode
+ *
+ * @param base DSPI peripheral address.
+ * @param mask The interrupt mask, can use the enum _dspi_interrupt_enable.
+ */
+static inline void DSPI_DisableInterrupts(SPI_Type *base, uint32_t mask)
+{
+ base->RSER &= ~mask;
+}
+
+/*!
+ *@}
+*/
+
+/*!
+ * @name DMA Control
+ * @{
+ */
+
+/*!
+ * @brief Enables the DSPI DMA request.
+ *
+ * This function configures the Rx and Tx DMA mask of the DSPI. The parameters are base and a DMA mask.
+ * @code
+ * DSPI_EnableDMA(base, kDSPI_TxDmaEnable | kDSPI_RxDmaEnable);
+ * @endcode
+ *
+ * @param base DSPI peripheral address.
+ * @param mask The interrupt mask can use the enum dspi_dma_enable.
+ */
+static inline void DSPI_EnableDMA(SPI_Type *base, uint32_t mask)
+{
+ base->RSER |= mask;
+}
+
+/*!
+ * @brief Disables the DSPI DMA request.
+ *
+ * This function configures the Rx and Tx DMA mask of the DSPI. The parameters are base and a DMA mask.
+ * @code
+ * SPI_DisableDMA(base, kDSPI_TxDmaEnable | kDSPI_RxDmaEnable);
+ * @endcode
+ *
+ * @param base DSPI peripheral address.
+ * @param mask The interrupt mask can use the enum dspi_dma_enable.
+ */
+static inline void DSPI_DisableDMA(SPI_Type *base, uint32_t mask)
+{
+ base->RSER &= ~mask;
+}
+
+/*!
+ * @brief Gets the DSPI master PUSHR data register address for the DMA operation.
+ *
+ * This function gets the DSPI master PUSHR data register address because this value is needed for the DMA operation.
+ *
+ * @param base DSPI peripheral address.
+ * @return The DSPI master PUSHR data register address.
+ */
+static inline uint32_t DSPI_MasterGetTxRegisterAddress(SPI_Type *base)
+{
+ return (uint32_t) & (base->PUSHR);
+}
+
+/*!
+ * @brief Gets the DSPI slave PUSHR data register address for the DMA operation.
+ *
+ * This function gets the DSPI slave PUSHR data register address as this value is needed for the DMA operation.
+ *
+ * @param base DSPI peripheral address.
+ * @return The DSPI slave PUSHR data register address.
+ */
+static inline uint32_t DSPI_SlaveGetTxRegisterAddress(SPI_Type *base)
+{
+ return (uint32_t) & (base->PUSHR_SLAVE);
+}
+
+/*!
+ * @brief Gets the DSPI POPR data register address for the DMA operation.
+ *
+ * This function gets the DSPI POPR data register address as this value is needed for the DMA operation.
+ *
+ * @param base DSPI peripheral address.
+ * @return The DSPI POPR data register address.
+ */
+static inline uint32_t DSPI_GetRxRegisterAddress(SPI_Type *base)
+{
+ return (uint32_t) & (base->POPR);
+}
+
+/*!
+ *@}
+*/
+
+/*!
+ * @name Bus Operations
+ * @{
+ */
+
+/*!
+ * @brief Configures the DSPI for master or slave.
+ *
+ * @param base DSPI peripheral address.
+ * @param mode Mode setting (master or slave) of type dspi_master_slave_mode_t.
+ */
+static inline void DSPI_SetMasterSlaveMode(SPI_Type *base, dspi_master_slave_mode_t mode)
+{
+ base->MCR = (base->MCR & (~SPI_MCR_MSTR_MASK)) | SPI_MCR_MSTR(mode);
+}
+
+/*!
+ * @brief Returns whether the DSPI module is in master mode.
+ *
+ * @param base DSPI peripheral address.
+ * @return Returns true if the module is in master mode or false if the module is in slave mode.
+ */
+static inline bool DSPI_IsMaster(SPI_Type *base)
+{
+ return (bool)((base->MCR) & SPI_MCR_MSTR_MASK);
+}
+/*!
+ * @brief Starts the DSPI transfers and clears HALT bit in MCR.
+ *
+ * This function sets the module to begin data transfer in either master or slave mode.
+ *
+ * @param base DSPI peripheral address.
+ */
+static inline void DSPI_StartTransfer(SPI_Type *base)
+{
+ base->MCR &= ~SPI_MCR_HALT_MASK;
+}
+/*!
+ * @brief Stops (halts) DSPI transfers and sets HALT bit in MCR.
+ *
+ * This function stops data transfers in either master or slave mode.
+ *
+ * @param base DSPI peripheral address.
+ */
+static inline void DSPI_StopTransfer(SPI_Type *base)
+{
+ base->MCR |= SPI_MCR_HALT_MASK;
+}
+
+/*!
+ * @brief Enables (or disables) the DSPI FIFOs.
+ *
+ * This function allows the caller to disable/enable the Tx and Rx FIFOs (independently).
+ * Note that to disable, the caller must pass in a logic 0 (false) for the particular FIFO configuration. To enable,
+ * the caller must pass in a logic 1 (true).
+ *
+ * @param base DSPI peripheral address.
+ * @param enableTxFifo Disables (false) the TX FIFO, else enables (true) the TX FIFO
+ * @param enableRxFifo Disables (false) the RX FIFO, else enables (true) the RX FIFO
+ */
+static inline void DSPI_SetFifoEnable(SPI_Type *base, bool enableTxFifo, bool enableRxFifo)
+{
+ base->MCR = (base->MCR & (~(SPI_MCR_DIS_RXF_MASK | SPI_MCR_DIS_TXF_MASK))) | SPI_MCR_DIS_TXF(!enableTxFifo) |
+ SPI_MCR_DIS_RXF(!enableRxFifo);
+}
+
+/*!
+ * @brief Flushes the DSPI FIFOs.
+ *
+ * @param base DSPI peripheral address.
+ * @param flushTxFifo Flushes (true) the Tx FIFO, else do not flush (false) the Tx FIFO
+ * @param flushRxFifo Flushes (true) the Rx FIFO, else do not flush (false) the Rx FIFO
+ */
+static inline void DSPI_FlushFifo(SPI_Type *base, bool flushTxFifo, bool flushRxFifo)
+{
+ base->MCR = (base->MCR & (~(SPI_MCR_CLR_TXF_MASK | SPI_MCR_CLR_RXF_MASK))) | SPI_MCR_CLR_TXF(flushTxFifo) |
+ SPI_MCR_CLR_RXF(flushRxFifo);
+}
+
+/*!
+ * @brief Configures the DSPI peripheral chip select polarity simultaneously.
+ * For example, PCS0 and PCS1 set to active low and other PCS set to active high. Note that the number of
+ * PCSs is specific to the device.
+ * @code
+ * DSPI_SetAllPcsPolarity(base, kDSPI_Pcs0ActiveLow | kDSPI_Pcs1ActiveLow);
+ @endcode
+ * @param base DSPI peripheral address.
+ * @param mask The PCS polarity mask , can use the enum _dspi_pcs_polarity.
+ */
+static inline void DSPI_SetAllPcsPolarity(SPI_Type *base, uint32_t mask)
+{
+ base->MCR = (base->MCR & ~SPI_MCR_PCSIS_MASK) | SPI_MCR_PCSIS(mask);
+}
+
+/*!
+ * @brief Sets the DSPI baud rate in bits per second.
+ *
+ * This function takes in the desired baudRate_Bps (baud rate) and calculates the nearest possible baud rate without
+ * exceeding the desired baud rate, and returns the calculated baud rate in bits-per-second. It requires that the
+ * caller also provide the frequency of the module source clock (in Hertz).
+ *
+ * @param base DSPI peripheral address.
+ * @param whichCtar The desired Clock and Transfer Attributes Register (CTAR) of the type dspi_ctar_selection_t
+ * @param baudRate_Bps The desired baud rate in bits per second
+ * @param srcClock_Hz Module source input clock in Hertz
+ * @return The actual calculated baud rate
+ */
+uint32_t DSPI_MasterSetBaudRate(SPI_Type *base,
+ dspi_ctar_selection_t whichCtar,
+ uint32_t baudRate_Bps,
+ uint32_t srcClock_Hz);
+
+/*!
+ * @brief Manually configures the delay prescaler and scaler for a particular CTAR.
+ *
+ * This function configures the PCS to SCK delay pre-scalar (PcsSCK) and scalar (CSSCK), after SCK delay pre-scalar
+ * (PASC) and scalar (ASC), and the delay after transfer pre-scalar (PDT)and scalar (DT).
+ *
+ * These delay names are available in type dspi_delay_type_t.
+ *
+ * The user passes the delay to configure along with the prescaler and scaler value.
+ * This allows the user to directly set the prescaler/scaler values if they have pre-calculated them or if they simply
+ * wish to manually increment either value.
+ *
+ * @param base DSPI peripheral address.
+ * @param whichCtar The desired Clock and Transfer Attributes Register (CTAR) of type dspi_ctar_selection_t.
+ * @param prescaler The prescaler delay value (can be an integer 0, 1, 2, or 3).
+ * @param scaler The scaler delay value (can be any integer between 0 to 15).
+ * @param whichDelay The desired delay to configure, must be of type dspi_delay_type_t
+ */
+void DSPI_MasterSetDelayScaler(
+ SPI_Type *base, dspi_ctar_selection_t whichCtar, uint32_t prescaler, uint32_t scaler, dspi_delay_type_t whichDelay);
+
+/*!
+ * @brief Calculates the delay prescaler and scaler based on the desired delay input in nanoseconds.
+ *
+ * This function calculates the values for:
+ * PCS to SCK delay pre-scalar (PCSSCK) and scalar (CSSCK), or
+ * After SCK delay pre-scalar (PASC) and scalar (ASC), or
+ * Delay after transfer pre-scalar (PDT)and scalar (DT).
+ *
+ * These delay names are available in type dspi_delay_type_t.
+ *
+ * The user passes which delay they want to configure along with the desired delay value in nanoseconds. The function
+ * calculates the values needed for the prescaler and scaler and returning the actual calculated delay as an exact
+ * delay match may not be possible. In this case, the closest match is calculated without going below the desired
+ * delay value input.
+ * It is possible to input a very large delay value that exceeds the capability of the part, in which case the maximum
+ * supported delay is returned. The higher-level peripheral driver alerts the user of an out of range delay
+ * input.
+ *
+ * @param base DSPI peripheral address.
+ * @param whichCtar The desired Clock and Transfer Attributes Register (CTAR) of type dspi_ctar_selection_t.
+ * @param whichDelay The desired delay to configure, must be of type dspi_delay_type_t
+ * @param srcClock_Hz Module source input clock in Hertz
+ * @param delayTimeInNanoSec The desired delay value in nanoseconds.
+ * @return The actual calculated delay value.
+ */
+uint32_t DSPI_MasterSetDelayTimes(SPI_Type *base,
+ dspi_ctar_selection_t whichCtar,
+ dspi_delay_type_t whichDelay,
+ uint32_t srcClock_Hz,
+ uint32_t delayTimeInNanoSec);
+
+/*!
+ * @brief Writes data into the data buffer for master mode.
+ *
+ * In master mode, the 16-bit data is appended to the 16-bit command info. The command portion
+ * provides characteristics of the data such as the optional continuous chip select
+ * operation between transfers, the desired Clock and Transfer Attributes register to use for the
+ * associated SPI frame, the desired PCS signal to use for the data transfer, whether the current
+ * transfer is the last in the queue, and whether to clear the transfer count (normally needed when
+ * sending the first frame of a data packet). This is an example:
+ * @code
+ * dspi_command_data_config_t commandConfig;
+ * commandConfig.isPcsContinuous = true;
+ * commandConfig.whichCtar = kDSPICtar0;
+ * commandConfig.whichPcs = kDSPIPcs0;
+ * commandConfig.clearTransferCount = false;
+ * commandConfig.isEndOfQueue = false;
+ * DSPI_MasterWriteData(base, &commandConfig, dataWord);
+ @endcode
+ *
+ * @param base DSPI peripheral address.
+ * @param command Pointer to command structure.
+ * @param data The data word to be sent.
+ */
+static inline void DSPI_MasterWriteData(SPI_Type *base, dspi_command_data_config_t *command, uint16_t data)
+{
+ base->PUSHR = SPI_PUSHR_CONT(command->isPcsContinuous) | SPI_PUSHR_CTAS(command->whichCtar) |
+ SPI_PUSHR_PCS(command->whichPcs) | SPI_PUSHR_EOQ(command->isEndOfQueue) |
+ SPI_PUSHR_CTCNT(command->clearTransferCount) | SPI_PUSHR_TXDATA(data);
+}
+
+/*!
+ * @brief Sets the dspi_command_data_config_t structure to default values.
+ *
+ * The purpose of this API is to get the configuration structure initialized for use in the DSPI_MasterWrite_xx().
+ * User may use the initialized structure unchanged in DSPI_MasterWrite_xx() or modify the structure
+ * before calling DSPI_MasterWrite_xx().
+ * Example:
+ * @code
+ * dspi_command_data_config_t command;
+ * DSPI_GetDefaultDataCommandConfig(&command);
+ * @endcode
+ * @param command pointer to dspi_command_data_config_t structure.
+ */
+void DSPI_GetDefaultDataCommandConfig(dspi_command_data_config_t *command);
+
+/*!
+ * @brief Writes data into the data buffer master mode and waits till complete to return.
+ *
+ * In master mode, the 16-bit data is appended to the 16-bit command info. The command portion
+ * provides characteristics of the data such as the optional continuous chip select
+ * operation between transfers, the desired Clock and Transfer Attributes register to use for the
+ * associated SPI frame, the desired PCS signal to use for the data transfer, whether the current
+ * transfer is the last in the queue, and whether to clear the transfer count (normally needed when
+ * sending the first frame of a data packet). This is an example:
+ * @code
+ * dspi_command_config_t commandConfig;
+ * commandConfig.isPcsContinuous = true;
+ * commandConfig.whichCtar = kDSPICtar0;
+ * commandConfig.whichPcs = kDSPIPcs1;
+ * commandConfig.clearTransferCount = false;
+ * commandConfig.isEndOfQueue = false;
+ * DSPI_MasterWriteDataBlocking(base, &commandConfig, dataWord);
+ * @endcode
+ *
+ * Note that this function does not return until after the transmit is complete. Also note that the DSPI must be
+ * enabled and running to transmit data (MCR[MDIS] & [HALT] = 0). Because the SPI is a synchronous protocol,
+ * receive data is available when transmit completes.
+ *
+ * @param base DSPI peripheral address.
+ * @param command Pointer to command structure.
+ * @param data The data word to be sent.
+ */
+void DSPI_MasterWriteDataBlocking(SPI_Type *base, dspi_command_data_config_t *command, uint16_t data);
+
+/*!
+ * @brief Returns the DSPI command word formatted to the PUSHR data register bit field.
+ *
+ * This function allows the caller to pass in the data command structure and returns the command word formatted
+ * according to the DSPI PUSHR register bit field placement. The user can then "OR" the returned command word with the
+ * desired data to send and use the function DSPI_HAL_WriteCommandDataMastermode or
+ * DSPI_HAL_WriteCommandDataMastermodeBlocking to write the entire 32-bit command data word to the PUSHR. This helps
+ * improve performance in cases where the command structure is constant. For example, the user calls this function
+ * before starting a transfer to generate the command word. When they are ready to transmit the data, they OR
+ * this formatted command word with the desired data to transmit. This process increases transmit performance when
+ * compared to calling send functions such as DSPI_HAL_WriteDataMastermode which format the command word each time a
+ * data word is to be sent.
+ *
+ * @param command Pointer to command structure.
+ * @return The command word formatted to the PUSHR data register bit field.
+ */
+static inline uint32_t DSPI_MasterGetFormattedCommand(dspi_command_data_config_t *command)
+{
+ /* Format the 16-bit command word according to the PUSHR data register bit field*/
+ return (uint32_t)(SPI_PUSHR_CONT(command->isPcsContinuous) | SPI_PUSHR_CTAS(command->whichCtar) |
+ SPI_PUSHR_PCS(command->whichPcs) | SPI_PUSHR_EOQ(command->isEndOfQueue) |
+ SPI_PUSHR_CTCNT(command->clearTransferCount));
+}
+
+/*!
+ * @brief Writes a 32-bit data word (16-bit command appended with 16-bit data) into the data
+ * buffer, master mode and waits till complete to return.
+ *
+ * In this function, the user must append the 16-bit data to the 16-bit command info then provide the total 32-bit word
+ * as the data to send.
+ * The command portion provides characteristics of the data such as the optional continuous chip select operation
+* between
+ * transfers, the desired Clock and Transfer Attributes register to use for the associated SPI frame, the desired PCS
+ * signal to use for the data transfer, whether the current transfer is the last in the queue, and whether to clear the
+ * transfer count (normally needed when sending the first frame of a data packet). The user is responsible for
+ * appending this command with the data to send. This is an example:
+ * @code
+ * dataWord = <16-bit command> | <16-bit data>;
+ * DSPI_HAL_WriteCommandDataMastermodeBlocking(base, dataWord);
+ * @endcode
+ *
+ * Note that this function does not return until after the transmit is complete. Also note that the DSPI must be
+ * enabled and running to transmit data (MCR[MDIS] & [HALT] = 0).
+ * Because the SPI is a synchronous protocol, the receive data is available when transmit completes.
+ *
+ * For a blocking polling transfer, see methods below.
+ * Option 1:
+* uint32_t command_to_send = DSPI_MasterGetFormattedCommand(&command);
+* uint32_t data0 = command_to_send | data_need_to_send_0;
+* uint32_t data1 = command_to_send | data_need_to_send_1;
+* uint32_t data2 = command_to_send | data_need_to_send_2;
+*
+* DSPI_MasterWriteCommandDataBlocking(base,data0);
+* DSPI_MasterWriteCommandDataBlocking(base,data1);
+* DSPI_MasterWriteCommandDataBlocking(base,data2);
+*
+* Option 2:
+* DSPI_MasterWriteDataBlocking(base,&command,data_need_to_send_0);
+* DSPI_MasterWriteDataBlocking(base,&command,data_need_to_send_1);
+* DSPI_MasterWriteDataBlocking(base,&command,data_need_to_send_2);
+*
+ * @param base DSPI peripheral address.
+ * @param data The data word (command and data combined) to be sent
+ */
+void DSPI_MasterWriteCommandDataBlocking(SPI_Type *base, uint32_t data);
+
+/*!
+ * @brief Writes data into the data buffer in slave mode.
+ *
+ * In slave mode, up to 16-bit words may be written.
+ *
+ * @param base DSPI peripheral address.
+ * @param data The data to send.
+ */
+static inline void DSPI_SlaveWriteData(SPI_Type *base, uint32_t data)
+{
+ base->PUSHR_SLAVE = data;
+}
+
+/*!
+ * @brief Writes data into the data buffer in slave mode, waits till data was transmitted, and returns.
+ *
+ * In slave mode, up to 16-bit words may be written. The function first clears the transmit complete flag, writes data
+ * into data register, and finally waits until the data is transmitted.
+ *
+ * @param base DSPI peripheral address.
+ * @param data The data to send.
+ */
+void DSPI_SlaveWriteDataBlocking(SPI_Type *base, uint32_t data);
+
+/*!
+ * @brief Reads data from the data buffer.
+ *
+ * @param base DSPI peripheral address.
+ * @return The data from the read data buffer.
+ */
+static inline uint32_t DSPI_ReadData(SPI_Type *base)
+{
+ return (base->POPR);
+}
+
+/*!
+ *@}
+*/
+
+/*!
+ * @name Transactional
+ * @{
+ */
+/*Transactional APIs*/
+
+/*!
+ * @brief Initializes the DSPI master handle.
+ *
+ * This function initializes the DSPI handle which can be used for other DSPI transactional APIs. Usually, for a
+ * specified DSPI instance, call this API once to get the initialized handle.
+ *
+ * @param base DSPI peripheral base address.
+ * @param handle DSPI handle pointer to dspi_master_handle_t.
+ * @param callback dspi callback.
+ * @param userData callback function parameter.
+ */
+void DSPI_MasterTransferCreateHandle(SPI_Type *base,
+ dspi_master_handle_t *handle,
+ dspi_master_transfer_callback_t callback,
+ void *userData);
+
+/*!
+ * @brief DSPI master transfer data using polling.
+ *
+ * This function transfers data with polling. This is a blocking function, which does not return until all transfers
+ * have been
+ * completed.
+ *
+ * @param base DSPI peripheral base address.
+ * @param transfer pointer to dspi_transfer_t structure.
+ * @return status of status_t.
+ */
+status_t DSPI_MasterTransferBlocking(SPI_Type *base, dspi_transfer_t *transfer);
+
+/*!
+ * @brief DSPI master transfer data using interrupts.
+ *
+ * This function transfers data using interrupts. This is a non-blocking function, which returns right away. When all
+ data
+ * have been transferred, the callback function is called.
+
+ * @param base DSPI peripheral base address.
+ * @param handle pointer to dspi_master_handle_t structure which stores the transfer state.
+ * @param transfer pointer to dspi_transfer_t structure.
+ * @return status of status_t.
+ */
+status_t DSPI_MasterTransferNonBlocking(SPI_Type *base, dspi_master_handle_t *handle, dspi_transfer_t *transfer);
+
+/*!
+ * @brief Gets the master transfer count.
+ *
+ * This function gets the master transfer count.
+ *
+ * @param base DSPI peripheral base address.
+ * @param handle pointer to dspi_master_handle_t structure which stores the transfer state.
+ * @param count Number of bytes transferred so far by the non-blocking transaction.
+ * @return status of status_t.
+ */
+status_t DSPI_MasterTransferGetCount(SPI_Type *base, dspi_master_handle_t *handle, size_t *count);
+
+/*!
+ * @brief DSPI master aborts transfer using an interrupt.
+ *
+ * This function aborts a transfer using an interrupt.
+ *
+ * @param base DSPI peripheral base address.
+ * @param handle pointer to dspi_master_handle_t structure which stores the transfer state.
+ */
+void DSPI_MasterTransferAbort(SPI_Type *base, dspi_master_handle_t *handle);
+
+/*!
+ * @brief DSPI Master IRQ handler function.
+ *
+ * This function processes the DSPI transmit and receive IRQ.
+
+ * @param base DSPI peripheral base address.
+ * @param handle pointer to dspi_master_handle_t structure which stores the transfer state.
+ */
+void DSPI_MasterTransferHandleIRQ(SPI_Type *base, dspi_master_handle_t *handle);
+
+/*!
+ * @brief Initializes the DSPI slave handle.
+ *
+ * This function initializes the DSPI handle, which can be used for other DSPI transactional APIs. Usually, for a
+ * specified DSPI instance, call this API once to get the initialized handle.
+ *
+ * @param handle DSPI handle pointer to dspi_slave_handle_t.
+ * @param base DSPI peripheral base address.
+ * @param callback DSPI callback.
+ * @param userData callback function parameter.
+ */
+void DSPI_SlaveTransferCreateHandle(SPI_Type *base,
+ dspi_slave_handle_t *handle,
+ dspi_slave_transfer_callback_t callback,
+ void *userData);
+
+/*!
+ * @brief DSPI slave transfers data using an interrupt.
+ *
+ * This function transfers data using an interrupt. This is a non-blocking function, which returns right away. When all
+ * data
+ * have been transferred, the callback function is called.
+ *
+ * @param base DSPI peripheral base address.
+ * @param handle pointer to dspi_slave_handle_t structure which stores the transfer state.
+ * @param transfer pointer to dspi_transfer_t structure.
+ * @return status of status_t.
+ */
+status_t DSPI_SlaveTransferNonBlocking(SPI_Type *base, dspi_slave_handle_t *handle, dspi_transfer_t *transfer);
+
+/*!
+ * @brief Gets the slave transfer count.
+ *
+ * This function gets the slave transfer count.
+ *
+ * @param base DSPI peripheral base address.
+ * @param handle pointer to dspi_master_handle_t structure which stores the transfer state.
+ * @param count Number of bytes transferred so far by the non-blocking transaction.
+ * @return status of status_t.
+ */
+status_t DSPI_SlaveTransferGetCount(SPI_Type *base, dspi_slave_handle_t *handle, size_t *count);
+
+/*!
+ * @brief DSPI slave aborts a transfer using an interrupt.
+ *
+ * This function aborts transfer using an interrupt.
+ *
+ * @param base DSPI peripheral base address.
+ * @param handle pointer to dspi_slave_handle_t structure which stores the transfer state.
+ */
+void DSPI_SlaveTransferAbort(SPI_Type *base, dspi_slave_handle_t *handle);
+
+/*!
+ * @brief DSPI Master IRQ handler function.
+ *
+ * This function processes the DSPI transmit and receive IRQ.
+ *
+ * @param base DSPI peripheral base address.
+ * @param handle pointer to dspi_slave_handle_t structure which stores the transfer state.
+ */
+void DSPI_SlaveTransferHandleIRQ(SPI_Type *base, dspi_slave_handle_t *handle);
+
+/*!
+ *@}
+*/
+
+#if defined(__cplusplus)
+}
+#endif /*_cplusplus*/
+ /*!
+ *@}
+ */
+
+#endif /*_FSL_DSPI_H_*/
diff --git a/drivers/fsl_dspi_edma.c b/drivers/fsl_dspi_edma.c
new file mode 100644
index 0000000..a1c2002
--- /dev/null
+++ b/drivers/fsl_dspi_edma.c
@@ -0,0 +1,1263 @@
+/*
+* Copyright (c) 2015, Freescale Semiconductor, Inc.
+* All rights reserved.
+*
+* 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 Freescale Semiconductor, Inc. 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_dspi_edma.h"
+
+/***********************************************************************************************************************
+* Definitons
+***********************************************************************************************************************/
+
+/*!
+* @brief Structure definition for dspi_master_edma_private_handle_t. The structure is private.
+*/
+typedef struct _dspi_master_edma_private_handle
+{
+ SPI_Type *base; /*!< DSPI peripheral base address. */
+ dspi_master_edma_handle_t *handle; /*!< dspi_master_edma_handle_t handle */
+} dspi_master_edma_private_handle_t;
+
+/*!
+* @brief Structure definition for dspi_slave_edma_private_handle_t. The structure is private.
+*/
+typedef struct _dspi_slave_edma_private_handle
+{
+ SPI_Type *base; /*!< DSPI peripheral base address. */
+ dspi_slave_edma_handle_t *handle; /*!< dspi_master_edma_handle_t handle */
+} dspi_slave_edma_private_handle_t;
+
+/***********************************************************************************************************************
+* Prototypes
+***********************************************************************************************************************/
+/*!
+* @brief EDMA_DspiMasterCallback after the DSPI master transfer completed by using EDMA.
+* This is not a public API as it is called from other driver functions.
+*/
+static void EDMA_DspiMasterCallback(edma_handle_t *edmaHandle,
+ void *g_dspiEdmaPrivateHandle,
+ bool transferDone,
+ uint32_t tcds);
+
+/*!
+* @brief EDMA_DspiSlaveCallback after the DSPI slave transfer completed by using EDMA.
+* This is not a public API as it is called from other driver functions.
+*/
+static void EDMA_DspiSlaveCallback(edma_handle_t *edmaHandle,
+ void *g_dspiEdmaPrivateHandle,
+ bool transferDone,
+ uint32_t tcds);
+/*!
+* @brief Get instance number for DSPI module.
+*
+* This is not a public API and it's extern from fsl_dspi.c.
+*
+* @param base DSPI peripheral base address
+*/
+extern uint32_t DSPI_GetInstance(SPI_Type *base);
+
+/***********************************************************************************************************************
+* Variables
+***********************************************************************************************************************/
+
+/*! @brief Pointers to dspi edma handles for each instance. */
+static dspi_master_edma_private_handle_t s_dspiMasterEdmaPrivateHandle[FSL_FEATURE_SOC_DSPI_COUNT];
+static dspi_slave_edma_private_handle_t s_dspiSlaveEdmaPrivateHandle[FSL_FEATURE_SOC_DSPI_COUNT];
+
+/***********************************************************************************************************************
+* Code
+***********************************************************************************************************************/
+
+void DSPI_MasterTransferCreateHandleEDMA(SPI_Type *base,
+ dspi_master_edma_handle_t *handle,
+ dspi_master_edma_transfer_callback_t callback,
+ void *userData,
+ edma_handle_t *edmaRxRegToRxDataHandle,
+ edma_handle_t *edmaTxDataToIntermediaryHandle,
+ edma_handle_t *edmaIntermediaryToTxRegHandle)
+{
+ assert(handle);
+
+ /* Zero the handle. */
+ memset(handle, 0, sizeof(*handle));
+
+ uint32_t instance = DSPI_GetInstance(base);
+
+ s_dspiMasterEdmaPrivateHandle[instance].base = base;
+ s_dspiMasterEdmaPrivateHandle[instance].handle = handle;
+
+ handle->callback = callback;
+ handle->userData = userData;
+
+ handle->edmaRxRegToRxDataHandle = edmaRxRegToRxDataHandle;
+ handle->edmaTxDataToIntermediaryHandle = edmaTxDataToIntermediaryHandle;
+ handle->edmaIntermediaryToTxRegHandle = edmaIntermediaryToTxRegHandle;
+}
+
+status_t DSPI_MasterTransferEDMA(SPI_Type *base, dspi_master_edma_handle_t *handle, dspi_transfer_t *transfer)
+{
+ assert(handle && transfer);
+
+ /* If the transfer count is zero, then return immediately.*/
+ if (transfer->dataSize == 0)
+ {
+ return kStatus_InvalidArgument;
+ }
+
+ /* If both send buffer and receive buffer is null */
+ if ((!(transfer->txData)) && (!(transfer->rxData)))
+ {
+ return kStatus_InvalidArgument;
+ }
+
+ /* Check that we're not busy.*/
+ if (handle->state == kDSPI_Busy)
+ {
+ return kStatus_DSPI_Busy;
+ }
+
+ uint32_t instance = DSPI_GetInstance(base);
+ uint16_t wordToSend = 0;
+ uint8_t dummyData = DSPI_DUMMY_DATA;
+ uint8_t dataAlreadyFed = 0;
+ uint8_t dataFedMax = 2;
+
+ uint32_t rxAddr = DSPI_GetRxRegisterAddress(base);
+ uint32_t txAddr = DSPI_MasterGetTxRegisterAddress(base);
+
+ edma_tcd_t *softwareTCD = (edma_tcd_t *)((uint32_t)(&handle->dspiSoftwareTCD[1]) & (~0x1FU));
+
+ edma_transfer_config_t transferConfigA;
+ edma_transfer_config_t transferConfigB;
+ edma_transfer_config_t transferConfigC;
+
+ handle->txBuffIfNull = ((uint32_t)DSPI_DUMMY_DATA << 8) | DSPI_DUMMY_DATA;
+
+ handle->state = kDSPI_Busy;
+
+ dspi_command_data_config_t commandStruct;
+ DSPI_StopTransfer(base);
+ DSPI_FlushFifo(base, true, true);
+ DSPI_ClearStatusFlags(base, kDSPI_AllStatusFlag);
+
+ commandStruct.whichPcs =
+ (dspi_which_pcs_t)(1U << ((transfer->configFlags & DSPI_MASTER_PCS_MASK) >> DSPI_MASTER_PCS_SHIFT));
+ commandStruct.isEndOfQueue = false;
+ commandStruct.clearTransferCount = false;
+ commandStruct.whichCtar =
+ (dspi_ctar_selection_t)((transfer->configFlags & DSPI_MASTER_CTAR_MASK) >> DSPI_MASTER_CTAR_SHIFT);
+ commandStruct.isPcsContinuous = (bool)(transfer->configFlags & kDSPI_MasterPcsContinuous);
+ handle->command = DSPI_MasterGetFormattedCommand(&(commandStruct));
+
+ commandStruct.isEndOfQueue = true;
+ commandStruct.isPcsContinuous = (bool)(transfer->configFlags & kDSPI_MasterActiveAfterTransfer);
+ handle->lastCommand = DSPI_MasterGetFormattedCommand(&(commandStruct));
+
+ handle->bitsPerFrame = ((base->CTAR[commandStruct.whichCtar] & SPI_CTAR_FMSZ_MASK) >> SPI_CTAR_FMSZ_SHIFT) + 1;
+
+ if ((base->MCR & SPI_MCR_DIS_RXF_MASK) || (base->MCR & SPI_MCR_DIS_TXF_MASK))
+ {
+ handle->fifoSize = 1;
+ }
+ else
+ {
+ handle->fifoSize = FSL_FEATURE_DSPI_FIFO_SIZEn(base);
+ }
+ handle->txData = transfer->txData;
+ handle->rxData = transfer->rxData;
+ handle->remainingSendByteCount = transfer->dataSize;
+ handle->remainingReceiveByteCount = transfer->dataSize;
+ handle->totalByteCount = transfer->dataSize;
+
+ /* this limits the amount of data we can transfer due to the linked channel.
+ * The max bytes is 511 if 8-bit/frame or 1022 if 16-bit/frame
+ */
+ if (handle->bitsPerFrame > 8)
+ {
+ if (transfer->dataSize > 1022)
+ {
+ return kStatus_DSPI_OutOfRange;
+ }
+ }
+ else
+ {
+ if (transfer->dataSize > 511)
+ {
+ return kStatus_DSPI_OutOfRange;
+ }
+ }
+
+ DSPI_DisableDMA(base, kDSPI_RxDmaEnable | kDSPI_TxDmaEnable);
+
+ EDMA_SetCallback(handle->edmaRxRegToRxDataHandle, EDMA_DspiMasterCallback,
+ &s_dspiMasterEdmaPrivateHandle[instance]);
+
+ handle->isThereExtraByte = false;
+ if (handle->bitsPerFrame > 8)
+ {
+ if (handle->remainingSendByteCount % 2 == 1)
+ {
+ handle->remainingSendByteCount++;
+ handle->remainingReceiveByteCount--;
+ handle->isThereExtraByte = true;
+ }
+ }
+
+ /*If dspi has separate dma request , prepare the first data in "intermediary" .
+ else (dspi has shared dma request) , send first 2 data if there is fifo or send first 1 data if there is no fifo*/
+ if (1 == FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base))
+ {
+ /* For DSPI instances with separate RX/TX DMA requests, we'll use the TX DMA request to
+ * trigger the TX DMA channel and RX DMA request to trigger the RX DMA channel
+ */
+
+ /*Prepare the firt data*/
+ if (handle->bitsPerFrame > 8)
+ {
+ /* If it's the last word */
+ if (handle->remainingSendByteCount <= 2)
+ {
+ if (handle->txData)
+ {
+ if (handle->isThereExtraByte)
+ {
+ wordToSend = *(handle->txData) | ((uint32_t)dummyData << 8);
+ }
+ else
+ {
+ wordToSend = *(handle->txData);
+ ++handle->txData; /* increment to next data byte */
+ wordToSend |= (unsigned)(*(handle->txData)) << 8U;
+ }
+ }
+ else
+ {
+ wordToSend = ((uint32_t)dummyData << 8) | dummyData;
+ }
+ handle->lastCommand = (handle->lastCommand & 0xffff0000U) | wordToSend;
+ }
+ else /* For all words except the last word , frame > 8bits */
+ {
+ if (handle->txData)
+ {
+ wordToSend = *(handle->txData);
+ ++handle->txData; /* increment to next data byte */
+ wordToSend |= (unsigned)(*(handle->txData)) << 8U;
+ ++handle->txData; /* increment to next data byte */
+ }
+ else
+ {
+ wordToSend = ((uint32_t)dummyData << 8) | dummyData;
+ }
+ handle->command = (handle->command & 0xffff0000U) | wordToSend;
+ }
+ }
+ else /* Optimized for bits/frame less than or equal to one byte. */
+ {
+ if (handle->txData)
+ {
+ wordToSend = *(handle->txData);
+ ++handle->txData; /* increment to next data word*/
+ }
+ else
+ {
+ wordToSend = dummyData;
+ }
+
+ if (handle->remainingSendByteCount == 1)
+ {
+ handle->lastCommand = (handle->lastCommand & 0xffff0000U) | wordToSend;
+ }
+ else
+ {
+ handle->command = (handle->command & 0xffff0000U) | wordToSend;
+ }
+ }
+ }
+
+ else /*dspi has shared dma request*/
+
+ {
+ /* For DSPI instances with shared RX/TX DMA requests, we'll use the RX DMA request to
+ * trigger ongoing transfers and will link to the TX DMA channel from the RX DMA channel.
+ */
+
+ /* If bits/frame is greater than one byte */
+ if (handle->bitsPerFrame > 8)
+ {
+ while (DSPI_GetStatusFlags(base) & kDSPI_TxFifoFillRequestFlag)
+ {
+ if (handle->remainingSendByteCount <= 2)
+ {
+ if (handle->txData)
+ {
+ if (handle->isThereExtraByte)
+ {
+ wordToSend = *(handle->txData) | ((uint32_t)dummyData << 8);
+ }
+ else
+ {
+ wordToSend = *(handle->txData);
+ ++handle->txData;
+ wordToSend |= (unsigned)(*(handle->txData)) << 8U;
+ }
+ }
+ else
+ {
+ wordToSend = ((uint32_t)dummyData << 8) | dummyData;
+ ;
+ }
+ handle->remainingSendByteCount = 0;
+ base->PUSHR = (handle->lastCommand & 0xffff0000U) | wordToSend;
+ }
+ /* For all words except the last word */
+ else
+ {
+ if (handle->txData)
+ {
+ wordToSend = *(handle->txData);
+ ++handle->txData;
+ wordToSend |= (unsigned)(*(handle->txData)) << 8U;
+ ++handle->txData;
+ }
+ else
+ {
+ wordToSend = ((uint32_t)dummyData << 8) | dummyData;
+ ;
+ }
+ handle->remainingSendByteCount -= 2;
+ base->PUSHR = (handle->command & 0xffff0000U) | wordToSend;
+ }
+
+ /* Try to clear the TFFF; if the TX FIFO is full this will clear */
+ DSPI_ClearStatusFlags(base, kDSPI_TxFifoFillRequestFlag);
+
+ dataAlreadyFed += 2;
+
+ /* exit loop if send count is zero, else update local variables for next loop */
+ if ((handle->remainingSendByteCount == 0) || (dataAlreadyFed == (dataFedMax * 2)))
+ {
+ break;
+ }
+ } /* End of TX FIFO fill while loop */
+ }
+ else /* Optimized for bits/frame less than or equal to one byte. */
+ {
+ while (DSPI_GetStatusFlags(base) & kDSPI_TxFifoFillRequestFlag)
+ {
+ if (handle->txData)
+ {
+ wordToSend = *(handle->txData);
+ ++handle->txData;
+ }
+ else
+ {
+ wordToSend = dummyData;
+ }
+
+ if (handle->remainingSendByteCount == 1)
+ {
+ base->PUSHR = (handle->lastCommand & 0xffff0000U) | wordToSend;
+ }
+ else
+ {
+ base->PUSHR = (handle->command & 0xffff0000U) | wordToSend;
+ }
+
+ /* Try to clear the TFFF; if the TX FIFO is full this will clear */
+ DSPI_ClearStatusFlags(base, kDSPI_TxFifoFillRequestFlag);
+
+ --handle->remainingSendByteCount;
+
+ dataAlreadyFed++;
+
+ /* exit loop if send count is zero, else update local variables for next loop */
+ if ((handle->remainingSendByteCount == 0) || (dataAlreadyFed == dataFedMax))
+ {
+ break;
+ }
+ } /* End of TX FIFO fill while loop */
+ }
+ }
+
+ /***channel_A *** used for carry the data from Rx_Data_Register(POPR) to User_Receive_Buffer*/
+ EDMA_ResetChannel(handle->edmaRxRegToRxDataHandle->base, handle->edmaRxRegToRxDataHandle->channel);
+
+ transferConfigA.srcAddr = (uint32_t)rxAddr;
+ transferConfigA.srcOffset = 0;
+
+ if (handle->rxData)
+ {
+ transferConfigA.destAddr = (uint32_t) & (handle->rxData[0]);
+ transferConfigA.destOffset = 1;
+ }
+ else
+ {
+ transferConfigA.destAddr = (uint32_t) & (handle->rxBuffIfNull);
+ transferConfigA.destOffset = 0;
+ }
+
+ transferConfigA.destTransferSize = kEDMA_TransferSize1Bytes;
+
+ if (handle->bitsPerFrame <= 8)
+ {
+ transferConfigA.srcTransferSize = kEDMA_TransferSize1Bytes;
+ transferConfigA.minorLoopBytes = 1;
+ transferConfigA.majorLoopCounts = handle->remainingReceiveByteCount;
+ }
+ else
+ {
+ transferConfigA.srcTransferSize = kEDMA_TransferSize2Bytes;
+ transferConfigA.minorLoopBytes = 2;
+ transferConfigA.majorLoopCounts = handle->remainingReceiveByteCount / 2;
+ }
+ EDMA_SetTransferConfig(handle->edmaRxRegToRxDataHandle->base, handle->edmaRxRegToRxDataHandle->channel,
+ &transferConfigA, NULL);
+ EDMA_EnableChannelInterrupts(handle->edmaRxRegToRxDataHandle->base, handle->edmaRxRegToRxDataHandle->channel,
+ kEDMA_MajorInterruptEnable);
+
+ /***channel_B *** used for carry the data from User_Send_Buffer to "intermediary" because the SPIx_PUSHR should
+ write the 32bits at once time . Then use channel_C to carry the "intermediary" to SPIx_PUSHR. Note that the
+ SPIx_PUSHR upper 16 bits are the "command" and the low 16bits are data */
+ EDMA_ResetChannel(handle->edmaTxDataToIntermediaryHandle->base, handle->edmaTxDataToIntermediaryHandle->channel);
+
+ if (handle->remainingSendByteCount > 0)
+ {
+ if (handle->txData)
+ {
+ transferConfigB.srcAddr = (uint32_t)(handle->txData);
+ transferConfigB.srcOffset = 1;
+ }
+ else
+ {
+ transferConfigB.srcAddr = (uint32_t)(&handle->txBuffIfNull);
+ transferConfigB.srcOffset = 0;
+ }
+
+ transferConfigB.destAddr = (uint32_t)(&handle->command);
+ transferConfigB.destOffset = 0;
+
+ transferConfigB.srcTransferSize = kEDMA_TransferSize1Bytes;
+
+ if (handle->bitsPerFrame <= 8)
+ {
+ transferConfigB.destTransferSize = kEDMA_TransferSize1Bytes;
+ transferConfigB.minorLoopBytes = 1;
+
+ if (1 == FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base))
+ {
+ /*already prepared the first data in "intermediary" , so minus 1 */
+ transferConfigB.majorLoopCounts = handle->remainingSendByteCount - 1;
+ }
+ else
+ {
+ /*Only enable channel_B minorlink to channel_C , so need to add one count due to the last time is
+ majorlink , the majorlink would not trigger the channel_C*/
+ transferConfigB.majorLoopCounts = handle->remainingSendByteCount + 1;
+ }
+ }
+ else
+ {
+ transferConfigB.destTransferSize = kEDMA_TransferSize2Bytes;
+ transferConfigB.minorLoopBytes = 2;
+ if (1 == FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base))
+ {
+ /*already prepared the first data in "intermediary" , so minus 1 */
+ transferConfigB.majorLoopCounts = handle->remainingSendByteCount / 2 - 1;
+ }
+ else
+ {
+ /*Only enable channel_B minorlink to channel_C , so need to add one count due to the last time is
+ * majorlink*/
+ transferConfigB.majorLoopCounts = handle->remainingSendByteCount / 2 + 1;
+ }
+ }
+
+ EDMA_SetTransferConfig(handle->edmaTxDataToIntermediaryHandle->base,
+ handle->edmaTxDataToIntermediaryHandle->channel, &transferConfigB, NULL);
+ }
+
+ /***channel_C ***carry the "intermediary" to SPIx_PUSHR. used the edma Scatter Gather function on channel_C to
+ handle the last data */
+ EDMA_ResetChannel(handle->edmaIntermediaryToTxRegHandle->base, handle->edmaIntermediaryToTxRegHandle->channel);
+
+ if (((handle->remainingSendByteCount > 0) && (1 != FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base))) ||
+ ((((handle->remainingSendByteCount > 1) && (handle->bitsPerFrame <= 8)) ||
+ ((handle->remainingSendByteCount > 2) && (handle->bitsPerFrame > 8))) &&
+ (1 == FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base))))
+ {
+ if (handle->txData)
+ {
+ uint32_t bufferIndex = 0;
+
+ if (1 == FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base))
+ {
+ if (handle->bitsPerFrame <= 8)
+ {
+ bufferIndex = handle->remainingSendByteCount - 1;
+ }
+ else
+ {
+ bufferIndex = handle->remainingSendByteCount - 2;
+ }
+ }
+ else
+ {
+ bufferIndex = handle->remainingSendByteCount;
+ }
+
+ if (handle->bitsPerFrame <= 8)
+ {
+ handle->lastCommand = (handle->lastCommand & 0xffff0000U) | handle->txData[bufferIndex - 1];
+ }
+ else
+ {
+ if (handle->isThereExtraByte)
+ {
+ handle->lastCommand = (handle->lastCommand & 0xffff0000U) | handle->txData[bufferIndex - 2] |
+ ((uint32_t)dummyData << 8);
+ }
+ else
+ {
+ handle->lastCommand = (handle->lastCommand & 0xffff0000U) |
+ ((uint32_t)handle->txData[bufferIndex - 1] << 8) |
+ handle->txData[bufferIndex - 2];
+ }
+ }
+ }
+ else
+ {
+ if (handle->bitsPerFrame <= 8)
+ {
+ wordToSend = dummyData;
+ }
+ else
+ {
+ wordToSend = ((uint32_t)dummyData << 8) | dummyData;
+ }
+ handle->lastCommand = (handle->lastCommand & 0xffff0000U) | wordToSend;
+ }
+ }
+
+ if ((1 == FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base)) ||
+ ((1 != FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base)) && (handle->remainingSendByteCount > 0)))
+ {
+ transferConfigC.srcAddr = (uint32_t) & (handle->lastCommand);
+ transferConfigC.destAddr = (uint32_t)txAddr;
+ transferConfigC.srcTransferSize = kEDMA_TransferSize4Bytes;
+ transferConfigC.destTransferSize = kEDMA_TransferSize4Bytes;
+ transferConfigC.srcOffset = 0;
+ transferConfigC.destOffset = 0;
+ transferConfigC.minorLoopBytes = 4;
+ transferConfigC.majorLoopCounts = 1;
+
+ EDMA_TcdReset(softwareTCD);
+ EDMA_TcdSetTransferConfig(softwareTCD, &transferConfigC, NULL);
+ }
+
+ if (((handle->remainingSendByteCount > 1) && (handle->bitsPerFrame <= 8)) ||
+ ((handle->remainingSendByteCount > 2) && (handle->bitsPerFrame > 8)))
+ {
+ transferConfigC.srcAddr = (uint32_t)(&(handle->command));
+ transferConfigC.destAddr = (uint32_t)txAddr;
+
+ transferConfigC.srcTransferSize = kEDMA_TransferSize4Bytes;
+ transferConfigC.destTransferSize = kEDMA_TransferSize4Bytes;
+ transferConfigC.srcOffset = 0;
+ transferConfigC.destOffset = 0;
+ transferConfigC.minorLoopBytes = 4;
+
+ if (handle->bitsPerFrame <= 8)
+ {
+ transferConfigC.majorLoopCounts = handle->remainingSendByteCount - 1;
+ }
+ else
+ {
+ transferConfigC.majorLoopCounts = handle->remainingSendByteCount / 2 - 1;
+ }
+
+ EDMA_SetTransferConfig(handle->edmaIntermediaryToTxRegHandle->base,
+ handle->edmaIntermediaryToTxRegHandle->channel, &transferConfigC, softwareTCD);
+ EDMA_EnableAutoStopRequest(handle->edmaIntermediaryToTxRegHandle->base,
+ handle->edmaIntermediaryToTxRegHandle->channel, false);
+ }
+ else
+ {
+ EDMA_SetTransferConfig(handle->edmaIntermediaryToTxRegHandle->base,
+ handle->edmaIntermediaryToTxRegHandle->channel, &transferConfigC, NULL);
+ }
+
+ /*Start the EDMA channel_A , channel_B , channel_C transfer*/
+ EDMA_StartTransfer(handle->edmaRxRegToRxDataHandle);
+ EDMA_StartTransfer(handle->edmaTxDataToIntermediaryHandle);
+ EDMA_StartTransfer(handle->edmaIntermediaryToTxRegHandle);
+
+ /*Set channel priority*/
+ uint8_t channelPriorityLow = handle->edmaRxRegToRxDataHandle->channel;
+ uint8_t channelPriorityMid = handle->edmaTxDataToIntermediaryHandle->channel;
+ uint8_t channelPriorityHigh = handle->edmaIntermediaryToTxRegHandle->channel;
+ uint8_t t = 0;
+ if (channelPriorityLow > channelPriorityMid)
+ {
+ t = channelPriorityLow;
+ channelPriorityLow = channelPriorityMid;
+ channelPriorityMid = t;
+ }
+
+ if (channelPriorityLow > channelPriorityHigh)
+ {
+ t = channelPriorityLow;
+ channelPriorityLow = channelPriorityHigh;
+ channelPriorityHigh = t;
+ }
+
+ if (channelPriorityMid > channelPriorityHigh)
+ {
+ t = channelPriorityMid;
+ channelPriorityMid = channelPriorityHigh;
+ channelPriorityHigh = t;
+ }
+ edma_channel_Preemption_config_t preemption_config_t;
+ preemption_config_t.enableChannelPreemption = true;
+ preemption_config_t.enablePreemptAbility = true;
+ preemption_config_t.channelPriority = channelPriorityLow;
+
+ if (1 != FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base))
+ {
+ EDMA_SetChannelPreemptionConfig(handle->edmaRxRegToRxDataHandle->base, handle->edmaRxRegToRxDataHandle->channel,
+ &preemption_config_t);
+
+ preemption_config_t.channelPriority = channelPriorityMid;
+ EDMA_SetChannelPreemptionConfig(handle->edmaTxDataToIntermediaryHandle->base,
+ handle->edmaTxDataToIntermediaryHandle->channel, &preemption_config_t);
+
+ preemption_config_t.channelPriority = channelPriorityHigh;
+ EDMA_SetChannelPreemptionConfig(handle->edmaIntermediaryToTxRegHandle->base,
+ handle->edmaIntermediaryToTxRegHandle->channel, &preemption_config_t);
+ }
+ else
+ {
+ EDMA_SetChannelPreemptionConfig(handle->edmaIntermediaryToTxRegHandle->base,
+ handle->edmaIntermediaryToTxRegHandle->channel, &preemption_config_t);
+
+ preemption_config_t.channelPriority = channelPriorityMid;
+ EDMA_SetChannelPreemptionConfig(handle->edmaTxDataToIntermediaryHandle->base,
+ handle->edmaTxDataToIntermediaryHandle->channel, &preemption_config_t);
+
+ preemption_config_t.channelPriority = channelPriorityHigh;
+ EDMA_SetChannelPreemptionConfig(handle->edmaRxRegToRxDataHandle->base, handle->edmaRxRegToRxDataHandle->channel,
+ &preemption_config_t);
+ }
+
+ /*Set the channel link.
+ For DSPI instances with shared RX/TX DMA requests: Rx DMA request -> channel_A -> channel_B-> channel_C.
+ For DSPI instances with separate RX and TX DMA requests:
+ Rx DMA request -> channel_A
+ Tx DMA request -> channel_C -> channel_B . (so need prepare the first data in "intermediary" before the DMA
+ transfer and then channel_B is used to prepare the next data to "intermediary" ) */
+ if (1 == FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base))
+ {
+ /*if there is Tx DMA request , carry the 32bits data (handle->command) to PUSHR first , then link to channelB
+ to prepare the next 32bits data (User_send_buffer to handle->command) */
+ if (handle->remainingSendByteCount > 1)
+ {
+ EDMA_SetChannelLink(handle->edmaIntermediaryToTxRegHandle->base,
+ handle->edmaIntermediaryToTxRegHandle->channel, kEDMA_MinorLink,
+ handle->edmaTxDataToIntermediaryHandle->channel);
+ }
+
+ DSPI_EnableDMA(base, kDSPI_RxDmaEnable | kDSPI_TxDmaEnable);
+ }
+ else
+ {
+ if (handle->remainingSendByteCount > 0)
+ {
+ EDMA_SetChannelLink(handle->edmaRxRegToRxDataHandle->base, handle->edmaRxRegToRxDataHandle->channel,
+ kEDMA_MinorLink, handle->edmaTxDataToIntermediaryHandle->channel);
+
+ if (handle->isThereExtraByte)
+ {
+ EDMA_SetChannelLink(handle->edmaRxRegToRxDataHandle->base, handle->edmaRxRegToRxDataHandle->channel,
+ kEDMA_MajorLink, handle->edmaTxDataToIntermediaryHandle->channel);
+ }
+
+ EDMA_SetChannelLink(handle->edmaTxDataToIntermediaryHandle->base,
+ handle->edmaTxDataToIntermediaryHandle->channel, kEDMA_MinorLink,
+ handle->edmaIntermediaryToTxRegHandle->channel);
+ }
+
+ DSPI_EnableDMA(base, kDSPI_RxDmaEnable);
+ }
+
+ DSPI_StartTransfer(base);
+
+ return kStatus_Success;
+}
+
+static void EDMA_DspiMasterCallback(edma_handle_t *edmaHandle,
+ void *g_dspiEdmaPrivateHandle,
+ bool transferDone,
+ uint32_t tcds)
+{
+ dspi_master_edma_private_handle_t *dspiEdmaPrivateHandle;
+
+ dspiEdmaPrivateHandle = (dspi_master_edma_private_handle_t *)g_dspiEdmaPrivateHandle;
+
+ uint32_t dataReceived;
+
+ DSPI_DisableDMA((dspiEdmaPrivateHandle->base), kDSPI_RxDmaEnable | kDSPI_TxDmaEnable);
+
+ if (dspiEdmaPrivateHandle->handle->isThereExtraByte)
+ {
+ while (!((dspiEdmaPrivateHandle->base)->SR & SPI_SR_RFDF_MASK))
+ {
+ }
+ dataReceived = (dspiEdmaPrivateHandle->base)->POPR;
+ if (dspiEdmaPrivateHandle->handle->rxData)
+ {
+ (dspiEdmaPrivateHandle->handle->rxData[dspiEdmaPrivateHandle->handle->totalByteCount - 1]) = dataReceived;
+ }
+ }
+
+ if (dspiEdmaPrivateHandle->handle->callback)
+ {
+ dspiEdmaPrivateHandle->handle->callback(dspiEdmaPrivateHandle->base, dspiEdmaPrivateHandle->handle,
+ kStatus_Success, dspiEdmaPrivateHandle->handle->userData);
+ }
+
+ dspiEdmaPrivateHandle->handle->state = kDSPI_Idle;
+}
+
+void DSPI_MasterTransferAbortEDMA(SPI_Type *base, dspi_master_edma_handle_t *handle)
+{
+ DSPI_StopTransfer(base);
+
+ DSPI_DisableDMA(base, kDSPI_RxDmaEnable | kDSPI_TxDmaEnable);
+
+ EDMA_AbortTransfer(handle->edmaRxRegToRxDataHandle);
+ EDMA_AbortTransfer(handle->edmaTxDataToIntermediaryHandle);
+ EDMA_AbortTransfer(handle->edmaIntermediaryToTxRegHandle);
+
+ handle->state = kDSPI_Idle;
+}
+
+status_t DSPI_MasterTransferGetCountEDMA(SPI_Type *base, dspi_master_edma_handle_t *handle, size_t *count)
+{
+ assert(handle);
+
+ if (!count)
+ {
+ return kStatus_InvalidArgument;
+ }
+
+ /* Catch when there is not an active transfer. */
+ if (handle->state != kDSPI_Busy)
+ {
+ *count = 0;
+ return kStatus_NoTransferInProgress;
+ }
+
+ size_t bytes;
+
+ bytes = EDMA_GetRemainingBytes(handle->edmaRxRegToRxDataHandle->base, handle->edmaRxRegToRxDataHandle->channel);
+
+ *count = handle->totalByteCount - bytes;
+
+ return kStatus_Success;
+}
+
+void DSPI_SlaveTransferCreateHandleEDMA(SPI_Type *base,
+ dspi_slave_edma_handle_t *handle,
+ dspi_slave_edma_transfer_callback_t callback,
+ void *userData,
+ edma_handle_t *edmaRxRegToRxDataHandle,
+ edma_handle_t *edmaTxDataToTxRegHandle)
+{
+ assert(handle);
+
+ /* Zero the handle. */
+ memset(handle, 0, sizeof(*handle));
+
+ uint32_t instance = DSPI_GetInstance(base);
+
+ s_dspiSlaveEdmaPrivateHandle[instance].base = base;
+ s_dspiSlaveEdmaPrivateHandle[instance].handle = handle;
+
+ handle->callback = callback;
+ handle->userData = userData;
+
+ handle->edmaRxRegToRxDataHandle = edmaRxRegToRxDataHandle;
+ handle->edmaTxDataToTxRegHandle = edmaTxDataToTxRegHandle;
+}
+
+status_t DSPI_SlaveTransferEDMA(SPI_Type *base, dspi_slave_edma_handle_t *handle, dspi_transfer_t *transfer)
+{
+ assert(handle && transfer);
+
+ /* If send/receive length is zero */
+ if (transfer->dataSize == 0)
+ {
+ return kStatus_InvalidArgument;
+ }
+
+ /* If both send buffer and receive buffer is null */
+ if ((!(transfer->txData)) && (!(transfer->rxData)))
+ {
+ return kStatus_InvalidArgument;
+ }
+
+ /* Check that we're not busy.*/
+ if (handle->state == kDSPI_Busy)
+ {
+ return kStatus_DSPI_Busy;
+ }
+
+ edma_tcd_t *softwareTCD = (edma_tcd_t *)((uint32_t)(&handle->dspiSoftwareTCD[1]) & (~0x1FU));
+
+ uint32_t instance = DSPI_GetInstance(base);
+ uint8_t whichCtar = (transfer->configFlags & DSPI_SLAVE_CTAR_MASK) >> DSPI_SLAVE_CTAR_SHIFT;
+ handle->bitsPerFrame =
+ (((base->CTAR_SLAVE[whichCtar]) & SPI_CTAR_SLAVE_FMSZ_MASK) >> SPI_CTAR_SLAVE_FMSZ_SHIFT) + 1;
+
+ /* If using a shared RX/TX DMA request, then this limits the amount of data we can transfer
+ * due to the linked channel. The max bytes is 511 if 8-bit/frame or 1022 if 16-bit/frame
+ */
+ if (1 != FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base))
+ {
+ if (handle->bitsPerFrame > 8)
+ {
+ if (transfer->dataSize > 1022)
+ {
+ return kStatus_DSPI_OutOfRange;
+ }
+ }
+ else
+ {
+ if (transfer->dataSize > 511)
+ {
+ return kStatus_DSPI_OutOfRange;
+ }
+ }
+ }
+
+ if ((handle->bitsPerFrame > 8) && (transfer->dataSize < 2))
+ {
+ return kStatus_InvalidArgument;
+ }
+
+ EDMA_SetCallback(handle->edmaRxRegToRxDataHandle, EDMA_DspiSlaveCallback, &s_dspiSlaveEdmaPrivateHandle[instance]);
+
+ handle->state = kDSPI_Busy;
+
+ /* Store transfer information */
+ handle->txData = transfer->txData;
+ handle->rxData = transfer->rxData;
+ handle->remainingSendByteCount = transfer->dataSize;
+ handle->remainingReceiveByteCount = transfer->dataSize;
+ handle->totalByteCount = transfer->dataSize;
+ handle->errorCount = 0;
+
+ handle->isThereExtraByte = false;
+ if (handle->bitsPerFrame > 8)
+ {
+ if (handle->remainingSendByteCount % 2 == 1)
+ {
+ handle->remainingSendByteCount++;
+ handle->remainingReceiveByteCount--;
+ handle->isThereExtraByte = true;
+ }
+ }
+
+ uint16_t wordToSend = 0;
+ uint8_t dummyData = DSPI_DUMMY_DATA;
+ uint8_t dataAlreadyFed = 0;
+ uint8_t dataFedMax = 2;
+
+ uint32_t rxAddr = DSPI_GetRxRegisterAddress(base);
+ uint32_t txAddr = DSPI_SlaveGetTxRegisterAddress(base);
+
+ edma_transfer_config_t transferConfigA;
+ edma_transfer_config_t transferConfigC;
+
+ DSPI_StopTransfer(base);
+
+ DSPI_FlushFifo(base, true, true);
+ DSPI_ClearStatusFlags(base, kDSPI_AllStatusFlag);
+
+ DSPI_DisableDMA(base, kDSPI_RxDmaEnable | kDSPI_TxDmaEnable);
+
+ DSPI_StartTransfer(base);
+
+ /*if dspi has separate dma request , need not prepare data first .
+ else (dspi has shared dma request) , send first 2 data into fifo if there is fifo or send first 1 data to
+ slaveGetTxRegister if there is no fifo*/
+ if (1 != FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base))
+ {
+ /* For DSPI instances with shared RX/TX DMA requests, we'll use the RX DMA request to
+ * trigger ongoing transfers and will link to the TX DMA channel from the RX DMA channel.
+ */
+ /* If bits/frame is greater than one byte */
+ if (handle->bitsPerFrame > 8)
+ {
+ while (DSPI_GetStatusFlags(base) & kDSPI_TxFifoFillRequestFlag)
+ {
+ if (handle->txData)
+ {
+ wordToSend = *(handle->txData);
+ ++handle->txData; /* Increment to next data byte */
+ if ((handle->remainingSendByteCount == 2) && (handle->isThereExtraByte))
+ {
+ wordToSend |= (unsigned)(dummyData) << 8U;
+ ++handle->txData; /* Increment to next data byte */
+ }
+ else
+ {
+ wordToSend |= (unsigned)(*(handle->txData)) << 8U;
+ ++handle->txData; /* Increment to next data byte */
+ }
+ }
+ else
+ {
+ wordToSend = ((uint32_t)dummyData << 8) | dummyData;
+ }
+ handle->remainingSendByteCount -= 2; /* decrement remainingSendByteCount by 2 */
+ base->PUSHR_SLAVE = wordToSend;
+
+ /* Try to clear the TFFF; if the TX FIFO is full this will clear */
+ DSPI_ClearStatusFlags(base, kDSPI_TxFifoFillRequestFlag);
+
+ dataAlreadyFed += 2;
+
+ /* Exit loop if send count is zero, else update local variables for next loop */
+ if ((handle->remainingSendByteCount == 0) || (dataAlreadyFed == (dataFedMax * 2)))
+ {
+ break;
+ }
+ } /* End of TX FIFO fill while loop */
+ }
+ else /* Optimized for bits/frame less than or equal to one byte. */
+ {
+ while (DSPI_GetStatusFlags(base) & kDSPI_TxFifoFillRequestFlag)
+ {
+ if (handle->txData)
+ {
+ wordToSend = *(handle->txData);
+ /* Increment to next data word*/
+ ++handle->txData;
+ }
+ else
+ {
+ wordToSend = dummyData;
+ }
+
+ base->PUSHR_SLAVE = wordToSend;
+
+ /* Try to clear the TFFF; if the TX FIFO is full this will clear */
+ DSPI_ClearStatusFlags(base, kDSPI_TxFifoFillRequestFlag);
+ /* Decrement remainingSendByteCount*/
+ --handle->remainingSendByteCount;
+
+ dataAlreadyFed++;
+
+ /* Exit loop if send count is zero, else update local variables for next loop */
+ if ((handle->remainingSendByteCount == 0) || (dataAlreadyFed == dataFedMax))
+ {
+ break;
+ }
+ } /* End of TX FIFO fill while loop */
+ }
+ }
+
+ /***channel_A *** used for carry the data from Rx_Data_Register(POPR) to User_Receive_Buffer*/
+ if (handle->remainingReceiveByteCount > 0)
+ {
+ EDMA_ResetChannel(handle->edmaRxRegToRxDataHandle->base, handle->edmaRxRegToRxDataHandle->channel);
+
+ transferConfigA.srcAddr = (uint32_t)rxAddr;
+ transferConfigA.srcOffset = 0;
+
+ if (handle->rxData)
+ {
+ transferConfigA.destAddr = (uint32_t) & (handle->rxData[0]);
+ transferConfigA.destOffset = 1;
+ }
+ else
+ {
+ transferConfigA.destAddr = (uint32_t) & (handle->rxBuffIfNull);
+ transferConfigA.destOffset = 0;
+ }
+
+ transferConfigA.destTransferSize = kEDMA_TransferSize1Bytes;
+
+ if (handle->bitsPerFrame <= 8)
+ {
+ transferConfigA.srcTransferSize = kEDMA_TransferSize1Bytes;
+ transferConfigA.minorLoopBytes = 1;
+ transferConfigA.majorLoopCounts = handle->remainingReceiveByteCount;
+ }
+ else
+ {
+ transferConfigA.srcTransferSize = kEDMA_TransferSize2Bytes;
+ transferConfigA.minorLoopBytes = 2;
+ transferConfigA.majorLoopCounts = handle->remainingReceiveByteCount / 2;
+ }
+ EDMA_SetTransferConfig(handle->edmaRxRegToRxDataHandle->base, handle->edmaRxRegToRxDataHandle->channel,
+ &transferConfigA, NULL);
+ EDMA_EnableChannelInterrupts(handle->edmaRxRegToRxDataHandle->base, handle->edmaRxRegToRxDataHandle->channel,
+ kEDMA_MajorInterruptEnable);
+ }
+
+ if (handle->remainingSendByteCount > 0)
+ {
+ /***channel_C *** used for carry the data from User_Send_Buffer to Tx_Data_Register(PUSHR_SLAVE)*/
+ EDMA_ResetChannel(handle->edmaTxDataToTxRegHandle->base, handle->edmaTxDataToTxRegHandle->channel);
+
+ /*If there is extra byte , it would use the */
+ if (handle->isThereExtraByte)
+ {
+ if (handle->txData)
+ {
+ handle->txLastData =
+ handle->txData[handle->remainingSendByteCount - 2] | ((uint32_t)DSPI_DUMMY_DATA << 8);
+ }
+ else
+ {
+ handle->txLastData = DSPI_DUMMY_DATA | ((uint32_t)DSPI_DUMMY_DATA << 8);
+ }
+ transferConfigC.srcAddr = (uint32_t)(&(handle->txLastData));
+ transferConfigC.destAddr = (uint32_t)txAddr;
+ transferConfigC.srcTransferSize = kEDMA_TransferSize4Bytes;
+ transferConfigC.destTransferSize = kEDMA_TransferSize4Bytes;
+ transferConfigC.srcOffset = 0;
+ transferConfigC.destOffset = 0;
+ transferConfigC.minorLoopBytes = 4;
+ transferConfigC.majorLoopCounts = 1;
+
+ EDMA_TcdReset(softwareTCD);
+ EDMA_TcdSetTransferConfig(softwareTCD, &transferConfigC, NULL);
+ }
+
+ /*Set another transferConfigC*/
+ if ((handle->isThereExtraByte) && (handle->remainingSendByteCount == 2))
+ {
+ EDMA_SetTransferConfig(handle->edmaTxDataToTxRegHandle->base, handle->edmaTxDataToTxRegHandle->channel,
+ &transferConfigC, NULL);
+ }
+ else
+ {
+ transferConfigC.destAddr = (uint32_t)txAddr;
+ transferConfigC.destOffset = 0;
+
+ if (handle->txData)
+ {
+ transferConfigC.srcAddr = (uint32_t)(&(handle->txData[0]));
+ transferConfigC.srcOffset = 1;
+ }
+ else
+ {
+ transferConfigC.srcAddr = (uint32_t)(&handle->txBuffIfNull);
+ transferConfigC.srcOffset = 0;
+ if (handle->bitsPerFrame <= 8)
+ {
+ handle->txBuffIfNull = DSPI_DUMMY_DATA;
+ }
+ else
+ {
+ handle->txBuffIfNull = (DSPI_DUMMY_DATA << 8) | DSPI_DUMMY_DATA;
+ }
+ }
+
+ transferConfigC.srcTransferSize = kEDMA_TransferSize1Bytes;
+
+ if (handle->bitsPerFrame <= 8)
+ {
+ transferConfigC.destTransferSize = kEDMA_TransferSize1Bytes;
+ transferConfigC.minorLoopBytes = 1;
+ transferConfigC.majorLoopCounts = handle->remainingSendByteCount;
+ }
+ else
+ {
+ transferConfigC.destTransferSize = kEDMA_TransferSize2Bytes;
+ transferConfigC.minorLoopBytes = 2;
+ if (handle->isThereExtraByte)
+ {
+ transferConfigC.majorLoopCounts = handle->remainingSendByteCount / 2 - 1;
+ }
+ else
+ {
+ transferConfigC.majorLoopCounts = handle->remainingSendByteCount / 2;
+ }
+ }
+
+ if (handle->isThereExtraByte)
+ {
+ EDMA_SetTransferConfig(handle->edmaTxDataToTxRegHandle->base, handle->edmaTxDataToTxRegHandle->channel,
+ &transferConfigC, softwareTCD);
+ EDMA_EnableAutoStopRequest(handle->edmaTxDataToTxRegHandle->base,
+ handle->edmaTxDataToTxRegHandle->channel, false);
+ }
+ else
+ {
+ EDMA_SetTransferConfig(handle->edmaTxDataToTxRegHandle->base, handle->edmaTxDataToTxRegHandle->channel,
+ &transferConfigC, NULL);
+ }
+
+ EDMA_StartTransfer(handle->edmaTxDataToTxRegHandle);
+ }
+ }
+
+ EDMA_StartTransfer(handle->edmaRxRegToRxDataHandle);
+
+ /*Set channel priority*/
+ uint8_t channelPriorityLow = handle->edmaRxRegToRxDataHandle->channel;
+ uint8_t channelPriorityHigh = handle->edmaTxDataToTxRegHandle->channel;
+ uint8_t t = 0;
+
+ if (channelPriorityLow > channelPriorityHigh)
+ {
+ t = channelPriorityLow;
+ channelPriorityLow = channelPriorityHigh;
+ channelPriorityHigh = t;
+ }
+
+ edma_channel_Preemption_config_t preemption_config_t;
+ preemption_config_t.enableChannelPreemption = true;
+ preemption_config_t.enablePreemptAbility = true;
+ preemption_config_t.channelPriority = channelPriorityLow;
+
+ if (1 != FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base))
+ {
+ EDMA_SetChannelPreemptionConfig(handle->edmaRxRegToRxDataHandle->base, handle->edmaRxRegToRxDataHandle->channel,
+ &preemption_config_t);
+
+ preemption_config_t.channelPriority = channelPriorityHigh;
+ EDMA_SetChannelPreemptionConfig(handle->edmaTxDataToTxRegHandle->base, handle->edmaTxDataToTxRegHandle->channel,
+ &preemption_config_t);
+ }
+ else
+ {
+ EDMA_SetChannelPreemptionConfig(handle->edmaTxDataToTxRegHandle->base, handle->edmaTxDataToTxRegHandle->channel,
+ &preemption_config_t);
+
+ preemption_config_t.channelPriority = channelPriorityHigh;
+ EDMA_SetChannelPreemptionConfig(handle->edmaRxRegToRxDataHandle->base, handle->edmaRxRegToRxDataHandle->channel,
+ &preemption_config_t);
+ }
+
+ /*Set the channel link.
+ For DSPI instances with shared RX/TX DMA requests: Rx DMA request -> channel_A -> channel_C.
+ For DSPI instances with separate RX and TX DMA requests:
+ Rx DMA request -> channel_A
+ Tx DMA request -> channel_C */
+ if (1 != FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base))
+ {
+ if (handle->remainingSendByteCount > 0)
+ {
+ EDMA_SetChannelLink(handle->edmaRxRegToRxDataHandle->base, handle->edmaRxRegToRxDataHandle->channel,
+ kEDMA_MinorLink, handle->edmaTxDataToTxRegHandle->channel);
+ }
+ DSPI_EnableDMA(base, kDSPI_RxDmaEnable);
+ }
+ else
+ {
+ DSPI_EnableDMA(base, kDSPI_RxDmaEnable | kDSPI_TxDmaEnable);
+ }
+
+ return kStatus_Success;
+}
+
+static void EDMA_DspiSlaveCallback(edma_handle_t *edmaHandle,
+ void *g_dspiEdmaPrivateHandle,
+ bool transferDone,
+ uint32_t tcds)
+{
+ dspi_slave_edma_private_handle_t *dspiEdmaPrivateHandle;
+
+ dspiEdmaPrivateHandle = (dspi_slave_edma_private_handle_t *)g_dspiEdmaPrivateHandle;
+
+ uint32_t dataReceived;
+
+ DSPI_DisableDMA((dspiEdmaPrivateHandle->base), kDSPI_RxDmaEnable | kDSPI_TxDmaEnable);
+
+ if (dspiEdmaPrivateHandle->handle->isThereExtraByte)
+ {
+ while (!((dspiEdmaPrivateHandle->base)->SR & SPI_SR_RFDF_MASK))
+ {
+ }
+ dataReceived = (dspiEdmaPrivateHandle->base)->POPR;
+ if (dspiEdmaPrivateHandle->handle->rxData)
+ {
+ (dspiEdmaPrivateHandle->handle->rxData[dspiEdmaPrivateHandle->handle->totalByteCount - 1]) = dataReceived;
+ }
+ }
+
+ if (dspiEdmaPrivateHandle->handle->callback)
+ {
+ dspiEdmaPrivateHandle->handle->callback(dspiEdmaPrivateHandle->base, dspiEdmaPrivateHandle->handle,
+ kStatus_Success, dspiEdmaPrivateHandle->handle->userData);
+ }
+
+ dspiEdmaPrivateHandle->handle->state = kDSPI_Idle;
+}
+
+void DSPI_SlaveTransferAbortEDMA(SPI_Type *base, dspi_slave_edma_handle_t *handle)
+{
+ DSPI_StopTransfer(base);
+
+ DSPI_DisableDMA(base, kDSPI_RxDmaEnable | kDSPI_TxDmaEnable);
+
+ EDMA_AbortTransfer(handle->edmaRxRegToRxDataHandle);
+ EDMA_AbortTransfer(handle->edmaTxDataToTxRegHandle);
+
+ handle->state = kDSPI_Idle;
+}
+
+status_t DSPI_SlaveTransferGetCountEDMA(SPI_Type *base, dspi_slave_edma_handle_t *handle, size_t *count)
+{
+ assert(handle);
+
+ if (!count)
+ {
+ return kStatus_InvalidArgument;
+ }
+
+ /* Catch when there is not an active transfer. */
+ if (handle->state != kDSPI_Busy)
+ {
+ *count = 0;
+ return kStatus_NoTransferInProgress;
+ }
+
+ size_t bytes;
+
+ bytes = EDMA_GetRemainingBytes(handle->edmaRxRegToRxDataHandle->base, handle->edmaRxRegToRxDataHandle->channel);
+
+ *count = handle->totalByteCount - bytes;
+
+ return kStatus_Success;
+}
diff --git a/drivers/fsl_dspi_edma.h b/drivers/fsl_dspi_edma.h
new file mode 100644
index 0000000..643efad
--- /dev/null
+++ b/drivers/fsl_dspi_edma.h
@@ -0,0 +1,282 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_DSPI_EDMA_H_
+#define _FSL_DSPI_EDMA_H_
+
+#include "fsl_dspi.h"
+#include "fsl_edma.h"
+/*!
+ * @addtogroup dspi_edma_driver
+ * @{
+ */
+
+
+/***********************************************************************************************************************
+ * Definitions
+ **********************************************************************************************************************/
+
+/*!
+* @brief Forward declaration of the DSPI eDMA master handle typedefs.
+*/
+typedef struct _dspi_master_edma_handle dspi_master_edma_handle_t;
+
+/*!
+* @brief Forward declaration of the DSPI eDMA slave handle typedefs.
+*/
+typedef struct _dspi_slave_edma_handle dspi_slave_edma_handle_t;
+
+/*!
+ * @brief Completion callback function pointer type.
+ *
+ * @param base DSPI peripheral base address.
+ * @param handle Pointer to the handle for the DSPI master.
+ * @param status Success or error code describing whether the transfer completed.
+ * @param userData Arbitrary pointer-dataSized value passed from the application.
+ */
+typedef void (*dspi_master_edma_transfer_callback_t)(SPI_Type *base,
+ dspi_master_edma_handle_t *handle,
+ status_t status,
+ void *userData);
+/*!
+ * @brief Completion callback function pointer type.
+ *
+ * @param base DSPI peripheral base address.
+ * @param handle Pointer to the handle for the DSPI slave.
+ * @param status Success or error code describing whether the transfer completed.
+ * @param userData Arbitrary pointer-dataSized value passed from the application.
+ */
+typedef void (*dspi_slave_edma_transfer_callback_t)(SPI_Type *base,
+ dspi_slave_edma_handle_t *handle,
+ status_t status,
+ void *userData);
+
+/*! @brief DSPI master eDMA transfer handle structure used for transactional API. */
+struct _dspi_master_edma_handle
+{
+ uint32_t bitsPerFrame; /*!< Desired number of bits per frame. */
+ volatile uint32_t command; /*!< Desired data command. */
+ volatile uint32_t lastCommand; /*!< Desired last data command. */
+
+ uint8_t fifoSize; /*!< FIFO dataSize. */
+
+ volatile bool isPcsActiveAfterTransfer; /*!< Is PCS signal keep active after the last frame transfer.*/
+ volatile bool isThereExtraByte; /*!< Is there extra byte.*/
+
+ uint8_t *volatile txData; /*!< Send buffer. */
+ uint8_t *volatile rxData; /*!< Receive buffer. */
+ volatile size_t remainingSendByteCount; /*!< Number of bytes remaining to send.*/
+ volatile size_t remainingReceiveByteCount; /*!< Number of bytes remaining to receive.*/
+ size_t totalByteCount; /*!< Number of transfer bytes*/
+
+ uint32_t rxBuffIfNull; /*!< Used if there is not rxData for DMA purpose.*/
+ uint32_t txBuffIfNull; /*!< Used if there is not txData for DMA purpose.*/
+
+ volatile uint8_t state; /*!< DSPI transfer state , _dspi_transfer_state.*/
+
+ dspi_master_edma_transfer_callback_t callback; /*!< Completion callback. */
+ void *userData; /*!< Callback user data. */
+
+ edma_handle_t *edmaRxRegToRxDataHandle; /*!<edma_handle_t handle point used for RxReg to RxData buff*/
+ edma_handle_t *edmaTxDataToIntermediaryHandle; /*!<edma_handle_t handle point used for TxData to Intermediary*/
+ edma_handle_t *edmaIntermediaryToTxRegHandle; /*!<edma_handle_t handle point used for Intermediary to TxReg*/
+
+ edma_tcd_t dspiSoftwareTCD[2]; /*!<SoftwareTCD , internal used*/
+};
+
+/*! @brief DSPI slave eDMA transfer handle structure used for transactional API.*/
+struct _dspi_slave_edma_handle
+{
+ uint32_t bitsPerFrame; /*!< Desired number of bits per frame. */
+ volatile bool isThereExtraByte; /*!< Is there extra byte.*/
+
+ uint8_t *volatile txData; /*!< Send buffer. */
+ uint8_t *volatile rxData; /*!< Receive buffer. */
+ volatile size_t remainingSendByteCount; /*!< Number of bytes remaining to send.*/
+ volatile size_t remainingReceiveByteCount; /*!< Number of bytes remaining to receive.*/
+ size_t totalByteCount; /*!< Number of transfer bytes*/
+
+ uint32_t rxBuffIfNull; /*!< Used if there is not rxData for DMA purpose.*/
+ uint32_t txBuffIfNull; /*!< Used if there is not txData for DMA purpose.*/
+ uint32_t txLastData; /*!< Used if there is an extra byte when 16bits per frame for DMA purpose.*/
+
+ volatile uint8_t state; /*!< DSPI transfer state.*/
+
+ uint32_t errorCount; /*!< Error count for slave transfer.*/
+
+ dspi_slave_edma_transfer_callback_t callback; /*!< Completion callback. */
+ void *userData; /*!< Callback user data. */
+
+ edma_handle_t *edmaRxRegToRxDataHandle; /*!<edma_handle_t handle point used for RxReg to RxData buff*/
+ edma_handle_t *edmaTxDataToTxRegHandle; /*!<edma_handle_t handle point used for TxData to TxReg*/
+
+ edma_tcd_t dspiSoftwareTCD[2]; /*!<SoftwareTCD , internal used*/
+};
+
+/***********************************************************************************************************************
+ * API
+ **********************************************************************************************************************/
+#if defined(__cplusplus)
+extern "C" {
+#endif /*_cplusplus*/
+
+/*Transactional APIs*/
+
+/*!
+ * @brief Initializes the DSPI master eDMA handle.
+ *
+ * This function initializes the DSPI eDMA handle which can be used for other DSPI transactional APIs. Usually, for a
+ * specified DSPI instance, user need only call this API once to get the initialized handle.
+ *
+ * Note that DSPI eDMA has separated (RX and TX as two sources) or shared (RX and TX are the same source) DMA request source.
+ * (1)For the separated DMA request source, enable and set the RX DMAMUX source for edmaRxRegToRxDataHandle and
+ * TX DMAMUX source for edmaIntermediaryToTxRegHandle.
+ * (2)For the shared DMA request source, enable and set the RX/RX DMAMUX source for the edmaRxRegToRxDataHandle.
+ *
+ * @param base DSPI peripheral base address.
+ * @param handle DSPI handle pointer to dspi_master_edma_handle_t.
+ * @param callback DSPI callback.
+ * @param userData callback function parameter.
+ * @param edmaRxRegToRxDataHandle edmaRxRegToRxDataHandle pointer to edma_handle_t.
+ * @param edmaTxDataToIntermediaryHandle edmaTxDataToIntermediaryHandle pointer to edma_handle_t.
+ * @param edmaIntermediaryToTxRegHandle edmaIntermediaryToTxRegHandle pointer to edma_handle_t.
+ */
+void DSPI_MasterTransferCreateHandleEDMA(SPI_Type *base,
+ dspi_master_edma_handle_t *handle,
+ dspi_master_edma_transfer_callback_t callback,
+ void *userData,
+ edma_handle_t *edmaRxRegToRxDataHandle,
+ edma_handle_t *edmaTxDataToIntermediaryHandle,
+ edma_handle_t *edmaIntermediaryToTxRegHandle);
+
+/*!
+ * @brief DSPI master transfer data using eDMA.
+ *
+ * This function transfer data using eDMA. This is non-blocking function, which returns right away. When all data
+ * have been transfer, the callback function is called.
+ *
+ * @param base DSPI peripheral base address.
+ * @param handle pointer to dspi_master_edma_handle_t structure which stores the transfer state.
+ * @param transfer pointer to dspi_transfer_t structure.
+ * @return status of status_t.
+ */
+status_t DSPI_MasterTransferEDMA(SPI_Type *base, dspi_master_edma_handle_t *handle, dspi_transfer_t *transfer);
+
+/*!
+ * @brief DSPI master aborts a transfer which using eDMA.
+ *
+ * This function aborts a transfer which using eDMA.
+ *
+ * @param base DSPI peripheral base address.
+ * @param handle pointer to dspi_master_edma_handle_t structure which stores the transfer state.
+ */
+void DSPI_MasterTransferAbortEDMA(SPI_Type *base, dspi_master_edma_handle_t *handle);
+
+/*!
+ * @brief Gets the master eDMA transfer count.
+ *
+ * This function get the master eDMA transfer count.
+ *
+ * @param base DSPI peripheral base address.
+ * @param handle pointer to dspi_master_edma_handle_t structure which stores the transfer state.
+ * @param count Number of bytes transferred so far by the non-blocking transaction.
+ * @return status of status_t.
+ */
+status_t DSPI_MasterTransferGetCountEDMA(SPI_Type *base, dspi_master_edma_handle_t *handle, size_t *count);
+
+/*!
+ * @brief Initializes the DSPI slave eDMA handle.
+ *
+ * This function initializes the DSPI eDMA handle which can be used for other DSPI transactional APIs. Usually, for a
+ * specified DSPI instance, call this API once to get the initialized handle.
+ *
+ * Note that DSPI eDMA has separated (RN and TX in 2 sources) or shared (RX and TX are the same source) DMA request source.
+ * (1)For the separated DMA request source, enable and set the RX DMAMUX source for edmaRxRegToRxDataHandle and
+ * TX DMAMUX source for edmaTxDataToTxRegHandle.
+ * (2)For the shared DMA request source, enable and set the RX/RX DMAMUX source for the edmaRxRegToRxDataHandle.
+ *
+ * @param base DSPI peripheral base address.
+ * @param handle DSPI handle pointer to dspi_slave_edma_handle_t.
+ * @param callback DSPI callback.
+ * @param userData callback function parameter.
+ * @param edmaRxRegToRxDataHandle edmaRxRegToRxDataHandle pointer to edma_handle_t.
+ * @param edmaTxDataToTxRegHandle edmaTxDataToTxRegHandle pointer to edma_handle_t.
+ */
+void DSPI_SlaveTransferCreateHandleEDMA(SPI_Type *base,
+ dspi_slave_edma_handle_t *handle,
+ dspi_slave_edma_transfer_callback_t callback,
+ void *userData,
+ edma_handle_t *edmaRxRegToRxDataHandle,
+ edma_handle_t *edmaTxDataToTxRegHandle);
+
+/*!
+ * @brief DSPI slave transfer data using eDMA.
+ *
+ * This function transfer data using eDMA. This is non-blocking function, which returns right away. When all data
+ * have been transfer, the callback function is called.
+ * Note that slave EDMA transfer cannot support the situation that transfer_size is 1 when the bitsPerFrame is greater
+ * than 8 .
+
+ * @param base DSPI peripheral base address.
+ * @param handle pointer to dspi_slave_edma_handle_t structure which stores the transfer state.
+ * @param transfer pointer to dspi_transfer_t structure.
+ * @return status of status_t.
+ */
+status_t DSPI_SlaveTransferEDMA(SPI_Type *base, dspi_slave_edma_handle_t *handle, dspi_transfer_t *transfer);
+
+/*!
+ * @brief DSPI slave aborts a transfer which using eDMA.
+ *
+ * This function aborts a transfer which using eDMA.
+ *
+ * @param base DSPI peripheral base address.
+ * @param handle pointer to dspi_slave_edma_handle_t structure which stores the transfer state.
+ */
+void DSPI_SlaveTransferAbortEDMA(SPI_Type *base, dspi_slave_edma_handle_t *handle);
+
+/*!
+ * @brief Gets the slave eDMA transfer count.
+ *
+ * This function gets the slave eDMA transfer count.
+ *
+ * @param base DSPI peripheral base address.
+ * @param handle pointer to dspi_slave_edma_handle_t structure which stores the transfer state.
+ * @param count Number of bytes transferred so far by the non-blocking transaction.
+ * @return status of status_t.
+ */
+status_t DSPI_SlaveTransferGetCountEDMA(SPI_Type *base, dspi_slave_edma_handle_t *handle, size_t *count);
+
+#if defined(__cplusplus)
+}
+#endif /*_cplusplus*/
+ /*!
+ *@}
+ */
+
+#endif /*_FSL_DSPI_EDMA_H_*/
diff --git a/drivers/fsl_edma.c b/drivers/fsl_edma.c
new file mode 100644
index 0000000..8ad12fc
--- /dev/null
+++ b/drivers/fsl_edma.c
@@ -0,0 +1,1313 @@
+/*
+* Copyright (c) 2015, Freescale Semiconductor, Inc.
+* All rights reserved.
+*
+* 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 Freescale Semiconductor, Inc. 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_edma.h"
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+#define EDMA_TRANSFER_ENABLED_MASK 0x80U
+
+/*******************************************************************************
+ * Prototypes
+ ******************************************************************************/
+
+/*!
+ * @brief Get instance number for EDMA.
+ *
+ * @param base EDMA peripheral base address.
+ */
+static uint32_t EDMA_GetInstance(DMA_Type *base);
+
+/*!
+ * @brief Push content of TCD structure into hardware TCD register.
+ *
+ * @param base EDMA peripheral base address.
+ * @param channel EDMA channel number.
+ * @param tcd Point to TCD structure.
+ */
+static void EDMA_InstallTCD(DMA_Type *base, uint32_t channel, edma_tcd_t *tcd);
+
+/*******************************************************************************
+ * Variables
+ ******************************************************************************/
+
+/*! @brief Array to map EDMA instance number to base pointer. */
+static DMA_Type *const s_edmaBases[] = DMA_BASE_PTRS;
+
+/*! @brief Array to map EDMA instance number to clock name. */
+static const clock_ip_name_t s_edmaClockName[] = EDMA_CLOCKS;
+
+/*! @brief Array to map EDMA instance number to IRQ number. */
+static const IRQn_Type s_edmaIRQNumber[] = DMA_CHN_IRQS;
+
+/*! @brief Pointers to transfer handle for each EDMA channel. */
+static edma_handle_t *s_EDMAHandle[FSL_FEATURE_EDMA_MODULE_CHANNEL * FSL_FEATURE_SOC_EDMA_COUNT];
+
+/*******************************************************************************
+ * Code
+ ******************************************************************************/
+
+static uint32_t EDMA_GetInstance(DMA_Type *base)
+{
+ uint32_t instance;
+
+ /* Find the instance index from base address mappings. */
+ for (instance = 0; instance < FSL_FEATURE_SOC_EDMA_COUNT; instance++)
+ {
+ if (s_edmaBases[instance] == base)
+ {
+ break;
+ }
+ }
+
+ assert(instance < FSL_FEATURE_SOC_EDMA_COUNT);
+
+ return instance;
+}
+
+static void EDMA_InstallTCD(DMA_Type *base, uint32_t channel, edma_tcd_t *tcd)
+{
+ assert(channel < FSL_FEATURE_EDMA_MODULE_CHANNEL);
+ assert(tcd != NULL);
+ assert(((uint32_t)tcd & 0x1FU) == 0);
+
+ /* Push tcd into hardware TCD register */
+ base->TCD[channel].SADDR = tcd->SADDR;
+ base->TCD[channel].SOFF = tcd->SOFF;
+ base->TCD[channel].ATTR = tcd->ATTR;
+ base->TCD[channel].NBYTES_MLNO = tcd->NBYTES;
+ base->TCD[channel].SLAST = tcd->SLAST;
+ base->TCD[channel].DADDR = tcd->DADDR;
+ base->TCD[channel].DOFF = tcd->DOFF;
+ base->TCD[channel].CITER_ELINKNO = tcd->CITER;
+ base->TCD[channel].DLAST_SGA = tcd->DLAST_SGA;
+ /* Clear DONE bit first, otherwise ESG cannot be set */
+ base->TCD[channel].CSR = 0;
+ base->TCD[channel].CSR = tcd->CSR;
+ base->TCD[channel].BITER_ELINKNO = tcd->BITER;
+}
+
+void EDMA_Init(DMA_Type *base, const edma_config_t *config)
+{
+ assert(config != NULL);
+
+ uint32_t tmpreg;
+
+ /* Ungate EDMA periphral clock */
+ CLOCK_EnableClock(s_edmaClockName[EDMA_GetInstance(base)]);
+ /* Configure EDMA peripheral according to the configuration structure. */
+ tmpreg = base->CR;
+ tmpreg &= ~(DMA_CR_ERCA_MASK | DMA_CR_HOE_MASK | DMA_CR_CLM_MASK | DMA_CR_EDBG_MASK);
+ tmpreg |= (DMA_CR_ERCA(config->enableRoundRobinArbitration) | DMA_CR_HOE(config->enableHaltOnError) |
+ DMA_CR_CLM(config->enableContinuousLinkMode) | DMA_CR_EDBG(config->enableDebugMode) | DMA_CR_EMLM(true));
+ base->CR = tmpreg;
+}
+
+void EDMA_Deinit(DMA_Type *base)
+{
+ /* Gate EDMA periphral clock */
+ CLOCK_DisableClock(s_edmaClockName[EDMA_GetInstance(base)]);
+}
+
+void EDMA_GetDefaultConfig(edma_config_t *config)
+{
+ assert(config != NULL);
+
+ config->enableRoundRobinArbitration = false;
+ config->enableHaltOnError = true;
+ config->enableContinuousLinkMode = false;
+ config->enableDebugMode = false;
+}
+
+void EDMA_ResetChannel(DMA_Type *base, uint32_t channel)
+{
+ assert(channel < FSL_FEATURE_EDMA_MODULE_CHANNEL);
+
+ EDMA_TcdReset((edma_tcd_t *)&base->TCD[channel]);
+}
+
+void EDMA_SetTransferConfig(DMA_Type *base, uint32_t channel, const edma_transfer_config_t *config, edma_tcd_t *nextTcd)
+{
+ assert(channel < FSL_FEATURE_EDMA_MODULE_CHANNEL);
+ assert(config != NULL);
+ assert(((uint32_t)nextTcd & 0x1FU) == 0);
+
+ EDMA_TcdSetTransferConfig((edma_tcd_t *)&base->TCD[channel], config, nextTcd);
+}
+
+void EDMA_SetMinorOffsetConfig(DMA_Type *base, uint32_t channel, const edma_minor_offset_config_t *config)
+{
+ assert(channel < FSL_FEATURE_EDMA_MODULE_CHANNEL);
+ assert(config != NULL);
+
+ uint32_t tmpreg;
+
+ tmpreg = base->TCD[channel].NBYTES_MLOFFYES;
+ tmpreg &= ~(DMA_NBYTES_MLOFFYES_SMLOE_MASK | DMA_NBYTES_MLOFFYES_DMLOE_MASK | DMA_NBYTES_MLOFFYES_MLOFF_MASK);
+ tmpreg |=
+ (DMA_NBYTES_MLOFFYES_SMLOE(config->enableSrcMinorOffset) |
+ DMA_NBYTES_MLOFFYES_DMLOE(config->enableDestMinorOffset) | DMA_NBYTES_MLOFFYES_MLOFF(config->minorOffset));
+ base->TCD[channel].NBYTES_MLOFFYES = tmpreg;
+}
+
+void EDMA_SetChannelLink(DMA_Type *base, uint32_t channel, edma_channel_link_type_t type, uint32_t linkedChannel)
+{
+ assert(channel < FSL_FEATURE_EDMA_MODULE_CHANNEL);
+ assert(linkedChannel < FSL_FEATURE_EDMA_MODULE_CHANNEL);
+
+ EDMA_TcdSetChannelLink((edma_tcd_t *)&base->TCD[channel], type, linkedChannel);
+}
+
+void EDMA_SetBandWidth(DMA_Type *base, uint32_t channel, edma_bandwidth_t bandWidth)
+{
+ assert(channel < FSL_FEATURE_EDMA_MODULE_CHANNEL);
+
+ base->TCD[channel].CSR = (base->TCD[channel].CSR & (~DMA_CSR_BWC_MASK)) | DMA_CSR_BWC(bandWidth);
+}
+
+void EDMA_SetModulo(DMA_Type *base, uint32_t channel, edma_modulo_t srcModulo, edma_modulo_t destModulo)
+{
+ assert(channel < FSL_FEATURE_EDMA_MODULE_CHANNEL);
+
+ uint32_t tmpreg;
+
+ tmpreg = base->TCD[channel].ATTR & (~(DMA_ATTR_SMOD_MASK | DMA_ATTR_DMOD_MASK));
+ base->TCD[channel].ATTR = tmpreg | DMA_ATTR_DMOD(destModulo) | DMA_ATTR_SMOD(srcModulo);
+}
+
+void EDMA_EnableChannelInterrupts(DMA_Type *base, uint32_t channel, uint32_t mask)
+{
+ assert(channel < FSL_FEATURE_EDMA_MODULE_CHANNEL);
+
+ /* Enable error interrupt */
+ if (mask & kEDMA_ErrorInterruptEnable)
+ {
+ base->EEI |= (0x1U << channel);
+ }
+
+ /* Enable Major interrupt */
+ if (mask & kEDMA_MajorInterruptEnable)
+ {
+ base->TCD[channel].CSR |= DMA_CSR_INTMAJOR_MASK;
+ }
+
+ /* Enable Half major interrupt */
+ if (mask & kEDMA_HalfInterruptEnable)
+ {
+ base->TCD[channel].CSR |= DMA_CSR_INTHALF_MASK;
+ }
+}
+
+void EDMA_DisableChannelInterrupts(DMA_Type *base, uint32_t channel, uint32_t mask)
+{
+ assert(channel < FSL_FEATURE_EDMA_MODULE_CHANNEL);
+
+ /* Disable error interrupt */
+ if (mask & kEDMA_ErrorInterruptEnable)
+ {
+ base->EEI &= ~(0x1U << channel);
+ }
+
+ /* Disable Major interrupt */
+ if (mask & kEDMA_MajorInterruptEnable)
+ {
+ base->TCD[channel].CSR &= ~DMA_CSR_INTMAJOR_MASK;
+ }
+
+ /* Disable Half major interrupt */
+ if (mask & kEDMA_HalfInterruptEnable)
+ {
+ base->TCD[channel].CSR &= ~DMA_CSR_INTHALF_MASK;
+ }
+}
+
+void EDMA_TcdReset(edma_tcd_t *tcd)
+{
+ assert(tcd != NULL);
+ assert(((uint32_t)tcd & 0x1FU) == 0);
+
+ /* Reset channel TCD */
+ tcd->SADDR = 0U;
+ tcd->SOFF = 0U;
+ tcd->ATTR = 0U;
+ tcd->NBYTES = 0U;
+ tcd->SLAST = 0U;
+ tcd->DADDR = 0U;
+ tcd->DOFF = 0U;
+ tcd->CITER = 0U;
+ tcd->DLAST_SGA = 0U;
+ /* Enable auto disable request feature */
+ tcd->CSR = DMA_CSR_DREQ(true);
+ tcd->BITER = 0U;
+}
+
+void EDMA_TcdSetTransferConfig(edma_tcd_t *tcd, const edma_transfer_config_t *config, edma_tcd_t *nextTcd)
+{
+ assert(tcd != NULL);
+ assert(((uint32_t)tcd & 0x1FU) == 0);
+ assert(config != NULL);
+ assert(((uint32_t)nextTcd & 0x1FU) == 0);
+
+ /* source address */
+ tcd->SADDR = config->srcAddr;
+ /* destination address */
+ tcd->DADDR = config->destAddr;
+ /* Source data and destination data transfer size */
+ tcd->ATTR = DMA_ATTR_SSIZE(config->srcTransferSize) | DMA_ATTR_DSIZE(config->destTransferSize);
+ /* Source address signed offset */
+ tcd->SOFF = config->srcOffset;
+ /* Destination address signed offset */
+ tcd->DOFF = config->destOffset;
+ /* Minor byte transfer count */
+ tcd->NBYTES = config->minorLoopBytes;
+ /* Current major iteration count */
+ tcd->CITER = config->majorLoopCounts;
+ /* Starting major iteration count */
+ tcd->BITER = config->majorLoopCounts;
+ /* Enable scatter/gather processing */
+ if (nextTcd != NULL)
+ {
+ tcd->DLAST_SGA = (uint32_t)nextTcd;
+ /*
+ Before call EDMA_TcdSetTransferConfig or EDMA_SetTransferConfig,
+ user must call EDMA_TcdReset or EDMA_ResetChannel which will set
+ DREQ, so must use "|" or "&" rather than "=".
+
+ Clear the DREQ bit because scatter gather has been enabled, so the
+ previous transfer is not the last transfer, and channel request should
+ be enabled at the next transfer(the next TCD).
+ */
+ tcd->CSR = (tcd->CSR | DMA_CSR_ESG_MASK) & ~DMA_CSR_DREQ_MASK;
+ }
+}
+
+void EDMA_TcdSetMinorOffsetConfig(edma_tcd_t *tcd, const edma_minor_offset_config_t *config)
+{
+ assert(tcd != NULL);
+ assert(((uint32_t)tcd & 0x1FU) == 0);
+
+ uint32_t tmpreg;
+
+ tmpreg = tcd->NBYTES &
+ ~(DMA_NBYTES_MLOFFYES_SMLOE_MASK | DMA_NBYTES_MLOFFYES_DMLOE_MASK | DMA_NBYTES_MLOFFYES_MLOFF_MASK);
+ tmpreg |=
+ (DMA_NBYTES_MLOFFYES_SMLOE(config->enableSrcMinorOffset) |
+ DMA_NBYTES_MLOFFYES_DMLOE(config->enableDestMinorOffset) | DMA_NBYTES_MLOFFYES_MLOFF(config->minorOffset));
+ tcd->NBYTES = tmpreg;
+}
+
+void EDMA_TcdSetChannelLink(edma_tcd_t *tcd, edma_channel_link_type_t type, uint32_t linkedChannel)
+{
+ assert(tcd != NULL);
+ assert(((uint32_t)tcd & 0x1FU) == 0);
+ assert(linkedChannel < FSL_FEATURE_EDMA_MODULE_CHANNEL);
+
+ if (type == kEDMA_MinorLink) /* Minor link config */
+ {
+ uint32_t tmpreg;
+
+ /* Enable minor link */
+ tcd->CITER |= DMA_CITER_ELINKYES_ELINK_MASK;
+ tcd->BITER |= DMA_BITER_ELINKYES_ELINK_MASK;
+ /* Set likned channel */
+ tmpreg = tcd->CITER & (~DMA_CITER_ELINKYES_LINKCH_MASK);
+ tmpreg |= DMA_CITER_ELINKYES_LINKCH(linkedChannel);
+ tcd->CITER = tmpreg;
+ tmpreg = tcd->BITER & (~DMA_BITER_ELINKYES_LINKCH_MASK);
+ tmpreg |= DMA_BITER_ELINKYES_LINKCH(linkedChannel);
+ tcd->BITER = tmpreg;
+ }
+ else if (type == kEDMA_MajorLink) /* Major link config */
+ {
+ uint32_t tmpreg;
+
+ /* Enable major link */
+ tcd->CSR |= DMA_CSR_MAJORELINK_MASK;
+ /* Set major linked channel */
+ tmpreg = tcd->CSR & (~DMA_CSR_MAJORLINKCH_MASK);
+ tcd->CSR = tmpreg | DMA_CSR_MAJORLINKCH(linkedChannel);
+ }
+ else /* Link none */
+ {
+ tcd->CITER &= ~DMA_CITER_ELINKYES_ELINK_MASK;
+ tcd->BITER &= ~DMA_BITER_ELINKYES_ELINK_MASK;
+ tcd->CSR &= ~DMA_CSR_MAJORELINK_MASK;
+ }
+}
+
+void EDMA_TcdSetModulo(edma_tcd_t *tcd, edma_modulo_t srcModulo, edma_modulo_t destModulo)
+{
+ assert(tcd != NULL);
+ assert(((uint32_t)tcd & 0x1FU) == 0);
+
+ uint32_t tmpreg;
+
+ tmpreg = tcd->ATTR & (~(DMA_ATTR_SMOD_MASK | DMA_ATTR_DMOD_MASK));
+ tcd->ATTR = tmpreg | DMA_ATTR_DMOD(destModulo) | DMA_ATTR_SMOD(srcModulo);
+}
+
+void EDMA_TcdEnableInterrupts(edma_tcd_t *tcd, uint32_t mask)
+{
+ assert(tcd != NULL);
+
+ /* Enable Major interrupt */
+ if (mask & kEDMA_MajorInterruptEnable)
+ {
+ tcd->CSR |= DMA_CSR_INTMAJOR_MASK;
+ }
+
+ /* Enable Half major interrupt */
+ if (mask & kEDMA_HalfInterruptEnable)
+ {
+ tcd->CSR |= DMA_CSR_INTHALF_MASK;
+ }
+}
+
+void EDMA_TcdDisableInterrupts(edma_tcd_t *tcd, uint32_t mask)
+{
+ assert(tcd != NULL);
+
+ /* Disable Major interrupt */
+ if (mask & kEDMA_MajorInterruptEnable)
+ {
+ tcd->CSR &= ~DMA_CSR_INTMAJOR_MASK;
+ }
+
+ /* Disable Half major interrupt */
+ if (mask & kEDMA_HalfInterruptEnable)
+ {
+ tcd->CSR &= ~DMA_CSR_INTHALF_MASK;
+ }
+}
+
+uint32_t EDMA_GetRemainingBytes(DMA_Type *base, uint32_t channel)
+{
+ assert(channel < FSL_FEATURE_EDMA_MODULE_CHANNEL);
+
+ uint32_t nbytes = 0;
+ uint32_t remainingBytes = 0;
+
+ if (DMA_CSR_DONE_MASK & base->TCD[channel].CSR)
+ {
+ remainingBytes = 0;
+ }
+ else
+ {
+ /* Calculate the nbytes */
+ if (base->TCD[channel].NBYTES_MLOFFYES & (DMA_NBYTES_MLOFFYES_SMLOE_MASK | DMA_NBYTES_MLOFFYES_DMLOE_MASK))
+ {
+ nbytes = (base->TCD[channel].NBYTES_MLOFFYES & DMA_NBYTES_MLOFFYES_NBYTES_MASK) >>
+ DMA_NBYTES_MLOFFYES_NBYTES_SHIFT;
+ }
+ else
+ {
+ nbytes =
+ (base->TCD[channel].NBYTES_MLOFFNO & DMA_NBYTES_MLOFFNO_NBYTES_MASK) >> DMA_NBYTES_MLOFFNO_NBYTES_SHIFT;
+ }
+ /* Calculate the unfinished bytes */
+ if (base->TCD[channel].CITER_ELINKNO & DMA_CITER_ELINKNO_ELINK_MASK)
+ {
+ remainingBytes = ((base->TCD[channel].CITER_ELINKYES & DMA_CITER_ELINKYES_CITER_MASK) >>
+ DMA_CITER_ELINKYES_CITER_SHIFT) *
+ nbytes;
+ }
+ else
+ {
+ remainingBytes =
+ ((base->TCD[channel].CITER_ELINKNO & DMA_CITER_ELINKNO_CITER_MASK) >> DMA_CITER_ELINKNO_CITER_SHIFT) *
+ nbytes;
+ }
+ }
+
+ return remainingBytes;
+}
+
+uint32_t EDMA_GetChannelStatusFlags(DMA_Type *base, uint32_t channel)
+{
+ assert(channel < FSL_FEATURE_EDMA_MODULE_CHANNEL);
+
+ uint32_t retval = 0;
+
+ /* Get DONE bit flag */
+ retval |= ((base->TCD[channel].CSR & DMA_CSR_DONE_MASK) >> DMA_CSR_DONE_SHIFT);
+ /* Get ERROR bit flag */
+ retval |= (((base->ERR >> channel) & 0x1U) << 1U);
+ /* Get INT bit flag */
+ retval |= (((base->INT >> channel) & 0x1U) << 2U);
+
+ return retval;
+}
+
+void EDMA_ClearChannelStatusFlags(DMA_Type *base, uint32_t channel, uint32_t mask)
+{
+ assert(channel < FSL_FEATURE_EDMA_MODULE_CHANNEL);
+
+ /* Clear DONE bit flag */
+ if (mask & kEDMA_DoneFlag)
+ {
+ base->CDNE = channel;
+ }
+ /* Clear ERROR bit flag */
+ if (mask & kEDMA_ErrorFlag)
+ {
+ base->CERR = channel;
+ }
+ /* Clear INT bit flag */
+ if (mask & kEDMA_InterruptFlag)
+ {
+ base->CINT = channel;
+ }
+}
+
+void EDMA_CreateHandle(edma_handle_t *handle, DMA_Type *base, uint32_t channel)
+{
+ assert(handle != NULL);
+ assert(channel < FSL_FEATURE_EDMA_MODULE_CHANNEL);
+
+ uint32_t edmaInstance;
+ uint32_t channelIndex;
+ edma_tcd_t *tcdRegs;
+
+ handle->base = base;
+ handle->channel = channel;
+ /* Get the DMA instance number */
+ edmaInstance = EDMA_GetInstance(base);
+ channelIndex = (edmaInstance * FSL_FEATURE_EDMA_MODULE_CHANNEL) + channel;
+ s_EDMAHandle[channelIndex] = handle;
+ /* Enable NVIC interrupt */
+ EnableIRQ(s_edmaIRQNumber[channelIndex]);
+ /*
+ Reset TCD registers to zero. Unlike the EDMA_TcdReset(DREQ will be set),
+ CSR will be 0. Because in order to suit EDMA busy check mechanism in
+ EDMA_SubmitTransfer, CSR must be set 0.
+ */
+ tcdRegs = (edma_tcd_t *)&handle->base->TCD[handle->channel];
+ tcdRegs->SADDR = 0;
+ tcdRegs->SOFF = 0;
+ tcdRegs->ATTR = 0;
+ tcdRegs->NBYTES = 0;
+ tcdRegs->SLAST = 0;
+ tcdRegs->DADDR = 0;
+ tcdRegs->DOFF = 0;
+ tcdRegs->CITER = 0;
+ tcdRegs->DLAST_SGA = 0;
+ tcdRegs->CSR = 0;
+ tcdRegs->BITER = 0;
+}
+
+void EDMA_InstallTCDMemory(edma_handle_t *handle, edma_tcd_t *tcdPool, uint32_t tcdSize)
+{
+ assert(handle != NULL);
+ assert(((uint32_t)tcdPool & 0x1FU) == 0);
+
+ /* Initialize tcd queue attibute. */
+ handle->header = 0;
+ handle->tail = 0;
+ handle->tcdUsed = 0;
+ handle->tcdSize = tcdSize;
+ handle->flags = 0;
+ handle->tcdPool = tcdPool;
+}
+
+void EDMA_SetCallback(edma_handle_t *handle, edma_callback callback, void *userData)
+{
+ assert(handle != NULL);
+
+ handle->callback = callback;
+ handle->userData = userData;
+}
+
+void EDMA_PrepareTransfer(edma_transfer_config_t *config,
+ void *srcAddr,
+ uint32_t srcWidth,
+ void *destAddr,
+ uint32_t destWidth,
+ uint32_t bytesEachRequest,
+ uint32_t transferBytes,
+ edma_transfer_type_t type)
+{
+ assert(config != NULL);
+ assert(srcAddr != NULL);
+ assert(destAddr != NULL);
+ assert((srcWidth == 1U) || (srcWidth == 2U) || (srcWidth == 4U) || (srcWidth == 16U) || (srcWidth == 32U));
+ assert((destWidth == 1U) || (destWidth == 2U) || (destWidth == 4U) || (destWidth == 16U) || (destWidth == 32U));
+ assert(transferBytes % bytesEachRequest == 0);
+
+ config->destAddr = (uint32_t)destAddr;
+ config->srcAddr = (uint32_t)srcAddr;
+ config->minorLoopBytes = bytesEachRequest;
+ config->majorLoopCounts = transferBytes / bytesEachRequest;
+ switch (srcWidth)
+ {
+ case 1U:
+ config->srcTransferSize = kEDMA_TransferSize1Bytes;
+ break;
+ case 2U:
+ config->srcTransferSize = kEDMA_TransferSize2Bytes;
+ break;
+ case 4U:
+ config->srcTransferSize = kEDMA_TransferSize4Bytes;
+ break;
+ case 16U:
+ config->srcTransferSize = kEDMA_TransferSize16Bytes;
+ break;
+ case 32U:
+ config->srcTransferSize = kEDMA_TransferSize32Bytes;
+ break;
+ default:
+ break;
+ }
+ switch (destWidth)
+ {
+ case 1U:
+ config->destTransferSize = kEDMA_TransferSize1Bytes;
+ break;
+ case 2U:
+ config->destTransferSize = kEDMA_TransferSize2Bytes;
+ break;
+ case 4U:
+ config->destTransferSize = kEDMA_TransferSize4Bytes;
+ break;
+ case 16U:
+ config->destTransferSize = kEDMA_TransferSize16Bytes;
+ break;
+ case 32U:
+ config->destTransferSize = kEDMA_TransferSize32Bytes;
+ break;
+ default:
+ break;
+ }
+ switch (type)
+ {
+ case kEDMA_MemoryToMemory:
+ config->destOffset = destWidth;
+ config->srcOffset = srcWidth;
+ break;
+ case kEDMA_MemoryToPeripheral:
+ config->destOffset = 0U;
+ config->srcOffset = srcWidth;
+ break;
+ case kEDMA_PeripheralToMemory:
+ config->destOffset = destWidth;
+ config->srcOffset = 0U;
+ break;
+ default:
+ break;
+ }
+}
+
+status_t EDMA_SubmitTransfer(edma_handle_t *handle, const edma_transfer_config_t *config)
+{
+ assert(handle != NULL);
+ assert(config != NULL);
+
+ edma_tcd_t *tcdRegs = (edma_tcd_t *)&handle->base->TCD[handle->channel];
+
+ if (handle->tcdPool == NULL)
+ {
+ /*
+ Check if EDMA is busy: if the given channel started transfer, CSR will be not zero. Because
+ if it is the last transfer, DREQ will be set. If not, ESG will be set. So in order to suit
+ this check mechanism, EDMA_CreatHandle will clear CSR register.
+ */
+ if ((tcdRegs->CSR != 0) && ((tcdRegs->CSR & DMA_CSR_DONE_MASK) == 0))
+ {
+ return kStatus_EDMA_Busy;
+ }
+ else
+ {
+ EDMA_SetTransferConfig(handle->base, handle->channel, config, NULL);
+ /* Enable auto disable request feature */
+ handle->base->TCD[handle->channel].CSR |= DMA_CSR_DREQ_MASK;
+ /* Enable major interrupt */
+ handle->base->TCD[handle->channel].CSR |= DMA_CSR_INTMAJOR_MASK;
+
+ return kStatus_Success;
+ }
+ }
+ else /* Use the TCD queue. */
+ {
+ uint32_t primask;
+ uint32_t csr;
+ int8_t currentTcd;
+ int8_t previousTcd;
+ int8_t nextTcd;
+
+ /* Check if tcd pool is full. */
+ primask = DisableGlobalIRQ();
+ if (handle->tcdUsed >= handle->tcdSize)
+ {
+ EnableGlobalIRQ(primask);
+
+ return kStatus_EDMA_QueueFull;
+ }
+ currentTcd = handle->tail;
+ handle->tcdUsed++;
+ /* Calculate index of next TCD */
+ nextTcd = currentTcd + 1U;
+ if (nextTcd == handle->tcdSize)
+ {
+ nextTcd = 0U;
+ }
+ /* Advance queue tail index */
+ handle->tail = nextTcd;
+ EnableGlobalIRQ(primask);
+ /* Calculate index of previous TCD */
+ previousTcd = currentTcd ? currentTcd - 1U : handle->tcdSize - 1U;
+ /* Configure current TCD block. */
+ EDMA_TcdReset(&handle->tcdPool[currentTcd]);
+ EDMA_TcdSetTransferConfig(&handle->tcdPool[currentTcd], config, NULL);
+ /* Enable major interrupt */
+ handle->tcdPool[currentTcd].CSR |= DMA_CSR_INTMAJOR_MASK;
+ /* Link current TCD with next TCD for identification of current TCD */
+ handle->tcdPool[currentTcd].DLAST_SGA = (uint32_t)&handle->tcdPool[nextTcd];
+ /* Chain from previous descriptor unless tcd pool size is 1(this descriptor is its own predecessor). */
+ if (currentTcd != previousTcd)
+ {
+ /* Enable scatter/gather feature in the previous TCD block. */
+ csr = (handle->tcdPool[previousTcd].CSR | DMA_CSR_ESG_MASK) & ~DMA_CSR_DREQ_MASK;
+ handle->tcdPool[previousTcd].CSR = csr;
+ /*
+ Check if the TCD blcok in the registers is the previous one (points to current TCD block). It
+ is used to check if the previous TCD linked has been loaded in TCD register. If so, it need to
+ link the TCD register in case link the current TCD with the dead chain when TCD loading occurs
+ before link the previous TCD block.
+ */
+ if (tcdRegs->DLAST_SGA == (uint32_t)&handle->tcdPool[currentTcd])
+ {
+ /* Enable scatter/gather also in the TCD registers. */
+ csr = (tcdRegs->CSR | DMA_CSR_ESG_MASK) & ~DMA_CSR_DREQ_MASK;
+ /* Must write the CSR register one-time, because the transfer maybe finished anytime. */
+ tcdRegs->CSR = csr;
+ /*
+ It is very important to check the ESG bit!
+ Because this hardware design: if DONE bit is set, the ESG bit can not be set. So it can
+ be used to check if the dynamic TCD link operation is successful. If ESG bit is not set
+ and the DLAST_SGA is not the next TCD address(it means the dynamic TCD link succeed and
+ the current TCD block has been loaded into TCD registers), it means transfer finished
+ and TCD link operation fail, so must install TCD content into TCD registers and enable
+ transfer again. And if ESG is set, it means transfer has notfinished, so TCD dynamic
+ link succeed.
+ */
+ if (tcdRegs->CSR & DMA_CSR_ESG_MASK)
+ {
+ return kStatus_Success;
+ }
+ /*
+ Check whether the current TCD block is already loaded in the TCD registers. It is another
+ condition when ESG bit is not set: it means the dynamic TCD link succeed and the current
+ TCD block has been loaded into TCD registers.
+ */
+ if (tcdRegs->DLAST_SGA == (uint32_t)&handle->tcdPool[nextTcd])
+ {
+ return kStatus_Success;
+ }
+ /*
+ If go to this, means the previous transfer finished, and the DONE bit is set.
+ So shall configure TCD registers.
+ */
+ }
+ else if (tcdRegs->DLAST_SGA != 0)
+ {
+ /* The current TCD block has been linked successfully. */
+ return kStatus_Success;
+ }
+ else
+ {
+ /*
+ DLAST_SGA is 0 and it means the first submit transfer, so shall configure
+ TCD registers.
+ */
+ }
+ }
+ /* There is no live chain, TCD block need to be installed in TCD registers. */
+ EDMA_InstallTCD(handle->base, handle->channel, &handle->tcdPool[currentTcd]);
+ /* Enable channel request again. */
+ if (handle->flags & EDMA_TRANSFER_ENABLED_MASK)
+ {
+ handle->base->SERQ = DMA_SERQ_SERQ(handle->channel);
+ }
+
+ return kStatus_Success;
+ }
+}
+
+void EDMA_StartTransfer(edma_handle_t *handle)
+{
+ assert(handle != NULL);
+
+ if (handle->tcdPool == NULL)
+ {
+ handle->base->SERQ = DMA_SERQ_SERQ(handle->channel);
+ }
+ else /* Use the TCD queue. */
+ {
+ uint32_t primask;
+ edma_tcd_t *tcdRegs = (edma_tcd_t *)&handle->base->TCD[handle->channel];
+
+ handle->flags |= EDMA_TRANSFER_ENABLED_MASK;
+
+ /* Check if there was at least one descriptor submitted since reset (TCD in registers is valid) */
+ if (tcdRegs->DLAST_SGA != 0U)
+ {
+ primask = DisableGlobalIRQ();
+ /* Check if channel request is actually disable. */
+ if ((handle->base->ERQ & (1U << handle->channel)) == 0U)
+ {
+ /* Check if transfer is paused. */
+ if ((!(tcdRegs->CSR & DMA_CSR_DONE_MASK)) || (tcdRegs->CSR & DMA_CSR_ESG_MASK))
+ {
+ /*
+ Re-enable channel request must be as soon as possible, so must put it into
+ critical section to avoid task switching or interrupt service routine.
+ */
+ handle->base->SERQ = DMA_SERQ_SERQ(handle->channel);
+ }
+ }
+ EnableGlobalIRQ(primask);
+ }
+ }
+}
+
+void EDMA_StopTransfer(edma_handle_t *handle)
+{
+ assert(handle != NULL);
+
+ handle->flags &= (~EDMA_TRANSFER_ENABLED_MASK);
+ handle->base->CERQ = DMA_CERQ_CERQ(handle->channel);
+}
+
+void EDMA_AbortTransfer(edma_handle_t *handle)
+{
+ handle->base->CERQ = DMA_CERQ_CERQ(handle->channel);
+ /*
+ Clear CSR to release channel. Because if the given channel started transfer,
+ CSR will be not zero. Because if it is the last transfer, DREQ will be set.
+ If not, ESG will be set.
+ */
+ handle->base->TCD[handle->channel].CSR = 0;
+ /* Cancel all next TCD transfer. */
+ handle->base->TCD[handle->channel].DLAST_SGA = 0;
+}
+
+void EDMA_HandleIRQ(edma_handle_t *handle)
+{
+ assert(handle != NULL);
+
+ /* Clear EDMA interrupt flag */
+ handle->base->CINT = handle->channel;
+ if ((handle->tcdPool == NULL) && (handle->callback != NULL))
+ {
+ (handle->callback)(handle, handle->userData, true, 0);
+ }
+ else /* Use the TCD queue. */
+ {
+ uint32_t sga = handle->base->TCD[handle->channel].DLAST_SGA;
+ uint32_t sga_index;
+ int32_t tcds_done;
+ uint8_t new_header;
+ bool transfer_done;
+
+ /* Check if transfer is already finished. */
+ transfer_done = ((handle->base->TCD[handle->channel].CSR & DMA_CSR_DONE_MASK) != 0);
+ /* Get the offset of the current transfer TCD blcoks. */
+ sga -= (uint32_t)handle->tcdPool;
+ /* Get the index of the current transfer TCD blcoks. */
+ sga_index = sga / sizeof(edma_tcd_t);
+ /* Adjust header positions. */
+ if (transfer_done)
+ {
+ /* New header shall point to the next TCD (current one is already finished) */
+ new_header = sga_index;
+ }
+ else
+ {
+ /* New header shall point to this descriptor (not finished yet) */
+ new_header = sga_index ? sga_index - 1U : handle->tcdSize - 1U;
+ }
+ /* Calculate the number of finished TCDs */
+ if (new_header == handle->header)
+ {
+ if (handle->tcdUsed == handle->tcdSize)
+ {
+ tcds_done = handle->tcdUsed;
+ }
+ else
+ {
+ /* Internal error occurs. */
+ tcds_done = 0;
+ }
+ }
+ else
+ {
+ tcds_done = new_header - handle->header;
+ if (tcds_done < 0)
+ {
+ tcds_done += handle->tcdSize;
+ }
+ }
+ /* Advance header to the point beyond the last finished TCD block. */
+ handle->header = new_header;
+ /* Release TCD blocks. */
+ handle->tcdUsed -= tcds_done;
+ /* Invoke callback function. */
+ if (handle->callback)
+ {
+ (handle->callback)(handle, handle->userData, transfer_done, tcds_done);
+ }
+ }
+}
+
+/* 8 channels (Shared): kl28 */
+#if defined(FSL_FEATURE_EDMA_MODULE_CHANNEL) && FSL_FEATURE_EDMA_MODULE_CHANNEL == 8U
+
+void DMA0_04_DriverIRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA0, 0U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[0]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA0, 4U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[4]);
+ }
+}
+
+void DMA0_15_DriverIRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA0, 1U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[1]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA0, 5U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[5]);
+ }
+}
+
+void DMA0_26_DriverIRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA0, 2U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[2]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA0, 6U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[6]);
+ }
+}
+
+void DMA0_37_DriverIRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA0, 3U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[3]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA0, 7U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[7]);
+ }
+}
+#endif /* 8 channels (Shared) */
+
+/* 32 channels (Shared): k80 */
+#if defined(FSL_FEATURE_EDMA_MODULE_CHANNEL) && FSL_FEATURE_EDMA_MODULE_CHANNEL == 32U
+
+void DMA0_DMA16_IRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA0, 0U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[0]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA0, 16U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[16]);
+ }
+}
+
+void DMA1_DMA17_IRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA0, 1U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[1]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA0, 17U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[17]);
+ }
+}
+
+void DMA2_DMA18_IRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA0, 2U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[2]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA0, 18U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[18]);
+ }
+}
+
+void DMA3_DMA19_IRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA0, 3U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[3]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA0, 19U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[19]);
+ }
+}
+
+void DMA4_DMA20_IRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA0, 4U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[4]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA0, 20U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[20]);
+ }
+}
+
+void DMA5_DMA21_IRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA0, 5U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[5]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA0, 21U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[21]);
+ }
+}
+
+void DMA6_DMA22_IRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA0, 6U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[6]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA0, 22U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[22]);
+ }
+}
+
+void DMA7_DMA23_IRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA0, 7U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[7]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA0, 23U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[23]);
+ }
+}
+
+void DMA8_DMA24_IRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA0, 8U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[8]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA0, 24U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[24]);
+ }
+}
+
+void DMA9_DMA25_IRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA0, 9U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[9]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA0, 25U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[25]);
+ }
+}
+
+void DMA10_DMA26_IRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA0, 10U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[10]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA0, 26U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[26]);
+ }
+}
+
+void DMA11_DMA27_IRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA0, 11U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[11]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA0, 27U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[27]);
+ }
+}
+
+void DMA12_DMA28_IRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA0, 12U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[12]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA0, 28U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[28]);
+ }
+}
+
+void DMA13_DMA29_IRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA0, 13U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[13]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA0, 29U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[29]);
+ }
+}
+
+void DMA14_DMA30_IRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA0, 14U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[14]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA0, 30U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[30]);
+ }
+}
+
+void DMA15_DMA31_IRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA0, 15U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[15]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA0, 31U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[31]);
+ }
+}
+#endif /* 32 channels (Shared) */
+
+/* 4 channels (No Shared): kv10 */
+#if defined(FSL_FEATURE_EDMA_MODULE_CHANNEL) && FSL_FEATURE_EDMA_MODULE_CHANNEL > 0
+
+void DMA0_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[0]);
+}
+
+void DMA1_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[1]);
+}
+
+void DMA2_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[2]);
+}
+
+void DMA3_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[3]);
+}
+
+/* 8 channels (No Shared) */
+#if defined(FSL_FEATURE_EDMA_MODULE_CHANNEL) && FSL_FEATURE_EDMA_MODULE_CHANNEL > 4U
+
+void DMA4_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[4]);
+}
+
+void DMA5_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[5]);
+}
+
+void DMA6_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[6]);
+}
+
+void DMA7_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[7]);
+}
+#endif /* FSL_FEATURE_EDMA_MODULE_CHANNEL == 8 */
+
+/* 16 channels (No Shared) */
+#if defined(FSL_FEATURE_EDMA_MODULE_CHANNEL) && FSL_FEATURE_EDMA_MODULE_CHANNEL > 8U
+
+void DMA8_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[8]);
+}
+
+void DMA9_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[9]);
+}
+
+void DMA10_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[10]);
+}
+
+void DMA11_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[11]);
+}
+
+void DMA12_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[12]);
+}
+
+void DMA13_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[13]);
+}
+
+void DMA14_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[14]);
+}
+
+void DMA15_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[15]);
+}
+#endif /* FSL_FEATURE_EDMA_MODULE_CHANNEL == 16 */
+
+/* 32 channels (No Shared) */
+#if defined(FSL_FEATURE_EDMA_MODULE_CHANNEL) && FSL_FEATURE_EDMA_MODULE_CHANNEL > 16U
+
+void DMA16_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[16]);
+}
+
+void DMA17_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[17]);
+}
+
+void DMA18_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[18]);
+}
+
+void DMA19_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[19]);
+}
+
+void DMA20_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[20]);
+}
+
+void DMA21_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[21]);
+}
+
+void DMA22_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[22]);
+}
+
+void DMA23_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[23]);
+}
+
+void DMA24_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[24]);
+}
+
+void DMA25_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[25]);
+}
+
+void DMA26_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[26]);
+}
+
+void DMA27_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[27]);
+}
+
+void DMA28_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[28]);
+}
+
+void DMA29_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[29]);
+}
+
+void DMA30_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[30]);
+}
+
+void DMA31_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[31]);
+}
+#endif /* FSL_FEATURE_EDMA_MODULE_CHANNEL == 32 */
+
+#endif /* 4/8/16/32 channels (No Shared) */
diff --git a/drivers/fsl_edma.h b/drivers/fsl_edma.h
new file mode 100644
index 0000000..02c4fab
--- /dev/null
+++ b/drivers/fsl_edma.h
@@ -0,0 +1,880 @@
+/*
+* Copyright (c) 2015, Freescale Semiconductor, Inc.
+* All rights reserved.
+*
+* 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 Freescale Semiconductor, Inc. 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_EDMA_H_
+#define _FSL_EDMA_H_
+
+#include "fsl_common.h"
+
+/*!
+ * @addtogroup edma
+ * @{
+ */
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+/*! @name Driver version */
+/*@{*/
+/*! @brief eDMA driver version */
+#define FSL_EDMA_DRIVER_VERSION (MAKE_VERSION(2, 0, 1)) /*!< Version 2.0.1. */
+/*@}*/
+
+/*! @brief Compute the offset unit from DCHPRI3 */
+#define DMA_DCHPRI_INDEX(channel) (((channel) & ~0x03U) | (3 - ((channel)&0x03U)))
+
+/*! @brief Get the pointer of DCHPRIn */
+#define DMA_DCHPRIn(base, channel) ((volatile uint8_t *)&(base->DCHPRI3))[DMA_DCHPRI_INDEX(channel)]
+
+/*! @brief eDMA transfer configuration */
+typedef enum _edma_transfer_size
+{
+ kEDMA_TransferSize1Bytes = 0x0U, /*!< Source/Destination data transfer size is 1 byte every time */
+ kEDMA_TransferSize2Bytes = 0x1U, /*!< Source/Destination data transfer size is 2 bytes every time */
+ kEDMA_TransferSize4Bytes = 0x2U, /*!< Source/Destination data transfer size is 4 bytes every time */
+ kEDMA_TransferSize16Bytes = 0x4U, /*!< Source/Destination data transfer size is 16 bytes every time */
+ kEDMA_TransferSize32Bytes = 0x5U, /*!< Source/Destination data transfer size is 32 bytes every time */
+} edma_transfer_size_t;
+
+/*! @brief eDMA modulo configuration */
+typedef enum _edma_modulo
+{
+ kEDMA_ModuloDisable = 0x0U, /*!< Disable modulo */
+ kEDMA_Modulo2bytes, /*!< Circular buffer size is 2 bytes. */
+ kEDMA_Modulo4bytes, /*!< Circular buffer size is 4 bytes. */
+ kEDMA_Modulo8bytes, /*!< Circular buffer size is 8 bytes. */
+ kEDMA_Modulo16bytes, /*!< Circular buffer size is 16 bytes. */
+ kEDMA_Modulo32bytes, /*!< Circular buffer size is 32 bytes. */
+ kEDMA_Modulo64bytes, /*!< Circular buffer size is 64 bytes. */
+ kEDMA_Modulo128bytes, /*!< Circular buffer size is 128 bytes. */
+ kEDMA_Modulo256bytes, /*!< Circular buffer size is 256 bytes. */
+ kEDMA_Modulo512bytes, /*!< Circular buffer size is 512 bytes. */
+ kEDMA_Modulo1Kbytes, /*!< Circular buffer size is 1K bytes. */
+ kEDMA_Modulo2Kbytes, /*!< Circular buffer size is 2K bytes. */
+ kEDMA_Modulo4Kbytes, /*!< Circular buffer size is 4K bytes. */
+ kEDMA_Modulo8Kbytes, /*!< Circular buffer size is 8K bytes. */
+ kEDMA_Modulo16Kbytes, /*!< Circular buffer size is 16K bytes. */
+ kEDMA_Modulo32Kbytes, /*!< Circular buffer size is 32K bytes. */
+ kEDMA_Modulo64Kbytes, /*!< Circular buffer size is 64K bytes. */
+ kEDMA_Modulo128Kbytes, /*!< Circular buffer size is 128K bytes. */
+ kEDMA_Modulo256Kbytes, /*!< Circular buffer size is 256K bytes. */
+ kEDMA_Modulo512Kbytes, /*!< Circular buffer size is 512K bytes. */
+ kEDMA_Modulo1Mbytes, /*!< Circular buffer size is 1M bytes. */
+ kEDMA_Modulo2Mbytes, /*!< Circular buffer size is 2M bytes. */
+ kEDMA_Modulo4Mbytes, /*!< Circular buffer size is 4M bytes. */
+ kEDMA_Modulo8Mbytes, /*!< Circular buffer size is 8M bytes. */
+ kEDMA_Modulo16Mbytes, /*!< Circular buffer size is 16M bytes. */
+ kEDMA_Modulo32Mbytes, /*!< Circular buffer size is 32M bytes. */
+ kEDMA_Modulo64Mbytes, /*!< Circular buffer size is 64M bytes. */
+ kEDMA_Modulo128Mbytes, /*!< Circular buffer size is 128M bytes. */
+ kEDMA_Modulo256Mbytes, /*!< Circular buffer size is 256M bytes. */
+ kEDMA_Modulo512Mbytes, /*!< Circular buffer size is 512M bytes. */
+ kEDMA_Modulo1Gbytes, /*!< Circular buffer size is 1G bytes. */
+ kEDMA_Modulo2Gbytes, /*!< Circular buffer size is 2G bytes. */
+} edma_modulo_t;
+
+/*! @brief Bandwidth control */
+typedef enum _edma_bandwidth
+{
+ kEDMA_BandwidthStallNone = 0x0U, /*!< No eDMA engine stalls. */
+ kEDMA_BandwidthStall4Cycle = 0x2U, /*!< eDMA engine stalls for 4 cycles after each read/write. */
+ kEDMA_BandwidthStall8Cycle = 0x3U, /*!< eDMA engine stalls for 8 cycles after each read/write. */
+} edma_bandwidth_t;
+
+/*! @brief Channel link type */
+typedef enum _edma_channel_link_type
+{
+ kEDMA_LinkNone = 0x0U, /*!< No channel link */
+ kEDMA_MinorLink, /*!< Channel link after each minor loop */
+ kEDMA_MajorLink, /*!< Channel link while major loop count exhausted */
+} edma_channel_link_type_t;
+
+/*!@brief eDMA channel status flags. */
+enum _edma_channel_status_flags
+{
+ kEDMA_DoneFlag = 0x1U, /*!< DONE flag, set while transfer finished, CITER value exhausted*/
+ kEDMA_ErrorFlag = 0x2U, /*!< eDMA error flag, an error occurred in a transfer */
+ kEDMA_InterruptFlag = 0x4U, /*!< eDMA interrupt flag, set while an interrupt occurred of this channel */
+};
+
+/*! @brief eDMA channel error status flags. */
+enum _edma_error_status_flags
+{
+ kEDMA_DestinationBusErrorFlag = DMA_ES_DBE_MASK, /*!< Bus error on destination address */
+ kEDMA_SourceBusErrorFlag = DMA_ES_SBE_MASK, /*!< Bus error on the source address */
+ kEDMA_ScatterGatherErrorFlag = DMA_ES_SGE_MASK, /*!< Error on the Scatter/Gather address, not 32byte aligned. */
+ kEDMA_NbytesErrorFlag = DMA_ES_NCE_MASK, /*!< NBYTES/CITER configuration error */
+ kEDMA_DestinationOffsetErrorFlag = DMA_ES_DOE_MASK, /*!< Destination offset not aligned with destination size */
+ kEDMA_DestinationAddressErrorFlag = DMA_ES_DAE_MASK, /*!< Destination address not aligned with destination size */
+ kEDMA_SourceOffsetErrorFlag = DMA_ES_SOE_MASK, /*!< Source offset not aligned with source size */
+ kEDMA_SourceAddressErrorFlag = DMA_ES_SAE_MASK, /*!< Source address not aligned with source size*/
+ kEDMA_ErrorChannelFlag = DMA_ES_ERRCHN_MASK, /*!< Error channel number of the cancelled channel number */
+ kEDMA_ChannelPriorityErrorFlag = DMA_ES_CPE_MASK, /*!< Channel priority is not unique. */
+ kEDMA_TransferCanceledFlag = DMA_ES_ECX_MASK, /*!< Transfer cancelled */
+#if defined(FSL_FEATURE_EDMA_CHANNEL_GROUP_COUNT) && FSL_FEATURE_EDMA_CHANNEL_GROUP_COUNT > 1
+ kEDMA_GroupPriorityErrorFlag = DMA_ES_GPE_MASK, /*!< Group priority is not unique. */
+#endif
+ kEDMA_ValidFlag = DMA_ES_VLD_MASK, /*!< No error occurred, this bit is 0. Otherwise, it is 1. */
+};
+
+/*! @brief eDMA interrupt source */
+typedef enum _edma_interrupt_enable
+{
+ kEDMA_ErrorInterruptEnable = 0x1U, /*!< Enable interrupt while channel error occurs. */
+ kEDMA_MajorInterruptEnable = DMA_CSR_INTMAJOR_MASK, /*!< Enable interrupt while major count exhausted. */
+ kEDMA_HalfInterruptEnable = DMA_CSR_INTHALF_MASK, /*!< Enable interrupt while major count to half value. */
+} edma_interrupt_enable_t;
+
+/*! @brief eDMA transfer type */
+typedef enum _edma_transfer_type
+{
+ kEDMA_MemoryToMemory = 0x0U, /*!< Transfer from memory to memory */
+ kEDMA_PeripheralToMemory, /*!< Transfer from peripheral to memory */
+ kEDMA_MemoryToPeripheral, /*!< Transfer from memory to peripheral */
+} edma_transfer_type_t;
+
+/*! @brief eDMA transfer status */
+enum _edma_transfer_status
+{
+ kStatus_EDMA_QueueFull = MAKE_STATUS(kStatusGroup_EDMA, 0), /*!< TCD queue is full. */
+ kStatus_EDMA_Busy = MAKE_STATUS(kStatusGroup_EDMA, 1), /*!< Channel is busy and can't handle the
+ transfer request. */
+};
+
+/*! @brief eDMA global configuration structure.*/
+typedef struct _edma_config
+{
+ bool enableContinuousLinkMode; /*!< Enable (true) continuous link mode. Upon minor loop completion, the channel
+ activates again if that channel has a minor loop channel link enabled and
+ the link channel is itself. */
+ bool enableHaltOnError; /*!< Enable (true) transfer halt on error. Any error causes the HALT bit to set.
+ Subsequently, all service requests are ignored until the HALT bit is cleared.*/
+ bool enableRoundRobinArbitration; /*!< Enable (true) round robin channel arbitration method, or fixed priority
+ arbitration is used for channel selection */
+ bool enableDebugMode; /*!< Enable(true) eDMA debug mode. When in debug mode, the eDMA stalls the start of
+ a new channel. Executing channels are allowed to complete. */
+} edma_config_t;
+
+/*!
+ * @brief eDMA transfer configuration
+ *
+ * This structure configures the source/destination transfer attribute.
+ * This figure shows the eDMA's transfer model:
+ * _________________________________________________
+ * | Transfer Size | |
+ * Minor Loop |_______________| Major loop Count 1 |
+ * Bytes | Transfer Size | |
+ * ____________|_______________|____________________|--> Minor loop complete
+ * ____________________________________
+ * | | |
+ * |_______________| Major Loop Count 2 |
+ * | | |
+ * |_______________|____________________|--> Minor loop Complete
+ *
+ * ---------------------------------------------------------> Transfer complete
+ */
+typedef struct _edma_transfer_config
+{
+ uint32_t srcAddr; /*!< Source data address. */
+ uint32_t destAddr; /*!< Destination data address. */
+ edma_transfer_size_t srcTransferSize; /*!< Source data transfer size. */
+ edma_transfer_size_t destTransferSize; /*!< Destination data transfer size. */
+ int16_t srcOffset; /*!< Sign-extended offset applied to the current source address to
+ form the next-state value as each source read is completed. */
+ int16_t destOffset; /*!< Sign-extended offset applied to the current destination address to
+ form the next-state value as each destination write is completed. */
+ uint16_t minorLoopBytes; /*!< Bytes to transfer in a minor loop*/
+ uint32_t majorLoopCounts; /*!< Major loop iteration count. */
+} edma_transfer_config_t;
+
+/*! @brief eDMA channel priority configuration */
+typedef struct _edma_channel_Preemption_config
+{
+ bool enableChannelPreemption; /*!< If true: channel can be suspended by other channel with higher priority */
+ bool enablePreemptAbility; /*!< If true: channel can suspend other channel with low priority */
+ uint8_t channelPriority; /*!< Channel priority */
+} edma_channel_Preemption_config_t;
+
+/*! @brief eDMA minor offset configuration */
+typedef struct _edma_minor_offset_config
+{
+ bool enableSrcMinorOffset; /*!< Enable(true) or Disable(false) source minor loop offset. */
+ bool enableDestMinorOffset; /*!< Enable(true) or Disable(false) destination minor loop offset. */
+ uint32_t minorOffset; /*!< Offset for minor loop mapping. */
+} edma_minor_offset_config_t;
+
+/*!
+ * @brief eDMA TCD.
+ *
+ * This structure is same as TCD register which is described in reference manual,
+ * and is used to configure the scatter/gather feature as a next hardware TCD.
+ */
+typedef struct _edma_tcd
+{
+ __IO uint32_t SADDR; /*!< SADDR register, used to save source address */
+ __IO uint16_t SOFF; /*!< SOFF register, save offset bytes every transfer */
+ __IO uint16_t ATTR; /*!< ATTR register, source/destination transfer size and modulo */
+ __IO uint32_t NBYTES; /*!< Nbytes register, minor loop length in bytes */
+ __IO uint32_t SLAST; /*!< SLAST register */
+ __IO uint32_t DADDR; /*!< DADDR register, used for destination address */
+ __IO uint16_t DOFF; /*!< DOFF register, used for destination offset */
+ __IO uint16_t CITER; /*!< CITER register, current minor loop numbers, for unfinished minor loop.*/
+ __IO uint32_t DLAST_SGA; /*!< DLASTSGA register, next stcd address used in scatter-gather mode */
+ __IO uint16_t CSR; /*!< CSR register, for TCD control status */
+ __IO uint16_t BITER; /*!< BITER register, begin minor loop count. */
+} edma_tcd_t;
+
+/*! @brief Callback for eDMA */
+struct _edma_handle;
+
+/*! @brief Define Callback function for eDMA. */
+typedef void (*edma_callback)(struct _edma_handle *handle, void *userData, bool transferDone, uint32_t tcds);
+
+/*! @brief eDMA transfer handle structure */
+typedef struct _edma_handle
+{
+ edma_callback callback; /*!< Callback function for major count exhausted. */
+ void *userData; /*!< Callback function parameter. */
+ DMA_Type *base; /*!< eDMA peripheral base address. */
+ edma_tcd_t *tcdPool; /*!< Pointer to memory stored TCDs. */
+ uint8_t channel; /*!< eDMA channel number. */
+ volatile int8_t header; /*!< The first TCD index. */
+ volatile int8_t tail; /*!< The last TCD index. */
+ volatile int8_t tcdUsed; /*!< The number of used TCD slots. */
+ volatile int8_t tcdSize; /*!< The total number of TCD slots in the queue. */
+ uint8_t flags; /*!< The status of the current channel. */
+} edma_handle_t;
+
+/*******************************************************************************
+ * APIs
+ ******************************************************************************/
+#if defined(__cplusplus)
+extern "C" {
+#endif /* __cplusplus */
+
+/*!
+ * @name eDMA initialization and De-initialization
+ * @{
+ */
+
+/*!
+ * @brief Initializes eDMA peripheral.
+ *
+ * This function ungates the eDMA clock and configures the eDMA peripheral according
+ * to the configuration structure.
+ *
+ * @param base eDMA peripheral base address.
+ * @param config Pointer to configuration structure, see "edma_config_t".
+ * @note This function enable the minor loop map feature.
+ */
+void EDMA_Init(DMA_Type *base, const edma_config_t *config);
+
+/*!
+ * @brief Deinitializes eDMA peripheral.
+ *
+ * This function gates the eDMA clock.
+ *
+ * @param base eDMA peripheral base address.
+ */
+void EDMA_Deinit(DMA_Type *base);
+
+/*!
+ * @brief Gets the eDMA default configuration structure.
+ *
+ * This function sets the configuration structure to a default value.
+ * The default configuration is set to the following value:
+ * @code
+ * config.enableContinuousLinkMode = false;
+ * config.enableHaltOnError = true;
+ * config.enableRoundRobinArbitration = false;
+ * config.enableDebugMode = false;
+ * @endcode
+ *
+ * @param config Pointer to eDMA configuration structure.
+ */
+void EDMA_GetDefaultConfig(edma_config_t *config);
+
+/* @} */
+/*!
+ * @name eDMA Channel Operation
+ * @{
+ */
+
+/*!
+ * @brief Sets all TCD registers to a default value.
+ *
+ * This function sets TCD registers for this channel to default value.
+ *
+ * @param base eDMA peripheral base address.
+ * @param channel eDMA channel number.
+ * @note This function must not be called while the channel transfer is on-going,
+ * or it causes unpredictable results.
+ * @note This function enables the auto stop request feature.
+ */
+void EDMA_ResetChannel(DMA_Type *base, uint32_t channel);
+
+/*!
+ * @brief Configures the eDMA transfer attribute.
+ *
+ * This function configures the transfer attribute, including source address, destination address,
+ * transfer size, address offset, and so on. It also configures the scatter gather feature if the
+ * user supplies the TCD address.
+ * Example:
+ * @code
+ * edma_transfer_t config;
+ * edma_tcd_t tcd;
+ * config.srcAddr = ..;
+ * config.destAddr = ..;
+ * ...
+ * EDMA_SetTransferConfig(DMA0, channel, &config, &stcd);
+ * @endcode
+ *
+ * @param base eDMA peripheral base address.
+ * @param channel eDMA channel number.
+ * @param config Pointer to eDMA transfer configuration structure.
+ * @param nextTcd Point to TCD structure. It can be NULL if users
+ * do not want to enable scatter/gather feature.
+ * @note If nextTcd is not NULL, it means scatter gather feature is enabled
+ * and DREQ bit is cleared in the previous transfer configuration, which
+ * is set in eDMA_ResetChannel.
+ */
+void EDMA_SetTransferConfig(DMA_Type *base,
+ uint32_t channel,
+ const edma_transfer_config_t *config,
+ edma_tcd_t *nextTcd);
+
+/*!
+ * @brief Configures the eDMA minor offset feature.
+ *
+ * Minor offset means signed-extended value added to source address or destination
+ * address after each minor loop.
+ *
+ * @param base eDMA peripheral base address.
+ * @param channel eDMA channel number.
+ * @param config Pointer to Minor offset configuration structure.
+ */
+void EDMA_SetMinorOffsetConfig(DMA_Type *base, uint32_t channel, const edma_minor_offset_config_t *config);
+
+/*!
+ * @brief Configures the eDMA channel preemption feature.
+ *
+ * This function configures the channel preemption attribute and the priority of the channel.
+ *
+ * @param base eDMA peripheral base address.
+ * @param channel eDMA channel number
+ * @param config Pointer to channel preemption configuration structure.
+ */
+static inline void EDMA_SetChannelPreemptionConfig(DMA_Type *base,
+ uint32_t channel,
+ const edma_channel_Preemption_config_t *config)
+{
+ assert(channel < FSL_FEATURE_EDMA_MODULE_CHANNEL);
+ assert(config != NULL);
+
+ DMA_DCHPRIn(base, channel) =
+ (DMA_DCHPRI0_DPA(!config->enablePreemptAbility) | DMA_DCHPRI0_ECP(config->enableChannelPreemption) |
+ DMA_DCHPRI0_CHPRI(config->channelPriority));
+}
+
+/*!
+ * @brief Sets the channel link for the eDMA transfer.
+ *
+ * This function configures minor link or major link mode. The minor link means that the channel link is
+ * triggered every time CITER decreases by 1. The major link means that the channel link is triggered when the CITER is
+ * exhausted.
+ *
+ * @param base eDMA peripheral base address.
+ * @param channel eDMA channel number.
+ * @param type Channel link type, it can be one of:
+ * @arg kEDMA_LinkNone
+ * @arg kEDMA_MinorLink
+ * @arg kEDMA_MajorLink
+ * @param linkedChannel The linked channel number.
+ * @note Users should ensure that DONE flag is cleared before calling this interface, or the configuration is invalid.
+ */
+void EDMA_SetChannelLink(DMA_Type *base, uint32_t channel, edma_channel_link_type_t type, uint32_t linkedChannel);
+
+/*!
+ * @brief Sets the bandwidth for the eDMA transfer.
+ *
+ * In general, because the eDMA processes the minor loop, it continuously generates read/write sequences
+ * until the minor count is exhausted. The bandwidth forces the eDMA to stall after the completion of
+ * each read/write access to control the bus request bandwidth seen by the crossbar switch.
+ *
+ * @param base eDMA peripheral base address.
+ * @param channel eDMA channel number.
+ * @param bandWidth Bandwidth setting, it can be one of:
+ * @arg kEDMABandwidthStallNone
+ * @arg kEDMABandwidthStall4Cycle
+ * @arg kEDMABandwidthStall8Cycle
+ */
+void EDMA_SetBandWidth(DMA_Type *base, uint32_t channel, edma_bandwidth_t bandWidth);
+
+/*!
+ * @brief Sets the source modulo and destination modulo for eDMA transfer.
+ *
+ * This function defines a specific address range specified to be the value after (SADDR + SOFF)/(DADDR + DOFF)
+ * calculation is performed or the original register value. It provides the ability to implement a circular data
+ * queue easily.
+ *
+ * @param base eDMA peripheral base address.
+ * @param channel eDMA channel number.
+ * @param srcModulo Source modulo value.
+ * @param destModulo Destination modulo value.
+ */
+void EDMA_SetModulo(DMA_Type *base, uint32_t channel, edma_modulo_t srcModulo, edma_modulo_t destModulo);
+
+#if defined(FSL_FEATURE_EDMA_ASYNCHRO_REQUEST_CHANNEL_COUNT) && FSL_FEATURE_EDMA_ASYNCHRO_REQUEST_CHANNEL_COUNT
+/*!
+ * @brief Enables an async request for the eDMA transfer.
+ *
+ * @param base eDMA peripheral base address.
+ * @param channel eDMA channel number.
+ * @param enable The command for enable(ture) or disable(false).
+ */
+static inline void EDMA_EnableAsyncRequest(DMA_Type *base, uint32_t channel, bool enable)
+{
+ assert(channel < FSL_FEATURE_DMAMUX_MODULE_CHANNEL);
+
+ base->EARS = (base->EARS & (~(1U << channel))) | ((uint32_t)enable << channel);
+}
+#endif /* FSL_FEATURE_EDMA_ASYNCHRO_REQUEST_CHANNEL_COUNT */
+
+/*!
+ * @brief Enables an auto stop request for the eDMA transfer.
+ *
+ * If enabling the auto stop request, the eDMA hardware automatically disables the hardware channel request.
+ *
+ * @param base eDMA peripheral base address.
+ * @param channel eDMA channel number.
+ * @param enable The command for enable (true) or disable (false).
+ */
+static inline void EDMA_EnableAutoStopRequest(DMA_Type *base, uint32_t channel, bool enable)
+{
+ assert(channel < FSL_FEATURE_DMAMUX_MODULE_CHANNEL);
+
+ base->TCD[channel].CSR = (base->TCD[channel].CSR & (~DMA_CSR_DREQ_MASK)) | DMA_CSR_DREQ(enable);
+}
+
+/*!
+ * @brief Enables the interrupt source for the eDMA transfer.
+ *
+ * @param base eDMA peripheral base address.
+ * @param channel eDMA channel number.
+ * @param mask The mask of interrupt source to be set. Users need to use
+ * the defined edma_interrupt_enable_t type.
+ */
+void EDMA_EnableChannelInterrupts(DMA_Type *base, uint32_t channel, uint32_t mask);
+
+/*!
+ * @brief Disables the interrupt source for the eDMA transfer.
+ *
+ * @param base eDMA peripheral base address.
+ * @param channel eDMA channel number.
+ * @param mask The mask of interrupt source to be set. Use
+ * the defined edma_interrupt_enable_t type.
+ */
+void EDMA_DisableChannelInterrupts(DMA_Type *base, uint32_t channel, uint32_t mask);
+
+/* @} */
+/*!
+ * @name eDMA TCD Operation
+ * @{
+ */
+
+/*!
+ * @brief Sets all fields to default values for the TCD structure.
+ *
+ * This function sets all fields for this TCD structure to default value.
+ *
+ * @param tcd Pointer to the TCD structure.
+ * @note This function enables the auto stop request feature.
+ */
+void EDMA_TcdReset(edma_tcd_t *tcd);
+
+/*!
+ * @brief Configures the eDMA TCD transfer attribute.
+ *
+ * TCD is a transfer control descriptor. The content of the TCD is the same as hardware TCD registers.
+ * STCD is used in scatter-gather mode.
+ * This function configures the TCD transfer attribute, including source address, destination address,
+ * transfer size, address offset, and so on. It also configures the scatter gather feature if the
+ * user supplies the next TCD address.
+ * Example:
+ * @code
+ * edma_transfer_t config = {
+ * ...
+ * }
+ * edma_tcd_t tcd __aligned(32);
+ * edma_tcd_t nextTcd __aligned(32);
+ * EDMA_TcdSetTransferConfig(&tcd, &config, &nextTcd);
+ * @endcode
+ *
+ * @param tcd Pointer to the TCD structure.
+ * @param config Pointer to eDMA transfer configuration structure.
+ * @param nextTcd Pointer to the next TCD structure. It can be NULL if users
+ * do not want to enable scatter/gather feature.
+ * @note TCD address should be 32 bytes aligned, or it causes an eDMA error.
+ * @note If the nextTcd is not NULL, the scatter gather feature is enabled
+ * and DREQ bit is cleared in the previous transfer configuration, which
+ * is set in the EDMA_TcdReset.
+ */
+void EDMA_TcdSetTransferConfig(edma_tcd_t *tcd, const edma_transfer_config_t *config, edma_tcd_t *nextTcd);
+
+/*!
+ * @brief Configures the eDMA TCD minor offset feature.
+ *
+ * Minor offset is a signed-extended value added to the source address or destination
+ * address after each minor loop.
+ *
+ * @param tcd Point to the TCD structure.
+ * @param config Pointer to Minor offset configuration structure.
+ */
+void EDMA_TcdSetMinorOffsetConfig(edma_tcd_t *tcd, const edma_minor_offset_config_t *config);
+
+/*!
+ * @brief Sets the channel link for eDMA TCD.
+ *
+ * This function configures either a minor link or a major link. The minor link means the channel link is
+ * triggered every time CITER decreases by 1. The major link means that the channel link is triggered when the CITER is
+ * exhausted.
+ *
+ * @note Users should ensure that DONE flag is cleared before calling this interface, or the configuration is invalid.
+ * @param tcd Point to the TCD structure.
+ * @param type Channel link type, it can be one of:
+ * @arg kEDMA_LinkNone
+ * @arg kEDMA_MinorLink
+ * @arg kEDMA_MajorLink
+ * @param linkedChannel The linked channel number.
+ */
+void EDMA_TcdSetChannelLink(edma_tcd_t *tcd, edma_channel_link_type_t type, uint32_t linkedChannel);
+
+/*!
+ * @brief Sets the bandwidth for the eDMA TCD.
+ *
+ * In general, because the eDMA processes the minor loop, it continuously generates read/write sequences
+ * until the minor count is exhausted. Bandwidth forces the eDMA to stall after the completion of
+ * each read/write access to control the bus request bandwidth seen by the crossbar switch.
+ * @param tcd Point to the TCD structure.
+ * @param bandWidth Bandwidth setting, it can be one of:
+ * @arg kEDMABandwidthStallNone
+ * @arg kEDMABandwidthStall4Cycle
+ * @arg kEDMABandwidthStall8Cycle
+ */
+static inline void EDMA_TcdSetBandWidth(edma_tcd_t *tcd, edma_bandwidth_t bandWidth)
+{
+ assert(tcd != NULL);
+ assert(((uint32_t)tcd & 0x1FU) == 0);
+
+ tcd->CSR = (tcd->CSR & (~DMA_CSR_BWC_MASK)) | DMA_CSR_BWC(bandWidth);
+}
+
+/*!
+ * @brief Sets the source modulo and destination modulo for eDMA TCD.
+ *
+ * This function defines a specific address range specified to be the value after (SADDR + SOFF)/(DADDR + DOFF)
+ * calculation is performed or the original register value. It provides the ability to implement a circular data
+ * queue easily.
+ *
+ * @param tcd Point to the TCD structure.
+ * @param srcModulo Source modulo value.
+ * @param destModulo Destination modulo value.
+ */
+void EDMA_TcdSetModulo(edma_tcd_t *tcd, edma_modulo_t srcModulo, edma_modulo_t destModulo);
+
+/*!
+ * @brief Sets the auto stop request for the eDMA TCD.
+ *
+ * If enabling the auto stop request, the eDMA hardware automatically disables the hardware channel request.
+ *
+ * @param tcd Point to the TCD structure.
+ * @param enable The command for enable(ture) or disable(false).
+ */
+static inline void EDMA_TcdEnableAutoStopRequest(edma_tcd_t *tcd, bool enable)
+{
+ assert(tcd != NULL);
+ assert(((uint32_t)tcd & 0x1FU) == 0);
+
+ tcd->CSR = (tcd->CSR & (~DMA_CSR_DREQ_MASK)) | DMA_CSR_DREQ(enable);
+}
+
+/*!
+ * @brief Enables the interrupt source for the eDMA TCD.
+ *
+ * @param tcd Point to the TCD structure.
+ * @param mask The mask of interrupt source to be set. Users need to use
+ * the defined edma_interrupt_enable_t type.
+ */
+void EDMA_TcdEnableInterrupts(edma_tcd_t *tcd, uint32_t mask);
+
+/*!
+ * @brief Disables the interrupt source for the eDMA TCD.
+ *
+ * @param tcd Point to the TCD structure.
+ * @param mask The mask of interrupt source to be set. Users need to use
+ * the defined edma_interrupt_enable_t type.
+ */
+void EDMA_TcdDisableInterrupts(edma_tcd_t *tcd, uint32_t mask);
+
+/*! @} */
+/*!
+ * @name eDMA Channel Transfer Operation
+ * @{
+ */
+
+/*!
+ * @brief Enables the eDMA hardware channel request.
+ *
+ * This function enables the hardware channel request.
+ *
+ * @param base eDMA peripheral base address.
+ * @param channel eDMA channel number.
+ */
+static inline void EDMA_EnableChannelRequest(DMA_Type *base, uint32_t channel)
+{
+ assert(channel < FSL_FEATURE_DMAMUX_MODULE_CHANNEL);
+
+ base->SERQ = DMA_SERQ_SERQ(channel);
+}
+
+/*!
+ * @brief Disables the eDMA hardware channel request.
+ *
+ * This function disables the hardware channel request.
+ *
+ * @param base eDMA peripheral base address.
+ * @param channel eDMA channel number.
+ */
+static inline void EDMA_DisableChannelRequest(DMA_Type *base, uint32_t channel)
+{
+ assert(channel < FSL_FEATURE_DMAMUX_MODULE_CHANNEL);
+
+ base->CERQ = DMA_CERQ_CERQ(channel);
+}
+
+/*!
+ * @brief Starts the eDMA transfer by software trigger.
+ *
+ * This function starts a minor loop transfer.
+ *
+ * @param base eDMA peripheral base address.
+ * @param channel eDMA channel number.
+ */
+static inline void EDMA_TriggerChannelStart(DMA_Type *base, uint32_t channel)
+{
+ assert(channel < FSL_FEATURE_DMAMUX_MODULE_CHANNEL);
+
+ base->SSRT = DMA_SSRT_SSRT(channel);
+}
+
+/*! @} */
+/*!
+ * @name eDMA Channel Status Operation
+ * @{
+ */
+
+/*!
+ * @brief Gets the Remaining bytes from the eDMA current channel TCD.
+ *
+ * This function checks the TCD (Task Control Descriptor) status for a specified
+ * eDMA channel and returns the the number of bytes that have not finished.
+ *
+ * @param base eDMA peripheral base address.
+ * @param channel eDMA channel number.
+ * @return Bytes have not been transferred yet for the current TCD.
+ * @note This function can only be used to get unfinished bytes of transfer without
+ * the next TCD, or it might be inaccuracy.
+ */
+uint32_t EDMA_GetRemainingBytes(DMA_Type *base, uint32_t channel);
+
+/*!
+ * @brief Gets the eDMA channel error status flags.
+ *
+ * @param base eDMA peripheral base address.
+ * @return The mask of error status flags. Users need to use the
+ * _edma_error_status_flags type to decode the return variables.
+ */
+static inline uint32_t EDMA_GetErrorStatusFlags(DMA_Type *base)
+{
+ return base->ES;
+}
+
+/*!
+ * @brief Gets the eDMA channel status flags.
+ *
+ * @param base eDMA peripheral base address.
+ * @param channel eDMA channel number.
+ * @return The mask of channel status flags. Users need to use the
+ * _edma_channel_status_flags type to decode the return variables.
+ */
+uint32_t EDMA_GetChannelStatusFlags(DMA_Type *base, uint32_t channel);
+
+/*!
+ * @brief Clears the eDMA channel status flags.
+ *
+ * @param base eDMA peripheral base address.
+ * @param channel eDMA channel number.
+ * @param mask The mask of channel status to be cleared. Users need to use
+ * the defined _edma_channel_status_flags type.
+ */
+void EDMA_ClearChannelStatusFlags(DMA_Type *base, uint32_t channel, uint32_t mask);
+
+/*! @} */
+/*!
+ * @name eDMA Transactional Operation
+ */
+
+/*!
+ * @brief Creates the eDMA handle.
+ *
+ * This function is called if using transaction API for eDMA. This function
+ * initializes the internal state of eDMA handle.
+ *
+ * @param handle eDMA handle pointer. The eDMA handle stores callback function and
+ * parameters.
+ * @param base eDMA peripheral base address.
+ * @param channel eDMA channel number.
+ */
+void EDMA_CreateHandle(edma_handle_t *handle, DMA_Type *base, uint32_t channel);
+
+/*!
+ * @brief Installs the TCDs memory pool into eDMA handle.
+ *
+ * This function is called after the EDMA_CreateHandle to use scatter/gather feature.
+ *
+ * @param handle eDMA handle pointer.
+ * @param tcdPool Memory pool to store TCDs. It must be 32 bytes aligned.
+ * @param tcdSize The number of TCD slots.
+ */
+void EDMA_InstallTCDMemory(edma_handle_t *handle, edma_tcd_t *tcdPool, uint32_t tcdSize);
+
+/*!
+ * @brief Installs a callback function for the eDMA transfer.
+ *
+ * This callback is called in eDMA IRQ handler. Use the callback to do something after
+ * the current major loop transfer completes.
+ *
+ * @param handle eDMA handle pointer.
+ * @param callback eDMA callback function pointer.
+ * @param userData Parameter for callback function.
+ */
+void EDMA_SetCallback(edma_handle_t *handle, edma_callback callback, void *userData);
+
+/*!
+ * @brief Prepares the eDMA transfer structure.
+ *
+ * This function prepares the transfer configuration structure according to the user input.
+ *
+ * @param config The user configuration structure of type edma_transfer_t.
+ * @param srcAddr eDMA transfer source address.
+ * @param srcWidth eDMA transfer source address width(bytes).
+ * @param destAddr eDMA transfer destination address.
+ * @param destWidth eDMA transfer destination address width(bytes).
+ * @param bytesEachRequest eDMA transfer bytes per channel request.
+ * @param transferBytes eDMA transfer bytes to be transferred.
+ * @param type eDMA transfer type.
+ * @note The data address and the data width must be consistent. For example, if the SRC
+ * is 4 bytes, so the source address must be 4 bytes aligned, or it shall result in
+ * source address error(SAE).
+ */
+void EDMA_PrepareTransfer(edma_transfer_config_t *config,
+ void *srcAddr,
+ uint32_t srcWidth,
+ void *destAddr,
+ uint32_t destWidth,
+ uint32_t bytesEachRequest,
+ uint32_t transferBytes,
+ edma_transfer_type_t type);
+
+/*!
+ * @brief Submits the eDMA transfer request.
+ *
+ * This function submits the eDMA transfer request according to the transfer configuration structure.
+ * If the user submits the transfer request repeatedly, this function packs an unprocessed request as
+ * a TCD and enables scatter/gather feature to process it in the next time.
+ *
+ * @param handle eDMA handle pointer.
+ * @param config Pointer to eDMA transfer configuration structure.
+ * @retval kStatus_EDMA_Success It means submit transfer request succeed.
+ * @retval kStatus_EDMA_QueueFull It means TCD queue is full. Submit transfer request is not allowed.
+ * @retval kStatus_EDMA_Busy It means the given channel is busy, need to submit request later.
+ */
+status_t EDMA_SubmitTransfer(edma_handle_t *handle, const edma_transfer_config_t *config);
+
+/*!
+ * @brief eDMA start transfer.
+ *
+ * This function enables the channel request. Users can call this function after submitting the transfer request
+ * or before submitting the transfer request.
+ *
+ * @param handle eDMA handle pointer.
+ */
+void EDMA_StartTransfer(edma_handle_t *handle);
+
+/*!
+ * @brief eDMA stop transfer.
+ *
+ * This function disables the channel request to pause the transfer. Users can call EDMA_StartTransfer()
+ * again to resume the transfer.
+ *
+ * @param handle eDMA handle pointer.
+ */
+void EDMA_StopTransfer(edma_handle_t *handle);
+
+/*!
+ * @brief eDMA abort transfer.
+ *
+ * This function disables the channel request and clear transfer status bits.
+ * Users can submit another transfer after calling this API.
+ *
+ * @param handle DMA handle pointer.
+ */
+void EDMA_AbortTransfer(edma_handle_t *handle);
+
+/*!
+ * @brief eDMA IRQ handler for current major loop transfer complete.
+ *
+ * This function clears the channel major interrupt flag and call
+ * the callback function if it is not NULL.
+ *
+ * @param handle eDMA handle pointer.
+ */
+void EDMA_HandleIRQ(edma_handle_t *handle);
+
+/* @} */
+
+#if defined(__cplusplus)
+}
+#endif /* __cplusplus */
+
+/* @} */
+
+#endif /*_FSL_EDMA_H_*/
diff --git a/drivers/fsl_ewm.c b/drivers/fsl_ewm.c
new file mode 100644
index 0000000..1a71a07
--- /dev/null
+++ b/drivers/fsl_ewm.c
@@ -0,0 +1,92 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_ewm.h"
+
+/*******************************************************************************
+ * Code
+ ******************************************************************************/
+
+void EWM_Init(EWM_Type *base, const ewm_config_t *config)
+{
+ assert(config);
+
+ uint32_t value = 0U;
+
+ CLOCK_EnableClock(kCLOCK_Ewm0);
+ value = EWM_CTRL_EWMEN(config->enableEwm) | EWM_CTRL_ASSIN(config->setInputAssertLogic) |
+ EWM_CTRL_INEN(config->enableEwmInput) | EWM_CTRL_INTEN(config->enableInterrupt);
+#if defined(FSL_FEATURE_EWM_HAS_PRESCALER) && FSL_FEATURE_EWM_HAS_PRESCALER
+ base->CLKPRESCALER = config->prescaler;
+#endif /* FSL_FEATURE_EWM_HAS_PRESCALER */
+
+#if defined(FSL_FEATURE_EWM_HAS_CLOCK_SELECT) && FSL_FEATURE_EWM_HAS_CLOCK_SELECT
+ base->CLKCTRL = config->clockSource;
+#endif /* FSL_FEATURE_EWM_HAS_CLOCK_SELECT*/
+
+ base->CMPL = config->compareLowValue;
+ base->CMPH = config->compareHighValue;
+ base->CTRL = value;
+}
+
+void EWM_Deinit(EWM_Type *base)
+{
+ EWM_DisableInterrupts(base, kEWM_InterruptEnable);
+ CLOCK_DisableClock(kCLOCK_Ewm0);
+}
+
+void EWM_GetDefaultConfig(ewm_config_t *config)
+{
+ assert(config);
+
+ config->enableEwm = true;
+ config->enableEwmInput = false;
+ config->setInputAssertLogic = false;
+ config->enableInterrupt = false;
+#if defined(FSL_FEATURE_EWM_HAS_CLOCK_SELECT) && FSL_FEATURE_EWM_HAS_CLOCK_SELECT
+ config->clockSource = kEWM_LpoClockSource0;
+#endif /* FSL_FEATURE_EWM_HAS_CLOCK_SELECT*/
+#if defined(FSL_FEATURE_EWM_HAS_PRESCALER) && FSL_FEATURE_EWM_HAS_PRESCALER
+ config->prescaler = 0U;
+#endif /* FSL_FEATURE_EWM_HAS_PRESCALER */
+ config->compareLowValue = 0U;
+ config->compareHighValue = 0xFEU;
+}
+
+void EWM_Refresh(EWM_Type *base)
+{
+ uint32_t primaskValue = 0U;
+
+ /* Disable the global interrupt to protect refresh sequence */
+ primaskValue = DisableGlobalIRQ();
+ base->SERV = (uint8_t)0xB4U;
+ base->SERV = (uint8_t)0x2CU;
+ EnableGlobalIRQ(primaskValue);
+}
diff --git a/drivers/fsl_ewm.h b/drivers/fsl_ewm.h
new file mode 100644
index 0000000..180575e
--- /dev/null
+++ b/drivers/fsl_ewm.h
@@ -0,0 +1,241 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_EWM_H_
+#define _FSL_EWM_H_
+
+#include "fsl_common.h"
+
+/*!
+ * @addtogroup ewm
+ * @{
+ */
+
+
+/*******************************************************************************
+ * Definitions
+ *******************************************************************************/
+
+/*! @name Driver version */
+/*@{*/
+/*! @brief EWM driver version 2.0.1. */
+#define FSL_EWM_DRIVER_VERSION (MAKE_VERSION(2, 0, 1))
+/*@}*/
+
+/*! @brief Describes EWM clock source. */
+#if defined(FSL_FEATURE_EWM_HAS_CLOCK_SELECT) && FSL_FEATURE_EWM_HAS_CLOCK_SELECT
+typedef enum _ewm_lpo_clock_source
+{
+ kEWM_LpoClockSource0 = 0U, /*!< EWM clock sourced from lpo_clk[0]*/
+ kEWM_LpoClockSource1 = 1U, /*!< EWM clock sourced from lpo_clk[1]*/
+ kEWM_LpoClockSource2 = 2U, /*!< EWM clock sourced from lpo_clk[2]*/
+ kEWM_LpoClockSource3 = 3U, /*!< EWM clock sourced from lpo_clk[3]*/
+} ewm_lpo_clock_source_t;
+#endif /* FSL_FEATURE_EWM_HAS_CLOCK_SELECT */
+
+/*!
+* @brief Data structure for EWM configuration.
+*
+* This structure is used to configure the EWM.
+*/
+typedef struct _ewm_config
+{
+ bool enableEwm; /*!< Enable EWM module */
+ bool enableEwmInput; /*!< Enable EWM_in input */
+ bool setInputAssertLogic; /*!< EWM_in signal assertion state */
+ bool enableInterrupt; /*!< Enable EWM interrupt */
+#if defined(FSL_FEATURE_EWM_HAS_CLOCK_SELECT) && FSL_FEATURE_EWM_HAS_CLOCK_SELECT
+ ewm_lpo_clock_source_t clockSource; /*!< Clock source select */
+#endif /* FSL_FEATURE_EWM_HAS_CLOCK_SELECT */
+#if defined(FSL_FEATURE_EWM_HAS_PRESCALER) && FSL_FEATURE_EWM_HAS_PRESCALER
+ uint8_t prescaler; /*!< Clock prescaler value */
+#endif /* FSL_FEATURE_EWM_HAS_PRESCALER */
+ uint8_t compareLowValue; /*!< Compare low-register value */
+ uint8_t compareHighValue; /*!< Compare high-register value */
+} ewm_config_t;
+
+/*!
+ * @brief EWM interrupt configuration structure, default settings all disabled.
+ *
+ * This structure contains the settings for all of the EWM interrupt configurations.
+ */
+enum _ewm_interrupt_enable_t
+{
+ kEWM_InterruptEnable = EWM_CTRL_INTEN_MASK, /*!< Enable EWM to generate an interrupt*/
+};
+
+/*!
+ * @brief EWM status flags.
+ *
+ * This structure contains the constants for the EWM status flags for use in the EWM functions.
+ */
+enum _ewm_status_flags_t
+{
+ kEWM_RunningFlag = EWM_CTRL_EWMEN_MASK, /*!< Running flag, set when EWM is enabled*/
+};
+
+/*******************************************************************************
+ * API
+ *******************************************************************************/
+
+#if defined(__cplusplus)
+extern "C" {
+#endif /* __cplusplus */
+
+/*!
+ * @name EWM Initialization and De-initialization
+ * @{
+ */
+
+/*!
+ * @brief Initializes the EWM peripheral.
+ *
+ * This function is used to initialize the EWM. After calling, the EWM
+ * runs immediately according to the configuration.
+ * Note that except for interrupt enable control bit, other control bits and registers are write once after a
+ * CPU reset. Modifying them more than once generates a bus transfer error.
+ *
+ * Example:
+ * @code
+ * ewm_config_t config;
+ * EWM_GetDefaultConfig(&config);
+ * config.compareHighValue = 0xAAU;
+ * EWM_Init(ewm_base,&config);
+ * @endcode
+ *
+ * @param base EWM peripheral base address
+ * @param config The configuration of EWM
+*/
+void EWM_Init(EWM_Type *base, const ewm_config_t *config);
+
+/*!
+ * @brief Deinitializes the EWM peripheral.
+ *
+ * This function is used to shut down the EWM.
+ *
+ * @param base EWM peripheral base address
+*/
+void EWM_Deinit(EWM_Type *base);
+
+/*!
+ * @brief Initializes the EWM configuration structure.
+ *
+ * This function initializes the EWM configuration structure to default values. The default
+ * values are:
+ * @code
+ * ewmConfig->enableEwm = true;
+ * ewmConfig->enableEwmInput = false;
+ * ewmConfig->setInputAssertLogic = false;
+ * ewmConfig->enableInterrupt = false;
+ * ewmConfig->ewm_lpo_clock_source_t = kEWM_LpoClockSource0;
+ * ewmConfig->prescaler = 0;
+ * ewmConfig->compareLowValue = 0;
+ * ewmConfig->compareHighValue = 0xFEU;
+ * @endcode
+ *
+ * @param config Pointer to EWM configuration structure.
+ * @see ewm_config_t
+ */
+void EWM_GetDefaultConfig(ewm_config_t *config);
+
+/* @} */
+
+/*!
+ * @name EWM functional Operation
+ * @{
+ */
+
+/*!
+ * @brief Enables the EWM interrupt.
+ *
+ * This function enables the EWM interrupt.
+ *
+ * @param base EWM peripheral base address
+ * @param mask The interrupts to enable
+ * The parameter can be combination of the following source if defined:
+ * @arg kEWM_InterruptEnable
+ */
+static inline void EWM_EnableInterrupts(EWM_Type *base, uint32_t mask)
+{
+ base->CTRL |= mask;
+}
+
+/*!
+ * @brief Disables the EWM interrupt.
+ *
+ * This function enables the EWM interrupt.
+ *
+ * @param base EWM peripheral base address
+ * @param mask The interrupts to disable
+ * The parameter can be combination of the following source if defined:
+ * @arg kEWM_InterruptEnable
+ */
+static inline void EWM_DisableInterrupts(EWM_Type *base, uint32_t mask)
+{
+ base->CTRL &= ~mask;
+}
+
+/*!
+ * @brief Gets EWM all status flags.
+ *
+ * This function gets all status flags.
+ *
+ * Example for getting Running Flag:
+ * @code
+ * uint32_t status;
+ * status = EWM_GetStatusFlags(ewm_base) & kEWM_RunningFlag;
+ * @endcode
+ * @param base EWM peripheral base address
+ * @return State of the status flag: asserted (true) or not-asserted (false).@see _ewm_status_flags_t
+ * - true: a related status flag has been set.
+ * - false: a related status flag is not set.
+ */
+static inline uint32_t EWM_GetStatusFlags(EWM_Type *base)
+{
+ return (base->CTRL & EWM_CTRL_EWMEN_MASK);
+}
+
+/*!
+ * @brief Services the EWM.
+ *
+ * This function reset EWM counter to zero.
+ *
+ * @param base EWM peripheral base address
+*/
+void EWM_Refresh(EWM_Type *base);
+
+/*@}*/
+
+#if defined(__cplusplus)
+}
+#endif /* __cplusplus */
+
+/*! @}*/
+
+#endif /* _FSL_EWM_H_ */
diff --git a/drivers/fsl_flash.c b/drivers/fsl_flash.c
new file mode 100644
index 0000000..9251c49
--- /dev/null
+++ b/drivers/fsl_flash.c
@@ -0,0 +1,2630 @@
+/*
+ * Copyright (c) 2015-2016, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_flash.h"
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+/*!
+ * @name Misc utility defines
+ * @{
+ */
+#ifndef ALIGN_DOWN
+#define ALIGN_DOWN(x, a) ((x) & (uint32_t)(-((int32_t)(a))))
+#endif
+#ifndef ALIGN_UP
+#define ALIGN_UP(x, a) (-((int32_t)((uint32_t)(-((int32_t)(x))) & (uint32_t)(-((int32_t)(a))))))
+#endif
+
+#define BYTES_JOIN_TO_WORD_1_3(x, y) ((((uint32_t)(x)&0xFFU) << 24) | ((uint32_t)(y)&0xFFFFFFU))
+#define BYTES_JOIN_TO_WORD_2_2(x, y) ((((uint32_t)(x)&0xFFFFU) << 16) | ((uint32_t)(y)&0xFFFFU))
+#define BYTES_JOIN_TO_WORD_3_1(x, y) ((((uint32_t)(x)&0xFFFFFFU) << 8) | ((uint32_t)(y)&0xFFU))
+#define BYTES_JOIN_TO_WORD_1_1_2(x, y, z) \
+ ((((uint32_t)(x)&0xFFU) << 24) | (((uint32_t)(y)&0xFFU) << 16) | ((uint32_t)(z)&0xFFFFU))
+#define BYTES_JOIN_TO_WORD_1_2_1(x, y, z) \
+ ((((uint32_t)(x)&0xFFU) << 24) | (((uint32_t)(y)&0xFFFFU) << 8) | ((uint32_t)(z)&0xFFU))
+#define BYTES_JOIN_TO_WORD_2_1_1(x, y, z) \
+ ((((uint32_t)(x)&0xFFFFU) << 16) | (((uint32_t)(y)&0xFFU) << 8) | ((uint32_t)(z)&0xFFU))
+#define BYTES_JOIN_TO_WORD_1_1_1_1(x, y, z, w) \
+ ((((uint32_t)(x)&0xFFU) << 24) | (((uint32_t)(y)&0xFFU) << 16) | (((uint32_t)(z)&0xFFU) << 8) | \
+ ((uint32_t)(w)&0xFFU))
+/*@}*/
+
+/*! @brief Data flash IFR map Field*/
+#if defined(FSL_FEATURE_FLASH_IS_FTFE) && FSL_FEATURE_FLASH_IS_FTFE
+#define DFLASH_IFR_READRESOURCE_START_ADDRESS 0x8003F8U
+#else /* FSL_FEATURE_FLASH_IS_FTFL == 1 or FSL_FEATURE_FLASH_IS_FTFA = =1 */
+#define DFLASH_IFR_READRESOURCE_START_ADDRESS 0x8000F8U
+#endif
+
+/*!
+ * @name Reserved FlexNVM size (For a variety of purposes) defines
+ * @{
+ */
+#define FLEX_NVM_DFLASH_SIZE_FOR_DEPART_RESERVED 0xFFFFFFFFU
+#define FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_RESERVED 0xFFFFU
+/*@}*/
+
+/*!
+ * @name Flash Program Once Field defines
+ * @{
+ */
+#if defined(FSL_FEATURE_FLASH_IS_FTFA) && FSL_FEATURE_FLASH_IS_FTFA
+/* FTFA parts(eg. K80, KL80, L5K) support both 4-bytes and 8-bytes unit size */
+#define FLASH_PROGRAM_ONCE_MIN_ID_8BYTES \
+ 0x10U /* Minimum Index indcating one of Progam Once Fields which is accessed in 8-byte records */
+#define FLASH_PROGRAM_ONCE_MAX_ID_8BYTES \
+ 0x13U /* Maximum Index indcating one of Progam Once Fields which is accessed in 8-byte records */
+#define FLASH_PROGRAM_ONCE_IS_4BYTES_UNIT_SUPPORT 1
+#define FLASH_PROGRAM_ONCE_IS_8BYTES_UNIT_SUPPORT 1
+#elif defined(FSL_FEATURE_FLASH_IS_FTFE) && FSL_FEATURE_FLASH_IS_FTFE
+/* FTFE parts(eg. K65, KE18) only support 8-bytes unit size */
+#define FLASH_PROGRAM_ONCE_IS_4BYTES_UNIT_SUPPORT 0
+#define FLASH_PROGRAM_ONCE_IS_8BYTES_UNIT_SUPPORT 1
+#elif defined(FSL_FEATURE_FLASH_IS_FTFL) && FSL_FEATURE_FLASH_IS_FTFL
+/* FTFL parts(eg. K20) only support 4-bytes unit size */
+#define FLASH_PROGRAM_ONCE_IS_4BYTES_UNIT_SUPPORT 1
+#define FLASH_PROGRAM_ONCE_IS_8BYTES_UNIT_SUPPORT 0
+#endif
+/*@}*/
+
+/*!
+ * @name Flash security status defines
+ * @{
+ */
+#define FLASH_SECURITY_STATE_KEYEN 0x80U
+#define FLASH_SECURITY_STATE_UNSECURED 0x02U
+#define FLASH_NOT_SECURE 0x01U
+#define FLASH_SECURE_BACKDOOR_ENABLED 0x02U
+#define FLASH_SECURE_BACKDOOR_DISABLED 0x04U
+/*@}*/
+
+/*!
+ * @name Flash controller command numbers
+ * @{
+ */
+#define FTFx_VERIFY_BLOCK 0x00U /*!< RD1BLK*/
+#define FTFx_VERIFY_SECTION 0x01U /*!< RD1SEC*/
+#define FTFx_PROGRAM_CHECK 0x02U /*!< PGMCHK*/
+#define FTFx_READ_RESOURCE 0x03U /*!< RDRSRC*/
+#define FTFx_PROGRAM_LONGWORD 0x06U /*!< PGM4*/
+#define FTFx_PROGRAM_PHRASE 0x07U /*!< PGM8*/
+#define FTFx_ERASE_BLOCK 0x08U /*!< ERSBLK*/
+#define FTFx_ERASE_SECTOR 0x09U /*!< ERSSCR*/
+#define FTFx_PROGRAM_SECTION 0x0BU /*!< PGMSEC*/
+#define FTFx_VERIFY_ALL_BLOCK 0x40U /*!< RD1ALL*/
+#define FTFx_READ_ONCE 0x41U /*!< RDONCE or RDINDEX*/
+#define FTFx_PROGRAM_ONCE 0x43U /*!< PGMONCE or PGMINDEX*/
+#define FTFx_ERASE_ALL_BLOCK 0x44U /*!< ERSALL*/
+#define FTFx_SECURITY_BY_PASS 0x45U /*!< VFYKEY*/
+#define FTFx_SWAP_CONTROL 0x46U /*!< SWAP*/
+#define FTFx_ERASE_ALL_BLOCK_UNSECURE 0x49U /*!< ERSALLU*/
+#define FTFx_VERIFY_ALL_EXECUTE_ONLY_SEGMENT 0x4AU /*!< RD1XA*/
+#define FTFx_ERASE_ALL_EXECUTE_ONLY_SEGMENT 0x4BU /*!< ERSXA*/
+#define FTFx_PROGRAM_PARTITION 0x80U /*!< PGMPART)*/
+#define FTFx_SET_FLEXRAM_FUNCTION 0x81U /*!< SETRAM*/
+ /*@}*/
+
+/*!
+ * @name Common flash register info defines
+ * @{
+ */
+#if defined(FTFA)
+#define FTFx FTFA
+#define FTFx_BASE FTFA_BASE
+#define FTFx_FSTAT_CCIF_MASK FTFA_FSTAT_CCIF_MASK
+#define FTFx_FSTAT_RDCOLERR_MASK FTFA_FSTAT_RDCOLERR_MASK
+#define FTFx_FSTAT_ACCERR_MASK FTFA_FSTAT_ACCERR_MASK
+#define FTFx_FSTAT_FPVIOL_MASK FTFA_FSTAT_FPVIOL_MASK
+#define FTFx_FSTAT_MGSTAT0_MASK FTFA_FSTAT_MGSTAT0_MASK
+#define FTFx_FSEC_SEC_MASK FTFA_FSEC_SEC_MASK
+#define FTFx_FSEC_KEYEN_MASK FTFA_FSEC_KEYEN_MASK
+#if defined(FSL_FEATURE_FLASH_HAS_FLEX_RAM) && FSL_FEATURE_FLASH_HAS_FLEX_RAM
+#define FTFx_FCNFG_RAMRDY_MASK FTFA_FCNFG_RAMRDY_MASK
+#endif /* FSL_FEATURE_FLASH_HAS_FLEX_RAM */
+#if defined(FSL_FEATURE_FLASH_HAS_FLEX_NVM) && FSL_FEATURE_FLASH_HAS_FLEX_NVM
+#define FTFx_FCNFG_EEERDY_MASK FTFA_FCNFG_EEERDY_MASK
+#endif /* FSL_FEATURE_FLASH_HAS_FLEX_NVM */
+#elif defined(FTFE)
+#define FTFx FTFE
+#define FTFx_BASE FTFE_BASE
+#define FTFx_FSTAT_CCIF_MASK FTFE_FSTAT_CCIF_MASK
+#define FTFx_FSTAT_RDCOLERR_MASK FTFE_FSTAT_RDCOLERR_MASK
+#define FTFx_FSTAT_ACCERR_MASK FTFE_FSTAT_ACCERR_MASK
+#define FTFx_FSTAT_FPVIOL_MASK FTFE_FSTAT_FPVIOL_MASK
+#define FTFx_FSTAT_MGSTAT0_MASK FTFE_FSTAT_MGSTAT0_MASK
+#define FTFx_FSEC_SEC_MASK FTFE_FSEC_SEC_MASK
+#define FTFx_FSEC_KEYEN_MASK FTFE_FSEC_KEYEN_MASK
+#if defined(FSL_FEATURE_FLASH_HAS_FLEX_RAM) && FSL_FEATURE_FLASH_HAS_FLEX_RAM
+#define FTFx_FCNFG_RAMRDY_MASK FTFE_FCNFG_RAMRDY_MASK
+#endif /* FSL_FEATURE_FLASH_HAS_FLEX_RAM */
+#if defined(FSL_FEATURE_FLASH_HAS_FLEX_NVM) && FSL_FEATURE_FLASH_HAS_FLEX_NVM
+#define FTFx_FCNFG_EEERDY_MASK FTFE_FCNFG_EEERDY_MASK
+#endif /* FSL_FEATURE_FLASH_HAS_FLEX_NVM */
+#elif defined(FTFL)
+#define FTFx FTFL
+#define FTFx_BASE FTFL_BASE
+#define FTFx_FSTAT_CCIF_MASK FTFL_FSTAT_CCIF_MASK
+#define FTFx_FSTAT_RDCOLERR_MASK FTFL_FSTAT_RDCOLERR_MASK
+#define FTFx_FSTAT_ACCERR_MASK FTFL_FSTAT_ACCERR_MASK
+#define FTFx_FSTAT_FPVIOL_MASK FTFL_FSTAT_FPVIOL_MASK
+#define FTFx_FSTAT_MGSTAT0_MASK FTFL_FSTAT_MGSTAT0_MASK
+#define FTFx_FSEC_SEC_MASK FTFL_FSEC_SEC_MASK
+#define FTFx_FSEC_KEYEN_MASK FTFL_FSEC_KEYEN_MASK
+#if defined(FSL_FEATURE_FLASH_HAS_FLEX_RAM) && FSL_FEATURE_FLASH_HAS_FLEX_RAM
+#define FTFx_FCNFG_RAMRDY_MASK FTFL_FCNFG_RAMRDY_MASK
+#endif /* FSL_FEATURE_FLASH_HAS_FLEX_RAM */
+#if defined(FSL_FEATURE_FLASH_HAS_FLEX_NVM) && FSL_FEATURE_FLASH_HAS_FLEX_NVM
+#define FTFx_FCNFG_EEERDY_MASK FTFL_FCNFG_EEERDY_MASK
+#endif /* FSL_FEATURE_FLASH_HAS_FLEX_NVM */
+#else
+#error "Unknown flash controller"
+#endif
+/*@}*/
+
+/*!
+ * @brief Enumeration for access segment property.
+ */
+enum _flash_access_segment_property
+{
+ kFLASH_AccessSegmentBase = 256UL,
+};
+
+/*!
+ * @brief Enumeration for flash config area.
+ */
+enum _flash_config_area_range
+{
+ kFLASH_ConfigAreaStart = 0x400U,
+ kFLASH_ConfigAreaEnd = 0x40FU
+};
+
+/*! @brief Total flash region count*/
+#define FSL_FEATURE_FTFx_REGION_COUNT (32U)
+
+/*!
+ * @name Flash register access type defines
+ * @{
+ */
+#if FLASH_DRIVER_IS_FLASH_RESIDENT
+#define FTFx_REG_ACCESS_TYPE volatile uint8_t *
+#define FTFx_REG32_ACCESS_TYPE volatile uint32_t *
+#endif /* FLASH_DRIVER_IS_FLASH_RESIDENT */
+ /*@}*/
+
+/*******************************************************************************
+ * Prototypes
+ ******************************************************************************/
+
+#if FLASH_DRIVER_IS_FLASH_RESIDENT
+/*! @brief Copy flash_run_command() to RAM*/
+static void copy_flash_run_command(uint32_t *flashRunCommand);
+/*! @brief Copy flash_cache_clear_command() to RAM*/
+static void copy_flash_cache_clear_command(uint32_t *flashCacheClearCommand);
+/*! @brief Check whether flash execute-in-ram functions are ready*/
+static status_t flash_check_execute_in_ram_function_info(flash_config_t *config);
+#endif /* FLASH_DRIVER_IS_FLASH_RESIDENT */
+
+/*! @brief Internal function Flash command sequence. Called by driver APIs only*/
+static status_t flash_command_sequence(flash_config_t *config);
+
+/*! @brief Perform the cache clear to the flash*/
+void flash_cache_clear(flash_config_t *config);
+
+/*! @brief Validates the range and alignment of the given address range.*/
+static status_t flash_check_range(flash_config_t *config,
+ uint32_t startAddress,
+ uint32_t lengthInBytes,
+ uint32_t alignmentBaseline);
+/*! @brief Gets the right address, sector and block size of current flash type which is indicated by address.*/
+static status_t flash_get_matched_operation_info(flash_config_t *config,
+ uint32_t address,
+ flash_operation_config_t *info);
+/*! @brief Validates the given user key for flash erase APIs.*/
+static status_t flash_check_user_key(uint32_t key);
+
+#if FLASH_SSD_IS_FLEXNVM_ENABLED
+/*! @brief Updates FlexNVM memory partition status according to data flash 0 IFR.*/
+static status_t flash_update_flexnvm_memory_partition_status(flash_config_t *config);
+#endif /* FLASH_SSD_IS_FLEXNVM_ENABLED */
+
+#if defined(FSL_FEATURE_FLASH_HAS_READ_RESOURCE_CMD) && FSL_FEATURE_FLASH_HAS_READ_RESOURCE_CMD
+/*! @brief Validates the range of the given resource address.*/
+static status_t flash_check_resource_range(uint32_t start,
+ uint32_t lengthInBytes,
+ uint32_t alignmentBaseline,
+ flash_read_resource_option_t option);
+#endif /* FSL_FEATURE_FLASH_HAS_READ_RESOURCE_CMD */
+
+#if defined(FSL_FEATURE_FLASH_HAS_SWAP_CONTROL_CMD) && FSL_FEATURE_FLASH_HAS_SWAP_CONTROL_CMD
+/*! @brief Validates the gived swap control option.*/
+static status_t flash_check_swap_control_option(flash_swap_control_option_t option);
+#endif /* FSL_FEATURE_FLASH_HAS_SWAP_CONTROL_CMD */
+
+#if defined(FSL_FEATURE_FLASH_HAS_PFLASH_BLOCK_SWAP) && FSL_FEATURE_FLASH_HAS_PFLASH_BLOCK_SWAP
+/*! @brief Validates the gived address to see if it is equal to swap indicator address in pflash swap IFR.*/
+static status_t flash_validate_swap_indicator_address(flash_config_t *config, uint32_t address);
+#endif /* FSL_FEATURE_FLASH_HAS_PFLASH_BLOCK_SWAP */
+
+#if defined(FSL_FEATURE_FLASH_HAS_SET_FLEXRAM_FUNCTION_CMD) && FSL_FEATURE_FLASH_HAS_SET_FLEXRAM_FUNCTION_CMD
+/*! @brief Validates the gived flexram function option.*/
+static inline status_t flasn_check_flexram_function_option_range(flash_flexram_function_option_t option);
+#endif /* FSL_FEATURE_FLASH_HAS_SET_FLEXRAM_FUNCTION_CMD */
+
+/*******************************************************************************
+ * Variables
+ ******************************************************************************/
+
+/*! @brief Access to FTFx->FCCOB */
+#if defined(FSL_FEATURE_FLASH_IS_FTFA) && FSL_FEATURE_FLASH_IS_FTFA
+volatile uint32_t *const kFCCOBx = (volatile uint32_t *)&FTFA->FCCOB3;
+#elif defined(FSL_FEATURE_FLASH_IS_FTFE) && FSL_FEATURE_FLASH_IS_FTFE
+volatile uint32_t *const kFCCOBx = (volatile uint32_t *)&FTFE->FCCOB3;
+#elif defined(FSL_FEATURE_FLASH_IS_FTFL) && FSL_FEATURE_FLASH_IS_FTFL
+volatile uint32_t *const kFCCOBx = (volatile uint32_t *)&FTFL->FCCOB3;
+#else
+#error "Unknown flash controller"
+#endif
+
+/*! @brief Access to FTFx->FPROT */
+#if defined(FSL_FEATURE_FLASH_IS_FTFA) && FSL_FEATURE_FLASH_IS_FTFA
+volatile uint32_t *const kFPROT = (volatile uint32_t *)&FTFA->FPROT3;
+#elif defined(FSL_FEATURE_FLASH_IS_FTFE) && FSL_FEATURE_FLASH_IS_FTFE
+volatile uint32_t *const kFPROT = (volatile uint32_t *)&FTFE->FPROT3;
+#elif defined(FSL_FEATURE_FLASH_IS_FTFL) && FSL_FEATURE_FLASH_IS_FTFL
+volatile uint32_t *const kFPROT = (volatile uint32_t *)&FTFL->FPROT3;
+#else
+#error "Unknown flash controller"
+#endif
+
+#if FLASH_DRIVER_IS_FLASH_RESIDENT
+/*! @brief A function pointer used to point to relocated flash_run_command() */
+static void (*callFlashRunCommand)(FTFx_REG_ACCESS_TYPE ftfx_fstat);
+/*! @brief A function pointer used to point to relocated flash_cache_clear_command() */
+static void (*callFlashCacheClearCommand)(FTFx_REG32_ACCESS_TYPE ftfx_reg);
+
+/*!
+ * @brief Position independent code of flash_run_command()
+ *
+ * Note1: The prototype of C function is shown as below:
+ * @code
+ * void flash_run_command(FTFx_REG_ACCESS_TYPE ftfx_fstat)
+ * {
+ * // clear CCIF bit
+ * *ftfx_fstat = FTFx_FSTAT_CCIF_MASK;
+ *
+ * // Check CCIF bit of the flash status register, wait till it is set.
+ * // IP team indicates that this loop will always complete.
+ * while (!((*ftfx_fstat) & FTFx_FSTAT_CCIF_MASK))
+ * {
+ * }
+ * }
+ * @endcode
+ * Note2: The binary code is generated by IAR 7.50.1
+ */
+const static uint16_t s_flashRunCommandFunctionCode[] = {
+ 0x2180, /* MOVS R1, #128 ; 0x80 */
+ 0x7001, /* STRB R1, [R0] */
+ /* @4: */
+ 0x7802, /* LDRB R2, [R0] */
+ 0x420a, /* TST R2, R1 */
+ 0xd0fc, /* BEQ.N @4 */
+ 0x4770 /* BX LR */
+};
+
+/*!
+ * @brief Position independent code of flash_cache_clear_command()
+ *
+ * Note1: The prototype of C function is shown as below:
+ * @code
+ * void flash_cache_clear_command(FTFx_REG32_ACCESS_TYPE ftfx_reg)
+ * {
+ * #if defined(FSL_FEATURE_FLASH_HAS_MCM_FLASH_CACHE_CONTROLS) && FSL_FEATURE_FLASH_HAS_MCM_FLASH_CACHE_CONTROLS
+ * *ftfx_reg |= MCM_PLACR_CFCC_MASK;
+ * #elif defined(FSL_FEATURE_FLASH_HAS_FMC_FLASH_CACHE_CONTROLS) && FSL_FEATURE_FLASH_HAS_FMC_FLASH_CACHE_CONTROLS
+ * #if defined(FMC_PFB01CR_CINV_WAY_MASK)
+ * *ftfx_reg = (*ftfx_reg & ~FMC_PFB01CR_CINV_WAY_MASK) | FMC_PFB01CR_CINV_WAY(~0);
+ * #else
+ * *ftfx_reg = (*ftfx_reg & ~FMC_PFB0CR_CINV_WAY_MASK) | FMC_PFB0CR_CINV_WAY(~0);
+ * #endif
+ * #elif defined(FSL_FEATURE_FLASH_HAS_MSCM_FLASH_CACHE_CONTROLS) && FSL_FEATURE_FLASH_HAS_MSCM_FLASH_CACHE_CONTROLS
+ * *ftfx_reg |= MSCM_OCMDR_OCMC1(2);
+ * *ftfx_reg |= MSCM_OCMDR_OCMC1(1);
+ * #else
+ * #if defined(FMC_PFB0CR_S_INV_MASK)
+ * *ftfx_reg |= FMC_PFB0CR_S_INV_MASK;
+ * #elif defined(FMC_PFB01CR_S_INV_MASK)
+ * *ftfx_reg |= FMC_PFB01CR_S_INV_MASK;
+ * #endif
+ * // #error "Unknown flash cache controller"
+ * #endif // FSL_FEATURE_FTFx_MCM_FLASH_CACHE_CONTROLS
+ * // Memory barriers for good measure.
+ * // All Cache, Branch predictor and TLB maintenance operations before this instruction complete
+ * __ISB();
+ * __DSB();
+ * }
+ * @endcode
+ * Note2: The binary code is generated by IAR 7.50.1
+ */
+#if defined(FSL_FEATURE_FLASH_HAS_MCM_FLASH_CACHE_CONTROLS) && FSL_FEATURE_FLASH_HAS_MCM_FLASH_CACHE_CONTROLS
+const static uint16_t s_flashCacheClearCommandFunctionCode[] = {
+ 0x6801, /* LDR R1, [R0] */
+ 0x2280, /* MOVS R2, #128 ; 0x80 */
+ 0x00d2, /* LSLS R2, R2, #3 */
+ 0x430a, /* ORRS R2, R2, R1 */
+ 0x6002, /* STR R2, [R0] */
+ 0xf3bf, 0x8f6f, /* ISB */
+ 0xf3bf, 0x8f4f, /* DSB */
+ 0x4770 /* BX LR */
+};
+#elif defined(FSL_FEATURE_FLASH_HAS_FMC_FLASH_CACHE_CONTROLS) && FSL_FEATURE_FLASH_HAS_FMC_FLASH_CACHE_CONTROLS
+const static uint16_t s_flashCacheClearCommandFunctionCode[] = {
+ 0x6801, /* LDR R1, [R0] */
+ 0x22f0, /* MOVS R2, #240 ; 0xf0 */
+ 0x0412, /* LSLS R2, R2, #16 */
+ 0x430a, /* ORRS R2, R2, R1 */
+ 0x6002, /* STR R2, [R0] */
+ 0xf3bf, 0x8f6f, /* ISB */
+ 0xf3bf, 0x8f4f, /* DSB */
+ 0x4770 /* BX LR */
+};
+#elif defined(FSL_FEATURE_FLASH_HAS_MSCM_FLASH_CACHE_CONTROLS) && FSL_FEATURE_FLASH_HAS_MSCM_FLASH_CACHE_CONTROLS
+const static uint16_t s_flashCacheClearCommandFunctionCode[] = {
+ 0x6801, /* LDR R1, [R0] */
+ 0x2220, /* MOVS R2, #32 ; 0x20 */
+ 0x430a, /* ORRS R2, R2, R1 */
+ 0x6002, /* STR R2, [R0] */
+ 0x6801, /* LDR R1, [R0] */
+ 0x2210, /* MOVS R2, #16 ; 0x10 */
+ 0x430a, /* ORRS R2, R2, R1 */
+ 0x6002, /* STR R2, [R0] */
+ 0xf3bf, 0x8f6f, /* ISB */
+ 0xf3bf, 0x8f4f, /* DSB */
+ 0x4770 /* BX LR */
+};
+#else
+#if defined(FMC_PFB0CR_S_INV_MASK) || defined(FMC_PFB01CR_S_INV_MASK)
+const static uint16_t s_flashCacheClearCommandFunctionCode[] = {
+ 0x6801, /* LDR R1, [R0] */
+ 0x2280, /* MOVS R2, #128 ; 0x80 */
+ 0x0312, /* LSLS R2, R2, #12 */
+ 0x430a, /* ORRS R2, R2, R1 */
+ 0x6002, /* STR R2, [R0] */
+ 0xf3bf, 0x8f6f, /* ISB */
+ 0xf3bf, 0x8f4f, /* DSB */
+ 0x4770 /* BX LR */
+};
+#else
+const static uint16_t s_flashCacheClearCommandFunctionCode[] = {
+ 0xf3bf, 0x8f6f, /* ISB */
+ 0xf3bf, 0x8f4f, /* DSB */
+ 0x4770 /* BX LR */
+};
+#endif
+#endif
+#endif /* FLASH_DRIVER_IS_FLASH_RESIDENT */
+
+#if (FLASH_DRIVER_IS_FLASH_RESIDENT && !FLASH_DRIVER_IS_EXPORTED)
+/*! @brief A static buffer used to hold flash_run_command() */
+static uint32_t s_flashRunCommand[kFLASH_ExecuteInRamFunctionMaxSizeInWords];
+/*! @brief A static buffer used to hold flash_cache_clear_command() */
+static uint32_t s_flashCacheClearCommand[kFLASH_ExecuteInRamFunctionMaxSizeInWords];
+/*! @brief Flash execute-in-ram function information */
+static flash_execute_in_ram_function_config_t s_flashExecuteInRamFunctionInfo;
+#endif
+
+/*!
+ * @brief Table of pflash sizes.
+ *
+ * The index into this table is the value of the SIM_FCFG1.PFSIZE bitfield.
+ *
+ * The values in this table have been right shifted 10 bits so that they will all fit within
+ * an 16-bit integer. To get the actual flash density, you must left shift the looked up value
+ * by 10 bits.
+ *
+ * Elements of this table have a value of 0 in cases where the PFSIZE bitfield value is
+ * reserved.
+ *
+ * Code to use the table:
+ * @code
+ * uint8_t pfsize = (SIM->FCFG1 & SIM_FCFG1_PFSIZE_MASK) >> SIM_FCFG1_PFSIZE_SHIFT;
+ * flashDensity = ((uint32_t)kPFlashDensities[pfsize]) << 10;
+ * @endcode
+ */
+const uint16_t kPFlashDensities[] = {
+ 8, /* 0x0 - 8192, 8KB */
+ 16, /* 0x1 - 16384, 16KB */
+ 24, /* 0x2 - 24576, 24KB */
+ 32, /* 0x3 - 32768, 32KB */
+ 48, /* 0x4 - 49152, 48KB */
+ 64, /* 0x5 - 65536, 64KB */
+ 96, /* 0x6 - 98304, 96KB */
+ 128, /* 0x7 - 131072, 128KB */
+ 192, /* 0x8 - 196608, 192KB */
+ 256, /* 0x9 - 262144, 256KB */
+ 384, /* 0xa - 393216, 384KB */
+ 512, /* 0xb - 524288, 512KB */
+ 768, /* 0xc - 786432, 768KB */
+ 1024, /* 0xd - 1048576, 1MB */
+ 1536, /* 0xe - 1572864, 1.5MB */
+ /* 2048, 0xf - 2097152, 2MB */
+};
+
+/*******************************************************************************
+ * Code
+ ******************************************************************************/
+
+status_t FLASH_Init(flash_config_t *config)
+{
+ uint32_t flashDensity;
+
+ if (config == NULL)
+ {
+ return kStatus_FLASH_InvalidArgument;
+ }
+
+ /* calculate the flash density from SIM_FCFG1.PFSIZE */
+ uint8_t pfsize = (SIM->FCFG1 & SIM_FCFG1_PFSIZE_MASK) >> SIM_FCFG1_PFSIZE_SHIFT;
+ /* PFSIZE=0xf means that on customer parts the IFR was not correctly programmed.
+ * We just use the pre-defined flash size in feature file here to support pre-production parts */
+ if (pfsize == 0xf)
+ {
+ flashDensity = FSL_FEATURE_FLASH_PFLASH_BLOCK_COUNT * FSL_FEATURE_FLASH_PFLASH_BLOCK_SIZE;
+ }
+ else
+ {
+ flashDensity = ((uint32_t)kPFlashDensities[pfsize]) << 10;
+ }
+
+ /* fill out a few of the structure members */
+ config->PFlashBlockBase = FSL_FEATURE_FLASH_PFLASH_START_ADDRESS;
+ config->PFlashTotalSize = flashDensity;
+ config->PFlashBlockCount = FSL_FEATURE_FLASH_PFLASH_BLOCK_COUNT;
+ config->PFlashSectorSize = FSL_FEATURE_FLASH_PFLASH_BLOCK_SECTOR_SIZE;
+
+#if defined(FSL_FEATURE_FLASH_HAS_ACCESS_CONTROL) && FSL_FEATURE_FLASH_HAS_ACCESS_CONTROL
+ config->PFlashAccessSegmentSize = kFLASH_AccessSegmentBase << FTFx->FACSS;
+ config->PFlashAccessSegmentCount = FTFx->FACSN;
+#else
+ config->PFlashAccessSegmentSize = 0;
+ config->PFlashAccessSegmentCount = 0;
+#endif /* FSL_FEATURE_FLASH_HAS_ACCESS_CONTROL */
+
+ config->PFlashCallback = NULL;
+
+/* copy required flash commands to RAM */
+#if (FLASH_DRIVER_IS_FLASH_RESIDENT && !FLASH_DRIVER_IS_EXPORTED)
+ if (kStatus_FLASH_Success != flash_check_execute_in_ram_function_info(config))
+ {
+ s_flashExecuteInRamFunctionInfo.activeFunctionCount = 0;
+ s_flashExecuteInRamFunctionInfo.flashRunCommand = s_flashRunCommand;
+ s_flashExecuteInRamFunctionInfo.flashCacheClearCommand = s_flashCacheClearCommand;
+ config->flashExecuteInRamFunctionInfo = &s_flashExecuteInRamFunctionInfo.activeFunctionCount;
+ FLASH_PrepareExecuteInRamFunctions(config);
+ }
+#endif
+
+ config->FlexRAMBlockBase = FSL_FEATURE_FLASH_FLEX_RAM_START_ADDRESS;
+ config->FlexRAMTotalSize = FSL_FEATURE_FLASH_FLEX_RAM_SIZE;
+
+#if FLASH_SSD_IS_FLEXNVM_ENABLED
+ {
+ status_t returnCode;
+ config->DFlashBlockBase = FSL_FEATURE_FLASH_FLEX_NVM_START_ADDRESS;
+ returnCode = flash_update_flexnvm_memory_partition_status(config);
+ if (returnCode != kStatus_FLASH_Success)
+ {
+ return returnCode;
+ }
+ }
+#endif
+
+ return kStatus_FLASH_Success;
+}
+
+status_t FLASH_SetCallback(flash_config_t *config, flash_callback_t callback)
+{
+ if (config == NULL)
+ {
+ return kStatus_FLASH_InvalidArgument;
+ }
+
+ config->PFlashCallback = callback;
+
+ return kStatus_FLASH_Success;
+}
+
+#if FLASH_DRIVER_IS_FLASH_RESIDENT
+status_t FLASH_PrepareExecuteInRamFunctions(flash_config_t *config)
+{
+ flash_execute_in_ram_function_config_t *flashExecuteInRamFunctionInfo;
+
+ if (config == NULL)
+ {
+ return kStatus_FLASH_InvalidArgument;
+ }
+
+ flashExecuteInRamFunctionInfo = (flash_execute_in_ram_function_config_t *)config->flashExecuteInRamFunctionInfo;
+
+ copy_flash_run_command(flashExecuteInRamFunctionInfo->flashRunCommand);
+ copy_flash_cache_clear_command(flashExecuteInRamFunctionInfo->flashCacheClearCommand);
+ flashExecuteInRamFunctionInfo->activeFunctionCount = kFLASH_ExecuteInRamFunctionTotalNum;
+
+ return kStatus_FLASH_Success;
+}
+#endif /* FLASH_DRIVER_IS_FLASH_RESIDENT */
+
+status_t FLASH_EraseAll(flash_config_t *config, uint32_t key)
+{
+ status_t returnCode;
+
+ if (config == NULL)
+ {
+ return kStatus_FLASH_InvalidArgument;
+ }
+
+ /* preparing passing parameter to erase all flash blocks */
+ kFCCOBx[0] = BYTES_JOIN_TO_WORD_1_3(FTFx_ERASE_ALL_BLOCK, 0xFFFFFFU);
+
+ /* Validate the user key */
+ returnCode = flash_check_user_key(key);
+ if (returnCode)
+ {
+ return returnCode;
+ }
+
+ /* calling flash command sequence function to execute the command */
+ returnCode = flash_command_sequence(config);
+
+ flash_cache_clear(config);
+
+#if FLASH_SSD_IS_FLEXNVM_ENABLED
+ /* Data flash IFR will be erased by erase all command, so we need to
+ * update FlexNVM memory partition status synchronously */
+ if (returnCode == kStatus_FLASH_Success)
+ {
+ returnCode = flash_update_flexnvm_memory_partition_status(config);
+ }
+#endif
+
+ return returnCode;
+}
+
+status_t FLASH_Erase(flash_config_t *config, uint32_t start, uint32_t lengthInBytes, uint32_t key)
+{
+ uint32_t sectorSize;
+ flash_operation_config_t flashInfo;
+ uint32_t endAddress; /* storing end address */
+ uint32_t numberOfSectors; /* number of sectors calculated by endAddress */
+ status_t returnCode;
+
+ flash_get_matched_operation_info(config, start, &flashInfo);
+
+ /* Check the supplied address range. */
+ returnCode = flash_check_range(config, start, lengthInBytes, flashInfo.sectorCmdAddressAligment);
+ if (returnCode)
+ {
+ return returnCode;
+ }
+
+ start = flashInfo.convertedAddress;
+ sectorSize = flashInfo.activeSectorSize;
+
+ /* calculating Flash end address */
+ endAddress = start + lengthInBytes - 1;
+
+ /* re-calculate the endAddress and align it to the start of the next sector
+ * which will be used in the comparison below */
+ if (endAddress % sectorSize)
+ {
+ numberOfSectors = endAddress / sectorSize + 1;
+ endAddress = numberOfSectors * sectorSize - 1;
+ }
+
+ /* the start address will increment to the next sector address
+ * until it reaches the endAdddress */
+ while (start <= endAddress)
+ {
+ /* preparing passing parameter to erase a flash block */
+ kFCCOBx[0] = BYTES_JOIN_TO_WORD_1_3(FTFx_ERASE_SECTOR, start);
+
+ /* Validate the user key */
+ returnCode = flash_check_user_key(key);
+ if (returnCode)
+ {
+ return returnCode;
+ }
+
+ /* calling flash command sequence function to execute the command */
+ returnCode = flash_command_sequence(config);
+
+ /* calling flash callback function if it is available */
+ if (config->PFlashCallback)
+ {
+ config->PFlashCallback();
+ }
+
+ /* checking the success of command execution */
+ if (kStatus_FLASH_Success != returnCode)
+ {
+ break;
+ }
+ else
+ {
+ /* Increment to the next sector */
+ start += sectorSize;
+ }
+ }
+
+ flash_cache_clear(config);
+
+ return (returnCode);
+}
+
+#if defined(FSL_FEATURE_FLASH_HAS_ERASE_ALL_BLOCKS_UNSECURE_CMD) && FSL_FEATURE_FLASH_HAS_ERASE_ALL_BLOCKS_UNSECURE_CMD
+status_t FLASH_EraseAllUnsecure(flash_config_t *config, uint32_t key)
+{
+ status_t returnCode;
+
+ if (config == NULL)
+ {
+ return kStatus_FLASH_InvalidArgument;
+ }
+
+ /* Prepare passing parameter to erase all flash blocks (unsecure). */
+ kFCCOBx[0] = BYTES_JOIN_TO_WORD_1_3(FTFx_ERASE_ALL_BLOCK_UNSECURE, 0xFFFFFFU);
+
+ /* Validate the user key */
+ returnCode = flash_check_user_key(key);
+ if (returnCode)
+ {
+ return returnCode;
+ }
+
+ /* calling flash command sequence function to execute the command */
+ returnCode = flash_command_sequence(config);
+
+ flash_cache_clear(config);
+
+#if FLASH_SSD_IS_FLEXNVM_ENABLED
+ /* Data flash IFR will be erased by erase all unsecure command, so we need to
+ * update FlexNVM memory partition status synchronously */
+ if (returnCode == kStatus_FLASH_Success)
+ {
+ returnCode = flash_update_flexnvm_memory_partition_status(config);
+ }
+#endif
+
+ return returnCode;
+}
+#endif /* FSL_FEATURE_FLASH_HAS_ERASE_ALL_BLOCKS_UNSECURE_CMD */
+
+status_t FLASH_EraseAllExecuteOnlySegments(flash_config_t *config, uint32_t key)
+{
+ status_t returnCode;
+
+ if (config == NULL)
+ {
+ return kStatus_FLASH_InvalidArgument;
+ }
+
+ /* preparing passing parameter to erase all execute-only segments
+ * 1st element for the FCCOB register */
+ kFCCOBx[0] = BYTES_JOIN_TO_WORD_1_3(FTFx_ERASE_ALL_EXECUTE_ONLY_SEGMENT, 0xFFFFFFU);
+
+ /* Validate the user key */
+ returnCode = flash_check_user_key(key);
+ if (returnCode)
+ {
+ return returnCode;
+ }
+
+ /* calling flash command sequence function to execute the command */
+ returnCode = flash_command_sequence(config);
+
+ flash_cache_clear(config);
+
+ return returnCode;
+}
+
+status_t FLASH_Program(flash_config_t *config, uint32_t start, uint32_t *src, uint32_t lengthInBytes)
+{
+ status_t returnCode;
+ flash_operation_config_t flashInfo;
+
+ if (src == NULL)
+ {
+ return kStatus_FLASH_InvalidArgument;
+ }
+
+ flash_get_matched_operation_info(config, start, &flashInfo);
+
+ /* Check the supplied address range. */
+ returnCode = flash_check_range(config, start, lengthInBytes, flashInfo.blockWriteUnitSize);
+ if (returnCode)
+ {
+ return returnCode;
+ }
+
+ start = flashInfo.convertedAddress;
+
+ while (lengthInBytes > 0)
+ {
+ /* preparing passing parameter to program the flash block */
+ kFCCOBx[1] = *src++;
+ if (4 == flashInfo.blockWriteUnitSize)
+ {
+ kFCCOBx[0] = BYTES_JOIN_TO_WORD_1_3(FTFx_PROGRAM_LONGWORD, start);
+ }
+ else if (8 == flashInfo.blockWriteUnitSize)
+ {
+ kFCCOBx[2] = *src++;
+ kFCCOBx[0] = BYTES_JOIN_TO_WORD_1_3(FTFx_PROGRAM_PHRASE, start);
+ }
+ else
+ {
+ }
+
+ /* calling flash command sequence function to execute the command */
+ returnCode = flash_command_sequence(config);
+
+ /* calling flash callback function if it is available */
+ if (config->PFlashCallback)
+ {
+ config->PFlashCallback();
+ }
+
+ /* checking for the success of command execution */
+ if (kStatus_FLASH_Success != returnCode)
+ {
+ break;
+ }
+ else
+ {
+ /* update start address for next iteration */
+ start += flashInfo.blockWriteUnitSize;
+
+ /* update lengthInBytes for next iteration */
+ lengthInBytes -= flashInfo.blockWriteUnitSize;
+ }
+ }
+
+ flash_cache_clear(config);
+
+ return (returnCode);
+}
+
+status_t FLASH_ProgramOnce(flash_config_t *config, uint32_t index, uint32_t *src, uint32_t lengthInBytes)
+{
+ status_t returnCode;
+
+ if ((config == NULL) || (src == NULL))
+ {
+ return kStatus_FLASH_InvalidArgument;
+ }
+
+ /* pass paramters to FTFx */
+ kFCCOBx[0] = BYTES_JOIN_TO_WORD_1_1_2(FTFx_PROGRAM_ONCE, index, 0xFFFFU);
+
+ kFCCOBx[1] = *src;
+
+/* Note: Have to seperate the first index from the rest if it equals 0
+ * to avoid a pointless comparison of unsigned int to 0 compiler warning */
+#if FLASH_PROGRAM_ONCE_IS_8BYTES_UNIT_SUPPORT
+#if FLASH_PROGRAM_ONCE_IS_4BYTES_UNIT_SUPPORT
+ if (((index == FLASH_PROGRAM_ONCE_MIN_ID_8BYTES) ||
+ /* Range check */
+ ((index >= FLASH_PROGRAM_ONCE_MIN_ID_8BYTES + 1) && (index <= FLASH_PROGRAM_ONCE_MAX_ID_8BYTES))) &&
+ (lengthInBytes == 8))
+#endif /* FLASH_PROGRAM_ONCE_IS_4BYTES_UNIT_SUPPORT */
+ {
+ kFCCOBx[2] = *(src + 1);
+ }
+#endif /* FLASH_PROGRAM_ONCE_IS_8BYTES_UNIT_SUPPORT */
+
+ /* calling flash command sequence function to execute the command */
+ returnCode = flash_command_sequence(config);
+
+ flash_cache_clear(config);
+
+ return returnCode;
+}
+
+#if defined(FSL_FEATURE_FLASH_HAS_PROGRAM_SECTION_CMD) && FSL_FEATURE_FLASH_HAS_PROGRAM_SECTION_CMD
+status_t FLASH_ProgramSection(flash_config_t *config, uint32_t start, uint32_t *src, uint32_t lengthInBytes)
+{
+ status_t returnCode;
+ uint32_t sectorSize;
+ flash_operation_config_t flashInfo;
+#if defined(FSL_FEATURE_FLASH_HAS_SET_FLEXRAM_FUNCTION_CMD) && FSL_FEATURE_FLASH_HAS_SET_FLEXRAM_FUNCTION_CMD
+ bool needSwitchFlexRamMode = false;
+#endif /* FSL_FEATURE_FLASH_HAS_SET_FLEXRAM_FUNCTION_CMD */
+
+ if (src == NULL)
+ {
+ return kStatus_FLASH_InvalidArgument;
+ }
+
+ flash_get_matched_operation_info(config, start, &flashInfo);
+
+ /* Check the supplied address range. */
+ returnCode = flash_check_range(config, start, lengthInBytes, flashInfo.sectionCmdAddressAligment);
+ if (returnCode)
+ {
+ return returnCode;
+ }
+
+ start = flashInfo.convertedAddress;
+ sectorSize = flashInfo.activeSectorSize;
+
+#if defined(FSL_FEATURE_FLASH_HAS_SET_FLEXRAM_FUNCTION_CMD) && FSL_FEATURE_FLASH_HAS_SET_FLEXRAM_FUNCTION_CMD
+ /* Switch function of FlexRAM if needed */
+ if (!(FTFx->FCNFG & FTFx_FCNFG_RAMRDY_MASK))
+ {
+ needSwitchFlexRamMode = true;
+
+ returnCode = FLASH_SetFlexramFunction(config, kFLASH_FlexramFunctionOptionAvailableAsRam);
+ if (returnCode != kStatus_FLASH_Success)
+ {
+ return kStatus_FLASH_SetFlexramAsRamError;
+ }
+ }
+#endif /* FSL_FEATURE_FLASH_HAS_SET_FLEXRAM_FUNCTION_CMD */
+
+ while (lengthInBytes > 0)
+ {
+ /* Make sure the write operation doesn't span two sectors */
+ uint32_t endAddressOfCurrentSector = ALIGN_UP(start, sectorSize);
+ uint32_t lengthTobeProgrammedOfCurrentSector;
+ uint32_t currentOffset = 0;
+
+ if (endAddressOfCurrentSector == start)
+ {
+ endAddressOfCurrentSector += sectorSize;
+ }
+
+ if (lengthInBytes + start > endAddressOfCurrentSector)
+ {
+ lengthTobeProgrammedOfCurrentSector = endAddressOfCurrentSector - start;
+ }
+ else
+ {
+ lengthTobeProgrammedOfCurrentSector = lengthInBytes;
+ }
+
+ /* Program Current Sector */
+ while (lengthTobeProgrammedOfCurrentSector > 0)
+ {
+ /* Make sure the program size doesn't exceeds Acceleration RAM size */
+ uint32_t programSizeOfCurrentPass;
+ uint32_t numberOfPhases;
+
+ if (lengthTobeProgrammedOfCurrentSector > kFLASH_AccelerationRamSize)
+ {
+ programSizeOfCurrentPass = kFLASH_AccelerationRamSize;
+ }
+ else
+ {
+ programSizeOfCurrentPass = lengthTobeProgrammedOfCurrentSector;
+ }
+
+ /* Copy data to FlexRAM */
+ memcpy((void *)FSL_FEATURE_FLASH_FLEX_RAM_START_ADDRESS, src + currentOffset / 4, programSizeOfCurrentPass);
+ /* Set start address of the data to be programmed */
+ kFCCOBx[0] = BYTES_JOIN_TO_WORD_1_3(FTFx_PROGRAM_SECTION, start + currentOffset);
+ /* Set program size in terms of FEATURE_FLASH_SECTION_CMD_ADDRESS_ALIGMENT */
+ numberOfPhases = programSizeOfCurrentPass / flashInfo.sectionCmdAddressAligment;
+
+ kFCCOBx[1] = BYTES_JOIN_TO_WORD_2_2(numberOfPhases, 0xFFFFU);
+
+ /* Peform command sequence */
+ returnCode = flash_command_sequence(config);
+
+ /* calling flash callback function if it is available */
+ if (config->PFlashCallback)
+ {
+ config->PFlashCallback();
+ }
+
+ if (returnCode != kStatus_FLASH_Success)
+ {
+ flash_cache_clear(config);
+ return returnCode;
+ }
+
+ lengthTobeProgrammedOfCurrentSector -= programSizeOfCurrentPass;
+ currentOffset += programSizeOfCurrentPass;
+ }
+
+ src += currentOffset / 4;
+ start += currentOffset;
+ lengthInBytes -= currentOffset;
+ }
+
+ flash_cache_clear(config);
+
+#if defined(FSL_FEATURE_FLASH_HAS_SET_FLEXRAM_FUNCTION_CMD) && FSL_FEATURE_FLASH_HAS_SET_FLEXRAM_FUNCTION_CMD
+ /* Restore function of FlexRAM if needed. */
+ if (needSwitchFlexRamMode)
+ {
+ returnCode = FLASH_SetFlexramFunction(config, kFLASH_FlexramFunctionOptionAvailableForEeprom);
+ if (returnCode != kStatus_FLASH_Success)
+ {
+ return kStatus_FLASH_RecoverFlexramAsEepromError;
+ }
+ }
+#endif /* FSL_FEATURE_FLASH_HAS_SET_FLEXRAM_FUNCTION_CMD */
+
+ return returnCode;
+}
+#endif /* FSL_FEATURE_FLASH_HAS_PROGRAM_SECTION_CMD */
+
+#if FLASH_SSD_IS_FLEXNVM_ENABLED
+status_t FLASH_EepromWrite(flash_config_t *config, uint32_t start, uint8_t *src, uint32_t lengthInBytes)
+{
+ status_t returnCode;
+ bool needSwitchFlexRamMode = false;
+
+ if (config == NULL)
+ {
+ return kStatus_FLASH_InvalidArgument;
+ }
+
+ /* Validates the range of the given address */
+ if ((start < config->FlexRAMBlockBase) ||
+ ((start + lengthInBytes) > (config->FlexRAMBlockBase + config->EEpromTotalSize)))
+ {
+ return kStatus_FLASH_AddressError;
+ }
+
+ returnCode = kStatus_FLASH_Success;
+
+ /* Switch function of FlexRAM if needed */
+ if (!(FTFx->FCNFG & FTFx_FCNFG_EEERDY_MASK))
+ {
+ needSwitchFlexRamMode = true;
+
+ returnCode = FLASH_SetFlexramFunction(config, kFLASH_FlexramFunctionOptionAvailableForEeprom);
+ if (returnCode != kStatus_FLASH_Success)
+ {
+ return kStatus_FLASH_SetFlexramAsEepromError;
+ }
+ }
+
+ /* Write data to FlexRAM when it is used as EEPROM emulator */
+ while (lengthInBytes > 0)
+ {
+ if ((!(start & 0x3U)) && (lengthInBytes >= 4))
+ {
+ *(uint32_t *)start = *(uint32_t *)src;
+ start += 4;
+ src += 4;
+ lengthInBytes -= 4;
+ }
+ else if ((!(start & 0x1U)) && (lengthInBytes >= 2))
+ {
+ *(uint16_t *)start = *(uint16_t *)src;
+ start += 2;
+ src += 2;
+ lengthInBytes -= 2;
+ }
+ else
+ {
+ *(uint8_t *)start = *src;
+ start += 1;
+ src += 1;
+ lengthInBytes -= 1;
+ }
+ /* Wait till EEERDY bit is set */
+ while (!(FTFx->FCNFG & FTFx_FCNFG_EEERDY_MASK))
+ {
+ }
+
+ /* Check for protection violation error */
+ if (FTFx->FSTAT & FTFx_FSTAT_FPVIOL_MASK)
+ {
+ return kStatus_FLASH_ProtectionViolation;
+ }
+ }
+
+ /* Switch function of FlexRAM if needed */
+ if (needSwitchFlexRamMode)
+ {
+ returnCode = FLASH_SetFlexramFunction(config, kFLASH_FlexramFunctionOptionAvailableAsRam);
+ if (returnCode != kStatus_FLASH_Success)
+ {
+ return kStatus_FLASH_RecoverFlexramAsRamError;
+ }
+ }
+
+ return returnCode;
+}
+#endif /* FLASH_SSD_IS_FLEXNVM_ENABLED */
+
+#if defined(FSL_FEATURE_FLASH_HAS_READ_RESOURCE_CMD) && FSL_FEATURE_FLASH_HAS_READ_RESOURCE_CMD
+status_t FLASH_ReadResource(
+ flash_config_t *config, uint32_t start, uint32_t *dst, uint32_t lengthInBytes, flash_read_resource_option_t option)
+{
+ status_t returnCode;
+ flash_operation_config_t flashInfo;
+
+ if ((config == NULL) || (dst == NULL))
+ {
+ return kStatus_FLASH_InvalidArgument;
+ }
+
+ flash_get_matched_operation_info(config, start, &flashInfo);
+
+ /* Check the supplied address range. */
+ returnCode = flash_check_resource_range(start, lengthInBytes, flashInfo.resourceCmdAddressAligment, option);
+ if (returnCode != kStatus_FLASH_Success)
+ {
+ return returnCode;
+ }
+
+ while (lengthInBytes > 0)
+ {
+ /* preparing passing parameter */
+ kFCCOBx[0] = BYTES_JOIN_TO_WORD_1_3(FTFx_READ_RESOURCE, start);
+ if (flashInfo.resourceCmdAddressAligment == 4)
+ {
+ kFCCOBx[2] = BYTES_JOIN_TO_WORD_1_3(option, 0xFFFFFFU);
+ }
+ else if (flashInfo.resourceCmdAddressAligment == 8)
+ {
+ kFCCOBx[1] = BYTES_JOIN_TO_WORD_1_3(option, 0xFFFFFFU);
+ }
+ else
+ {
+ }
+
+ /* calling flash command sequence function to execute the command */
+ returnCode = flash_command_sequence(config);
+
+ if (kStatus_FLASH_Success != returnCode)
+ {
+ break;
+ }
+
+ /* fetch data */
+ *dst++ = kFCCOBx[1];
+ if (flashInfo.resourceCmdAddressAligment == 8)
+ {
+ *dst++ = kFCCOBx[2];
+ }
+ /* update start address for next iteration */
+ start += flashInfo.resourceCmdAddressAligment;
+ /* update lengthInBytes for next iteration */
+ lengthInBytes -= flashInfo.resourceCmdAddressAligment;
+ }
+
+ return (returnCode);
+}
+#endif /* FSL_FEATURE_FLASH_HAS_READ_RESOURCE_CMD */
+
+status_t FLASH_ReadOnce(flash_config_t *config, uint32_t index, uint32_t *dst, uint32_t lengthInBytes)
+{
+ status_t returnCode;
+
+ if ((config == NULL) || (dst == NULL))
+ {
+ return kStatus_FLASH_InvalidArgument;
+ }
+
+ /* pass paramters to FTFx */
+ kFCCOBx[0] = BYTES_JOIN_TO_WORD_1_1_2(FTFx_READ_ONCE, index, 0xFFFFU);
+
+ /* calling flash command sequence function to execute the command */
+ returnCode = flash_command_sequence(config);
+
+ if (kStatus_FLASH_Success == returnCode)
+ {
+ *dst = kFCCOBx[1];
+/* Note: Have to seperate the first index from the rest if it equals 0
+ * to avoid a pointless comparison of unsigned int to 0 compiler warning */
+#if FLASH_PROGRAM_ONCE_IS_8BYTES_UNIT_SUPPORT
+#if FLASH_PROGRAM_ONCE_IS_4BYTES_UNIT_SUPPORT
+ if (((index == FLASH_PROGRAM_ONCE_MIN_ID_8BYTES) ||
+ /* Range check */
+ ((index >= FLASH_PROGRAM_ONCE_MIN_ID_8BYTES + 1) && (index <= FLASH_PROGRAM_ONCE_MAX_ID_8BYTES))) &&
+ (lengthInBytes == 8))
+#endif /* FLASH_PROGRAM_ONCE_IS_4BYTES_UNIT_SUPPORT */
+ {
+ *(dst + 1) = kFCCOBx[2];
+ }
+#endif /* FLASH_PROGRAM_ONCE_IS_8BYTES_UNIT_SUPPORT */
+ }
+
+ return returnCode;
+}
+
+status_t FLASH_GetSecurityState(flash_config_t *config, flash_security_state_t *state)
+{
+ /* store data read from flash register */
+ uint8_t registerValue;
+
+ if ((config == NULL) || (state == NULL))
+ {
+ return kStatus_FLASH_InvalidArgument;
+ }
+
+ /* Get flash security register value */
+ registerValue = FTFx->FSEC;
+
+ /* check the status of the flash security bits in the security register */
+ if (FLASH_SECURITY_STATE_UNSECURED == (registerValue & FTFx_FSEC_SEC_MASK))
+ {
+ /* Flash in unsecured state */
+ *state = kFLASH_SecurityStateNotSecure;
+ }
+ else
+ {
+ /* Flash in secured state
+ * check for backdoor key security enable bit */
+ if (FLASH_SECURITY_STATE_KEYEN == (registerValue & FTFx_FSEC_KEYEN_MASK))
+ {
+ /* Backdoor key security enabled */
+ *state = kFLASH_SecurityStateBackdoorEnabled;
+ }
+ else
+ {
+ /* Backdoor key security disabled */
+ *state = kFLASH_SecurityStateBackdoorDisabled;
+ }
+ }
+
+ return (kStatus_FLASH_Success);
+}
+
+status_t FLASH_SecurityBypass(flash_config_t *config, const uint8_t *backdoorKey)
+{
+ uint8_t registerValue; /* registerValue */
+ status_t returnCode; /* return code variable */
+
+ if ((config == NULL) || (backdoorKey == NULL))
+ {
+ return kStatus_FLASH_InvalidArgument;
+ }
+
+ /* set the default return code as kStatus_Success */
+ returnCode = kStatus_FLASH_Success;
+
+ /* Get flash security register value */
+ registerValue = FTFx->FSEC;
+
+ /* Check to see if flash is in secure state (any state other than 0x2)
+ * If not, then skip this since flash is not secure */
+ if (0x02 != (registerValue & 0x03))
+ {
+ /* preparing passing parameter to erase a flash block */
+ kFCCOBx[0] = BYTES_JOIN_TO_WORD_1_3(FTFx_SECURITY_BY_PASS, 0xFFFFFFU);
+ kFCCOBx[1] = BYTES_JOIN_TO_WORD_1_1_1_1(backdoorKey[0], backdoorKey[1], backdoorKey[2], backdoorKey[3]);
+ kFCCOBx[2] = BYTES_JOIN_TO_WORD_1_1_1_1(backdoorKey[4], backdoorKey[5], backdoorKey[6], backdoorKey[7]);
+
+ /* calling flash command sequence function to execute the command */
+ returnCode = flash_command_sequence(config);
+ }
+
+ return (returnCode);
+}
+
+status_t FLASH_VerifyEraseAll(flash_config_t *config, flash_margin_value_t margin)
+{
+ if (config == NULL)
+ {
+ return kStatus_FLASH_InvalidArgument;
+ }
+
+ /* preparing passing parameter to verify all block command */
+ kFCCOBx[0] = BYTES_JOIN_TO_WORD_1_1_2(FTFx_VERIFY_ALL_BLOCK, margin, 0xFFFFU);
+
+ /* calling flash command sequence function to execute the command */
+ return flash_command_sequence(config);
+}
+
+status_t FLASH_VerifyErase(flash_config_t *config, uint32_t start, uint32_t lengthInBytes, flash_margin_value_t margin)
+{
+ /* Check arguments. */
+ uint32_t blockSize;
+ flash_operation_config_t flashInfo;
+ uint32_t nextBlockStartAddress;
+ uint32_t remainingBytes;
+ status_t returnCode;
+
+ flash_get_matched_operation_info(config, start, &flashInfo);
+
+ returnCode = flash_check_range(config, start, lengthInBytes, flashInfo.sectionCmdAddressAligment);
+ if (returnCode)
+ {
+ return returnCode;
+ }
+
+ flash_get_matched_operation_info(config, start, &flashInfo);
+ start = flashInfo.convertedAddress;
+ blockSize = flashInfo.activeBlockSize;
+
+ nextBlockStartAddress = ALIGN_UP(start, blockSize);
+ if (nextBlockStartAddress == start)
+ {
+ nextBlockStartAddress += blockSize;
+ }
+
+ remainingBytes = lengthInBytes;
+
+ while (remainingBytes)
+ {
+ uint32_t numberOfPhrases;
+ uint32_t verifyLength = nextBlockStartAddress - start;
+ if (verifyLength > remainingBytes)
+ {
+ verifyLength = remainingBytes;
+ }
+
+ numberOfPhrases = verifyLength / flashInfo.sectionCmdAddressAligment;
+
+ /* Fill in verify section command parameters. */
+ kFCCOBx[0] = BYTES_JOIN_TO_WORD_1_3(FTFx_VERIFY_SECTION, start);
+ kFCCOBx[1] = BYTES_JOIN_TO_WORD_2_1_1(numberOfPhrases, margin, 0xFFU);
+
+ /* calling flash command sequence function to execute the command */
+ returnCode = flash_command_sequence(config);
+ if (returnCode)
+ {
+ return returnCode;
+ }
+
+ remainingBytes -= verifyLength;
+ start += verifyLength;
+ nextBlockStartAddress += blockSize;
+ }
+
+ return kStatus_FLASH_Success;
+}
+
+status_t FLASH_VerifyProgram(flash_config_t *config,
+ uint32_t start,
+ uint32_t lengthInBytes,
+ const uint32_t *expectedData,
+ flash_margin_value_t margin,
+ uint32_t *failedAddress,
+ uint32_t *failedData)
+{
+ status_t returnCode;
+ flash_operation_config_t flashInfo;
+
+ if (expectedData == NULL)
+ {
+ return kStatus_FLASH_InvalidArgument;
+ }
+
+ flash_get_matched_operation_info(config, start, &flashInfo);
+
+ returnCode = flash_check_range(config, start, lengthInBytes, flashInfo.checkCmdAddressAligment);
+ if (returnCode)
+ {
+ return returnCode;
+ }
+
+ start = flashInfo.convertedAddress;
+
+ while (lengthInBytes)
+ {
+ /* preparing passing parameter to program check the flash block */
+ kFCCOBx[0] = BYTES_JOIN_TO_WORD_1_3(FTFx_PROGRAM_CHECK, start);
+ kFCCOBx[1] = BYTES_JOIN_TO_WORD_1_3(margin, 0xFFFFFFU);
+ kFCCOBx[2] = *expectedData;
+
+ /* calling flash command sequence function to execute the command */
+ returnCode = flash_command_sequence(config);
+
+ /* checking for the success of command execution */
+ if (kStatus_FLASH_Success != returnCode)
+ {
+ if (failedAddress)
+ {
+ *failedAddress = start;
+ }
+ if (failedData)
+ {
+ *failedData = 0;
+ }
+ break;
+ }
+
+ lengthInBytes -= flashInfo.checkCmdAddressAligment;
+ expectedData += flashInfo.checkCmdAddressAligment / sizeof(*expectedData);
+ start += flashInfo.checkCmdAddressAligment;
+ }
+
+ return (returnCode);
+}
+
+status_t FLASH_VerifyEraseAllExecuteOnlySegments(flash_config_t *config, flash_margin_value_t margin)
+{
+ if (config == NULL)
+ {
+ return kStatus_FLASH_InvalidArgument;
+ }
+
+ /* preparing passing parameter to verify erase all execute-only segments command */
+ kFCCOBx[0] = BYTES_JOIN_TO_WORD_1_1_2(FTFx_VERIFY_ALL_EXECUTE_ONLY_SEGMENT, margin, 0xFFFFU);
+
+ /* calling flash command sequence function to execute the command */
+ return flash_command_sequence(config);
+}
+
+status_t FLASH_IsProtected(flash_config_t *config,
+ uint32_t start,
+ uint32_t lengthInBytes,
+ flash_protection_state_t *protection_state)
+{
+ uint32_t endAddress; /* end address for protection check */
+ uint32_t protectionRegionSize; /* size of flash protection region */
+ uint32_t regionCheckedCounter; /* increments each time the flash address was checked for
+ * protection status */
+ uint32_t regionCounter; /* incrementing variable used to increment through the flash
+ * protection regions */
+ uint32_t protectStatusCounter; /* increments each time a flash region was detected as protected */
+
+ uint8_t flashRegionProtectStatus[FSL_FEATURE_FTFx_REGION_COUNT]; /* array of the protection status for each
+ * protection region */
+ uint32_t flashRegionAddress[FSL_FEATURE_FTFx_REGION_COUNT + 1]; /* array of the start addresses for each flash
+ * protection region. Note this is REGION_COUNT+1
+ * due to requiring the next start address after
+ * the end of flash for loop-check purposes below */
+ status_t returnCode;
+
+ if (protection_state == NULL)
+ {
+ return kStatus_FLASH_InvalidArgument;
+ }
+
+ /* Check the supplied address range. */
+ returnCode = flash_check_range(config, start, lengthInBytes, FSL_FEATURE_FLASH_PFLASH_BLOCK_WRITE_UNIT_SIZE);
+ if (returnCode)
+ {
+ return returnCode;
+ }
+
+ /* calculating Flash end address */
+ endAddress = start + lengthInBytes;
+
+ /* Calculate the size of the flash protection region
+ * If the flash density is > 32KB, then protection region is 1/32 of total flash density
+ * Else if flash density is < 32KB, then flash protection region is set to 1KB */
+ if (config->PFlashTotalSize > 32 * 1024)
+ {
+ protectionRegionSize = (config->PFlashTotalSize) / FSL_FEATURE_FTFx_REGION_COUNT;
+ }
+ else
+ {
+ protectionRegionSize = 1024;
+ }
+
+ /* populate the flashRegionAddress array with the start address of each flash region */
+ regionCounter = 0; /* make sure regionCounter is initialized to 0 first */
+
+ /* populate up to 33rd element of array, this is the next address after end of flash array */
+ while (regionCounter <= FSL_FEATURE_FTFx_REGION_COUNT)
+ {
+ flashRegionAddress[regionCounter] = config->PFlashBlockBase + protectionRegionSize * regionCounter;
+ regionCounter++;
+ }
+
+ /* populate flashRegionProtectStatus array with status information
+ * Protection status for each region is stored in the FPROT[3:0] registers
+ * Each bit represents one region of flash
+ * 4 registers * 8-bits-per-register = 32-bits (32-regions)
+ * The convention is:
+ * FPROT3[bit 0] is the first protection region (start of flash memory)
+ * FPROT0[bit 7] is the last protection region (end of flash memory)
+ * regionCounter is used to determine which FPROT[3:0] register to check for protection status
+ * Note: FPROT=1 means NOT protected, FPROT=0 means protected */
+ regionCounter = 0; /* make sure regionCounter is initialized to 0 first */
+ while (regionCounter < FSL_FEATURE_FTFx_REGION_COUNT)
+ {
+ if (regionCounter < 8)
+ {
+ flashRegionProtectStatus[regionCounter] = ((FTFx->FPROT3) >> regionCounter) & (0x01u);
+ }
+ else if ((regionCounter >= 8) && (regionCounter < 16))
+ {
+ flashRegionProtectStatus[regionCounter] = ((FTFx->FPROT2) >> (regionCounter - 8)) & (0x01u);
+ }
+ else if ((regionCounter >= 16) && (regionCounter < 24))
+ {
+ flashRegionProtectStatus[regionCounter] = ((FTFx->FPROT1) >> (regionCounter - 16)) & (0x01u);
+ }
+ else
+ {
+ flashRegionProtectStatus[regionCounter] = ((FTFx->FPROT0) >> (regionCounter - 24)) & (0x01u);
+ }
+ regionCounter++;
+ }
+
+ /* loop through the flash regions and check
+ * desired flash address range for protection status
+ * loop stops when it is detected that start has exceeded the endAddress */
+ regionCounter = 0; /* make sure regionCounter is initialized to 0 first */
+ regionCheckedCounter = 0;
+ protectStatusCounter = 0; /* make sure protectStatusCounter is initialized to 0 first */
+ while (start < endAddress)
+ {
+ /* check to see if the address falls within this protection region
+ * Note that if the entire flash is to be checked, the last protection
+ * region checked would consist of the last protection start address and
+ * the start address following the end of flash */
+ if ((start >= flashRegionAddress[regionCounter]) && (start < flashRegionAddress[regionCounter + 1]))
+ {
+ /* increment regionCheckedCounter to indicate this region was checked */
+ regionCheckedCounter++;
+
+ /* check the protection status of this region
+ * Note: FPROT=1 means NOT protected, FPROT=0 means protected */
+ if (!flashRegionProtectStatus[regionCounter])
+ {
+ /* increment protectStatusCounter to indicate this region is protected */
+ protectStatusCounter++;
+ }
+ start += protectionRegionSize; /* increment to an address within the next region */
+ }
+ regionCounter++; /* increment regionCounter to check for the next flash protection region */
+ }
+
+ /* if protectStatusCounter == 0, then no region of the desired flash region is protected */
+ if (protectStatusCounter == 0)
+ {
+ *protection_state = kFLASH_ProtectionStateUnprotected;
+ }
+ /* if protectStatusCounter == regionCheckedCounter, then each region checked was protected */
+ else if (protectStatusCounter == regionCheckedCounter)
+ {
+ *protection_state = kFLASH_ProtectionStateProtected;
+ }
+ /* if protectStatusCounter != regionCheckedCounter, then protection status is mixed
+ * In other words, some regions are protected while others are unprotected */
+ else
+ {
+ *protection_state = kFLASH_ProtectionStateMixed;
+ }
+
+ return (returnCode);
+}
+
+status_t FLASH_IsExecuteOnly(flash_config_t *config,
+ uint32_t start,
+ uint32_t lengthInBytes,
+ flash_execute_only_access_state_t *access_state)
+{
+ status_t returnCode;
+
+ if (access_state == NULL)
+ {
+ return kStatus_FLASH_InvalidArgument;
+ }
+
+ /* Check the supplied address range. */
+ returnCode = flash_check_range(config, start, lengthInBytes, FSL_FEATURE_FLASH_PFLASH_BLOCK_WRITE_UNIT_SIZE);
+ if (returnCode)
+ {
+ return returnCode;
+ }
+
+#if defined(FSL_FEATURE_FLASH_HAS_ACCESS_CONTROL) && FSL_FEATURE_FLASH_HAS_ACCESS_CONTROL
+ {
+ uint32_t executeOnlySegmentCounter = 0;
+
+ /* calculating end address */
+ uint32_t endAddress = start + lengthInBytes;
+
+ /* Aligning start address and end address */
+ uint32_t alignedStartAddress = ALIGN_DOWN(start, config->PFlashAccessSegmentSize);
+ uint32_t alignedEndAddress = ALIGN_UP(endAddress, config->PFlashAccessSegmentSize);
+
+ uint32_t segmentIndex = 0;
+ uint32_t maxSupportedExecuteOnlySegmentCount =
+ (alignedEndAddress - alignedStartAddress) / config->PFlashAccessSegmentSize;
+
+ while (start < endAddress)
+ {
+ uint32_t xacc;
+
+ segmentIndex = start / config->PFlashAccessSegmentSize;
+
+ if (segmentIndex < 32)
+ {
+ xacc = *(const volatile uint32_t *)&FTFx->XACCL3;
+ }
+ else if (segmentIndex < config->PFlashAccessSegmentCount)
+ {
+ xacc = *(const volatile uint32_t *)&FTFx->XACCH3;
+ segmentIndex -= 32;
+ }
+ else
+ {
+ break;
+ }
+
+ /* Determine if this address range is in a execute-only protection flash segment. */
+ if ((~xacc) & (1u << segmentIndex))
+ {
+ executeOnlySegmentCounter++;
+ }
+
+ start += config->PFlashAccessSegmentSize;
+ }
+
+ if (executeOnlySegmentCounter < 1u)
+ {
+ *access_state = kFLASH_AccessStateUnLimited;
+ }
+ else if (executeOnlySegmentCounter < maxSupportedExecuteOnlySegmentCount)
+ {
+ *access_state = kFLASH_AccessStateMixed;
+ }
+ else
+ {
+ *access_state = kFLASH_AccessStateExecuteOnly;
+ }
+ }
+#else
+ *access_state = kFLASH_AccessStateUnLimited;
+#endif /* FSL_FEATURE_FLASH_HAS_ACCESS_CONTROL */
+
+ return (returnCode);
+}
+
+status_t FLASH_GetProperty(flash_config_t *config, flash_property_tag_t whichProperty, uint32_t *value)
+{
+ if ((config == NULL) || (value == NULL))
+ {
+ return kStatus_FLASH_InvalidArgument;
+ }
+
+ switch (whichProperty)
+ {
+ case kFLASH_PropertyPflashSectorSize:
+ *value = config->PFlashSectorSize;
+ break;
+
+ case kFLASH_PropertyPflashTotalSize:
+ *value = config->PFlashTotalSize;
+ break;
+
+ case kFLASH_PropertyPflashBlockSize:
+ *value = config->PFlashTotalSize / FSL_FEATURE_FLASH_PFLASH_BLOCK_COUNT;
+ break;
+
+ case kFLASH_PropertyPflashBlockCount:
+ *value = config->PFlashBlockCount;
+ break;
+
+ case kFLASH_PropertyPflashBlockBaseAddr:
+ *value = config->PFlashBlockBase;
+ break;
+
+ case kFLASH_PropertyPflashFacSupport:
+#if defined(FSL_FEATURE_FLASH_HAS_ACCESS_CONTROL)
+ *value = FSL_FEATURE_FLASH_HAS_ACCESS_CONTROL;
+#else
+ *value = 0;
+#endif /* FSL_FEATURE_FLASH_HAS_ACCESS_CONTROL */
+ break;
+
+ case kFLASH_PropertyPflashAccessSegmentSize:
+ *value = config->PFlashAccessSegmentSize;
+ break;
+
+ case kFLASH_PropertyPflashAccessSegmentCount:
+ *value = config->PFlashAccessSegmentCount;
+ break;
+
+ case kFLASH_PropertyFlexRamBlockBaseAddr:
+ *value = config->FlexRAMBlockBase;
+ break;
+
+ case kFLASH_PropertyFlexRamTotalSize:
+ *value = config->FlexRAMTotalSize;
+ break;
+
+#if FLASH_SSD_IS_FLEXNVM_ENABLED
+ case kFLASH_PropertyDflashSectorSize:
+ *value = FSL_FEATURE_FLASH_FLEX_NVM_BLOCK_SECTOR_SIZE;
+ break;
+ case kFLASH_PropertyDflashTotalSize:
+ *value = config->DFlashTotalSize;
+ break;
+ case kFLASH_PropertyDflashBlockSize:
+ *value = FSL_FEATURE_FLASH_FLEX_NVM_BLOCK_SIZE;
+ break;
+ case kFLASH_PropertyDflashBlockCount:
+ *value = FSL_FEATURE_FLASH_FLEX_NVM_BLOCK_COUNT;
+ break;
+ case kFLASH_PropertyDflashBlockBaseAddr:
+ *value = config->DFlashBlockBase;
+ break;
+ case kFLASH_PropertyEepromTotalSize:
+ *value = config->EEpromTotalSize;
+ break;
+#endif /* FLASH_SSD_IS_FLEXNVM_ENABLED */
+
+ default: /* catch inputs that are not recognized */
+ return kStatus_FLASH_UnknownProperty;
+ }
+
+ return kStatus_FLASH_Success;
+}
+
+#if defined(FSL_FEATURE_FLASH_HAS_SET_FLEXRAM_FUNCTION_CMD) && FSL_FEATURE_FLASH_HAS_SET_FLEXRAM_FUNCTION_CMD
+status_t FLASH_SetFlexramFunction(flash_config_t *config, flash_flexram_function_option_t option)
+{
+ status_t status;
+
+ if (config == NULL)
+ {
+ return kStatus_FLASH_InvalidArgument;
+ }
+
+ status = flasn_check_flexram_function_option_range(option);
+ if (status != kStatus_FLASH_Success)
+ {
+ return status;
+ }
+
+ /* preparing passing parameter to verify all block command */
+ kFCCOBx[0] = BYTES_JOIN_TO_WORD_1_1_2(FTFx_SET_FLEXRAM_FUNCTION, option, 0xFFFFU);
+
+ /* calling flash command sequence function to execute the command */
+ return flash_command_sequence(config);
+}
+#endif /* FSL_FEATURE_FLASH_HAS_SET_FLEXRAM_FUNCTION_CMD */
+
+#if defined(FSL_FEATURE_FLASH_HAS_SWAP_CONTROL_CMD) && FSL_FEATURE_FLASH_HAS_SWAP_CONTROL_CMD
+status_t FLASH_SwapControl(flash_config_t *config,
+ uint32_t address,
+ flash_swap_control_option_t option,
+ flash_swap_state_config_t *returnInfo)
+{
+ status_t returnCode;
+
+ if ((config == NULL) || (returnInfo == NULL))
+ {
+ return kStatus_FLASH_InvalidArgument;
+ }
+
+ if (address & (FSL_FEATURE_FLASH_PFLASH_SWAP_CONTROL_CMD_ADDRESS_ALIGMENT - 1))
+ {
+ return kStatus_FLASH_AlignmentError;
+ }
+
+ /* Make sure address provided is in the lower half of Program flash but not in the Flash Configuration Field */
+ if ((address >= (config->PFlashTotalSize / 2)) ||
+ ((address >= kFLASH_ConfigAreaStart) && (address <= kFLASH_ConfigAreaEnd)))
+ {
+ return kStatus_FLASH_SwapIndicatorAddressError;
+ }
+
+ /* Check the option. */
+ returnCode = flash_check_swap_control_option(option);
+ if (returnCode)
+ {
+ return returnCode;
+ }
+
+ kFCCOBx[0] = BYTES_JOIN_TO_WORD_1_3(FTFx_SWAP_CONTROL, address);
+ kFCCOBx[1] = BYTES_JOIN_TO_WORD_1_3(option, 0xFFFFFFU);
+
+ returnCode = flash_command_sequence(config);
+
+ returnInfo->flashSwapState = (flash_swap_state_t)FTFx->FCCOB5;
+ returnInfo->currentSwapBlockStatus = (flash_swap_block_status_t)FTFx->FCCOB6;
+ returnInfo->nextSwapBlockStatus = (flash_swap_block_status_t)FTFx->FCCOB7;
+
+ return returnCode;
+}
+#endif /* FSL_FEATURE_FLASH_HAS_SWAP_CONTROL_CMD */
+
+#if defined(FSL_FEATURE_FLASH_HAS_PFLASH_BLOCK_SWAP) && FSL_FEATURE_FLASH_HAS_PFLASH_BLOCK_SWAP
+status_t FLASH_Swap(flash_config_t *config, uint32_t address, flash_swap_function_option_t option)
+{
+ flash_swap_state_config_t returnInfo;
+ status_t returnCode;
+
+ memset(&returnInfo, 0xFFU, sizeof(returnInfo));
+
+ do
+ {
+ returnCode = FLASH_SwapControl(config, address, kFLASH_SwapControlOptionReportStatus, &returnInfo);
+ if (returnCode != kStatus_FLASH_Success)
+ {
+ return returnCode;
+ }
+
+ if (kFLASH_SwapFunctionOptionDisable == option)
+ {
+ if (returnInfo.flashSwapState == kFLASH_SwapStateDisabled)
+ {
+ return kStatus_FLASH_Success;
+ }
+ else if (returnInfo.flashSwapState == kFLASH_SwapStateUninitialized)
+ {
+ /* The swap system changed to the DISABLED state with Program flash block 0
+ * located at relative flash address 0x0_0000 */
+ returnCode = FLASH_SwapControl(config, address, kFLASH_SwapControlOptionDisableSystem, &returnInfo);
+ }
+ else
+ {
+ /* Swap disable should be requested only when swap system is in the uninitialized state */
+ return kStatus_FLASH_SwapSystemNotInUninitialized;
+ }
+ }
+ else
+ {
+ /* When first swap: the initial swap state is Uninitialized, flash swap inidicator address is unset,
+ * the swap procedure should be Uninitialized -> Update-Erased -> Complete.
+ * After the first swap has been completed, the flash swap inidicator address cannot be modified
+ * unless EraseAllBlocks command is issued, the swap procedure is changed to Update -> Update-Erased ->
+ * Complete. */
+ switch (returnInfo.flashSwapState)
+ {
+ case kFLASH_SwapStateUninitialized:
+ /* If current swap mode is Uninitialized, Initialize Swap to Initialized/READY state. */
+ returnCode =
+ FLASH_SwapControl(config, address, kFLASH_SwapControlOptionIntializeSystem, &returnInfo);
+ break;
+ case kFLASH_SwapStateReady:
+ /* Validate whether the address provided to the swap system is matched to
+ * swap indicator address in the IFR */
+ returnCode = flash_validate_swap_indicator_address(config, address);
+ if (returnCode == kStatus_FLASH_Success)
+ {
+ /* If current swap mode is Initialized/Ready, Initialize Swap to UPDATE state. */
+ returnCode =
+ FLASH_SwapControl(config, address, kFLASH_SwapControlOptionSetInUpdateState, &returnInfo);
+ }
+ break;
+ case kFLASH_SwapStateUpdate:
+ /* If current swap mode is Update, Erase indicator sector in non active block
+ * to proceed swap system to update-erased state */
+ returnCode = FLASH_Erase(config, address + (config->PFlashTotalSize >> 1),
+ FSL_FEATURE_FLASH_PFLASH_SECTOR_CMD_ADDRESS_ALIGMENT, kFLASH_ApiEraseKey);
+ break;
+ case kFLASH_SwapStateUpdateErased:
+ /* If current swap mode is Update or Update-Erased, progress Swap to COMPLETE State */
+ returnCode =
+ FLASH_SwapControl(config, address, kFLASH_SwapControlOptionSetInCompleteState, &returnInfo);
+ break;
+ case kFLASH_SwapStateComplete:
+ break;
+ case kFLASH_SwapStateDisabled:
+ /* When swap system is in disabled state, We need to clear swap system back to uninitialized
+ * by issuing EraseAllBlocks command */
+ returnCode = kStatus_FLASH_SwapSystemNotInUninitialized;
+ break;
+ default:
+ returnCode = kStatus_FLASH_InvalidArgument;
+ break;
+ }
+ }
+ if (returnCode != kStatus_FLASH_Success)
+ {
+ break;
+ }
+ } while (!((kFLASH_SwapStateComplete == returnInfo.flashSwapState) && (kFLASH_SwapFunctionOptionEnable == option)));
+
+ return returnCode;
+}
+#endif /* FSL_FEATURE_FLASH_HAS_PFLASH_BLOCK_SWAP */
+
+#if defined(FSL_FEATURE_FLASH_HAS_PROGRAM_PARTITION_CMD) && FSL_FEATURE_FLASH_HAS_PROGRAM_PARTITION_CMD
+status_t FLASH_ProgramPartition(flash_config_t *config,
+ flash_partition_flexram_load_option_t option,
+ uint32_t eepromDataSizeCode,
+ uint32_t flexnvmPartitionCode)
+{
+ status_t returnCode;
+
+ if (config == NULL)
+ {
+ return kStatus_FLASH_InvalidArgument;
+ }
+
+ /* eepromDataSizeCode[7:6], flexnvmPartitionCode[7:4] should be all 1'b0
+ * or it will cause access error. */
+ /* eepromDataSizeCode &= 0x3FU; */
+ /* flexnvmPartitionCode &= 0x0FU; */
+
+ /* preparing passing parameter to program the flash block */
+ kFCCOBx[0] = BYTES_JOIN_TO_WORD_1_2_1(FTFx_PROGRAM_PARTITION, 0xFFFFU, option);
+ kFCCOBx[1] = BYTES_JOIN_TO_WORD_1_1_2(eepromDataSizeCode, flexnvmPartitionCode, 0xFFFFU);
+
+ /* calling flash command sequence function to execute the command */
+ returnCode = flash_command_sequence(config);
+
+ flash_cache_clear(config);
+
+#if FLASH_SSD_IS_FLEXNVM_ENABLED
+ /* Data flash IFR will be updated by program partition command during reset sequence,
+ * so we just set reserved values for partitioned FlexNVM size here */
+ config->EEpromTotalSize = FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_RESERVED;
+ config->DFlashTotalSize = FLEX_NVM_DFLASH_SIZE_FOR_DEPART_RESERVED;
+#endif
+
+ return (returnCode);
+}
+#endif /* FSL_FEATURE_FLASH_HAS_PROGRAM_PARTITION_CMD */
+
+status_t FLASH_PflashSetProtection(flash_config_t *config, uint32_t protectStatus)
+{
+ if (config == NULL)
+ {
+ return kStatus_FLASH_InvalidArgument;
+ }
+
+ *kFPROT = protectStatus;
+
+ if (protectStatus != *kFPROT)
+ {
+ return kStatus_FLASH_CommandFailure;
+ }
+
+ return kStatus_FLASH_Success;
+}
+
+status_t FLASH_PflashGetProtection(flash_config_t *config, uint32_t *protectStatus)
+{
+ if ((config == NULL) || (protectStatus == NULL))
+ {
+ return kStatus_FLASH_InvalidArgument;
+ }
+
+ *protectStatus = *kFPROT;
+
+ return kStatus_FLASH_Success;
+}
+
+#if FLASH_SSD_IS_FLEXNVM_ENABLED
+status_t FLASH_DflashSetProtection(flash_config_t *config, uint8_t protectStatus)
+{
+ if (config == NULL)
+ {
+ return kStatus_FLASH_InvalidArgument;
+ }
+
+ if ((config->DFlashTotalSize == 0) || (config->DFlashTotalSize == FLEX_NVM_DFLASH_SIZE_FOR_DEPART_RESERVED))
+ {
+ return kStatus_FLASH_CommandNotSupported;
+ }
+
+ FTFx->FDPROT = protectStatus;
+
+ if (FTFx->FDPROT != protectStatus)
+ {
+ return kStatus_FLASH_CommandFailure;
+ }
+
+ return kStatus_FLASH_Success;
+}
+#endif /* FLASH_SSD_IS_FLEXNVM_ENABLED */
+
+#if FLASH_SSD_IS_FLEXNVM_ENABLED
+status_t FLASH_DflashGetProtection(flash_config_t *config, uint8_t *protectStatus)
+{
+ if ((config == NULL) || (protectStatus == NULL))
+ {
+ return kStatus_FLASH_InvalidArgument;
+ }
+
+ if ((config->DFlashTotalSize == 0) || (config->DFlashTotalSize == FLEX_NVM_DFLASH_SIZE_FOR_DEPART_RESERVED))
+ {
+ return kStatus_FLASH_CommandNotSupported;
+ }
+
+ *protectStatus = FTFx->FDPROT;
+
+ return kStatus_FLASH_Success;
+}
+#endif /* FLASH_SSD_IS_FLEXNVM_ENABLED */
+
+#if FLASH_SSD_IS_FLEXNVM_ENABLED
+status_t FLASH_EepromSetProtection(flash_config_t *config, uint8_t protectStatus)
+{
+ if (config == NULL)
+ {
+ return kStatus_FLASH_InvalidArgument;
+ }
+
+ if ((config->EEpromTotalSize == 0) || (config->EEpromTotalSize == FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_RESERVED))
+ {
+ return kStatus_FLASH_CommandNotSupported;
+ }
+
+ FTFx->FEPROT = protectStatus;
+
+ if (FTFx->FEPROT != protectStatus)
+ {
+ return kStatus_FLASH_CommandFailure;
+ }
+
+ return kStatus_FLASH_Success;
+}
+#endif /* FLASH_SSD_IS_FLEXNVM_ENABLED */
+
+#if FLASH_SSD_IS_FLEXNVM_ENABLED
+status_t FLASH_EepromGetProtection(flash_config_t *config, uint8_t *protectStatus)
+{
+ if ((config == NULL) || (protectStatus == NULL))
+ {
+ return kStatus_FLASH_InvalidArgument;
+ }
+
+ if ((config->EEpromTotalSize == 0) || (config->EEpromTotalSize == FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_RESERVED))
+ {
+ return kStatus_FLASH_CommandNotSupported;
+ }
+
+ *protectStatus = FTFx->FEPROT;
+
+ return kStatus_FLASH_Success;
+}
+#endif /* FLASH_SSD_IS_FLEXNVM_ENABLED */
+
+#if FLASH_DRIVER_IS_FLASH_RESIDENT
+/*!
+ * @brief Copy PIC of flash_run_command() to RAM
+ */
+static void copy_flash_run_command(uint32_t *flashRunCommand)
+{
+ assert(sizeof(s_flashRunCommandFunctionCode) <= (kFLASH_ExecuteInRamFunctionMaxSizeInWords * 4));
+
+ /* Since the value of ARM function pointer is always odd, but the real start address
+ * of function memory should be even, that's why +1 operation exist. */
+ memcpy((void *)flashRunCommand, (void *)s_flashRunCommandFunctionCode, sizeof(s_flashRunCommandFunctionCode));
+ callFlashRunCommand = (void (*)(FTFx_REG_ACCESS_TYPE ftfx_fstat))((uint32_t)flashRunCommand + 1);
+}
+#endif /* FLASH_DRIVER_IS_FLASH_RESIDENT */
+
+/*!
+ * @brief Flash Command Sequence
+ *
+ * This function is used to perform the command write sequence to the flash.
+ *
+ * @param driver Pointer to storage for the driver runtime state.
+ * @return An error code or kStatus_FLASH_Success
+ */
+static status_t flash_command_sequence(flash_config_t *config)
+{
+ uint8_t registerValue;
+
+#if FLASH_DRIVER_IS_FLASH_RESIDENT
+ /* clear RDCOLERR & ACCERR & FPVIOL flag in flash status register */
+ FTFx->FSTAT = FTFx_FSTAT_RDCOLERR_MASK | FTFx_FSTAT_ACCERR_MASK | FTFx_FSTAT_FPVIOL_MASK;
+
+ status_t returnCode = flash_check_execute_in_ram_function_info(config);
+ if (kStatus_FLASH_Success != returnCode)
+ {
+ return returnCode;
+ }
+
+ /* We pass the ftfx_fstat address as a parameter to flash_run_comamnd() instead of using
+ * pre-processed MICRO sentences or operating global variable in flash_run_comamnd()
+ * to make sure that flash_run_command() will be compiled into position-independent code (PIC). */
+ callFlashRunCommand((FTFx_REG_ACCESS_TYPE)(&FTFx->FSTAT));
+#else
+ /* clear RDCOLERR & ACCERR & FPVIOL flag in flash status register */
+ FTFx->FSTAT = FTFx_FSTAT_RDCOLERR_MASK | FTFx_FSTAT_ACCERR_MASK | FTFx_FSTAT_FPVIOL_MASK;
+
+ /* clear CCIF bit */
+ FTFx->FSTAT = FTFx_FSTAT_CCIF_MASK;
+
+ /* Check CCIF bit of the flash status register, wait till it is set.
+ * IP team indicates that this loop will always complete. */
+ while (!(FTFx->FSTAT & FTFx_FSTAT_CCIF_MASK))
+ {
+ }
+#endif /* FLASH_DRIVER_IS_FLASH_RESIDENT */
+
+ /* Check error bits */
+ /* Get flash status register value */
+ registerValue = FTFx->FSTAT;
+
+ /* checking access error */
+ if (registerValue & FTFx_FSTAT_ACCERR_MASK)
+ {
+ return kStatus_FLASH_AccessError;
+ }
+ /* checking protection error */
+ else if (registerValue & FTFx_FSTAT_FPVIOL_MASK)
+ {
+ return kStatus_FLASH_ProtectionViolation;
+ }
+ /* checking MGSTAT0 non-correctable error */
+ else if (registerValue & FTFx_FSTAT_MGSTAT0_MASK)
+ {
+ return kStatus_FLASH_CommandFailure;
+ }
+ else
+ {
+ return kStatus_FLASH_Success;
+ }
+}
+
+#if FLASH_DRIVER_IS_FLASH_RESIDENT
+/*!
+ * @brief Copy PIC of flash_cache_clear_command() to RAM
+ *
+ */
+static void copy_flash_cache_clear_command(uint32_t *flashCacheClearCommand)
+{
+ assert(sizeof(s_flashCacheClearCommandFunctionCode) <= (kFLASH_ExecuteInRamFunctionMaxSizeInWords * 4));
+
+ /* Since the value of ARM function pointer is always odd, but the real start address
+ * of function memory should be even, that's why +1 operation exist. */
+ memcpy((void *)flashCacheClearCommand, (void *)s_flashCacheClearCommandFunctionCode,
+ sizeof(s_flashCacheClearCommandFunctionCode));
+ callFlashCacheClearCommand = (void (*)(FTFx_REG32_ACCESS_TYPE ftfx_reg))((uint32_t)flashCacheClearCommand + 1);
+}
+#endif /* FLASH_DRIVER_IS_FLASH_RESIDENT */
+
+/*!
+ * @brief Flash Cache Clear
+ *
+ * This function is used to perform the cache clear to the flash.
+ */
+#if (defined(__GNUC__))
+/* #pragma GCC push_options */
+/* #pragma GCC optimize("O0") */
+void __attribute__((optimize("O0"))) flash_cache_clear(flash_config_t *config)
+#else
+#if (defined(__ICCARM__))
+#pragma optimize = none
+#endif
+#if (defined(__CC_ARM))
+#pragma push
+#pragma O0
+#endif
+void flash_cache_clear(flash_config_t *config)
+#endif
+{
+#if FLASH_DRIVER_IS_FLASH_RESIDENT
+ status_t returnCode = flash_check_execute_in_ram_function_info(config);
+ if (kStatus_FLASH_Success != returnCode)
+ {
+ return;
+ }
+
+/* We pass the ftfx register address as a parameter to flash_cache_clear_comamnd() instead of using
+ * pre-processed MACROs or a global variable in flash_cache_clear_comamnd()
+ * to make sure that flash_cache_clear_command() will be compiled into position-independent code (PIC). */
+#if defined(FSL_FEATURE_FLASH_HAS_MCM_FLASH_CACHE_CONTROLS) && FSL_FEATURE_FLASH_HAS_MCM_FLASH_CACHE_CONTROLS
+#if defined(MCM)
+ callFlashCacheClearCommand((FTFx_REG32_ACCESS_TYPE)&MCM->PLACR);
+#endif
+#if defined(MCM0)
+ callFlashCacheClearCommand((FTFx_REG32_ACCESS_TYPE)&MCM0->PLACR);
+#endif
+#if defined(MCM1)
+ callFlashCacheClearCommand((FTFx_REG32_ACCESS_TYPE)&MCM1->PLACR);
+#endif
+#elif defined(FSL_FEATURE_FLASH_HAS_FMC_FLASH_CACHE_CONTROLS) && FSL_FEATURE_FLASH_HAS_FMC_FLASH_CACHE_CONTROLS
+#if defined(FMC_PFB01CR_CINV_WAY_MASK)
+ callFlashCacheClearCommand((FTFx_REG32_ACCESS_TYPE)&FMC->PFB01CR);
+#else
+ callFlashCacheClearCommand((FTFx_REG32_ACCESS_TYPE)&FMC->PFB0CR);
+#endif
+#elif defined(FSL_FEATURE_FLASH_HAS_MSCM_FLASH_CACHE_CONTROLS) && FSL_FEATURE_FLASH_HAS_MSCM_FLASH_CACHE_CONTROLS
+ callFlashCacheClearCommand((FTFx_REG32_ACCESS_TYPE)&MSCM->OCMDR[0]);
+#else
+#if defined(FMC_PFB0CR_S_INV_MASK)
+ callFlashCacheClearCommand((FTFx_REG32_ACCESS_TYPE)&FMC->PFB0CR);
+#elif defined(FMC_PFB01CR_S_INV_MASK)
+ callFlashCacheClearCommand((FTFx_REG32_ACCESS_TYPE)&FMC->PFB01CR);
+#else
+ /* meaningless code, just a workaround to solve warning*/
+ callFlashCacheClearCommand((FTFx_REG32_ACCESS_TYPE)0);
+#endif
+/* #error "Unknown flash cache controller" */
+#endif /* FSL_FEATURE_FTFx_MCM_FLASH_CACHE_CONTROLS */
+
+#else
+
+#if defined(FSL_FEATURE_FLASH_HAS_MCM_FLASH_CACHE_CONTROLS) && FSL_FEATURE_FLASH_HAS_MCM_FLASH_CACHE_CONTROLS
+#if defined(MCM)
+ MCM->PLACR |= MCM_PLACR_CFCC_MASK;
+#endif
+#if defined(MCM0)
+ MCM0->PLACR |= MCM_PLACR_CFCC_MASK;
+#endif
+#if defined(MCM1)
+ MCM1->PLACR |= MCM_PLACR_CFCC_MASK;
+#endif
+#elif defined(FSL_FEATURE_FLASH_HAS_FMC_FLASH_CACHE_CONTROLS) && FSL_FEATURE_FLASH_HAS_FMC_FLASH_CACHE_CONTROLS
+#if defined(FMC_PFB01CR_CINV_WAY_MASK)
+ FMC->PFB01CR = (FMC->PFB01CR & ~FMC_PFB01CR_CINV_WAY_MASK) | FMC_PFB01CR_CINV_WAY(~0);
+#else
+ FMC->PFB0CR = (FMC->PFB0CR & ~FMC_PFB0CR_CINV_WAY_MASK) | FMC_PFB0CR_CINV_WAY(~0);
+#endif
+#elif defined(FSL_FEATURE_FLASH_HAS_MSCM_FLASH_CACHE_CONTROLS) && FSL_FEATURE_FLASH_HAS_MSCM_FLASH_CACHE_CONTROLS
+ MSCM->OCMDR[0] |= MSCM_OCMDR_OCMC1(2);
+ MSCM->OCMDR[0] |= MSCM_OCMDR_OCMC1(1);
+#else
+#if defined(FMC_PFB0CR_S_INV_MASK)
+ FMC->PFB0CR |= FMC_PFB0CR_S_INV_MASK;
+#elif defined(FMC_PFB01CR_S_INV_MASK)
+ FMC->PFB01CR |= FMC_PFB01CR_S_INV_MASK;
+#endif
+/* #error "Unknown flash cache controller" */
+#endif /* FSL_FEATURE_FTFx_MCM_FLASH_CACHE_CONTROLS */
+#endif /* FLASH_DRIVER_IS_FLASH_RESIDENT */
+}
+#if (defined(__CC_ARM))
+#pragma pop
+#endif
+#if (defined(__GNUC__))
+/* #pragma GCC pop_options */
+#endif
+
+#if FLASH_DRIVER_IS_FLASH_RESIDENT
+/*! @brief Check whether flash execute-in-ram functions are ready */
+static status_t flash_check_execute_in_ram_function_info(flash_config_t *config)
+{
+ flash_execute_in_ram_function_config_t *flashExecuteInRamFunctionInfo;
+
+ if (config == NULL)
+ {
+ return kStatus_FLASH_InvalidArgument;
+ }
+
+ flashExecuteInRamFunctionInfo = (flash_execute_in_ram_function_config_t *)config->flashExecuteInRamFunctionInfo;
+
+ if ((config->flashExecuteInRamFunctionInfo) &&
+ (kFLASH_ExecuteInRamFunctionTotalNum == flashExecuteInRamFunctionInfo->activeFunctionCount))
+ {
+ return kStatus_FLASH_Success;
+ }
+
+ return kStatus_FLASH_ExecuteInRamFunctionNotReady;
+}
+#endif /* FLASH_DRIVER_IS_FLASH_RESIDENT */
+
+/*! @brief Validates the range and alignment of the given address range.*/
+static status_t flash_check_range(flash_config_t *config,
+ uint32_t startAddress,
+ uint32_t lengthInBytes,
+ uint32_t alignmentBaseline)
+{
+ if (config == NULL)
+ {
+ return kStatus_FLASH_InvalidArgument;
+ }
+
+ /* Verify the start and length are alignmentBaseline aligned. */
+ if ((startAddress & (alignmentBaseline - 1)) || (lengthInBytes & (alignmentBaseline - 1)))
+ {
+ return kStatus_FLASH_AlignmentError;
+ }
+
+/* check for valid range of the target addresses */
+#if !FLASH_SSD_IS_FLEXNVM_ENABLED
+ if ((startAddress < config->PFlashBlockBase) ||
+ ((startAddress + lengthInBytes) > (config->PFlashBlockBase + config->PFlashTotalSize)))
+#else
+ if (!(((startAddress >= config->PFlashBlockBase) &&
+ ((startAddress + lengthInBytes) <= (config->PFlashBlockBase + config->PFlashTotalSize))) ||
+ ((startAddress >= config->DFlashBlockBase) &&
+ ((startAddress + lengthInBytes) <= (config->DFlashBlockBase + config->DFlashTotalSize)))))
+#endif
+ {
+ return kStatus_FLASH_AddressError;
+ }
+
+ return kStatus_FLASH_Success;
+}
+
+/*! @brief Gets the right address, sector and block size of current flash type which is indicated by address.*/
+static status_t flash_get_matched_operation_info(flash_config_t *config,
+ uint32_t address,
+ flash_operation_config_t *info)
+{
+ if (config == NULL)
+ {
+ return kStatus_FLASH_InvalidArgument;
+ }
+
+ /* Clean up info Structure*/
+ memset(info, 0, sizeof(flash_operation_config_t));
+
+/* When required by the command, address bit 23 selects between program flash memory
+ * (=0) and data flash memory (=1).*/
+#if FLASH_SSD_IS_FLEXNVM_ENABLED
+ if ((address >= config->DFlashBlockBase) && (address <= (config->DFlashBlockBase + config->DFlashTotalSize)))
+ {
+ info->convertedAddress = address - config->DFlashBlockBase + 0x800000U;
+ info->activeSectorSize = FSL_FEATURE_FLASH_FLEX_NVM_BLOCK_SECTOR_SIZE;
+ info->activeBlockSize = config->DFlashTotalSize / FSL_FEATURE_FLASH_FLEX_NVM_BLOCK_COUNT;
+
+ info->blockWriteUnitSize = FSL_FEATURE_FLASH_FLEX_NVM_BLOCK_WRITE_UNIT_SIZE;
+ info->sectorCmdAddressAligment = FSL_FEATURE_FLASH_FLEX_NVM_SECTOR_CMD_ADDRESS_ALIGMENT;
+ info->sectionCmdAddressAligment = FSL_FEATURE_FLASH_FLEX_NVM_SECTION_CMD_ADDRESS_ALIGMENT;
+ info->resourceCmdAddressAligment = FSL_FEATURE_FLASH_FLEX_NVM_RESOURCE_CMD_ADDRESS_ALIGMENT;
+ info->checkCmdAddressAligment = FSL_FEATURE_FLASH_FLEX_NVM_CHECK_CMD_ADDRESS_ALIGMENT;
+ }
+ else
+#endif /* FLASH_SSD_IS_FLEXNVM_ENABLED */
+ {
+ info->convertedAddress = address - config->PFlashBlockBase;
+ info->activeSectorSize = config->PFlashSectorSize;
+ info->activeBlockSize = config->PFlashTotalSize / config->PFlashBlockCount;
+
+ info->blockWriteUnitSize = FSL_FEATURE_FLASH_PFLASH_BLOCK_WRITE_UNIT_SIZE;
+ info->sectorCmdAddressAligment = FSL_FEATURE_FLASH_PFLASH_SECTOR_CMD_ADDRESS_ALIGMENT;
+ info->sectionCmdAddressAligment = FSL_FEATURE_FLASH_PFLASH_SECTION_CMD_ADDRESS_ALIGMENT;
+ info->resourceCmdAddressAligment = FSL_FEATURE_FLASH_PFLASH_RESOURCE_CMD_ADDRESS_ALIGMENT;
+ info->checkCmdAddressAligment = FSL_FEATURE_FLASH_PFLASH_CHECK_CMD_ADDRESS_ALIGMENT;
+ }
+
+ return kStatus_FLASH_Success;
+}
+
+/*! @brief Validates the given user key for flash erase APIs.*/
+static status_t flash_check_user_key(uint32_t key)
+{
+ /* Validate the user key */
+ if (key != kFLASH_ApiEraseKey)
+ {
+ return kStatus_FLASH_EraseKeyError;
+ }
+
+ return kStatus_FLASH_Success;
+}
+
+#if FLASH_SSD_IS_FLEXNVM_ENABLED
+/*! @brief Updates FlexNVM memory partition status according to data flash 0 IFR.*/
+static status_t flash_update_flexnvm_memory_partition_status(flash_config_t *config)
+{
+ struct
+ {
+ uint32_t reserved0;
+ uint8_t FlexNVMPartitionCode;
+ uint8_t EEPROMDataSetSize;
+ uint16_t reserved1;
+ } dataIFRReadOut;
+ status_t returnCode;
+
+ if (config == NULL)
+ {
+ return kStatus_FLASH_InvalidArgument;
+ }
+
+ /* Get FlexNVM memory partition info from data flash IFR */
+ returnCode = FLASH_ReadResource(config, DFLASH_IFR_READRESOURCE_START_ADDRESS, (uint32_t *)&dataIFRReadOut,
+ sizeof(dataIFRReadOut), kFLASH_ResourceOptionFlashIfr);
+ if (returnCode != kStatus_FLASH_Success)
+ {
+ return kStatus_FLASH_PartitionStatusUpdateFailure;
+ }
+
+ /* Fill out partitioned EEPROM size */
+ dataIFRReadOut.EEPROMDataSetSize &= 0x0FU;
+ switch (dataIFRReadOut.EEPROMDataSetSize)
+ {
+ case 0x00U:
+ config->EEpromTotalSize = FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_0000;
+ break;
+ case 0x01U:
+ config->EEpromTotalSize = FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_0001;
+ break;
+ case 0x02U:
+ config->EEpromTotalSize = FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_0010;
+ break;
+ case 0x03U:
+ config->EEpromTotalSize = FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_0011;
+ break;
+ case 0x04U:
+ config->EEpromTotalSize = FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_0100;
+ break;
+ case 0x05U:
+ config->EEpromTotalSize = FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_0101;
+ break;
+ case 0x06U:
+ config->EEpromTotalSize = FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_0110;
+ break;
+ case 0x07U:
+ config->EEpromTotalSize = FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_0111;
+ break;
+ case 0x08U:
+ config->EEpromTotalSize = FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_1000;
+ break;
+ case 0x09U:
+ config->EEpromTotalSize = FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_1001;
+ break;
+ case 0x0AU:
+ config->EEpromTotalSize = FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_1010;
+ break;
+ case 0x0BU:
+ config->EEpromTotalSize = FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_1011;
+ break;
+ case 0x0CU:
+ config->EEpromTotalSize = FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_1100;
+ break;
+ case 0x0DU:
+ config->EEpromTotalSize = FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_1101;
+ break;
+ case 0x0EU:
+ config->EEpromTotalSize = FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_1110;
+ break;
+ case 0x0FU:
+ config->EEpromTotalSize = FSL_FEATURE_FLASH_FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_1111;
+ break;
+ default:
+ config->EEpromTotalSize = FLEX_NVM_EEPROM_SIZE_FOR_EEESIZE_RESERVED;
+ break;
+ }
+
+ /* Fill out partitioned DFlash size */
+ dataIFRReadOut.FlexNVMPartitionCode &= 0x0FU;
+ switch (dataIFRReadOut.FlexNVMPartitionCode)
+ {
+ case 0x00U:
+#if (FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_0000 != 0xFFFFFFFF)
+ config->DFlashTotalSize = FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_0000;
+#else
+ config->DFlashTotalSize = FLEX_NVM_DFLASH_SIZE_FOR_DEPART_RESERVED;
+#endif /* FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_0000 */
+ break;
+ case 0x01U:
+#if (FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_0001 != 0xFFFFFFFF)
+ config->DFlashTotalSize = FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_0001;
+#else
+ config->DFlashTotalSize = FLEX_NVM_DFLASH_SIZE_FOR_DEPART_RESERVED;
+#endif /* FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_0001 */
+ break;
+ case 0x02U:
+#if (FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_0010 != 0xFFFFFFFF)
+ config->DFlashTotalSize = FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_0010;
+#else
+ config->DFlashTotalSize = FLEX_NVM_DFLASH_SIZE_FOR_DEPART_RESERVED;
+#endif /* FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_0010 */
+ break;
+ case 0x03U:
+#if (FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_0011 != 0xFFFFFFFF)
+ config->DFlashTotalSize = FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_0011;
+#else
+ config->DFlashTotalSize = FLEX_NVM_DFLASH_SIZE_FOR_DEPART_RESERVED;
+#endif /* FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_0011 */
+ break;
+ case 0x04U:
+#if (FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_0100 != 0xFFFFFFFF)
+ config->DFlashTotalSize = FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_0100;
+#else
+ config->DFlashTotalSize = FLEX_NVM_DFLASH_SIZE_FOR_DEPART_RESERVED;
+#endif /* FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_0100 */
+ break;
+ case 0x05U:
+#if (FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_0101 != 0xFFFFFFFF)
+ config->DFlashTotalSize = FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_0101;
+#else
+ config->DFlashTotalSize = FLEX_NVM_DFLASH_SIZE_FOR_DEPART_RESERVED;
+#endif /* FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_0101 */
+ break;
+ case 0x06U:
+#if (FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_0110 != 0xFFFFFFFF)
+ config->DFlashTotalSize = FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_0110;
+#else
+ config->DFlashTotalSize = FLEX_NVM_DFLASH_SIZE_FOR_DEPART_RESERVED;
+#endif /* FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_0110 */
+ break;
+ case 0x07U:
+#if (FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_0111 != 0xFFFFFFFF)
+ config->DFlashTotalSize = FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_0111;
+#else
+ config->DFlashTotalSize = FLEX_NVM_DFLASH_SIZE_FOR_DEPART_RESERVED;
+#endif /* FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_0111 */
+ break;
+ case 0x08U:
+#if (FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_1000 != 0xFFFFFFFF)
+ config->DFlashTotalSize = FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_1000;
+#else
+ config->DFlashTotalSize = FLEX_NVM_DFLASH_SIZE_FOR_DEPART_RESERVED;
+#endif /* FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_1000 */
+ break;
+ case 0x09U:
+#if (FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_1001 != 0xFFFFFFFF)
+ config->DFlashTotalSize = FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_1001;
+#else
+ config->DFlashTotalSize = FLEX_NVM_DFLASH_SIZE_FOR_DEPART_RESERVED;
+#endif /* FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_1001 */
+ break;
+ case 0x0AU:
+#if (FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_1010 != 0xFFFFFFFF)
+ config->DFlashTotalSize = FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_1010;
+#else
+ config->DFlashTotalSize = FLEX_NVM_DFLASH_SIZE_FOR_DEPART_RESERVED;
+#endif /* FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_1010 */
+ break;
+ case 0x0BU:
+#if (FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_1011 != 0xFFFFFFFF)
+ config->DFlashTotalSize = FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_1011;
+#else
+ config->DFlashTotalSize = FLEX_NVM_DFLASH_SIZE_FOR_DEPART_RESERVED;
+#endif /* FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_1011 */
+ break;
+ case 0x0CU:
+#if (FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_1100 != 0xFFFFFFFF)
+ config->DFlashTotalSize = FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_1100;
+#else
+ config->DFlashTotalSize = FLEX_NVM_DFLASH_SIZE_FOR_DEPART_RESERVED;
+#endif /* FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_1100 */
+ break;
+ case 0x0DU:
+#if (FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_1101 != 0xFFFFFFFF)
+ config->DFlashTotalSize = FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_1101;
+#else
+ config->DFlashTotalSize = FLEX_NVM_DFLASH_SIZE_FOR_DEPART_RESERVED;
+#endif /* FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_1101 */
+ break;
+ case 0x0EU:
+#if (FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_1110 != 0xFFFFFFFF)
+ config->DFlashTotalSize = FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_1110;
+#else
+ config->DFlashTotalSize = FLEX_NVM_DFLASH_SIZE_FOR_DEPART_RESERVED;
+#endif /* FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_1110 */
+ break;
+ case 0x0FU:
+#if (FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_1111 != 0xFFFFFFFF)
+ config->DFlashTotalSize = FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_1111;
+#else
+ config->DFlashTotalSize = FLEX_NVM_DFLASH_SIZE_FOR_DEPART_RESERVED;
+#endif /* FSL_FEATURE_FLASH_FLEX_NVM_DFLASH_SIZE_FOR_DEPART_1111 */
+ break;
+ default:
+ config->DFlashTotalSize = FLEX_NVM_DFLASH_SIZE_FOR_DEPART_RESERVED;
+ break;
+ }
+
+ return kStatus_FLASH_Success;
+}
+#endif /* FLASH_SSD_IS_FLEXNVM_ENABLED */
+
+#if defined(FSL_FEATURE_FLASH_HAS_READ_RESOURCE_CMD) && FSL_FEATURE_FLASH_HAS_READ_RESOURCE_CMD
+/*! @brief Validates the range of the given resource address.*/
+static status_t flash_check_resource_range(uint32_t start,
+ uint32_t lengthInBytes,
+ uint32_t alignmentBaseline,
+ flash_read_resource_option_t option)
+{
+ status_t status;
+ uint32_t maxReadbleAddress;
+
+ if ((start & (alignmentBaseline - 1)) || (lengthInBytes & (alignmentBaseline - 1)))
+ {
+ return kStatus_FLASH_AlignmentError;
+ }
+
+ status = kStatus_FLASH_Success;
+
+ maxReadbleAddress = start + lengthInBytes - 1;
+ if (option == kFLASH_ResourceOptionVersionId)
+ {
+ if ((start != kFLASH_ResourceRangeVersionIdStart) ||
+ ((start + lengthInBytes - 1) != kFLASH_ResourceRangeVersionIdEnd))
+ {
+ status = kStatus_FLASH_InvalidArgument;
+ }
+ }
+ else if (option == kFLASH_ResourceOptionFlashIfr)
+ {
+ if (maxReadbleAddress < kFLASH_ResourceRangePflashIfrSizeInBytes)
+ {
+ }
+#if defined(FSL_FEATURE_FLASH_HAS_PFLASH_BLOCK_SWAP) && FSL_FEATURE_FLASH_HAS_PFLASH_BLOCK_SWAP
+ else if ((start >= kFLASH_ResourceRangePflashSwapIfrStart) &&
+ (maxReadbleAddress <= kFLASH_ResourceRangePflashSwapIfrEnd))
+ {
+ }
+#endif /* FSL_FEATURE_FLASH_HAS_PFLASH_BLOCK_SWAP */
+ else if ((start >= kFLASH_ResourceRangeDflashIfrStart) &&
+ (maxReadbleAddress <= kFLASH_ResourceRangeDflashIfrEnd))
+ {
+ }
+ else
+ {
+ status = kStatus_FLASH_InvalidArgument;
+ }
+ }
+ else
+ {
+ status = kStatus_FLASH_InvalidArgument;
+ }
+
+ return status;
+}
+#endif /* FSL_FEATURE_FLASH_HAS_READ_RESOURCE_CMD */
+
+#if defined(FSL_FEATURE_FLASH_HAS_SWAP_CONTROL_CMD) && FSL_FEATURE_FLASH_HAS_SWAP_CONTROL_CMD
+/*! @brief Validates the gived swap control option.*/
+static status_t flash_check_swap_control_option(flash_swap_control_option_t option)
+{
+ if ((option == kFLASH_SwapControlOptionIntializeSystem) || (option == kFLASH_SwapControlOptionSetInUpdateState) ||
+ (option == kFLASH_SwapControlOptionSetInCompleteState) || (option == kFLASH_SwapControlOptionReportStatus) ||
+ (option == kFLASH_SwapControlOptionDisableSystem))
+ {
+ return kStatus_FLASH_Success;
+ }
+
+ return kStatus_FLASH_InvalidArgument;
+}
+#endif /* FSL_FEATURE_FLASH_HAS_SWAP_CONTROL_CMD */
+
+#if defined(FSL_FEATURE_FLASH_HAS_PFLASH_BLOCK_SWAP) && FSL_FEATURE_FLASH_HAS_PFLASH_BLOCK_SWAP
+/*! @brief Validates the gived address to see if it is equal to swap indicator address in pflash swap IFR.*/
+static status_t flash_validate_swap_indicator_address(flash_config_t *config, uint32_t address)
+{
+ flash_swap_ifr_field_data_t flashSwapIfrFieldData;
+ uint32_t swapIndicatorAddress;
+
+ status_t returnCode;
+ returnCode =
+ FLASH_ReadResource(config, kFLASH_ResourceRangePflashSwapIfrStart, flashSwapIfrFieldData.flashSwapIfrData,
+ sizeof(flashSwapIfrFieldData.flashSwapIfrData), kFLASH_ResourceOptionFlashIfr);
+
+ if (returnCode != kStatus_FLASH_Success)
+ {
+ return returnCode;
+ }
+
+ /* The high bits value of Swap Indicator Address is stored in Program Flash Swap IFR Field,
+ * the low severval bit value of Swap Indicator Address is always 1'b0 */
+ swapIndicatorAddress = (uint32_t)flashSwapIfrFieldData.flashSwapIfrField.swapIndicatorAddress *
+ FSL_FEATURE_FLASH_PFLASH_SWAP_CONTROL_CMD_ADDRESS_ALIGMENT;
+ if (address != swapIndicatorAddress)
+ {
+ return kStatus_FLASH_SwapIndicatorAddressError;
+ }
+
+ return returnCode;
+}
+#endif /* FSL_FEATURE_FLASH_HAS_PFLASH_BLOCK_SWAP */
+
+#if defined(FSL_FEATURE_FLASH_HAS_SET_FLEXRAM_FUNCTION_CMD) && FSL_FEATURE_FLASH_HAS_SET_FLEXRAM_FUNCTION_CMD
+/*! @brief Validates the gived flexram function option.*/
+static inline status_t flasn_check_flexram_function_option_range(flash_flexram_function_option_t option)
+{
+ if ((option != kFLASH_FlexramFunctionOptionAvailableAsRam) &&
+ (option != kFLASH_FlexramFunctionOptionAvailableForEeprom))
+ {
+ return kStatus_FLASH_InvalidArgument;
+ }
+
+ return kStatus_FLASH_Success;
+}
+#endif /* FSL_FEATURE_FLASH_HAS_SET_FLEXRAM_FUNCTION_CMD */
diff --git a/drivers/fsl_flash.h b/drivers/fsl_flash.h
new file mode 100644
index 0000000..8941ad7
--- /dev/null
+++ b/drivers/fsl_flash.h
@@ -0,0 +1,1209 @@
+/*
+ * Copyright (c) 2013-2016, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_FLASH_H_
+#define _FSL_FLASH_H_
+
+#if (defined(BL_TARGET_FLASH) || defined(BL_TARGET_ROM) || defined(BL_TARGET_RAM))
+#include <assert.h>
+#include <string.h>
+#include "fsl_device_registers.h"
+#include "bootloader_common.h"
+#else
+#include "fsl_common.h"
+#endif
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+/*!
+ * @addtogroup flash_driver
+ * @{
+ */
+
+/*!
+ * @name Flash version
+ * @{
+ */
+/*! @brief Construct the version number for drivers. */
+#if !defined(MAKE_VERSION)
+#define MAKE_VERSION(major, minor, bugfix) (((major) << 16) | ((minor) << 8) | (bugfix))
+#endif
+
+/*! @brief FLASH driver version for SDK*/
+#define FSL_FLASH_DRIVER_VERSION (MAKE_VERSION(2, 1, 0)) /*!< Version 2.1.0. */
+
+/*! @brief FLASH driver version for ROM*/
+enum _flash_driver_version_constants
+{
+ kFLASH_DriverVersionName = 'F', /*!< Flash driver version name.*/
+ kFLASH_DriverVersionMajor = 2, /*!< Major flash driver version.*/
+ kFLASH_DriverVersionMinor = 1, /*!< Minor flash driver version.*/
+ kFLASH_DriverVersionBugfix = 0 /*!< Bugfix for flash driver version.*/
+};
+/*@}*/
+
+/*!
+ * @name Flash configuration
+ * @{
+ */
+/*! @brief Whether to support FlexNVM in flash driver */
+#if !defined(FLASH_SSD_CONFIG_ENABLE_FLEXNVM_SUPPORT)
+#define FLASH_SSD_CONFIG_ENABLE_FLEXNVM_SUPPORT 1 /*!< Enable FlexNVM support by default. */
+#endif
+
+/*! @brief Whether the FlexNVM is enabled in flash driver */
+#define FLASH_SSD_IS_FLEXNVM_ENABLED (FLASH_SSD_CONFIG_ENABLE_FLEXNVM_SUPPORT && FSL_FEATURE_FLASH_HAS_FLEX_NVM)
+
+/*! @brief Flash driver location. */
+#if !defined(FLASH_DRIVER_IS_FLASH_RESIDENT)
+#if (!defined(BL_TARGET_ROM) && !defined(BL_TARGET_RAM))
+#define FLASH_DRIVER_IS_FLASH_RESIDENT 1 /*!< Used for flash resident application. */
+#else
+#define FLASH_DRIVER_IS_FLASH_RESIDENT 0 /*!< Used for non-flash resident application. */
+#endif
+#endif
+
+/*! @brief Flash Driver Export option */
+#if !defined(FLASH_DRIVER_IS_EXPORTED)
+#if (defined(BL_TARGET_ROM) || defined(BL_TARGET_FLASH))
+#define FLASH_DRIVER_IS_EXPORTED 1 /*!< Used for ROM bootloader. */
+#else
+#define FLASH_DRIVER_IS_EXPORTED 0 /*!< Used for SDK application. */
+#endif
+#endif
+/*@}*/
+
+/*!
+ * @name Flash status
+ * @{
+ */
+/*! @brief Flash driver status group. */
+#if defined(kStatusGroup_FlashDriver)
+#define kStatusGroupGeneric kStatusGroup_Generic
+#define kStatusGroupFlashDriver kStatusGroup_FlashDriver
+#elif defined(kStatusGroup_FLASH)
+#define kStatusGroupGeneric kStatusGroup_Generic
+#define kStatusGroupFlashDriver kStatusGroup_FLASH
+#else
+#define kStatusGroupGeneric 0
+#define kStatusGroupFlashDriver 1
+#endif
+
+/*! @brief Construct a status code value from a group and code number. */
+#if !defined(MAKE_STATUS)
+#define MAKE_STATUS(group, code) ((((group)*100) + (code)))
+#endif
+
+/*!
+ * @brief Flash driver status codes.
+ */
+enum _flash_status
+{
+ kStatus_FLASH_Success = MAKE_STATUS(kStatusGroupGeneric, 0), /*!< API is executed successfully*/
+ kStatus_FLASH_InvalidArgument = MAKE_STATUS(kStatusGroupGeneric, 4), /*!< Invalid argument*/
+ kStatus_FLASH_SizeError = MAKE_STATUS(kStatusGroupFlashDriver, 0), /*!< Error size*/
+ kStatus_FLASH_AlignmentError =
+ MAKE_STATUS(kStatusGroupFlashDriver, 1), /*!< Parameter is not aligned with specified baseline*/
+ kStatus_FLASH_AddressError = MAKE_STATUS(kStatusGroupFlashDriver, 2), /*!< Address is out of range */
+ kStatus_FLASH_AccessError =
+ MAKE_STATUS(kStatusGroupFlashDriver, 3), /*!< Invalid instruction codes and out-of bounds addresses */
+ kStatus_FLASH_ProtectionViolation = MAKE_STATUS(
+ kStatusGroupFlashDriver, 4), /*!< The program/erase operation is requested to execute on protected areas */
+ kStatus_FLASH_CommandFailure =
+ MAKE_STATUS(kStatusGroupFlashDriver, 5), /*!< Run-time error during command execution. */
+ kStatus_FLASH_UnknownProperty = MAKE_STATUS(kStatusGroupFlashDriver, 6), /*!< Unknown property.*/
+ kStatus_FLASH_EraseKeyError = MAKE_STATUS(kStatusGroupFlashDriver, 7), /*!< API erase key is invalid.*/
+ kStatus_FLASH_RegionExecuteOnly = MAKE_STATUS(kStatusGroupFlashDriver, 8), /*!< Current region is execute only.*/
+ kStatus_FLASH_ExecuteInRamFunctionNotReady =
+ MAKE_STATUS(kStatusGroupFlashDriver, 9), /*!< Execute-in-RAM function is not available.*/
+ kStatus_FLASH_PartitionStatusUpdateFailure =
+ MAKE_STATUS(kStatusGroupFlashDriver, 10), /*!< Failed to update partition status.*/
+ kStatus_FLASH_SetFlexramAsEepromError =
+ MAKE_STATUS(kStatusGroupFlashDriver, 11), /*!< Failed to set flexram as eeprom.*/
+ kStatus_FLASH_RecoverFlexramAsRamError =
+ MAKE_STATUS(kStatusGroupFlashDriver, 12), /*!< Failed to recover flexram as RAM.*/
+ kStatus_FLASH_SetFlexramAsRamError = MAKE_STATUS(kStatusGroupFlashDriver, 13), /*!< Failed to set flexram as RAM.*/
+ kStatus_FLASH_RecoverFlexramAsEepromError =
+ MAKE_STATUS(kStatusGroupFlashDriver, 14), /*!< Failed to recover flexram as eeprom.*/
+ kStatus_FLASH_CommandNotSupported = MAKE_STATUS(kStatusGroupFlashDriver, 15), /*!< Flash API is not supported.*/
+ kStatus_FLASH_SwapSystemNotInUninitialized =
+ MAKE_STATUS(kStatusGroupFlashDriver, 16), /*!< Swap system is not in uninitialzed state.*/
+ kStatus_FLASH_SwapIndicatorAddressError =
+ MAKE_STATUS(kStatusGroupFlashDriver, 17), /*!< Swap indicator address is invalid.*/
+};
+/*@}*/
+
+/*!
+ * @name Flash API key
+ * @{
+ */
+/*! @brief Construct the four char code for flash driver API key. */
+#if !defined(FOUR_CHAR_CODE)
+#define FOUR_CHAR_CODE(a, b, c, d) (((d) << 24) | ((c) << 16) | ((b) << 8) | ((a)))
+#endif
+
+/*!
+ * @brief Enumeration for flash driver API keys.
+ *
+ * @note The resulting value is built with a byte order such that the string
+ * being readable in expected order when viewed in a hex editor, if the value
+ * is treated as a 32-bit little endian value.
+ */
+enum _flash_driver_api_keys
+{
+ kFLASH_ApiEraseKey = FOUR_CHAR_CODE('k', 'f', 'e', 'k') /*!< Key value used to validate all flash erase APIs.*/
+};
+/*@}*/
+
+/*!
+ * @brief Enumeration for supported flash margin levels.
+ */
+typedef enum _flash_margin_value
+{
+ kFLASH_MarginValueNormal, /*!< Use the 'normal' read level for 1s.*/
+ kFLASH_MarginValueUser, /*!< Apply the 'User' margin to the normal read-1 level.*/
+ kFLASH_MarginValueFactory, /*!< Apply the 'Factory' margin to the normal read-1 level.*/
+ kFLASH_MarginValueInvalid /*!< Not real margin level, Used to determine the range of valid margin level. */
+} flash_margin_value_t;
+
+/*!
+ * @brief Enumeration for the three possible flash security states.
+ */
+typedef enum _flash_security_state
+{
+ kFLASH_SecurityStateNotSecure, /*!< Flash is not secure.*/
+ kFLASH_SecurityStateBackdoorEnabled, /*!< Flash backdoor is enabled.*/
+ kFLASH_SecurityStateBackdoorDisabled /*!< Flash backdoor is disabled.*/
+} flash_security_state_t;
+
+/*!
+ * @brief Enumeration for the three possible flash protection levels.
+ */
+typedef enum _flash_protection_state
+{
+ kFLASH_ProtectionStateUnprotected, /*!< Flash region is not protected.*/
+ kFLASH_ProtectionStateProtected, /*!< Flash region is protected.*/
+ kFLASH_ProtectionStateMixed /*!< Flash is mixed with protected and unprotected region.*/
+} flash_protection_state_t;
+
+/*!
+ * @brief Enumeration for the three possible flash execute access levels.
+ */
+typedef enum _flash_execute_only_access_state
+{
+ kFLASH_AccessStateUnLimited, /*!< Flash region is unLimited.*/
+ kFLASH_AccessStateExecuteOnly, /*!< Flash region is execute only.*/
+ kFLASH_AccessStateMixed /*!< Flash is mixed with unLimited and execute only region.*/
+} flash_execute_only_access_state_t;
+
+/*!
+ * @brief Enumeration for various flash properties.
+ */
+typedef enum _flash_property_tag
+{
+ kFLASH_PropertyPflashSectorSize = 0x00U, /*!< Pflash sector size property.*/
+ kFLASH_PropertyPflashTotalSize = 0x01U, /*!< Pflash total size property.*/
+ kFLASH_PropertyPflashBlockSize = 0x02U, /*!< Pflash block size property.*/
+ kFLASH_PropertyPflashBlockCount = 0x03U, /*!< Pflash block count property.*/
+ kFLASH_PropertyPflashBlockBaseAddr = 0x04U, /*!< Pflash block base address property.*/
+ kFLASH_PropertyPflashFacSupport = 0x05U, /*!< Pflash fac support property.*/
+ kFLASH_PropertyPflashAccessSegmentSize = 0x06U, /*!< Pflash access segment size property.*/
+ kFLASH_PropertyPflashAccessSegmentCount = 0x07U, /*!< Pflash access segment count property.*/
+ kFLASH_PropertyFlexRamBlockBaseAddr = 0x08U, /*!< FlexRam block base address property.*/
+ kFLASH_PropertyFlexRamTotalSize = 0x09U, /*!< FlexRam total size property.*/
+ kFLASH_PropertyDflashSectorSize = 0x10U, /*!< Dflash sector size property.*/
+ kFLASH_PropertyDflashTotalSize = 0x11U, /*!< Dflash total size property.*/
+ kFLASH_PropertyDflashBlockSize = 0x12U, /*!< Dflash block count property.*/
+ kFLASH_PropertyDflashBlockCount = 0x13U, /*!< Dflash block base address property.*/
+ kFLASH_PropertyDflashBlockBaseAddr = 0x14U, /*!< Eeprom total size property.*/
+ kFLASH_PropertyEepromTotalSize = 0x15U
+} flash_property_tag_t;
+
+/*!
+ * @brief Constants for execute-in-RAM flash function.
+ */
+enum _flash_execute_in_ram_function_constants
+{
+ kFLASH_ExecuteInRamFunctionMaxSizeInWords = 16U, /*!< Max size of execute-in-RAM function.*/
+ kFLASH_ExecuteInRamFunctionTotalNum = 2U /*!< Total number of execute-in-RAM functions.*/
+};
+
+/*!
+ * @brief Flash execute-in-RAM function information.
+ */
+typedef struct _flash_execute_in_ram_function_config
+{
+ uint32_t activeFunctionCount; /*!< Number of available execute-in-RAM functions.*/
+ uint32_t *flashRunCommand; /*!< execute-in-RAM function: flash_run_command.*/
+ uint32_t *flashCacheClearCommand; /*!< execute-in-RAM function: flash_cache_clear_command.*/
+} flash_execute_in_ram_function_config_t;
+
+/*!
+ * @brief Enumeration for the two possible options of flash read resource command.
+ */
+typedef enum _flash_read_resource_option
+{
+ kFLASH_ResourceOptionFlashIfr =
+ 0x00U, /*!< Select code for Program flash 0 IFR, Program flash swap 0 IFR, Data flash 0 IFR */
+ kFLASH_ResourceOptionVersionId = 0x01U /*!< Select code for Version ID*/
+} flash_read_resource_option_t;
+
+/*!
+ * @brief Enumeration for the range of special-purpose flash resource
+ */
+enum _flash_read_resource_range
+{
+#if (FSL_FEATURE_FLASH_IS_FTFE == 1)
+ kFLASH_ResourceRangePflashIfrSizeInBytes = 1024U, /*!< Pflash IFR size in byte.*/
+ kFLASH_ResourceRangeVersionIdSizeInBytes = 8U, /*!< Version ID IFR size in byte.*/
+ kFLASH_ResourceRangeVersionIdStart = 0x08U, /*!< Version ID IFR start address.*/
+ kFLASH_ResourceRangeVersionIdEnd = 0x0FU, /*!< Version ID IFR end address.*/
+ kFLASH_ResourceRangePflashSwapIfrStart = 0x40000U, /*!< Pflash swap IFR start address.*/
+ kFLASH_ResourceRangePflashSwapIfrEnd =
+ (kFLASH_ResourceRangePflashSwapIfrStart + 0x3FFU), /*!< Pflash swap IFR end address.*/
+#else /* FSL_FEATURE_FLASH_IS_FTFL == 1 or FSL_FEATURE_FLASH_IS_FTFA = =1 */
+ kFLASH_ResourceRangePflashIfrSizeInBytes = 256U, /*!< Pflash IFR size in byte.*/
+ kFLASH_ResourceRangeVersionIdSizeInBytes = 8U, /*!< Version ID IFR size in byte.*/
+ kFLASH_ResourceRangeVersionIdStart = 0x00U, /*!< Version ID IFR start address.*/
+ kFLASH_ResourceRangeVersionIdEnd = 0x07U, /*!< Version ID IFR end address.*/
+#if 0x20000U == (FSL_FEATURE_FLASH_PFLASH_BLOCK_COUNT * FSL_FEATURE_FLASH_PFLASH_BLOCK_SIZE)
+ kFLASH_ResourceRangePflashSwapIfrStart = 0x8000U, /*!< Pflash swap IFR start address.*/
+#elif 0x40000U == (FSL_FEATURE_FLASH_PFLASH_BLOCK_COUNT * FSL_FEATURE_FLASH_PFLASH_BLOCK_SIZE)
+ kFLASH_ResourceRangePflashSwapIfrStart = 0x10000U, /*!< Pflash swap IFR start address.*/
+#elif 0x80000U == (FSL_FEATURE_FLASH_PFLASH_BLOCK_COUNT * FSL_FEATURE_FLASH_PFLASH_BLOCK_SIZE)
+ kFLASH_ResourceRangePflashSwapIfrStart = 0x20000U, /*!< Pflash swap IFR start address.*/
+#else
+ kFLASH_ResourceRangePflashSwapIfrStart = 0,
+#endif
+ kFLASH_ResourceRangePflashSwapIfrEnd =
+ (kFLASH_ResourceRangePflashSwapIfrStart + 0xFFU), /*!< Pflash swap IFR end address.*/
+#endif
+ kFLASH_ResourceRangeDflashIfrStart = 0x800000U, /*!< Dflash IFR start address.*/
+ kFLASH_ResourceRangeDflashIfrEnd = 0x8003FFU, /*!< Dflash IFR end address.*/
+};
+
+/*!
+ * @brief Enumeration for the two possilbe options of set flexram function command.
+ */
+typedef enum _flash_flexram_function_option
+{
+ kFLASH_FlexramFunctionOptionAvailableAsRam = 0xFFU, /*!< Option used to make FlexRAM available as RAM */
+ kFLASH_FlexramFunctionOptionAvailableForEeprom = 0x00U /*!< Option used to make FlexRAM available for EEPROM */
+} flash_flexram_function_option_t;
+
+/*!
+ * @brief Enumeration for acceleration RAM property.
+ */
+enum _flash_acceleration_ram_property
+{
+ kFLASH_AccelerationRamSize = 0x400U
+};
+
+/*!
+ * @brief Enumeration for the possible options of Swap function
+ */
+typedef enum _flash_swap_function_option
+{
+ kFLASH_SwapFunctionOptionEnable = 0x00U, /*!< Option used to enable Swap function */
+ kFLASH_SwapFunctionOptionDisable = 0x01U /*!< Option used to Disable Swap function */
+} flash_swap_function_option_t;
+
+/*!
+ * @brief Enumeration for the possible options of Swap Control commands
+ */
+typedef enum _flash_swap_control_option
+{
+ kFLASH_SwapControlOptionIntializeSystem = 0x01U, /*!< Option used to Intialize Swap System */
+ kFLASH_SwapControlOptionSetInUpdateState = 0x02U, /*!< Option used to Set Swap in Update State */
+ kFLASH_SwapControlOptionSetInCompleteState = 0x04U, /*!< Option used to Set Swap in Complete State */
+ kFLASH_SwapControlOptionReportStatus = 0x08U, /*!< Option used to Report Swap Status */
+ kFLASH_SwapControlOptionDisableSystem = 0x10U /*!< Option used to Disable Swap Status */
+} flash_swap_control_option_t;
+
+/*!
+ * @brief Enumeration for the possible flash swap status.
+ */
+typedef enum _flash_swap_state
+{
+ kFLASH_SwapStateUninitialized = 0x00U, /*!< Flash swap system is in uninitialized state.*/
+ kFLASH_SwapStateReady = 0x01U, /*!< Flash swap system is in ready state.*/
+ kFLASH_SwapStateUpdate = 0x02U, /*!< Flash swap system is in update state.*/
+ kFLASH_SwapStateUpdateErased = 0x03U, /*!< Flash swap system is in updateErased state.*/
+ kFLASH_SwapStateComplete = 0x04U, /*!< Flash swap system is in complete state.*/
+ kFLASH_SwapStateDisabled = 0x05U /*!< Flash swap system is in disabled state.*/
+} flash_swap_state_t;
+
+/*!
+ * @breif Enumeration for the possible flash swap block status
+ */
+typedef enum _flash_swap_block_status
+{
+ kFLASH_SwapBlockStatusLowerHalfProgramBlocksAtZero =
+ 0x00U, /*!< Swap block status is that lower half program block at zero.*/
+ kFLASH_SwapBlockStatusUpperHalfProgramBlocksAtZero =
+ 0x01U, /*!< Swap block status is that upper half program block at zero.*/
+} flash_swap_block_status_t;
+
+/*!
+ * @brief Flash Swap information.
+ */
+typedef struct _flash_swap_state_config
+{
+ flash_swap_state_t flashSwapState; /*!< Current swap system status.*/
+ flash_swap_block_status_t currentSwapBlockStatus; /*!< Current swap block status.*/
+ flash_swap_block_status_t nextSwapBlockStatus; /*!< Next swap block status.*/
+} flash_swap_state_config_t;
+
+/*!
+ * @brief Flash Swap IFR fields.
+ */
+typedef struct _flash_swap_ifr_field_config
+{
+ uint16_t swapIndicatorAddress; /*!< Swap indicator address field.*/
+ uint16_t swapEnableWord; /*!< Swap enable word field.*/
+ uint8_t reserved0[4]; /*!< Reserved field.*/
+#if (FSL_FEATURE_FLASH_IS_FTFE == 1)
+ uint8_t reserved1[2]; /*!< Reserved field.*/
+ uint16_t swapDisableWord; /*!< Swap disable word field.*/
+ uint8_t reserved2[4]; /*!< Reserved field.*/
+#endif
+} flash_swap_ifr_field_config_t;
+
+/*!
+ * @brief Flash Swap IFR field data.
+ */
+typedef union _flash_swap_ifr_field_data
+{
+ uint32_t flashSwapIfrData[2]; /*!< Flash Swap IFR field data .*/
+ flash_swap_ifr_field_config_t flashSwapIfrField; /*!< Flash Swap IFR field struct.*/
+} flash_swap_ifr_field_data_t;
+
+/*!
+ * @brief Enumeration for FlexRAM load during reset option.
+ */
+typedef enum _flash_partition_flexram_load_option
+{
+ kFLASH_PartitionFlexramLoadOptionLoadedWithValidEepromData =
+ 0x00U, /*!< FlexRAM is loaded with valid EEPROM data during reset sequence.*/
+ kFLASH_PartitionFlexramLoadOptionNotLoaded = 0x01U /*!< FlexRAM is not loaded during reset sequence.*/
+} flash_partition_flexram_load_option_t;
+
+/*! @brief callback type used for pflash block*/
+typedef void (*flash_callback_t)(void);
+
+/*!
+ * @brief Active flash information for current operation.
+ */
+typedef struct _flash_operation_config
+{
+ uint32_t convertedAddress; /*!< Converted address for current flash type.*/
+ uint32_t activeSectorSize; /*!< Sector size of current flash type.*/
+ uint32_t activeBlockSize; /*!< Block size of current flash type.*/
+ uint32_t blockWriteUnitSize; /*!< write unit size.*/
+ uint32_t sectorCmdAddressAligment; /*!< Erase sector command address alignment.*/
+ uint32_t sectionCmdAddressAligment; /*!< Program/Verify section command address alignment.*/
+ uint32_t resourceCmdAddressAligment; /*!< Read resource command address alignment.*/
+ uint32_t checkCmdAddressAligment; /*!< Program check command address alignment.*/
+} flash_operation_config_t;
+
+/*! @brief Flash driver state information.
+ *
+ * An instance of this structure is allocated by the user of the flash driver and
+ * passed into each of the driver APIs.
+ */
+typedef struct _flash_config
+{
+ uint32_t PFlashBlockBase; /*!< Base address of the first PFlash block */
+ uint32_t PFlashTotalSize; /*!< Size of all combined PFlash block. */
+ uint32_t PFlashBlockCount; /*!< Number of PFlash blocks. */
+ uint32_t PFlashSectorSize; /*!< Size in bytes of a sector of PFlash. */
+ flash_callback_t PFlashCallback; /*!< Callback function for flash API. */
+ uint32_t PFlashAccessSegmentSize; /*!< Size in bytes of a access segment of PFlash. */
+ uint32_t PFlashAccessSegmentCount; /*!< Number of PFlash access segments. */
+ uint32_t *flashExecuteInRamFunctionInfo; /*!< Info struct of flash execute-in-RAM function. */
+ uint32_t FlexRAMBlockBase; /*!< For FlexNVM device, this is the base address of FlexRAM
+ For non-FlexNVM device, this is the base address of acceleration RAM memory */
+ uint32_t FlexRAMTotalSize; /*!< For FlexNVM device, this is the size of FlexRAM
+ For non-FlexNVM device, this is the size of acceleration RAM memory */
+ uint32_t DFlashBlockBase; /*!< For FlexNVM device, this is the base address of D-Flash memory (FlexNVM memory);
+ For non-FlexNVM device, this field is unused */
+ uint32_t DFlashTotalSize; /*!< For FlexNVM device, this is total size of the FlexNVM memory;
+ For non-FlexNVM device, this field is unused */
+ uint32_t EEpromTotalSize; /*!< For FlexNVM device, this is the size in byte of EEPROM area which was partitioned
+ from FlexRAM;
+ For non-FlexNVM device, this field is unused */
+} flash_config_t;
+
+/*******************************************************************************
+ * API
+ ******************************************************************************/
+
+#if defined(__cplusplus)
+extern "C" {
+#endif
+
+/*!
+ * @name Initialization
+ * @{
+ */
+
+/*!
+ * @brief Initializes global flash properties structure members
+ *
+ * This function checks and initializes Flash module for the other Flash APIs.
+ *
+ * @param config Pointer to storage for the driver runtime state.
+ *
+ * @retval #kStatus_FLASH_Success API was executed successfully.
+ * @retval #kStatus_FLASH_InvalidArgument Invalid argument is provided.
+ * @retval #kStatus_FLASH_ExecuteInRamFunctionNotReady Execute-in-RAM function is not available.
+ * @retval #kStatus_FLASH_PartitionStatusUpdateFailure Failed to update partition status.
+ */
+status_t FLASH_Init(flash_config_t *config);
+
+/*!
+ * @brief Set the desired flash callback function
+ *
+ * @param config Pointer to storage for the driver runtime state.
+ * @param callback callback function to be stored in driver
+ *
+ * @retval #kStatus_FLASH_Success API was executed successfully.
+ * @retval #kStatus_FLASH_InvalidArgument Invalid argument is provided.
+ */
+status_t FLASH_SetCallback(flash_config_t *config, flash_callback_t callback);
+
+/*!
+ * @brief Prepare flash execute-in-RAM functions
+ *
+ * @param config Pointer to storage for the driver runtime state.
+ *
+ * @retval #kStatus_FLASH_Success API was executed successfully.
+ * @retval #kStatus_FLASH_InvalidArgument Invalid argument is provided.
+ */
+#if FLASH_DRIVER_IS_FLASH_RESIDENT
+status_t FLASH_PrepareExecuteInRamFunctions(flash_config_t *config);
+#endif
+
+/*@}*/
+
+/*!
+ * @name Erasing
+ * @{
+ */
+
+/*!
+ * @brief Erases entire flash
+ *
+ * @param config Pointer to storage for the driver runtime state.
+ * @param key value used to validate all flash erase APIs.
+ *
+ * @retval #kStatus_FLASH_Success API was executed successfully.
+ * @retval #kStatus_FLASH_InvalidArgument Invalid argument is provided.
+ * @retval #kStatus_FLASH_EraseKeyError API erase key is invalid.
+ * @retval #kStatus_FLASH_ExecuteInRamFunctionNotReady Execute-in-RAM function is not available.
+ * @retval #kStatus_FLASH_AccessError Invalid instruction codes and out-of bounds addresses.
+ * @retval #kStatus_FLASH_ProtectionViolation The program/erase operation is requested to execute on protected areas.
+ * @retval #kStatus_FLASH_CommandFailure Run-time error during command execution.
+ * @retval #kStatus_FLASH_PartitionStatusUpdateFailure Failed to update partition status
+ */
+status_t FLASH_EraseAll(flash_config_t *config, uint32_t key);
+
+/*!
+ * @brief Erases flash sectors encompassed by parameters passed into function
+ *
+ * This function erases the appropriate number of flash sectors based on the
+ * desired start address and length.
+ *
+ * @param config Pointer to storage for the driver runtime state.
+ * @param start The start address of the desired flash memory to be erased.
+ * The start address does not need to be sector aligned but must be word-aligned.
+ * @param lengthInBytes The length, given in bytes (not words or long-words)
+ * to be erased. Must be word aligned.
+ * @param key value used to validate all flash erase APIs.
+ *
+ * @retval #kStatus_FLASH_Success API was executed successfully.
+ * @retval #kStatus_FLASH_InvalidArgument Invalid argument is provided.
+ * @retval #kStatus_FLASH_AlignmentError Parameter is not aligned with specified baseline.
+ * @retval #kStatus_FLASH_AddressError Address is out of range.
+ * @retval #kStatus_FLASH_EraseKeyError API erase key is invalid.
+ * @retval #kStatus_FLASH_ExecuteInRamFunctionNotReady Execute-in-RAM function is not available.
+ * @retval #kStatus_FLASH_AccessError Invalid instruction codes and out-of bounds addresses.
+ * @retval #kStatus_FLASH_ProtectionViolation The program/erase operation is requested to execute on protected areas.
+ * @retval #kStatus_FLASH_CommandFailure Run-time error during command execution.
+ */
+status_t FLASH_Erase(flash_config_t *config, uint32_t start, uint32_t lengthInBytes, uint32_t key);
+
+/*!
+ * @brief Erases entire flash, including protected sectors.
+ *
+ * @param config Pointer to storage for the driver runtime state.
+ * @param key value used to validate all flash erase APIs.
+ *
+ * @retval #kStatus_FLASH_Success API was executed successfully.
+ * @retval #kStatus_FLASH_InvalidArgument Invalid argument is provided.
+ * @retval #kStatus_FLASH_EraseKeyError API erase key is invalid.
+ * @retval #kStatus_FLASH_ExecuteInRamFunctionNotReady Execute-in-RAM function is not available.
+ * @retval #kStatus_FLASH_AccessError Invalid instruction codes and out-of bounds addresses.
+ * @retval #kStatus_FLASH_ProtectionViolation The program/erase operation is requested to execute on protected areas.
+ * @retval #kStatus_FLASH_CommandFailure Run-time error during command execution.
+ * @retval #kStatus_FLASH_PartitionStatusUpdateFailure Failed to update partition status
+ */
+#if defined(FSL_FEATURE_FLASH_HAS_ERASE_ALL_BLOCKS_UNSECURE_CMD) && FSL_FEATURE_FLASH_HAS_ERASE_ALL_BLOCKS_UNSECURE_CMD
+status_t FLASH_EraseAllUnsecure(flash_config_t *config, uint32_t key);
+#endif
+
+/*!
+ * @brief Erases all program flash execute-only segments defined by the FXACC registers.
+ *
+ * @param config Pointer to storage for the driver runtime state.
+ * @param key value used to validate all flash erase APIs.
+ *
+ * @retval #kStatus_FLASH_Success API was executed successfully.
+ * @retval #kStatus_FLASH_InvalidArgument Invalid argument is provided.
+ * @retval #kStatus_FLASH_EraseKeyError API erase key is invalid.
+ * @retval #kStatus_FLASH_ExecuteInRamFunctionNotReady Execute-in-RAM function is not available.
+ * @retval #kStatus_FLASH_AccessError Invalid instruction codes and out-of bounds addresses.
+ * @retval #kStatus_FLASH_ProtectionViolation The program/erase operation is requested to execute on protected areas.
+ * @retval #kStatus_FLASH_CommandFailure Run-time error during command execution.
+ */
+status_t FLASH_EraseAllExecuteOnlySegments(flash_config_t *config, uint32_t key);
+
+/*@}*/
+
+/*!
+ * @name Programming
+ * @{
+ */
+
+/*!
+ * @brief Programs flash with data at locations passed in through parameters
+ *
+ * This function programs the flash memory with desired data for a given
+ * flash area as determined by the start address and length.
+ *
+ * @param config Pointer to storage for the driver runtime state.
+ * @param start The start address of the desired flash memory to be programmed. Must be
+ * word-aligned.
+ * @param src Pointer to the source buffer of data that is to be programmed
+ * into the flash.
+ * @param lengthInBytes The length, given in bytes (not words or long-words)
+ * to be programmed. Must be word-aligned.
+ *
+ * @retval #kStatus_FLASH_Success API was executed successfully.
+ * @retval #kStatus_FLASH_InvalidArgument Invalid argument is provided.
+ * @retval #kStatus_FLASH_AlignmentError Parameter is not aligned with specified baseline.
+ * @retval #kStatus_FLASH_AddressError Address is out of range.
+ * @retval #kStatus_FLASH_ExecuteInRamFunctionNotReady Execute-in-RAM function is not available.
+ * @retval #kStatus_FLASH_AccessError Invalid instruction codes and out-of bounds addresses.
+ * @retval #kStatus_FLASH_ProtectionViolation The program/erase operation is requested to execute on protected areas.
+ * @retval #kStatus_FLASH_CommandFailure Run-time error during command execution.
+ */
+status_t FLASH_Program(flash_config_t *config, uint32_t start, uint32_t *src, uint32_t lengthInBytes);
+
+/*!
+ * @brief Programs Program Once Field through parameters
+ *
+ * This function programs the Program Once Field with desired data for a given
+ * flash area as determined by the index and length.
+ *
+ * @param config Pointer to storage for the driver runtime state.
+ * @param index The index indicating which area of Program Once Field to be programmed.
+ * @param src Pointer to the source buffer of data that is to be programmed
+ * into the Program Once Field.
+ * @param lengthInBytes The length, given in bytes (not words or long-words)
+ * to be programmed. Must be word-aligned.
+ *
+ * @retval #kStatus_FLASH_Success API was executed successfully.
+ * @retval #kStatus_FLASH_InvalidArgument Invalid argument is provided.
+ * @retval #kStatus_FLASH_ExecuteInRamFunctionNotReady Execute-in-RAM function is not available.
+ * @retval #kStatus_FLASH_AccessError Invalid instruction codes and out-of bounds addresses.
+ * @retval #kStatus_FLASH_ProtectionViolation The program/erase operation is requested to execute on protected areas.
+ * @retval #kStatus_FLASH_CommandFailure Run-time error during command execution.
+ */
+status_t FLASH_ProgramOnce(flash_config_t *config, uint32_t index, uint32_t *src, uint32_t lengthInBytes);
+
+/*!
+ * @brief Programs flash with data at locations passed in through parameters via Program Section command
+ *
+ * This function programs the flash memory with desired data for a given
+ * flash area as determined by the start address and length.
+ *
+ * @param config Pointer to storage for the driver runtime state.
+ * @param start The start address of the desired flash memory to be programmed. Must be
+ * word-aligned.
+ * @param src Pointer to the source buffer of data that is to be programmed
+ * into the flash.
+ * @param lengthInBytes The length, given in bytes (not words or long-words)
+ * to be programmed. Must be word-aligned.
+ *
+ * @retval #kStatus_FLASH_Success API was executed successfully.
+ * @retval #kStatus_FLASH_InvalidArgument Invalid argument is provided.
+ * @retval #kStatus_FLASH_AlignmentError Parameter is not aligned with specified baseline.
+ * @retval #kStatus_FLASH_AddressError Address is out of range.
+ * @retval #kStatus_FLASH_SetFlexramAsRamError Failed to set flexram as RAM
+ * @retval #kStatus_FLASH_ExecuteInRamFunctionNotReady Execute-in-RAM function is not available.
+ * @retval #kStatus_FLASH_AccessError Invalid instruction codes and out-of bounds addresses.
+ * @retval #kStatus_FLASH_ProtectionViolation The program/erase operation is requested to execute on protected areas.
+ * @retval #kStatus_FLASH_CommandFailure Run-time error during command execution.
+ * @retval #kStatus_FLASH_RecoverFlexramAsEepromError Failed to recover flexram as eeprom
+ */
+#if defined(FSL_FEATURE_FLASH_HAS_PROGRAM_SECTION_CMD) && FSL_FEATURE_FLASH_HAS_PROGRAM_SECTION_CMD
+status_t FLASH_ProgramSection(flash_config_t *config, uint32_t start, uint32_t *src, uint32_t lengthInBytes);
+#endif
+
+/*!
+ * @brief Programs EEPROM with data at locations passed in through parameters
+ *
+ * This function programs the Emulated EEPROM with desired data for a given
+ * flash area as determined by the start address and length.
+ *
+ * @param config Pointer to storage for the driver runtime state.
+ * @param start The start address of the desired flash memory to be programmed. Must be
+ * word-aligned.
+ * @param src Pointer to the source buffer of data that is to be programmed
+ * into the flash.
+ * @param lengthInBytes The length, given in bytes (not words or long-words)
+ * to be programmed. Must be word-aligned.
+ *
+ * @retval #kStatus_FLASH_Success API was executed successfully.
+ * @retval #kStatus_FLASH_InvalidArgument Invalid argument is provided.
+ * @retval #kStatus_FLASH_AddressError Address is out of range.
+ * @retval #kStatus_FLASH_SetFlexramAsEepromError Failed to set flexram as eeprom.
+ * @retval #kStatus_FLASH_ProtectionViolation The program/erase operation is requested to execute on protected areas.
+ * @retval #kStatus_FLASH_RecoverFlexramAsRamError Failed to recover flexram as RAM
+ */
+#if FLASH_SSD_IS_FLEXNVM_ENABLED
+status_t FLASH_EepromWrite(flash_config_t *config, uint32_t start, uint8_t *src, uint32_t lengthInBytes);
+#endif
+
+/*@}*/
+
+/*!
+ * @name Reading
+ * @{
+ */
+
+/*!
+ * @brief Read resource with data at locations passed in through parameters
+ *
+ * This function reads the flash memory with desired location for a given
+ * flash area as determined by the start address and length.
+ *
+ * @param config Pointer to storage for the driver runtime state.
+ * @param start The start address of the desired flash memory to be programmed. Must be
+ * word-aligned.
+ * @param dst Pointer to the destination buffer of data that is used to store
+ * data to be read.
+ * @param lengthInBytes The length, given in bytes (not words or long-words)
+ * to be read. Must be word-aligned.
+ * @param option The resource option which indicates which area should be read back.
+ *
+ * @retval #kStatus_FLASH_Success API was executed successfully.
+ * @retval #kStatus_FLASH_InvalidArgument Invalid argument is provided.
+ * @retval #kStatus_FLASH_AlignmentError Parameter is not aligned with specified baseline.
+ * @retval #kStatus_FLASH_ExecuteInRamFunctionNotReady Execute-in-RAM function is not available.
+ * @retval #kStatus_FLASH_AccessError Invalid instruction codes and out-of bounds addresses.
+ * @retval #kStatus_FLASH_ProtectionViolation The program/erase operation is requested to execute on protected areas.
+ * @retval #kStatus_FLASH_CommandFailure Run-time error during command execution.
+ */
+#if defined(FSL_FEATURE_FLASH_HAS_READ_RESOURCE_CMD) && FSL_FEATURE_FLASH_HAS_READ_RESOURCE_CMD
+status_t FLASH_ReadResource(
+ flash_config_t *config, uint32_t start, uint32_t *dst, uint32_t lengthInBytes, flash_read_resource_option_t option);
+#endif
+
+/*!
+ * @brief Read Program Once Field through parameters
+ *
+ * This function reads the read once feild with given index and length
+ *
+ * @param config Pointer to storage for the driver runtime state.
+ * @param index The index indicating the area of program once field to be read.
+ * @param dst Pointer to the destination buffer of data that is used to store
+ * data to be read.
+ * @param lengthInBytes The length, given in bytes (not words or long-words)
+ * to be programmed. Must be word-aligned.
+ *
+ * @retval #kStatus_FLASH_Success API was executed successfully.
+ * @retval #kStatus_FLASH_InvalidArgument Invalid argument is provided.
+ * @retval #kStatus_FLASH_ExecuteInRamFunctionNotReady Execute-in-RAM function is not available.
+ * @retval #kStatus_FLASH_AccessError Invalid instruction codes and out-of bounds addresses.
+ * @retval #kStatus_FLASH_ProtectionViolation The program/erase operation is requested to execute on protected areas.
+ * @retval #kStatus_FLASH_CommandFailure Run-time error during command execution.
+ */
+status_t FLASH_ReadOnce(flash_config_t *config, uint32_t index, uint32_t *dst, uint32_t lengthInBytes);
+
+/*@}*/
+
+/*!
+ * @name Security
+ * @{
+ */
+
+/*!
+ * @brief Returns the security state via the pointer passed into the function
+ *
+ * This function retrieves the current Flash security status, including the
+ * security enabling state and the backdoor key enabling state.
+ *
+ * @param config Pointer to storage for the driver runtime state.
+ * @param state Pointer to the value returned for the current security status code:
+ *
+ * @retval #kStatus_FLASH_Success API was executed successfully.
+ * @retval #kStatus_FLASH_InvalidArgument Invalid argument is provided.
+ */
+status_t FLASH_GetSecurityState(flash_config_t *config, flash_security_state_t *state);
+
+/*!
+ * @brief Allows user to bypass security with a backdoor key
+ *
+ * If the MCU is in secured state, this function will unsecure the MCU by
+ * comparing the provided backdoor key with ones in the Flash Configuration
+ * Field.
+ *
+ * @param config Pointer to storage for the driver runtime state.
+ * @param backdoorKey Pointer to the user buffer containing the backdoor key.
+ *
+ * @retval #kStatus_FLASH_Success API was executed successfully.
+ * @retval #kStatus_FLASH_InvalidArgument Invalid argument is provided.
+ * @retval #kStatus_FLASH_ExecuteInRamFunctionNotReady Execute-in-RAM function is not available.
+ * @retval #kStatus_FLASH_AccessError Invalid instruction codes and out-of bounds addresses.
+ * @retval #kStatus_FLASH_ProtectionViolation The program/erase operation is requested to execute on protected areas.
+ * @retval #kStatus_FLASH_CommandFailure Run-time error during command execution.
+ */
+status_t FLASH_SecurityBypass(flash_config_t *config, const uint8_t *backdoorKey);
+
+/*@}*/
+
+/*!
+ * @name Verification
+ * @{
+ */
+
+/*!
+ * @brief Verifies erasure of entire flash at specified margin level
+ *
+ * This function will check to see if the flash have been erased to the
+ * specified read margin level.
+ *
+ * @param config Pointer to storage for the driver runtime state.
+ * @param margin Read margin choice
+ *
+ * @retval #kStatus_FLASH_Success API was executed successfully.
+ * @retval #kStatus_FLASH_InvalidArgument Invalid argument is provided.
+ * @retval #kStatus_FLASH_ExecuteInRamFunctionNotReady Execute-in-RAM function is not available.
+ * @retval #kStatus_FLASH_AccessError Invalid instruction codes and out-of bounds addresses.
+ * @retval #kStatus_FLASH_ProtectionViolation The program/erase operation is requested to execute on protected areas.
+ * @retval #kStatus_FLASH_CommandFailure Run-time error during command execution.
+ */
+status_t FLASH_VerifyEraseAll(flash_config_t *config, flash_margin_value_t margin);
+
+/*!
+ * @brief Verifies erasure of desired flash area at specified margin level
+ *
+ * This function will check the appropriate number of flash sectors based on
+ * the desired start address and length to see if the flash have been erased
+ * to the specified read margin level.
+ *
+ * @param config Pointer to storage for the driver runtime state.
+ * @param start The start address of the desired flash memory to be verified.
+ * The start address does not need to be sector aligned but must be word-aligned.
+ * @param lengthInBytes The length, given in bytes (not words or long-words)
+ * to be verified. Must be word-aligned.
+ * @param margin Read margin choice
+ *
+ * @retval #kStatus_FLASH_Success API was executed successfully.
+ * @retval #kStatus_FLASH_InvalidArgument Invalid argument is provided.
+ * @retval #kStatus_FLASH_AlignmentError Parameter is not aligned with specified baseline.
+ * @retval #kStatus_FLASH_AddressError Address is out of range.
+ * @retval #kStatus_FLASH_ExecuteInRamFunctionNotReady Execute-in-RAM function is not available.
+ * @retval #kStatus_FLASH_AccessError Invalid instruction codes and out-of bounds addresses.
+ * @retval #kStatus_FLASH_ProtectionViolation The program/erase operation is requested to execute on protected areas.
+ * @retval #kStatus_FLASH_CommandFailure Run-time error during command execution.
+ */
+status_t FLASH_VerifyErase(flash_config_t *config, uint32_t start, uint32_t lengthInBytes, flash_margin_value_t margin);
+
+/*!
+ * @brief Verifies programming of desired flash area at specified margin level
+ *
+ * This function verifies the data programed in the flash memory using the
+ * Flash Program Check Command and compares it with expected data for a given
+ * flash area as determined by the start address and length.
+ *
+ * @param config Pointer to storage for the driver runtime state.
+ * @param start The start address of the desired flash memory to be verified. Must be word-aligned.
+ * @param lengthInBytes The length, given in bytes (not words or long-words)
+ * to be verified. Must be word-aligned.
+ * @param expectedData Pointer to the expected data that is to be
+ * verified against.
+ * @param margin Read margin choice
+ * @param failedAddress Pointer to returned failing address.
+ * @param failedData Pointer to returned failing data. Some derivitives do
+ * not included failed data as part of the FCCOBx registers. In this
+ * case, zeros are returned upon failure.
+ *
+ * @retval #kStatus_FLASH_Success API was executed successfully.
+ * @retval #kStatus_FLASH_InvalidArgument Invalid argument is provided.
+ * @retval #kStatus_FLASH_AlignmentError Parameter is not aligned with specified baseline.
+ * @retval #kStatus_FLASH_AddressError Address is out of range.
+ * @retval #kStatus_FLASH_ExecuteInRamFunctionNotReady Execute-in-RAM function is not available.
+ * @retval #kStatus_FLASH_AccessError Invalid instruction codes and out-of bounds addresses.
+ * @retval #kStatus_FLASH_ProtectionViolation The program/erase operation is requested to execute on protected areas.
+ * @retval #kStatus_FLASH_CommandFailure Run-time error during command execution.
+ */
+status_t FLASH_VerifyProgram(flash_config_t *config,
+ uint32_t start,
+ uint32_t lengthInBytes,
+ const uint32_t *expectedData,
+ flash_margin_value_t margin,
+ uint32_t *failedAddress,
+ uint32_t *failedData);
+
+/*!
+ * @brief Verifies if the program flash executeonly segments have been erased to
+ * the specified read margin level
+ *
+ * @param config Pointer to storage for the driver runtime state.
+ * @param margin Read margin choice
+ *
+ * @retval #kStatus_FLASH_Success API was executed successfully.
+ * @retval #kStatus_FLASH_InvalidArgument Invalid argument is provided.
+ * @retval #kStatus_FLASH_ExecuteInRamFunctionNotReady Execute-in-RAM function is not available.
+ * @retval #kStatus_FLASH_AccessError Invalid instruction codes and out-of bounds addresses.
+ * @retval #kStatus_FLASH_ProtectionViolation The program/erase operation is requested to execute on protected areas.
+ * @retval #kStatus_FLASH_CommandFailure Run-time error during command execution.
+ */
+status_t FLASH_VerifyEraseAllExecuteOnlySegments(flash_config_t *config, flash_margin_value_t margin);
+
+/*@}*/
+
+/*!
+ * @name Protection
+ * @{
+ */
+
+/*!
+ * @brief Returns the protection state of desired flash area via the pointer passed into the function
+ *
+ * This function retrieves the current Flash protect status for a given
+ * flash area as determined by the start address and length.
+ *
+ * @param config Pointer to storage for the driver runtime state.
+ * @param start The start address of the desired flash memory to be checked. Must be word-aligned.
+ * @param lengthInBytes The length, given in bytes (not words or long-words)
+ * to be checked. Must be word-aligned.
+ * @param protection_state Pointer to the value returned for the current
+ * protection status code for the desired flash area.
+ *
+ * @retval #kStatus_FLASH_Success API was executed successfully.
+ * @retval #kStatus_FLASH_InvalidArgument Invalid argument is provided.
+ * @retval #kStatus_FLASH_AlignmentError Parameter is not aligned with specified baseline.
+ * @retval #kStatus_FLASH_AddressError Address is out of range.
+ */
+status_t FLASH_IsProtected(flash_config_t *config,
+ uint32_t start,
+ uint32_t lengthInBytes,
+ flash_protection_state_t *protection_state);
+
+/*!
+ * @brief Returns the access state of desired flash area via the pointer passed into the function
+ *
+ * This function retrieves the current Flash access status for a given
+ * flash area as determined by the start address and length.
+ *
+ * @param config Pointer to storage for the driver runtime state.
+ * @param start The start address of the desired flash memory to be checked. Must be word-aligned.
+ * @param lengthInBytes The length, given in bytes (not words or long-words)
+ * to be checked. Must be word-aligned.
+ * @param access_state Pointer to the value returned for the current
+ * access status code for the desired flash area.
+ *
+ * @retval #kStatus_FLASH_Success API was executed successfully.
+ * @retval #kStatus_FLASH_InvalidArgument Invalid argument is provided.
+ * @retval #kStatus_FLASH_AlignmentError Parameter is not aligned with specified baseline.
+ * @retval #kStatus_FLASH_AddressError Address is out of range.
+ */
+status_t FLASH_IsExecuteOnly(flash_config_t *config,
+ uint32_t start,
+ uint32_t lengthInBytes,
+ flash_execute_only_access_state_t *access_state);
+
+/*@}*/
+
+/*!
+ * @name Properties
+ * @{
+ */
+
+/*!
+ * @brief Returns the desired flash property.
+ *
+ * @param config Pointer to storage for the driver runtime state.
+ * @param whichProperty The desired property from the list of properties in
+ * enum flash_property_tag_t
+ * @param value Pointer to the value returned for the desired flash property
+ *
+ * @retval #kStatus_FLASH_Success API was executed successfully.
+ * @retval #kStatus_FLASH_InvalidArgument Invalid argument is provided.
+ * @retval #kStatus_FLASH_UnknownProperty unknown property tag
+ */
+status_t FLASH_GetProperty(flash_config_t *config, flash_property_tag_t whichProperty, uint32_t *value);
+
+/*@}*/
+
+/*!
+ * @name FlexRAM
+ * @{
+ */
+
+/*!
+ * @brief Set FlexRAM Function command
+ *
+ * @param config Pointer to storage for the driver runtime state.
+ * @param option The option used to set work mode of FlexRAM
+ *
+ * @retval #kStatus_FLASH_Success API was executed successfully.
+ * @retval #kStatus_FLASH_InvalidArgument Invalid argument is provided.
+ * @retval #kStatus_FLASH_ExecuteInRamFunctionNotReady Execute-in-RAM function is not available.
+ * @retval #kStatus_FLASH_AccessError Invalid instruction codes and out-of bounds addresses.
+ * @retval #kStatus_FLASH_ProtectionViolation The program/erase operation is requested to execute on protected areas.
+ * @retval #kStatus_FLASH_CommandFailure Run-time error during command execution.
+ */
+#if defined(FSL_FEATURE_FLASH_HAS_SET_FLEXRAM_FUNCTION_CMD) && FSL_FEATURE_FLASH_HAS_SET_FLEXRAM_FUNCTION_CMD
+status_t FLASH_SetFlexramFunction(flash_config_t *config, flash_flexram_function_option_t option);
+#endif
+
+/*@}*/
+
+/*!
+ * @name Swap
+ * @{
+ */
+
+/*!
+ * @brief Configure Swap function or Check the swap state of Flash Module
+ *
+ * @param config Pointer to storage for the driver runtime state.
+ * @param address Address used to configure the flash swap function
+ * @param option The possible option used to configure Flash Swap function or check the flash swap status
+ * @param returnInfo Pointer to the data which is used to return the information of flash swap.
+ *
+ * @retval #kStatus_FLASH_Success API was executed successfully.
+ * @retval #kStatus_FLASH_InvalidArgument Invalid argument is provided.
+ * @retval #kStatus_FLASH_AlignmentError Parameter is not aligned with specified baseline.
+ * @retval #kStatus_FLASH_SwapIndicatorAddressError Swap indicator address is invalid
+ * @retval #kStatus_FLASH_ExecuteInRamFunctionNotReady Execute-in-RAM function is not available.
+ * @retval #kStatus_FLASH_AccessError Invalid instruction codes and out-of bounds addresses.
+ * @retval #kStatus_FLASH_ProtectionViolation The program/erase operation is requested to execute on protected areas.
+ * @retval #kStatus_FLASH_CommandFailure Run-time error during command execution.
+ */
+#if defined(FSL_FEATURE_FLASH_HAS_SWAP_CONTROL_CMD) && FSL_FEATURE_FLASH_HAS_SWAP_CONTROL_CMD
+status_t FLASH_SwapControl(flash_config_t *config,
+ uint32_t address,
+ flash_swap_control_option_t option,
+ flash_swap_state_config_t *returnInfo);
+#endif
+
+/*!
+ * @brief Swap the lower half flash with the higher half flaock
+ *
+ * @param config Pointer to storage for the driver runtime state.
+ * @param address Address used to configure the flash swap function
+ * @param option The possible option used to configure Flash Swap function or check the flash swap status
+ *
+ * @retval #kStatus_FLASH_Success API was executed successfully.
+ * @retval #kStatus_FLASH_InvalidArgument Invalid argument is provided.
+ * @retval #kStatus_FLASH_AlignmentError Parameter is not aligned with specified baseline.
+ * @retval #kStatus_FLASH_SwapIndicatorAddressError Swap indicator address is invalid
+ * @retval #kStatus_FLASH_ExecuteInRamFunctionNotReady Execute-in-RAM function is not available.
+ * @retval #kStatus_FLASH_AccessError Invalid instruction codes and out-of bounds addresses.
+ * @retval #kStatus_FLASH_ProtectionViolation The program/erase operation is requested to execute on protected areas.
+ * @retval #kStatus_FLASH_CommandFailure Run-time error during command execution.
+ * @retval #kStatus_FLASH_SwapSystemNotInUninitialized Swap system is not in uninitialzed state
+ */
+#if defined(FSL_FEATURE_FLASH_HAS_PFLASH_BLOCK_SWAP) && FSL_FEATURE_FLASH_HAS_PFLASH_BLOCK_SWAP
+status_t FLASH_Swap(flash_config_t *config, uint32_t address, flash_swap_function_option_t option);
+#endif
+
+/*!
+ * @name FlexNVM
+ * @{
+ */
+
+/*!
+ * @brief Prepares the FlexNVM block for use as data flash, EEPROM backup, or a combination of both and initializes the
+ * FlexRAM.
+ *
+ * @param config Pointer to storage for the driver runtime state.
+ * @param option The option used to set FlexRAM load behavior during reset.
+ * @param eepromDataSizeCode Determines the amount of FlexRAM used in each of the available EEPROM subsystems.
+ * @param flexnvmPartitionCode Specifies how to split the FlexNVM block between data flash memory and EEPROM backup
+ * memory supporting EEPROM functions.
+ *
+ * @retval #kStatus_FLASH_Success API was executed successfully.
+ * @retval #kStatus_FLASH_InvalidArgument Invalid argument is provided.
+ * @retval #kStatus_FLASH_ExecuteInRamFunctionNotReady Execute-in-RAM function is not available.
+ * @retval #kStatus_FLASH_AccessError Invalid instruction codes and out-of bounds addresses.
+ * @retval #kStatus_FLASH_ProtectionViolation The program/erase operation is requested to execute on protected areas.
+ * @retval #kStatus_FLASH_CommandFailure Run-time error during command execution.
+ */
+#if defined(FSL_FEATURE_FLASH_HAS_PROGRAM_PARTITION_CMD) && FSL_FEATURE_FLASH_HAS_PROGRAM_PARTITION_CMD
+status_t FLASH_ProgramPartition(flash_config_t *config,
+ flash_partition_flexram_load_option_t option,
+ uint32_t eepromDataSizeCode,
+ uint32_t flexnvmPartitionCode);
+#endif
+
+/*@}*/
+
+/*!
+* @name Flash Protection Utilities
+* @{
+*/
+
+/*!
+ * @brief Set PFLASH Protection to the intended protection status.
+ *
+ * @param config Pointer to storage for the driver runtime state.
+ * @param protectStatus The expected protect status user wants to set to PFlash protection register. Each bit is
+ * corresponding to protection of 1/32 of the total PFlash. The least significant bit is corresponding to the lowest
+ * address area of P-Flash. The most significant bit is corresponding to the highest address area of PFlash. There are
+ * two possible cases as shown below:
+ * 0: this area is protected.
+ * 1: this area is unprotected.
+ *
+ * @retval #kStatus_FLASH_Success API was executed successfully.
+ * @retval #kStatus_FLASH_InvalidArgument Invalid argument is provided.
+ * @retval #kStatus_FLASH_CommandFailure Run-time error during command execution.
+ */
+status_t FLASH_PflashSetProtection(flash_config_t *config, uint32_t protectStatus);
+
+/*!
+ * @brief Get PFLASH Protection Status.
+ *
+ * @param config Pointer to storage for the driver runtime state.
+ * @param protectStatus Protect status returned by PFlash IP. Each bit is corresponding to protection of 1/32 of the
+ * total PFlash. The least significant bit is corresponding to the lowest address area of PFlash. The most significant
+ * bit is corresponding to the highest address area of PFlash. Thee are two possible cases as below:
+ * 0: this area is protected.
+ * 1: this area is unprotected.
+ *
+ * @retval #kStatus_FLASH_Success API was executed successfully.
+ * @retval #kStatus_FLASH_InvalidArgument Invalid argument is provided.
+ */
+status_t FLASH_PflashGetProtection(flash_config_t *config, uint32_t *protectStatus);
+
+/*!
+ * @brief Set DFLASH Protection to the intended protection status.
+ *
+ * @param config Pointer to storage for the driver runtime state.
+ * @param protectStatus The expected protect status user wants to set to DFlash protection register. Each bit is
+ * corresponding to protection of 1/8 of the total DFlash. The least significant bit is corresponding to the lowest
+ * address area of DFlash. The most significant bit is corresponding to the highest address area of DFlash. There are
+ * two possible cases as shown below:
+ * 0: this area is protected.
+ * 1: this area is unprotected.
+ *
+ * @retval #kStatus_FLASH_Success API was executed successfully.
+ * @retval #kStatus_FLASH_InvalidArgument Invalid argument is provided.
+ * @retval #kStatus_FLASH_CommandNotSupported Flash API is not supported
+ * @retval #kStatus_FLASH_CommandFailure Run-time error during command execution.
+ */
+#if FLASH_SSD_IS_FLEXNVM_ENABLED
+status_t FLASH_DflashSetProtection(flash_config_t *config, uint8_t protectStatus);
+#endif
+
+/*!
+ * @brief Get DFLASH Protection Status.
+ *
+ * @param config Pointer to storage for the driver runtime state.
+ * @param protectStatus DFlash Protect status returned by PFlash IP. Each bit is corresponding to protection of 1/8 of
+ * the total DFlash. The least significant bit is corresponding to the lowest address area of DFlash. The most
+ * significant bit is corresponding to the highest address area of DFlash and so on. There are two possible cases as
+ * below:
+ * 0: this area is protected.
+ * 1: this area is unprotected.
+ *
+ * @retval #kStatus_FLASH_Success API was executed successfully.
+ * @retval #kStatus_FLASH_InvalidArgument Invalid argument is provided.
+ * @retval #kStatus_FLASH_CommandNotSupported Flash API is not supported
+ */
+#if FLASH_SSD_IS_FLEXNVM_ENABLED
+status_t FLASH_DflashGetProtection(flash_config_t *config, uint8_t *protectStatus);
+#endif
+
+/*!
+ * @brief Set EEPROM Protection to the intended protection status.
+ *
+ * @param config Pointer to storage for the driver runtime state.
+ * @param protectStatus The expected protect status user wants to set to EEPROM protection register. Each bit is
+ * corresponding to protection of 1/8 of the total EEPROM. The least significant bit is corresponding to the lowest
+ * address area of EEPROM. The most significant bit is corresponding to the highest address area of EEPROM, and so on.
+ * There are two possible cases as shown below:
+ * 0: this area is protected.
+ * 1: this area is unprotected.
+ *
+ * @retval #kStatus_FLASH_Success API was executed successfully.
+ * @retval #kStatus_FLASH_InvalidArgument Invalid argument is provided.
+ * @retval #kStatus_FLASH_CommandNotSupported Flash API is not supported
+ * @retval #kStatus_FLASH_CommandFailure Run-time error during command execution.
+ */
+#if FLASH_SSD_IS_FLEXNVM_ENABLED
+status_t FLASH_EepromSetProtection(flash_config_t *config, uint8_t protectStatus);
+#endif
+
+/*!
+ * @brief Get DFLASH Protection Status.
+ *
+ * @param config Pointer to storage for the driver runtime state.
+ * @param protectStatus DFlash Protect status returned by PFlash IP. Each bit is corresponding to protection of 1/8 of
+ * the total EEPROM. The least significant bit is corresponding to the lowest address area of EEPROM. The most
+ * significant bit is corresponding to the highest address area of EEPROM. There are two possible cases as below:
+ * 0: this area is protected.
+ * 1: this area is unprotected.
+ *
+ * @retval #kStatus_FLASH_Success API was executed successfully.
+ * @retval #kStatus_FLASH_InvalidArgument Invalid argument is provided.
+ * @retval #kStatus_FLASH_CommandNotSupported Flash API is not supported.
+ */
+#if FLASH_SSD_IS_FLEXNVM_ENABLED
+status_t FLASH_EepromGetProtection(flash_config_t *config, uint8_t *protectStatus);
+#endif
+
+/*@}*/
+
+#if defined(__cplusplus)
+}
+#endif
+
+/*! @}*/
+
+#endif /* _FSL_FLASH_H_ */
diff --git a/drivers/fsl_flexbus.c b/drivers/fsl_flexbus.c
new file mode 100644
index 0000000..4e29285
--- /dev/null
+++ b/drivers/fsl_flexbus.c
@@ -0,0 +1,196 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_flexbus.h"
+
+/*******************************************************************************
+ * Prototypes
+ ******************************************************************************/
+
+/*!
+ * @brief Gets the instance from the base address
+ *
+ * @param base FLEXBUS peripheral base address
+ *
+ * @return The FLEXBUS instance
+ */
+static uint32_t FLEXBUS_GetInstance(FB_Type *base);
+
+/*******************************************************************************
+ * Variables
+ ******************************************************************************/
+
+/*! @brief Pointers to FLEXBUS bases for each instance. */
+static FB_Type *const s_flexbusBases[] = FB_BASE_PTRS;
+
+/*! @brief Pointers to FLEXBUS clocks for each instance. */
+static const clock_ip_name_t s_flexbusClocks[] = FLEXBUS_CLOCKS;
+
+/*******************************************************************************
+ * Code
+ ******************************************************************************/
+
+static uint32_t FLEXBUS_GetInstance(FB_Type *base)
+{
+ uint32_t instance;
+
+ /* Find the instance index from base address mappings. */
+ for (instance = 0; instance < FSL_FEATURE_SOC_FB_COUNT; instance++)
+ {
+ if (s_flexbusBases[instance] == base)
+ {
+ break;
+ }
+ }
+
+ assert(instance < FSL_FEATURE_SOC_FB_COUNT);
+
+ return instance;
+}
+
+void FLEXBUS_Init(FB_Type *base, const flexbus_config_t *config)
+{
+ assert(config != NULL);
+ assert(config->chip < FB_CSAR_COUNT);
+ assert(config->waitStates <= 0x3FU);
+
+ uint32_t chip = 0;
+ uint32_t reg_value = 0;
+
+ /* Ungate clock for FLEXBUS */
+ CLOCK_EnableClock(s_flexbusClocks[FLEXBUS_GetInstance(base)]);
+
+ /* Reset all the register to default state */
+ for (chip = 0; chip < FB_CSAR_COUNT; chip++)
+ {
+ /* Reset CSMR register, all chips not valid (disabled) */
+ base->CS[chip].CSMR = 0x0000U;
+ /* Set default base address */
+ base->CS[chip].CSAR &= (~FB_CSAR_BA_MASK);
+ /* Reset FB_CSCRx register */
+ base->CS[chip].CSCR = 0x0000U;
+ }
+ /* Set FB_CSPMCR register */
+ /* FlexBus signal group 1 multiplex control */
+ reg_value |= kFLEXBUS_MultiplexGroup1_FB_ALE << FB_CSPMCR_GROUP1_SHIFT;
+ /* FlexBus signal group 2 multiplex control */
+ reg_value |= kFLEXBUS_MultiplexGroup2_FB_CS4 << FB_CSPMCR_GROUP2_SHIFT;
+ /* FlexBus signal group 3 multiplex control */
+ reg_value |= kFLEXBUS_MultiplexGroup3_FB_CS5 << FB_CSPMCR_GROUP3_SHIFT;
+ /* FlexBus signal group 4 multiplex control */
+ reg_value |= kFLEXBUS_MultiplexGroup4_FB_TBST << FB_CSPMCR_GROUP4_SHIFT;
+ /* FlexBus signal group 5 multiplex control */
+ reg_value |= kFLEXBUS_MultiplexGroup5_FB_TA << FB_CSPMCR_GROUP5_SHIFT;
+ /* Write to CSPMCR register */
+ base->CSPMCR = reg_value;
+
+ /* Update chip value */
+ chip = config->chip;
+
+ /* Base address */
+ reg_value = config->chipBaseAddress;
+ /* Write to CSAR register */
+ base->CS[chip].CSAR = reg_value;
+ /* Chip-select validation */
+ reg_value = 0x1U << FB_CSMR_V_SHIFT;
+ /* Write protect */
+ reg_value |= (uint32_t)(config->writeProtect) << FB_CSMR_WP_SHIFT;
+ /* Base address mask */
+ reg_value |= config->chipBaseAddressMask << FB_CSMR_BAM_SHIFT;
+ /* Write to CSMR register */
+ base->CS[chip].CSMR = reg_value;
+ /* Burst write */
+ reg_value = (uint32_t)(config->burstWrite) << FB_CSCR_BSTW_SHIFT;
+ /* Burst read */
+ reg_value |= (uint32_t)(config->burstRead) << FB_CSCR_BSTR_SHIFT;
+ /* Byte-enable mode */
+ reg_value |= (uint32_t)(config->byteEnableMode) << FB_CSCR_BEM_SHIFT;
+ /* Port size */
+ reg_value |= (uint32_t)config->portSize << FB_CSCR_PS_SHIFT;
+ /* The internal transfer acknowledge for accesses */
+ reg_value |= (uint32_t)(config->autoAcknowledge) << FB_CSCR_AA_SHIFT;
+ /* Byte-Lane shift */
+ reg_value |= (uint32_t)config->byteLaneShift << FB_CSCR_BLS_SHIFT;
+ /* The number of wait states */
+ reg_value |= (uint32_t)config->waitStates << FB_CSCR_WS_SHIFT;
+ /* Write address hold or deselect */
+ reg_value |= (uint32_t)config->writeAddressHold << FB_CSCR_WRAH_SHIFT;
+ /* Read address hold or deselect */
+ reg_value |= (uint32_t)config->readAddressHold << FB_CSCR_RDAH_SHIFT;
+ /* Address setup */
+ reg_value |= (uint32_t)config->addressSetup << FB_CSCR_ASET_SHIFT;
+ /* Extended transfer start/extended address latch */
+ reg_value |= (uint32_t)(config->extendTransferAddress) << FB_CSCR_EXTS_SHIFT;
+ /* Secondary wait state */
+ reg_value |= (uint32_t)(config->secondaryWaitStates) << FB_CSCR_SWSEN_SHIFT;
+ /* Write to CSCR register */
+ base->CS[chip].CSCR = reg_value;
+ /* FlexBus signal group 1 multiplex control */
+ reg_value = (uint32_t)config->group1MultiplexControl << FB_CSPMCR_GROUP1_SHIFT;
+ /* FlexBus signal group 2 multiplex control */
+ reg_value |= (uint32_t)config->group2MultiplexControl << FB_CSPMCR_GROUP2_SHIFT;
+ /* FlexBus signal group 3 multiplex control */
+ reg_value |= (uint32_t)config->group3MultiplexControl << FB_CSPMCR_GROUP3_SHIFT;
+ /* FlexBus signal group 4 multiplex control */
+ reg_value |= (uint32_t)config->group4MultiplexControl << FB_CSPMCR_GROUP4_SHIFT;
+ /* FlexBus signal group 5 multiplex control */
+ reg_value |= (uint32_t)config->group5MultiplexControl << FB_CSPMCR_GROUP5_SHIFT;
+ /* Write to CSPMCR register */
+ base->CSPMCR = reg_value;
+}
+
+void FLEXBUS_Deinit(FB_Type *base)
+{
+ /* Gate clock for FLEXBUS */
+ CLOCK_DisableClock(s_flexbusClocks[FLEXBUS_GetInstance(base)]);
+}
+
+void FLEXBUS_GetDefaultConfig(flexbus_config_t *config)
+{
+ config->chip = 0; /* Chip 0 FlexBus for validation */
+ config->writeProtect = 0; /* Write accesses are allowed */
+ config->burstWrite = 0; /* Burst-Write disable */
+ config->burstRead = 0; /* Burst-Read disable */
+ config->byteEnableMode = 0; /* Byte-Enable mode is asserted for data write only */
+ config->autoAcknowledge = true; /* Auto-Acknowledge enable */
+ config->extendTransferAddress = 0; /* Extend transfer start/extend address latch disable */
+ config->secondaryWaitStates = 0; /* Secondary wait state disable */
+ config->byteLaneShift = kFLEXBUS_NotShifted; /* Byte-Lane shift disable */
+ config->writeAddressHold = kFLEXBUS_Hold1Cycle; /* Write address hold 1 cycles */
+ config->readAddressHold = kFLEXBUS_Hold1Or0Cycles; /* Read address hold 0 cycles */
+ config->addressSetup =
+ kFLEXBUS_FirstRisingEdge; /* Assert ~FB_CSn on the first rising clock edge after the address is asserted */
+ config->portSize = kFLEXBUS_1Byte; /* 1 byte port size of transfer */
+ config->group1MultiplexControl = kFLEXBUS_MultiplexGroup1_FB_ALE; /* FB_ALE */
+ config->group2MultiplexControl = kFLEXBUS_MultiplexGroup2_FB_CS4; /* FB_CS4 */
+ config->group3MultiplexControl = kFLEXBUS_MultiplexGroup3_FB_CS5; /* FB_CS5 */
+ config->group4MultiplexControl = kFLEXBUS_MultiplexGroup4_FB_TBST; /* FB_TBST */
+ config->group5MultiplexControl = kFLEXBUS_MultiplexGroup5_FB_TA; /* FB_TA */
+}
diff --git a/drivers/fsl_flexbus.h b/drivers/fsl_flexbus.h
new file mode 100644
index 0000000..0f2886d
--- /dev/null
+++ b/drivers/fsl_flexbus.h
@@ -0,0 +1,265 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_FLEXBUS_H_
+#define _FSL_FLEXBUS_H_
+
+#include "fsl_common.h"
+
+/*!
+ * @addtogroup flexbus
+ * @{
+ */
+
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+/*! @name Driver version */
+/*@{*/
+#define FSL_FLEXBUS_DRIVER_VERSION (MAKE_VERSION(2, 0, 0)) /*!< Version 2.0.0. */
+/*@}*/
+
+/*!
+ * @brief Defines port size for FlexBus peripheral.
+ */
+typedef enum _flexbus_port_size
+{
+ kFLEXBUS_4Bytes = 0x00U, /*!< 32-bit port size */
+ kFLEXBUS_1Byte = 0x01U, /*!< 8-bit port size */
+ kFLEXBUS_2Bytes = 0x02U /*!< 16-bit port size */
+} flexbus_port_size_t;
+
+/*!
+ * @brief Defines number of cycles to hold address and attributes for FlexBus peripheral.
+ */
+typedef enum _flexbus_write_address_hold
+{
+ kFLEXBUS_Hold1Cycle = 0x00U, /*!< Hold address and attributes one cycles after FB_CSn negates on writes */
+ kFLEXBUS_Hold2Cycles = 0x01U, /*!< Hold address and attributes two cycles after FB_CSn negates on writes */
+ kFLEXBUS_Hold3Cycles = 0x02U, /*!< Hold address and attributes three cycles after FB_CSn negates on writes */
+ kFLEXBUS_Hold4Cycles = 0x03U /*!< Hold address and attributes four cycles after FB_CSn negates on writes */
+} flexbus_write_address_hold_t;
+
+/*!
+ * @brief Defines number of cycles to hold address and attributes for FlexBus peripheral.
+ */
+typedef enum _flexbus_read_address_hold
+{
+ kFLEXBUS_Hold1Or0Cycles = 0x00U, /*!< Hold address and attributes 1 or 0 cycles on reads */
+ kFLEXBUS_Hold2Or1Cycles = 0x01U, /*!< Hold address and attributes 2 or 1 cycles on reads */
+ kFLEXBUS_Hold3Or2Cycle = 0x02U, /*!< Hold address and attributes 3 or 2 cycles on reads */
+ kFLEXBUS_Hold4Or3Cycle = 0x03U /*!< Hold address and attributes 4 or 3 cycles on reads */
+} flexbus_read_address_hold_t;
+
+/*!
+ * @brief Address setup for FlexBus peripheral.
+ */
+typedef enum _flexbus_address_setup
+{
+ kFLEXBUS_FirstRisingEdge = 0x00U, /*!< Assert FB_CSn on first rising clock edge after address is asserted */
+ kFLEXBUS_SecondRisingEdge = 0x01U, /*!< Assert FB_CSn on second rising clock edge after address is asserted */
+ kFLEXBUS_ThirdRisingEdge = 0x02U, /*!< Assert FB_CSn on third rising clock edge after address is asserted */
+ kFLEXBUS_FourthRisingEdge = 0x03U, /*!< Assert FB_CSn on fourth rising clock edge after address is asserted */
+} flexbus_address_setup_t;
+
+/*!
+ * @brief Defines byte-lane shift for FlexBus peripheral.
+ */
+typedef enum _flexbus_bytelane_shift
+{
+ kFLEXBUS_NotShifted = 0x00U, /*!< Not shifted. Data is left-justified on FB_AD */
+ kFLEXBUS_Shifted = 0x01U, /*!< Shifted. Data is right justified on FB_AD */
+} flexbus_bytelane_shift_t;
+
+/*!
+ * @brief Defines multiplex group1 valid signals.
+ */
+typedef enum _flexbus_multiplex_group1_signal
+{
+ kFLEXBUS_MultiplexGroup1_FB_ALE = 0x00U, /*!< FB_ALE */
+ kFLEXBUS_MultiplexGroup1_FB_CS1 = 0x01U, /*!< FB_CS1 */
+ kFLEXBUS_MultiplexGroup1_FB_TS = 0x02U, /*!< FB_TS */
+} flexbus_multiplex_group1_t;
+
+/*!
+ * @brief Defines multiplex group2 valid signals.
+ */
+typedef enum _flexbus_multiplex_group2_signal
+{
+ kFLEXBUS_MultiplexGroup2_FB_CS4 = 0x00U, /*!< FB_CS4 */
+ kFLEXBUS_MultiplexGroup2_FB_TSIZ0 = 0x01U, /*!< FB_TSIZ0 */
+ kFLEXBUS_MultiplexGroup2_FB_BE_31_24 = 0x02U, /*!< FB_BE_31_24 */
+} flexbus_multiplex_group2_t;
+
+/*!
+ * @brief Defines multiplex group3 valid signals.
+ */
+typedef enum _flexbus_multiplex_group3_signal
+{
+ kFLEXBUS_MultiplexGroup3_FB_CS5 = 0x00U, /*!< FB_CS5 */
+ kFLEXBUS_MultiplexGroup3_FB_TSIZ1 = 0x01U, /*!< FB_TSIZ1 */
+ kFLEXBUS_MultiplexGroup3_FB_BE_23_16 = 0x02U, /*!< FB_BE_23_16 */
+} flexbus_multiplex_group3_t;
+
+/*!
+ * @brief Defines multiplex group4 valid signals.
+ */
+typedef enum _flexbus_multiplex_group4_signal
+{
+ kFLEXBUS_MultiplexGroup4_FB_TBST = 0x00U, /*!< FB_TBST */
+ kFLEXBUS_MultiplexGroup4_FB_CS2 = 0x01U, /*!< FB_CS2 */
+ kFLEXBUS_MultiplexGroup4_FB_BE_15_8 = 0x02U, /*!< FB_BE_15_8 */
+} flexbus_multiplex_group4_t;
+
+/*!
+ * @brief Defines multiplex group5 valid signals.
+ */
+typedef enum _flexbus_multiplex_group5_signal
+{
+ kFLEXBUS_MultiplexGroup5_FB_TA = 0x00U, /*!< FB_TA */
+ kFLEXBUS_MultiplexGroup5_FB_CS3 = 0x01U, /*!< FB_CS3 */
+ kFLEXBUS_MultiplexGroup5_FB_BE_7_0 = 0x02U, /*!< FB_BE_7_0 */
+} flexbus_multiplex_group5_t;
+
+/*!
+ * @brief Configuration structure that the user needs to set.
+ */
+typedef struct _flexbus_config
+{
+ uint8_t chip; /*!< Chip FlexBus for validation */
+ uint8_t waitStates; /*!< Value of wait states */
+ uint32_t chipBaseAddress; /*!< Chip base address for using FlexBus */
+ uint32_t chipBaseAddressMask; /*!< Chip base address mask */
+ bool writeProtect; /*!< Write protected */
+ bool burstWrite; /*!< Burst-Write enable */
+ bool burstRead; /*!< Burst-Read enable */
+ bool byteEnableMode; /*!< Byte-enable mode support */
+ bool autoAcknowledge; /*!< Auto acknowledge setting */
+ bool extendTransferAddress; /*!< Extend transfer start/extend address latch enable */
+ bool secondaryWaitStates; /*!< Secondary wait states number */
+ flexbus_port_size_t portSize; /*!< Port size of transfer */
+ flexbus_bytelane_shift_t byteLaneShift; /*!< Byte-lane shift enable */
+ flexbus_write_address_hold_t writeAddressHold; /*!< Write address hold or deselect option */
+ flexbus_read_address_hold_t readAddressHold; /*!< Read address hold or deselect option */
+ flexbus_address_setup_t addressSetup; /*!< Address setup setting */
+ flexbus_multiplex_group1_t group1MultiplexControl; /*!< FlexBus Signal Group 1 Multiplex control */
+ flexbus_multiplex_group2_t group2MultiplexControl; /*!< FlexBus Signal Group 2 Multiplex control */
+ flexbus_multiplex_group3_t group3MultiplexControl; /*!< FlexBus Signal Group 3 Multiplex control */
+ flexbus_multiplex_group4_t group4MultiplexControl; /*!< FlexBus Signal Group 4 Multiplex control */
+ flexbus_multiplex_group5_t group5MultiplexControl; /*!< FlexBus Signal Group 5 Multiplex control */
+} flexbus_config_t;
+
+/*******************************************************************************
+ * API
+ ******************************************************************************/
+
+#if defined(__cplusplus)
+extern "C" {
+#endif /* __cplusplus */
+
+/*!
+ * @name FlexBus functional operation
+ * @{
+ */
+
+/*!
+ * @brief Initializes and configures the FlexBus module.
+ *
+ * This function enables the clock gate for FlexBus module.
+ * Only chip 0 is validated and set to known values. Other chips are disabled.
+ * NOTE: In this function, certain parameters, depending on external memories, must
+ * be set before using FLEXBUS_Init() function.
+ * This example shows how to set up the uart_state_t and the
+ * flexbus_config_t parameters and how to call the FLEXBUS_Init function by passing
+ * in these parameters:
+ @code
+ flexbus_config_t flexbusConfig;
+ FLEXBUS_GetDefaultConfig(&flexbusConfig);
+ flexbusConfig.waitStates = 2U;
+ flexbusConfig.chipBaseAddress = 0x60000000U;
+ flexbusConfig.chipBaseAddressMask = 7U;
+ FLEXBUS_Init(FB, &flexbusConfig);
+ @endcode
+ *
+ * @param base FlexBus peripheral address.
+ * @param config Pointer to the configure structure
+*/
+void FLEXBUS_Init(FB_Type *base, const flexbus_config_t *config);
+
+/*!
+ * @brief De-initializes a FlexBus instance.
+ *
+ * This function disables the clock gate of the FlexBus module clock.
+ *
+ * @param base FlexBus peripheral address.
+ */
+void FLEXBUS_Deinit(FB_Type *base);
+
+/*!
+ * @brief Initializes the FlexBus configuration structure.
+ *
+ * This function initializes the FlexBus configuration structure to default value. The default
+ * values are:
+ @code
+ fbConfig->chip = 0;
+ fbConfig->writeProtect = 0;
+ fbConfig->burstWrite = 0;
+ fbConfig->burstRead = 0;
+ fbConfig->byteEnableMode = 0;
+ fbConfig->autoAcknowledge = true;
+ fbConfig->extendTransferAddress = 0;
+ fbConfig->secondaryWaitStates = 0;
+ fbConfig->byteLaneShift = kFLEXBUS_NotShifted;
+ fbConfig->writeAddressHold = kFLEXBUS_Hold1Cycle;
+ fbConfig->readAddressHold = kFLEXBUS_Hold1Or0Cycles;
+ fbConfig->addressSetup = kFLEXBUS_FirstRisingEdge;
+ fbConfig->portSize = kFLEXBUS_1Byte;
+ fbConfig->group1MultiplexControl = kFLEXBUS_MultiplexGroup1_FB_ALE;
+ fbConfig->group2MultiplexControl = kFLEXBUS_MultiplexGroup2_FB_CS4 ;
+ fbConfig->group3MultiplexControl = kFLEXBUS_MultiplexGroup3_FB_CS5;
+ fbConfig->group4MultiplexControl = kFLEXBUS_MultiplexGroup4_FB_TBST;
+ fbConfig->group5MultiplexControl = kFLEXBUS_MultiplexGroup5_FB_TA;
+ @endcode
+ * @param config Pointer to the initialization structure.
+ * @see FLEXBUS_Init
+ */
+void FLEXBUS_GetDefaultConfig(flexbus_config_t *config);
+
+/*! @}*/
+
+#if defined(__cplusplus)
+}
+#endif /* __cplusplus */
+
+/*! @}*/
+
+#endif /* _FSL_FLEXBUS_H_ */
diff --git a/drivers/fsl_flexcan.c b/drivers/fsl_flexcan.c
new file mode 100644
index 0000000..395def5
--- /dev/null
+++ b/drivers/fsl_flexcan.c
@@ -0,0 +1,1345 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_flexcan.h"
+
+/*******************************************************************************
+ * Definitons
+ ******************************************************************************/
+
+#define FLEXCAN_TIME_QUANTA_NUM (10)
+
+/*! @brief FlexCAN Internal State. */
+enum _flexcan_state
+{
+ kFLEXCAN_StateIdle = 0x0, /*!< MB/RxFIFO idle.*/
+ kFLEXCAN_StateRxData = 0x1, /*!< MB receiving.*/
+ kFLEXCAN_StateRxRemote = 0x2, /*!< MB receiving remote reply.*/
+ kFLEXCAN_StateTxData = 0x3, /*!< MB transmitting.*/
+ kFLEXCAN_StateTxRemote = 0x4, /*!< MB transmitting remote request.*/
+ kFLEXCAN_StateRxFifo = 0x5, /*!< RxFIFO receiving.*/
+};
+
+/*! @brief FlexCAN message buffer CODE for Rx buffers. */
+enum _flexcan_mb_code_rx
+{
+ kFLEXCAN_RxMbInactive = 0x0, /*!< MB is not active.*/
+ kFLEXCAN_RxMbFull = 0x2, /*!< MB is full.*/
+ kFLEXCAN_RxMbEmpty = 0x4, /*!< MB is active and empty.*/
+ kFLEXCAN_RxMbOverrun = 0x6, /*!< MB is overwritten into a full buffer.*/
+ kFLEXCAN_RxMbBusy = 0x8, /*!< FlexCAN is updating the contents of the MB.*/
+ /*! The CPU must not access the MB.*/
+ kFLEXCAN_RxMbRanswer = 0xA, /*!< A frame was configured to recognize a Remote Request Frame */
+ /*! and transmit a Response Frame in return.*/
+ kFLEXCAN_RxMbNotUsed = 0xF, /*!< Not used.*/
+};
+
+/*! @brief FlexCAN message buffer CODE FOR Tx buffers. */
+enum _flexcan_mb_code_tx
+{
+ kFLEXCAN_TxMbInactive = 0x8, /*!< MB is not active.*/
+ kFLEXCAN_TxMbAbort = 0x9, /*!< MB is aborted.*/
+ kFLEXCAN_TxMbDataOrRemote = 0xC, /*!< MB is a TX Data Frame(when MB RTR = 0) or */
+ /*!< MB is a TX Remote Request Frame (when MB RTR = 1).*/
+ kFLEXCAN_TxMbTanswer = 0xE, /*!< MB is a TX Response Request Frame from */
+ /*! an incoming Remote Request Frame.*/
+ kFLEXCAN_TxMbNotUsed = 0xF, /*!< Not used.*/
+};
+
+/* Typedef for interrupt handler. */
+typedef void (*flexcan_isr_t)(CAN_Type *base, flexcan_handle_t *handle);
+
+/*******************************************************************************
+ * Prototypes
+ ******************************************************************************/
+
+/*!
+ * @brief Get the FlexCAN instance from peripheral base address.
+ *
+ * @param base FlexCAN peripheral base address.
+ * @return FlexCAN instance.
+ */
+uint32_t FLEXCAN_GetInstance(CAN_Type *base);
+
+/*!
+ * @brief Enter FlexCAN Freeze Mode.
+ *
+ * This function makes the FlexCAN work under Freeze Mode.
+ *
+ * @param base FlexCAN peripheral base address.
+ */
+static void FLEXCAN_EnterFreezeMode(CAN_Type *base);
+
+/*!
+ * @brief Exit FlexCAN Freeze Mode.
+ *
+ * This function makes the FlexCAN leave Freeze Mode.
+ *
+ * @param base FlexCAN peripheral base address.
+ */
+static void FLEXCAN_ExitFreezeMode(CAN_Type *base);
+
+#if !defined(NDEBUG)
+/*!
+ * @brief Check if Message Buffer is occupied by Rx FIFO.
+ *
+ * This function check if Message Buffer is occupied by Rx FIFO.
+ *
+ * @param base FlexCAN peripheral base address.
+ * @param mbIdx The FlexCAN Message Buffer index.
+ */
+static bool FLEXCAN_IsMbOccupied(CAN_Type *base, uint8_t mbIdx);
+#endif
+
+#if (defined(FSL_FEATURE_FLEXCAN_HAS_ERRATA_5641) && FSL_FEATURE_FLEXCAN_HAS_ERRATA_5641)
+/*!
+ * @brief Get the first valid Message buffer ID of give FlexCAN instance.
+ *
+ * This function is a helper function for Errata 5641 workaround.
+ *
+ * @param base FlexCAN peripheral base address.
+ * @return The first valid Message Buffer Number.
+ */
+static uint32_t FLEXCAN_GetFirstValidMb(CAN_Type *base);
+#endif
+
+/*!
+ * @brief Check if Message Buffer interrupt is enabled.
+ *
+ * This function check if Message Buffer interrupt is enabled.
+ *
+ * @param base FlexCAN peripheral base address.
+ * @param mbIdx The FlexCAN Message Buffer index.
+ */
+static bool FLEXCAN_IsMbIntEnabled(CAN_Type *base, uint8_t mbIdx);
+
+/*!
+ * @brief Reset the FlexCAN Instance.
+ *
+ * Restores the FlexCAN module to reset state, notice that this function
+ * will set all the registers to reset state so the FlexCAN module can not work
+ * after calling this API.
+ *
+ * @param base FlexCAN peripheral base address.
+*/
+static void FLEXCAN_Reset(CAN_Type *base);
+
+/*!
+ * @brief Set Baud Rate of FlexCAN.
+ *
+ * This function set the baud rate of FlexCAN.
+ *
+ * @param base FlexCAN peripheral base address.
+ * @param sourceClock_Hz Source Clock in Hz.
+ * @param baudRate_Bps Baud Rate in Bps.
+ */
+static void FLEXCAN_SetBaudRate(CAN_Type *base, uint32_t sourceClock_Hz, uint32_t baudRate_Bps);
+
+/*******************************************************************************
+ * Variables
+ ******************************************************************************/
+/* Array of FlexCAN handle. */
+static flexcan_handle_t *s_flexcanHandle[FSL_FEATURE_SOC_FLEXCAN_COUNT];
+
+/* Array of FlexCAN peripheral base address. */
+static CAN_Type *const s_flexcanBases[] = CAN_BASE_PTRS;
+
+/* Array of FlexCAN IRQ number. */
+static const IRQn_Type s_flexcanRxWarningIRQ[] = CAN_Rx_Warning_IRQS;
+static const IRQn_Type s_flexcanTxWarningIRQ[] = CAN_Tx_Warning_IRQS;
+static const IRQn_Type s_flexcanWakeUpIRQ[] = CAN_Wake_Up_IRQS;
+static const IRQn_Type s_flexcanErrorIRQ[] = CAN_Error_IRQS;
+static const IRQn_Type s_flexcanBusOffIRQ[] = CAN_Bus_Off_IRQS;
+static const IRQn_Type s_flexcanMbIRQ[] = CAN_ORed_Message_buffer_IRQS;
+
+/* Array of FlexCAN clock name. */
+static const clock_ip_name_t s_flexcanClock[] = FLEXCAN_CLOCKS;
+
+/* FlexCAN ISR for transactional APIs. */
+static flexcan_isr_t s_flexcanIsr;
+
+/*******************************************************************************
+ * Code
+ ******************************************************************************/
+
+uint32_t FLEXCAN_GetInstance(CAN_Type *base)
+{
+ uint32_t instance;
+
+ /* Find the instance index from base address mappings. */
+ for (instance = 0; instance < FSL_FEATURE_SOC_FLEXCAN_COUNT; instance++)
+ {
+ if (s_flexcanBases[instance] == base)
+ {
+ break;
+ }
+ }
+
+ assert(instance < FSL_FEATURE_SOC_FLEXCAN_COUNT);
+
+ return instance;
+}
+
+static void FLEXCAN_EnterFreezeMode(CAN_Type *base)
+{
+ /* Set Freeze, Halt bits. */
+ base->MCR |= CAN_MCR_HALT_MASK;
+
+ /* Wait until the FlexCAN Module enter freeze mode. */
+ while (!(base->MCR & CAN_MCR_FRZACK_MASK))
+ {
+ }
+}
+
+static void FLEXCAN_ExitFreezeMode(CAN_Type *base)
+{
+ /* Clear Freeze, Halt bits. */
+ base->MCR &= ~CAN_MCR_HALT_MASK;
+
+ /* Wait until the FlexCAN Module exit freeze mode. */
+ while (base->MCR & CAN_MCR_FRZACK_MASK)
+ {
+ }
+}
+
+#if !defined(NDEBUG)
+static bool FLEXCAN_IsMbOccupied(CAN_Type *base, uint8_t mbIdx)
+{
+ uint8_t lastOccupiedMb;
+
+ /* Is Rx FIFO enabled? */
+ if (base->MCR & CAN_MCR_RFEN_MASK)
+ {
+ /* Get RFFN value. */
+ lastOccupiedMb = ((base->CTRL2 & CAN_CTRL2_RFFN_MASK) >> CAN_CTRL2_RFFN_SHIFT);
+ /* Calculate the number of last Message Buffer occupied by Rx FIFO. */
+ lastOccupiedMb = ((lastOccupiedMb + 1) * 2) + 5;
+
+#if (defined(FSL_FEATURE_FLEXCAN_HAS_ERRATA_5641) && FSL_FEATURE_FLEXCAN_HAS_ERRATA_5641)
+ if (mbIdx <= (lastOccupiedMb + 1))
+#else
+ if (mbIdx <= lastOccupiedMb)
+#endif
+ {
+ return true;
+ }
+ else
+ {
+ return false;
+ }
+ }
+ else
+ {
+#if (defined(FSL_FEATURE_FLEXCAN_HAS_ERRATA_5641) && FSL_FEATURE_FLEXCAN_HAS_ERRATA_5641)
+ if (0 == mbIdx)
+ {
+ return true;
+ }
+ else
+ {
+ return false;
+ }
+#else
+ return false;
+#endif
+ }
+}
+#endif
+
+#if (defined(FSL_FEATURE_FLEXCAN_HAS_ERRATA_5641) && FSL_FEATURE_FLEXCAN_HAS_ERRATA_5641)
+static uint32_t FLEXCAN_GetFirstValidMb(CAN_Type *base)
+{
+ uint32_t firstValidMbNum;
+
+ if (base->MCR & CAN_MCR_RFEN_MASK)
+ {
+ firstValidMbNum = ((base->CTRL2 & CAN_CTRL2_RFFN_MASK) >> CAN_CTRL2_RFFN_SHIFT);
+ firstValidMbNum = ((firstValidMbNum + 1) * 2) + 6;
+ }
+ else
+ {
+ firstValidMbNum = 0;
+ }
+
+ return firstValidMbNum;
+}
+#endif
+
+static bool FLEXCAN_IsMbIntEnabled(CAN_Type *base, uint8_t mbIdx)
+{
+ /* Assertion. */
+ assert(mbIdx < FSL_FEATURE_FLEXCAN_HAS_MESSAGE_BUFFER_MAX_NUMBERn(base));
+
+#if (FSL_FEATURE_FLEXCAN_HAS_EXTENDED_FLAG_REGISTER > 0)
+ if (mbIdx < 32)
+ {
+#endif
+ if (base->IMASK1 & ((uint32_t)(1 << mbIdx)))
+ {
+ return true;
+ }
+ else
+ {
+ return false;
+ }
+#if (FSL_FEATURE_FLEXCAN_HAS_EXTENDED_FLAG_REGISTER > 0)
+ }
+ else
+ {
+ if (base->IMASK2 & ((uint32_t)(1 << (mbIdx - 32))))
+ return true;
+ else
+ return false;
+ }
+#endif
+}
+
+static void FLEXCAN_Reset(CAN_Type *base)
+{
+ /* The module must should be first exit from low power
+ * mode, and then soft reset can be applied.
+ */
+ assert(!(base->MCR & CAN_MCR_MDIS_MASK));
+
+ uint8_t i;
+
+#if (FSL_FEATURE_FLEXCAN_HAS_DOZE_MODE_SUPPORT != 0)
+ /* De-assert DOZE Enable Bit. */
+ base->MCR &= ~CAN_MCR_DOZE_MASK;
+#endif
+
+ /* Wait until FlexCAN exit from any Low Power Mode. */
+ while (base->MCR & CAN_MCR_LPMACK_MASK)
+ {
+ }
+
+ /* Assert Soft Reset Signal. */
+ base->MCR |= CAN_MCR_SOFTRST_MASK;
+ /* Wait until FlexCAN reset completes. */
+ while (base->MCR & CAN_MCR_SOFTRST_MASK)
+ {
+ }
+
+/* Reset MCR rigister. */
+#if (defined(FSL_FEATURE_FLEXCAN_HAS_GLITCH_FILTER) && FSL_FEATURE_FLEXCAN_HAS_GLITCH_FILTER)
+ base->MCR |= CAN_MCR_WRNEN_MASK | CAN_MCR_WAKSRC_MASK |
+ CAN_MCR_MAXMB(FSL_FEATURE_FLEXCAN_HAS_MESSAGE_BUFFER_MAX_NUMBERn(base) - 1);
+#else
+ base->MCR |= CAN_MCR_WRNEN_MASK | CAN_MCR_MAXMB(FSL_FEATURE_FLEXCAN_HAS_MESSAGE_BUFFER_MAX_NUMBERn(base) - 1);
+#endif
+
+ /* Reset CTRL1 and CTRL2 rigister. */
+ base->CTRL1 = CAN_CTRL1_SMP_MASK;
+ base->CTRL2 = CAN_CTRL2_TASD(0x16) | CAN_CTRL2_RRS_MASK | CAN_CTRL2_EACEN_MASK;
+
+ /* Clean all individual Rx Mask of Message Buffers. */
+ for (i = 0; i < FSL_FEATURE_FLEXCAN_HAS_MESSAGE_BUFFER_MAX_NUMBERn(base); i++)
+ {
+ base->RXIMR[i] = 0x3FFFFFFF;
+ }
+
+ /* Clean Global Mask of Message Buffers. */
+ base->RXMGMASK = 0x3FFFFFFF;
+ /* Clean Global Mask of Message Buffer 14. */
+ base->RX14MASK = 0x3FFFFFFF;
+ /* Clean Global Mask of Message Buffer 15. */
+ base->RX15MASK = 0x3FFFFFFF;
+ /* Clean Global Mask of Rx FIFO. */
+ base->RXFGMASK = 0x3FFFFFFF;
+
+ /* Clean all Message Buffer CS fields. */
+ for (i = 0; i < FSL_FEATURE_FLEXCAN_HAS_MESSAGE_BUFFER_MAX_NUMBERn(base); i++)
+ {
+ base->MB[i].CS = 0x0;
+ }
+}
+
+static void FLEXCAN_SetBaudRate(CAN_Type *base, uint32_t sourceClock_Hz, uint32_t baudRate_Bps)
+{
+ flexcan_timing_config_t timingConfig;
+ uint32_t priDiv = baudRate_Bps * FLEXCAN_TIME_QUANTA_NUM;
+
+ /* Assertion: Desired baud rate is too high. */
+ assert(baudRate_Bps <= 1000000U);
+ /* Assertion: Source clock should greater than baud rate * FLEXCAN_TIME_QUANTA_NUM. */
+ assert(priDiv <= sourceClock_Hz);
+
+ if (0 == priDiv)
+ {
+ priDiv = 1;
+ }
+
+ priDiv = (sourceClock_Hz / priDiv) - 1;
+
+ /* Desired baud rate is too low. */
+ if (priDiv > 0xFF)
+ {
+ priDiv = 0xFF;
+ }
+
+ /* FlexCAN timing setting formula:
+ * FLEXCAN_TIME_QUANTA_NUM = 1 + (PSEG1 + 1) + (PSEG2 + 1) + (PROPSEG + 1);
+ */
+ timingConfig.preDivider = priDiv;
+ timingConfig.phaseSeg1 = 3;
+ timingConfig.phaseSeg2 = 2;
+ timingConfig.propSeg = 1;
+ timingConfig.rJumpwidth = 1;
+
+ /* Update actual timing characteristic. */
+ FLEXCAN_SetTimingConfig(base, &timingConfig);
+}
+
+void FLEXCAN_Init(CAN_Type *base, const flexcan_config_t *config, uint32_t sourceClock_Hz)
+{
+ uint32_t mcrTemp;
+
+ /* Assertion. */
+ assert(config);
+ assert((config->maxMbNum > 0) && (config->maxMbNum <= FSL_FEATURE_FLEXCAN_HAS_MESSAGE_BUFFER_MAX_NUMBERn(base)));
+
+ /* Enable FlexCAN clock. */
+ CLOCK_EnableClock(s_flexcanClock[FLEXCAN_GetInstance(base)]);
+
+ /* Disable FlexCAN Module. */
+ FLEXCAN_Enable(base, false);
+
+ /* Protocol-Engine clock source selection, This bit must be set
+ * when FlexCAN Module in Disable Mode.
+ */
+ base->CTRL1 = (kFLEXCAN_ClkSrcOsc == config->clkSrc) ? base->CTRL1 & ~CAN_CTRL1_CLKSRC_MASK :
+ base->CTRL1 | CAN_CTRL1_CLKSRC_MASK;
+
+ /* Enable FlexCAN Module for configuartion. */
+ FLEXCAN_Enable(base, true);
+
+ /* Reset to known status. */
+ FLEXCAN_Reset(base);
+
+ /* Save current MCR value and enable to enter Freeze mode(enabled by default). */
+ mcrTemp = base->MCR;
+
+ /* Set the maximum number of Message Buffers */
+ mcrTemp = (mcrTemp & ~CAN_MCR_MAXMB_MASK) | CAN_MCR_MAXMB(config->maxMbNum - 1);
+
+ /* Enable Loop Back Mode? */
+ base->CTRL1 = (config->enableLoopBack) ? base->CTRL1 | CAN_CTRL1_LPB_MASK : base->CTRL1 & ~CAN_CTRL1_LPB_MASK;
+
+ /* Enable Self Wake Up Mode? */
+ mcrTemp = (config->enableSelfWakeup) ? mcrTemp | CAN_MCR_SLFWAK_MASK : mcrTemp & ~CAN_MCR_SLFWAK_MASK;
+
+ /* Enable Individual Rx Masking? */
+ mcrTemp = (config->enableIndividMask) ? mcrTemp | CAN_MCR_IRMQ_MASK : mcrTemp & ~CAN_MCR_IRMQ_MASK;
+
+#if (defined(FSL_FEATURE_FLEXCAN_HAS_DOZE_MODE_SUPPORT) && FSL_FEATURE_FLEXCAN_HAS_DOZE_MODE_SUPPORT)
+ /* Enable Doze Mode? */
+ mcrTemp = (config->enableDoze) ? mcrTemp | CAN_MCR_DOZE_MASK : mcrTemp & ~CAN_MCR_DOZE_MASK;
+#endif
+
+ /* Save MCR Configuation. */
+ base->MCR = mcrTemp;
+
+ /* Baud Rate Configuration.*/
+ FLEXCAN_SetBaudRate(base, sourceClock_Hz, config->baudRate);
+}
+
+void FLEXCAN_Deinit(CAN_Type *base)
+{
+ /* Reset all Register Contents. */
+ FLEXCAN_Reset(base);
+
+ /* Disable FlexCAN module. */
+ FLEXCAN_Enable(base, false);
+
+ /* Disable FlexCAN clock. */
+ CLOCK_DisableClock(s_flexcanClock[FLEXCAN_GetInstance(base)]);
+}
+
+void FLEXCAN_GetDefaultConfig(flexcan_config_t *config)
+{
+ /* Assertion. */
+ assert(config);
+
+ /* Initialize FlexCAN Module config struct with default value. */
+ config->clkSrc = kFLEXCAN_ClkSrcOsc;
+ config->baudRate = 125000U;
+ config->maxMbNum = 16;
+ config->enableLoopBack = false;
+ config->enableSelfWakeup = false;
+ config->enableIndividMask = false;
+#if (defined(FSL_FEATURE_FLEXCAN_HAS_DOZE_MODE_SUPPORT) && FSL_FEATURE_FLEXCAN_HAS_DOZE_MODE_SUPPORT)
+ config->enableDoze = false;
+#endif
+}
+
+void FLEXCAN_SetTimingConfig(CAN_Type *base, const flexcan_timing_config_t *config)
+{
+ /* Assertion. */
+ assert(config);
+
+ /* Enter Freeze Mode. */
+ FLEXCAN_EnterFreezeMode(base);
+
+ /* Cleaning previous Timing Setting. */
+ base->CTRL1 &= ~(CAN_CTRL1_PRESDIV_MASK | CAN_CTRL1_RJW_MASK | CAN_CTRL1_PSEG1_MASK | CAN_CTRL1_PSEG2_MASK |
+ CAN_CTRL1_PROPSEG_MASK);
+
+ /* Updating Timing Setting according to configuration structure. */
+ base->CTRL1 |=
+ (CAN_CTRL1_PRESDIV(config->preDivider) | CAN_CTRL1_RJW(config->rJumpwidth) |
+ CAN_CTRL1_PSEG1(config->phaseSeg1) | CAN_CTRL1_PSEG2(config->phaseSeg2) | CAN_CTRL1_PROPSEG(config->propSeg));
+
+ /* Exit Freeze Mode. */
+ FLEXCAN_ExitFreezeMode(base);
+}
+
+void FLEXCAN_SetRxMbGlobalMask(CAN_Type *base, uint32_t mask)
+{
+ /* Enter Freeze Mode. */
+ FLEXCAN_EnterFreezeMode(base);
+
+ /* Setting Rx Message Buffer Global Mask value. */
+ base->RXMGMASK = mask;
+ base->RX14MASK = mask;
+ base->RX15MASK = mask;
+
+ /* Exit Freeze Mode. */
+ FLEXCAN_ExitFreezeMode(base);
+}
+
+void FLEXCAN_SetRxFifoGlobalMask(CAN_Type *base, uint32_t mask)
+{
+ /* Enter Freeze Mode. */
+ FLEXCAN_EnterFreezeMode(base);
+
+ /* Setting Rx FIFO Global Mask value. */
+ base->RXFGMASK = mask;
+
+ /* Exit Freeze Mode. */
+ FLEXCAN_ExitFreezeMode(base);
+}
+
+void FLEXCAN_SetRxIndividualMask(CAN_Type *base, uint8_t maskIdx, uint32_t mask)
+{
+ assert(maskIdx <= (base->MCR & CAN_MCR_MAXMB_MASK));
+
+ /* Enter Freeze Mode. */
+ FLEXCAN_EnterFreezeMode(base);
+
+ /* Setting Rx Individual Mask value. */
+ base->RXIMR[maskIdx] = mask;
+
+ /* Exit Freeze Mode. */
+ FLEXCAN_ExitFreezeMode(base);
+}
+
+void FLEXCAN_SetTxMbConfig(CAN_Type *base, uint8_t mbIdx, bool enable)
+{
+ /* Assertion. */
+ assert(mbIdx <= (base->MCR & CAN_MCR_MAXMB_MASK));
+ assert(!FLEXCAN_IsMbOccupied(base, mbIdx));
+
+ /* Inactivate Message Buffer. */
+ if (enable)
+ {
+ base->MB[mbIdx].CS = CAN_CS_CODE(kFLEXCAN_TxMbInactive);
+ }
+ else
+ {
+ base->MB[mbIdx].CS = 0;
+ }
+
+ /* Clean Message Buffer content. */
+ base->MB[mbIdx].ID = 0x0;
+ base->MB[mbIdx].WORD0 = 0x0;
+ base->MB[mbIdx].WORD1 = 0x0;
+}
+
+void FLEXCAN_SetRxMbConfig(CAN_Type *base, uint8_t mbIdx, const flexcan_rx_mb_config_t *config, bool enable)
+{
+ /* Assertion. */
+ assert(mbIdx <= (base->MCR & CAN_MCR_MAXMB_MASK));
+ assert(((config) || (false == enable)));
+ assert(!FLEXCAN_IsMbOccupied(base, mbIdx));
+
+ uint32_t cs_temp = 0;
+
+ /* Inactivate Message Buffer. */
+ base->MB[mbIdx].CS = 0;
+
+ /* Clean Message Buffer content. */
+ base->MB[mbIdx].ID = 0x0;
+ base->MB[mbIdx].WORD0 = 0x0;
+ base->MB[mbIdx].WORD1 = 0x0;
+
+ if (enable)
+ {
+ /* Setup Message Buffer ID. */
+ base->MB[mbIdx].ID = config->id;
+
+ /* Setup Message Buffer format. */
+ if (kFLEXCAN_FrameFormatExtend == config->format)
+ {
+ cs_temp |= CAN_CS_IDE_MASK;
+ }
+
+ /* Setup Message Buffer type. */
+ if (kFLEXCAN_FrameTypeRemote == config->type)
+ {
+ cs_temp |= CAN_CS_RTR_MASK;
+ }
+
+ /* Activate Rx Message Buffer. */
+ cs_temp |= CAN_CS_CODE(kFLEXCAN_RxMbEmpty);
+ base->MB[mbIdx].CS = cs_temp;
+ }
+}
+
+void FLEXCAN_SetRxFifoConfig(CAN_Type *base, const flexcan_rx_fifo_config_t *config, bool enable)
+{
+ /* Assertion. */
+ assert((config) || (false == enable));
+
+ volatile uint32_t *idFilterRegion = (volatile uint32_t *)(&base->MB[6].CS);
+ uint8_t setup_mb, i, rffn = 0;
+
+ /* Enter Freeze Mode. */
+ FLEXCAN_EnterFreezeMode(base);
+
+ if (enable)
+ {
+ assert(config->idFilterNum <= 128);
+
+ /* Get the setup_mb value. */
+ setup_mb = (base->MCR & CAN_MCR_MAXMB_MASK) >> CAN_MCR_MAXMB_SHIFT;
+ setup_mb = (setup_mb < FSL_FEATURE_FLEXCAN_HAS_MESSAGE_BUFFER_MAX_NUMBERn(base)) ?
+ setup_mb :
+ FSL_FEATURE_FLEXCAN_HAS_MESSAGE_BUFFER_MAX_NUMBERn(base);
+
+ /* Determine RFFN value. */
+ for (i = 0; i <= 0xF; i++)
+ {
+ if ((8 * (i + 1)) >= config->idFilterNum)
+ {
+ rffn = i;
+ assert(((setup_mb - 8) - (2 * rffn)) > 0);
+
+ base->CTRL2 = (base->CTRL2 & ~CAN_CTRL2_RFFN_MASK) | CAN_CTRL2_RFFN(rffn);
+ break;
+ }
+ }
+ }
+ else
+ {
+ rffn = (base->CTRL2 & CAN_CTRL2_RFFN_MASK) >> CAN_CTRL2_RFFN_SHIFT;
+ }
+
+ /* Clean ID filter table occuyied Message Buffer Region. */
+ rffn = (rffn + 1) * 8;
+ for (i = 0; i < rffn; i++)
+ {
+ idFilterRegion[i] = 0x0;
+ }
+
+ if (enable)
+ {
+ /* Disable unused Rx FIFO Filter. */
+ for (i = config->idFilterNum; i < rffn; i++)
+ {
+ idFilterRegion[i] = 0xFFFFFFFFU;
+ }
+
+ /* Copy ID filter table to Message Buffer Region. */
+ for (i = 0; i < config->idFilterNum; i++)
+ {
+ idFilterRegion[i] = config->idFilterTable[i];
+ }
+
+ /* Setup ID Fitlter Type. */
+ switch (config->idFilterType)
+ {
+ case kFLEXCAN_RxFifoFilterTypeA:
+ base->MCR = (base->MCR & ~CAN_MCR_IDAM_MASK) | CAN_MCR_IDAM(0x0);
+ break;
+ case kFLEXCAN_RxFifoFilterTypeB:
+ base->MCR = (base->MCR & ~CAN_MCR_IDAM_MASK) | CAN_MCR_IDAM(0x1);
+ break;
+ case kFLEXCAN_RxFifoFilterTypeC:
+ base->MCR = (base->MCR & ~CAN_MCR_IDAM_MASK) | CAN_MCR_IDAM(0x2);
+ break;
+ case kFLEXCAN_RxFifoFilterTypeD:
+ /* All frames rejected. */
+ base->MCR = (base->MCR & ~CAN_MCR_IDAM_MASK) | CAN_MCR_IDAM(0x3);
+ break;
+ default:
+ break;
+ }
+
+ /* Setting Message Reception Priority. */
+ base->CTRL2 = (config->priority == kFLEXCAN_RxFifoPrioHigh) ? base->CTRL2 & ~CAN_CTRL2_MRP_MASK :
+ base->CTRL2 | CAN_CTRL2_MRP_MASK;
+
+ /* Enable Rx Message FIFO. */
+ base->MCR |= CAN_MCR_RFEN_MASK;
+ }
+ else
+ {
+ /* Disable Rx Message FIFO. */
+ base->MCR &= ~CAN_MCR_RFEN_MASK;
+
+ /* Clean MB0 ~ MB5. */
+ FLEXCAN_SetRxMbConfig(base, 0, NULL, false);
+ FLEXCAN_SetRxMbConfig(base, 1, NULL, false);
+ FLEXCAN_SetRxMbConfig(base, 2, NULL, false);
+ FLEXCAN_SetRxMbConfig(base, 3, NULL, false);
+ FLEXCAN_SetRxMbConfig(base, 4, NULL, false);
+ FLEXCAN_SetRxMbConfig(base, 5, NULL, false);
+ }
+
+ /* Exit Freeze Mode. */
+ FLEXCAN_ExitFreezeMode(base);
+}
+
+#if (defined(FSL_FEATURE_FLEXCAN_HAS_RX_FIFO_DMA) && FSL_FEATURE_FLEXCAN_HAS_RX_FIFO_DMA)
+void FLEXCAN_EnableRxFifoDMA(CAN_Type *base, bool enable)
+{
+ if (enable)
+ {
+ /* Enter Freeze Mode. */
+ FLEXCAN_EnterFreezeMode(base);
+
+ /* Enable FlexCAN DMA. */
+ base->MCR |= CAN_MCR_DMA_MASK;
+
+ /* Exit Freeze Mode. */
+ FLEXCAN_ExitFreezeMode(base);
+ }
+ else
+ {
+ /* Enter Freeze Mode. */
+ FLEXCAN_EnterFreezeMode(base);
+
+ /* Disable FlexCAN DMA. */
+ base->MCR &= ~CAN_MCR_DMA_MASK;
+
+ /* Exit Freeze Mode. */
+ FLEXCAN_ExitFreezeMode(base);
+ }
+}
+#endif /* FSL_FEATURE_FLEXCAN_HAS_RX_FIFO_DMA */
+
+status_t FLEXCAN_WriteTxMb(CAN_Type *base, uint8_t mbIdx, const flexcan_frame_t *txFrame)
+{
+ /* Assertion. */
+ assert(mbIdx <= (base->MCR & CAN_MCR_MAXMB_MASK));
+ assert(txFrame);
+ assert(txFrame->length <= 8);
+ assert(!FLEXCAN_IsMbOccupied(base, mbIdx));
+
+ uint32_t cs_temp = 0;
+
+ /* Check if Message Buffer is available. */
+ if (CAN_CS_CODE(kFLEXCAN_TxMbDataOrRemote) != (base->MB[mbIdx].CS & CAN_CS_CODE_MASK))
+ {
+ /* Inactive Tx Message Buffer. */
+ base->MB[mbIdx].CS = (base->MB[mbIdx].CS & ~CAN_CS_CODE_MASK) | CAN_CS_CODE(kFLEXCAN_TxMbInactive);
+
+ /* Fill Message ID field. */
+ base->MB[mbIdx].ID = txFrame->id;
+
+ /* Fill Message Format field. */
+ if (kFLEXCAN_FrameFormatExtend == txFrame->format)
+ {
+ cs_temp |= CAN_CS_SRR_MASK | CAN_CS_IDE_MASK;
+ }
+
+ /* Fill Message Type field. */
+ if (kFLEXCAN_FrameTypeRemote == txFrame->type)
+ {
+ cs_temp |= CAN_CS_RTR_MASK;
+ }
+
+ cs_temp |= CAN_CS_CODE(kFLEXCAN_TxMbDataOrRemote) | CAN_CS_DLC(txFrame->length);
+
+ /* Load Message Payload. */
+ base->MB[mbIdx].WORD0 = txFrame->dataWord0;
+ base->MB[mbIdx].WORD1 = txFrame->dataWord1;
+
+ /* Activate Tx Message Buffer. */
+ base->MB[mbIdx].CS = cs_temp;
+
+#if (defined(FSL_FEATURE_FLEXCAN_HAS_ERRATA_5641) && FSL_FEATURE_FLEXCAN_HAS_ERRATA_5641)
+ base->MB[FLEXCAN_GetFirstValidMb(base)].CS = CAN_CS_CODE(kFLEXCAN_TxMbInactive);
+ base->MB[FLEXCAN_GetFirstValidMb(base)].CS = CAN_CS_CODE(kFLEXCAN_TxMbInactive);
+#endif
+
+ return kStatus_Success;
+ }
+ else
+ {
+ /* Tx Message Buffer is activated, return immediately. */
+ return kStatus_Fail;
+ }
+}
+
+status_t FLEXCAN_ReadRxMb(CAN_Type *base, uint8_t mbIdx, flexcan_frame_t *rxFrame)
+{
+ /* Assertion. */
+ assert(mbIdx <= (base->MCR & CAN_MCR_MAXMB_MASK));
+ assert(rxFrame);
+ assert(!FLEXCAN_IsMbOccupied(base, mbIdx));
+
+ uint32_t cs_temp;
+ uint8_t rx_code;
+
+ /* Read CS field of Rx Message Buffer to lock Message Buffer. */
+ cs_temp = base->MB[mbIdx].CS;
+ /* Get Rx Message Buffer Code field. */
+ rx_code = (cs_temp & CAN_CS_CODE_MASK) >> CAN_CS_CODE_SHIFT;
+
+ /* Check to see if Rx Message Buffer is full. */
+ if ((kFLEXCAN_RxMbFull == rx_code) || (kFLEXCAN_RxMbOverrun == rx_code))
+ {
+ /* Store Message ID. */
+ rxFrame->id = base->MB[mbIdx].ID & (CAN_ID_EXT_MASK | CAN_ID_STD_MASK);
+
+ /* Get the message ID and format. */
+ rxFrame->format = (cs_temp & CAN_CS_IDE_MASK) ? kFLEXCAN_FrameFormatExtend : kFLEXCAN_FrameFormatStandard;
+
+ /* Get the message type. */
+ rxFrame->type = (cs_temp & CAN_CS_RTR_MASK) ? kFLEXCAN_FrameTypeRemote : kFLEXCAN_FrameTypeData;
+
+ /* Get the message length. */
+ rxFrame->length = (cs_temp & CAN_CS_DLC_MASK) >> CAN_CS_DLC_SHIFT;
+
+ /* Store Message Payload. */
+ rxFrame->dataWord0 = base->MB[mbIdx].WORD0;
+ rxFrame->dataWord1 = base->MB[mbIdx].WORD1;
+
+ /* Read free-running timer to unlock Rx Message Buffer. */
+ (void)base->TIMER;
+
+ if (kFLEXCAN_RxMbFull == rx_code)
+ {
+ return kStatus_Success;
+ }
+ else
+ {
+ return kStatus_FLEXCAN_RxOverflow;
+ }
+ }
+ else
+ {
+ /* Read free-running timer to unlock Rx Message Buffer. */
+ (void)base->TIMER;
+
+ return kStatus_Fail;
+ }
+}
+
+status_t FLEXCAN_ReadRxFifo(CAN_Type *base, flexcan_frame_t *rxFrame)
+{
+ /* Assertion. */
+ assert(rxFrame);
+
+ uint32_t cs_temp;
+
+ /* Check if Rx FIFO is Enabled. */
+ if (base->MCR & CAN_MCR_RFEN_MASK)
+ {
+ /* Read CS field of Rx Message Buffer to lock Message Buffer. */
+ cs_temp = base->MB[0].CS;
+
+ /* Read data from Rx FIFO output port. */
+ /* Store Message ID. */
+ rxFrame->id = base->MB[0].ID & (CAN_ID_EXT_MASK | CAN_ID_STD_MASK);
+
+ /* Get the message ID and format. */
+ rxFrame->format = (cs_temp & CAN_CS_IDE_MASK) ? kFLEXCAN_FrameFormatExtend : kFLEXCAN_FrameFormatStandard;
+
+ /* Get the message type. */
+ rxFrame->type = (cs_temp & CAN_CS_RTR_MASK) ? kFLEXCAN_FrameTypeRemote : kFLEXCAN_FrameTypeData;
+
+ /* Get the message length. */
+ rxFrame->length = (cs_temp & CAN_CS_DLC_MASK) >> CAN_CS_DLC_SHIFT;
+
+ /* Store Message Payload. */
+ rxFrame->dataWord0 = base->MB[0].WORD0;
+ rxFrame->dataWord1 = base->MB[0].WORD1;
+
+ /* Store ID Filter Hit Index. */
+ rxFrame->idhit = (uint8_t)(base->RXFIR & CAN_RXFIR_IDHIT_MASK);
+
+ /* Read free-running timer to unlock Rx Message Buffer. */
+ (void)base->TIMER;
+
+ return kStatus_Success;
+ }
+ else
+ {
+ return kStatus_Fail;
+ }
+}
+
+status_t FLEXCAN_TransferSendBlocking(CAN_Type *base, uint8_t mbIdx, flexcan_frame_t *txFrame)
+{
+ /* Write Tx Message Buffer to initiate a data sending. */
+ if (kStatus_Success == FLEXCAN_WriteTxMb(base, mbIdx, txFrame))
+ {
+ /* Wait until CAN Message send out. */
+ while (!FLEXCAN_GetMbStatusFlags(base, 1 << mbIdx))
+ {
+ }
+
+ /* Clean Tx Message Buffer Flag. */
+ FLEXCAN_ClearMbStatusFlags(base, 1 << mbIdx);
+
+ return kStatus_Success;
+ }
+ else
+ {
+ return kStatus_Fail;
+ }
+}
+
+status_t FLEXCAN_TransferReceiveBlocking(CAN_Type *base, uint8_t mbIdx, flexcan_frame_t *rxFrame)
+{
+ /* Wait until Rx Message Buffer non-empty. */
+ while (!FLEXCAN_GetMbStatusFlags(base, 1 << mbIdx))
+ {
+ }
+
+ /* Clean Rx Message Buffer Flag. */
+ FLEXCAN_ClearMbStatusFlags(base, 1 << mbIdx);
+
+ /* Read Received CAN Message. */
+ return FLEXCAN_ReadRxMb(base, mbIdx, rxFrame);
+}
+
+status_t FLEXCAN_TransferReceiveFifoBlocking(CAN_Type *base, flexcan_frame_t *rxFrame)
+{
+ status_t rxFifoStatus;
+
+ /* Wait until Rx FIFO non-empty. */
+ while (!FLEXCAN_GetMbStatusFlags(base, kFLEXCAN_RxFifoFrameAvlFlag))
+ {
+ }
+
+ /* */
+ rxFifoStatus = FLEXCAN_ReadRxFifo(base, rxFrame);
+
+ /* Clean Rx Fifo available flag. */
+ FLEXCAN_ClearMbStatusFlags(base, kFLEXCAN_RxFifoFrameAvlFlag);
+
+ return rxFifoStatus;
+}
+
+void FLEXCAN_TransferCreateHandle(CAN_Type *base,
+ flexcan_handle_t *handle,
+ flexcan_transfer_callback_t callback,
+ void *userData)
+{
+ assert(handle);
+
+ uint8_t instance;
+
+ /* Clean FlexCAN transfer handle. */
+ memset(handle, 0, sizeof(*handle));
+
+ /* Get instance from peripheral base address. */
+ instance = FLEXCAN_GetInstance(base);
+
+ /* Save the context in global variables to support the double weak mechanism. */
+ s_flexcanHandle[instance] = handle;
+
+ /* Register Callback function. */
+ handle->callback = callback;
+ handle->userData = userData;
+
+ s_flexcanIsr = FLEXCAN_TransferHandleIRQ;
+
+ /* We Enable Error & Status interrupt here, because this interrupt just
+ * report current status of FlexCAN module through Callback function.
+ * It is insignificance without a available callback function.
+ */
+ if (handle->callback != NULL)
+ {
+ FLEXCAN_EnableInterrupts(base, kFLEXCAN_BusOffInterruptEnable | kFLEXCAN_ErrorInterruptEnable |
+ kFLEXCAN_RxWarningInterruptEnable | kFLEXCAN_TxWarningInterruptEnable |
+ kFLEXCAN_WakeUpInterruptEnable);
+ }
+ else
+ {
+ FLEXCAN_DisableInterrupts(base, kFLEXCAN_BusOffInterruptEnable | kFLEXCAN_ErrorInterruptEnable |
+ kFLEXCAN_RxWarningInterruptEnable | kFLEXCAN_TxWarningInterruptEnable |
+ kFLEXCAN_WakeUpInterruptEnable);
+ }
+
+ /* Enable interrupts in NVIC. */
+ EnableIRQ((IRQn_Type)(s_flexcanRxWarningIRQ[instance]));
+ EnableIRQ((IRQn_Type)(s_flexcanTxWarningIRQ[instance]));
+ EnableIRQ((IRQn_Type)(s_flexcanWakeUpIRQ[instance]));
+ EnableIRQ((IRQn_Type)(s_flexcanErrorIRQ[instance]));
+ EnableIRQ((IRQn_Type)(s_flexcanBusOffIRQ[instance]));
+ EnableIRQ((IRQn_Type)(s_flexcanMbIRQ[instance]));
+}
+
+status_t FLEXCAN_TransferSendNonBlocking(CAN_Type *base, flexcan_handle_t *handle, flexcan_mb_transfer_t *xfer)
+{
+ /* Assertion. */
+ assert(handle);
+ assert(xfer);
+ assert(xfer->mbIdx <= (base->MCR & CAN_MCR_MAXMB_MASK));
+ assert(!FLEXCAN_IsMbOccupied(base, xfer->mbIdx));
+
+ /* Check if Message Buffer is idle. */
+ if (kFLEXCAN_StateIdle == handle->mbState[xfer->mbIdx])
+ {
+ /* Distinguish transmit type. */
+ if (kFLEXCAN_FrameTypeRemote == xfer->frame->type)
+ {
+ handle->mbState[xfer->mbIdx] = kFLEXCAN_StateTxRemote;
+
+ /* Register user Frame buffer to receive remote Frame. */
+ handle->mbFrameBuf[xfer->mbIdx] = xfer->frame;
+ }
+ else
+ {
+ handle->mbState[xfer->mbIdx] = kFLEXCAN_StateTxData;
+ }
+
+ if (kStatus_Success == FLEXCAN_WriteTxMb(base, xfer->mbIdx, xfer->frame))
+ {
+ /* Enable Message Buffer Interrupt. */
+ FLEXCAN_EnableMbInterrupts(base, 1 << xfer->mbIdx);
+
+ return kStatus_Success;
+ }
+ else
+ {
+ handle->mbState[xfer->mbIdx] = kFLEXCAN_StateIdle;
+ return kStatus_Fail;
+ }
+ }
+ else
+ {
+ return kStatus_FLEXCAN_TxBusy;
+ }
+}
+
+status_t FLEXCAN_TransferReceiveNonBlocking(CAN_Type *base, flexcan_handle_t *handle, flexcan_mb_transfer_t *xfer)
+{
+ /* Assertion. */
+ assert(handle);
+ assert(xfer);
+ assert(xfer->mbIdx <= (base->MCR & CAN_MCR_MAXMB_MASK));
+ assert(!FLEXCAN_IsMbOccupied(base, xfer->mbIdx));
+
+ /* Check if Message Buffer is idle. */
+ if (kFLEXCAN_StateIdle == handle->mbState[xfer->mbIdx])
+ {
+ handle->mbState[xfer->mbIdx] = kFLEXCAN_StateRxData;
+
+ /* Register Message Buffer. */
+ handle->mbFrameBuf[xfer->mbIdx] = xfer->frame;
+
+ /* Enable Message Buffer Interrupt. */
+ FLEXCAN_EnableMbInterrupts(base, 1 << xfer->mbIdx);
+
+ return kStatus_Success;
+ }
+ else
+ {
+ return kStatus_FLEXCAN_RxBusy;
+ }
+}
+
+status_t FLEXCAN_TransferReceiveFifoNonBlocking(CAN_Type *base, flexcan_handle_t *handle, flexcan_fifo_transfer_t *xfer)
+{
+ /* Assertion. */
+ assert(handle);
+ assert(xfer);
+
+ /* Check if Message Buffer is idle. */
+ if (kFLEXCAN_StateIdle == handle->rxFifoState)
+ {
+ handle->rxFifoState = kFLEXCAN_StateRxFifo;
+
+ /* Register Message Buffer. */
+ handle->rxFifoFrameBuf = xfer->frame;
+
+ /* Enable Message Buffer Interrupt. */
+ FLEXCAN_EnableMbInterrupts(
+ base, kFLEXCAN_RxFifoOverflowFlag | kFLEXCAN_RxFifoWarningFlag | kFLEXCAN_RxFifoFrameAvlFlag);
+
+ return kStatus_Success;
+ }
+ else
+ {
+ return kStatus_FLEXCAN_RxFifoBusy;
+ }
+}
+
+void FLEXCAN_TransferAbortSend(CAN_Type *base, flexcan_handle_t *handle, uint8_t mbIdx)
+{
+ /* Assertion. */
+ assert(handle);
+ assert(mbIdx <= (base->MCR & CAN_MCR_MAXMB_MASK));
+ assert(!FLEXCAN_IsMbOccupied(base, mbIdx));
+
+ /* Disable Message Buffer Interrupt. */
+ FLEXCAN_DisableMbInterrupts(base, 1 << mbIdx);
+
+ /* Un-register handle. */
+ handle->mbFrameBuf[mbIdx] = 0x0;
+
+ /* Clean Message Buffer. */
+ FLEXCAN_SetTxMbConfig(base, mbIdx, true);
+
+ handle->mbState[mbIdx] = kFLEXCAN_StateIdle;
+}
+
+void FLEXCAN_TransferAbortReceive(CAN_Type *base, flexcan_handle_t *handle, uint8_t mbIdx)
+{
+ /* Assertion. */
+ assert(handle);
+ assert(mbIdx <= (base->MCR & CAN_MCR_MAXMB_MASK));
+ assert(!FLEXCAN_IsMbOccupied(base, mbIdx));
+
+ /* Disable Message Buffer Interrupt. */
+ FLEXCAN_DisableMbInterrupts(base, 1 << mbIdx);
+
+ /* Un-register handle. */
+ handle->mbFrameBuf[mbIdx] = 0x0;
+ handle->mbState[mbIdx] = kFLEXCAN_StateIdle;
+}
+
+void FLEXCAN_TransferAbortReceiveFifo(CAN_Type *base, flexcan_handle_t *handle)
+{
+ /* Assertion. */
+ assert(handle);
+
+ /* Check if Rx FIFO is enabled. */
+ if (base->MCR & CAN_MCR_RFEN_MASK)
+ {
+ /* Disable Rx Message FIFO Interrupts. */
+ FLEXCAN_DisableMbInterrupts(
+ base, kFLEXCAN_RxFifoOverflowFlag | kFLEXCAN_RxFifoWarningFlag | kFLEXCAN_RxFifoFrameAvlFlag);
+
+ /* Un-register handle. */
+ handle->rxFifoFrameBuf = 0x0;
+ }
+
+ handle->rxFifoState = kFLEXCAN_StateIdle;
+}
+
+void FLEXCAN_TransferHandleIRQ(CAN_Type *base, flexcan_handle_t *handle)
+{
+ /* Assertion. */
+ assert(handle);
+
+ status_t status = kStatus_FLEXCAN_UnHandled;
+ uint32_t result;
+
+ /* Store Current FlexCAN Module Error and Status. */
+ result = base->ESR1;
+
+ do
+ {
+ /* Solve FlexCAN Error and Status Interrupt. */
+ if (result & (kFLEXCAN_TxWarningIntFlag | kFLEXCAN_RxWarningIntFlag | kFLEXCAN_BusOffIntFlag |
+ kFLEXCAN_ErrorIntFlag | kFLEXCAN_WakeUpIntFlag))
+ {
+ status = kStatus_FLEXCAN_ErrorStatus;
+
+ /* Clear FlexCAN Error and Status Interrupt. */
+ FLEXCAN_ClearStatusFlags(base, kFLEXCAN_TxWarningIntFlag | kFLEXCAN_RxWarningIntFlag |
+ kFLEXCAN_BusOffIntFlag | kFLEXCAN_ErrorIntFlag | kFLEXCAN_WakeUpIntFlag);
+ }
+ /* Solve FlexCAN Rx FIFO & Message Buffer Interrupt. */
+ else
+ {
+ /* For this implementation, we solve the Message with lowest MB index first. */
+ for (result = 0; result < FSL_FEATURE_FLEXCAN_HAS_MESSAGE_BUFFER_MAX_NUMBERn(base); result++)
+ {
+ /* Get the lowest unhandled Message Buffer */
+ if ((FLEXCAN_GetMbStatusFlags(base, 1 << result)) && (FLEXCAN_IsMbIntEnabled(base, result)))
+ {
+ break;
+ }
+ }
+
+ /* Does not find Message to deal with. */
+ if (result == FSL_FEATURE_FLEXCAN_HAS_MESSAGE_BUFFER_MAX_NUMBERn(base))
+ {
+ break;
+ }
+
+ /* Solve Rx FIFO interrupt. */
+ if ((kFLEXCAN_StateIdle != handle->rxFifoState) && ((1 << result) <= kFLEXCAN_RxFifoOverflowFlag))
+ {
+ switch (1 << result)
+ {
+ case kFLEXCAN_RxFifoOverflowFlag:
+ status = kStatus_FLEXCAN_RxFifoOverflow;
+ break;
+
+ case kFLEXCAN_RxFifoWarningFlag:
+ status = kStatus_FLEXCAN_RxFifoWarning;
+ break;
+
+ case kFLEXCAN_RxFifoFrameAvlFlag:
+ status = FLEXCAN_ReadRxFifo(base, handle->rxFifoFrameBuf);
+ if (kStatus_Success == status)
+ {
+ status = kStatus_FLEXCAN_RxFifoIdle;
+ }
+ FLEXCAN_TransferAbortReceiveFifo(base, handle);
+ break;
+
+ default:
+ status = kStatus_FLEXCAN_UnHandled;
+ break;
+ }
+ }
+ else
+ {
+ /* Get current State of Message Buffer. */
+ switch (handle->mbState[result])
+ {
+ /* Solve Rx Data Frame. */
+ case kFLEXCAN_StateRxData:
+ status = FLEXCAN_ReadRxMb(base, result, handle->mbFrameBuf[result]);
+ if (kStatus_Success == status)
+ {
+ status = kStatus_FLEXCAN_RxIdle;
+ }
+ FLEXCAN_TransferAbortReceive(base, handle, result);
+ break;
+
+ /* Solve Rx Remote Frame. */
+ case kFLEXCAN_StateRxRemote:
+ status = FLEXCAN_ReadRxMb(base, result, handle->mbFrameBuf[result]);
+ if (kStatus_Success == status)
+ {
+ status = kStatus_FLEXCAN_RxIdle;
+ }
+ FLEXCAN_TransferAbortReceive(base, handle, result);
+ break;
+
+ /* Solve Tx Data Frame. */
+ case kFLEXCAN_StateTxData:
+ status = kStatus_FLEXCAN_TxIdle;
+ FLEXCAN_TransferAbortSend(base, handle, result);
+ break;
+
+ /* Solve Tx Remote Frame. */
+ case kFLEXCAN_StateTxRemote:
+ handle->mbState[result] = kFLEXCAN_StateRxRemote;
+ status = kStatus_FLEXCAN_TxSwitchToRx;
+ break;
+
+ default:
+ status = kStatus_FLEXCAN_UnHandled;
+ break;
+ }
+ }
+
+ /* Clear resolved Message Buffer IRQ. */
+ FLEXCAN_ClearMbStatusFlags(base, 1 << result);
+ }
+
+ /* Calling Callback Function if has one. */
+ if (handle->callback != NULL)
+ {
+ handle->callback(base, handle, status, result, handle->userData);
+ }
+
+ /* Reset return status */
+ status = kStatus_FLEXCAN_UnHandled;
+
+ /* Store Current FlexCAN Module Error and Status. */
+ result = base->ESR1;
+ }
+#if (defined(FSL_FEATURE_FLEXCAN_HAS_EXTENDED_FLAG_REGISTER)) && (FSL_FEATURE_FLEXCAN_HAS_EXTENDED_FLAG_REGISTER > 0)
+ while ((0 != FLEXCAN_GetMbStatusFlags(base, 0xFFFFFFFFFFFFFFFFU)) ||
+ (0 != (result & (kFLEXCAN_TxWarningIntFlag | kFLEXCAN_RxWarningIntFlag | kFLEXCAN_BusOffIntFlag |
+ kFLEXCAN_ErrorIntFlag | kFLEXCAN_WakeUpIntFlag))));
+#else
+ while ((0 != FLEXCAN_GetMbStatusFlags(base, 0xFFFFFFFFU)) ||
+ (0 != (result & (kFLEXCAN_TxWarningIntFlag | kFLEXCAN_RxWarningIntFlag | kFLEXCAN_BusOffIntFlag |
+ kFLEXCAN_ErrorIntFlag | kFLEXCAN_WakeUpIntFlag))));
+#endif
+}
+
+#if (FSL_FEATURE_SOC_FLEXCAN_COUNT > 0)
+void CAN0_DriverIRQHandler(void)
+{
+ assert(s_flexcanHandle[0]);
+
+ s_flexcanIsr(CAN0, s_flexcanHandle[0]);
+}
+#endif
+
+#if (FSL_FEATURE_SOC_FLEXCAN_COUNT > 1)
+void CAN1_DriverIRQHandler(void)
+{
+ assert(s_flexcanHandle[1]);
+
+ s_flexcanIsr(CAN1, s_flexcanHandle[1]);
+}
+#endif
+
+#if (FSL_FEATURE_SOC_FLEXCAN_COUNT > 2)
+void CAN2_DriverIRQHandler(void)
+{
+ assert(s_flexcanHandle[2]);
+
+ s_flexcanIsr(CAN2, s_flexcanHandle[2]);
+}
+#endif
+
+#if (FSL_FEATURE_SOC_FLEXCAN_COUNT > 3)
+void CAN3_DriverIRQHandler(void)
+{
+ assert(s_flexcanHandle[3]);
+
+ s_flexcanIsr(CAN3, s_flexcanHandle[3]);
+}
+#endif
+
+#if (FSL_FEATURE_SOC_FLEXCAN_COUNT > 4)
+void CAN4_DriverIRQHandler(void)
+{
+ assert(s_flexcanHandle[4]);
+
+ s_flexcanIsr(CAN4, s_flexcanHandle[4]);
+}
+#endif
diff --git a/drivers/fsl_flexcan.h b/drivers/fsl_flexcan.h
new file mode 100644
index 0000000..203212e
--- /dev/null
+++ b/drivers/fsl_flexcan.h
@@ -0,0 +1,1052 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_FLEXCAN_H_
+#define _FSL_FLEXCAN_H_
+
+#include "fsl_common.h"
+
+/*!
+ * @addtogroup flexcan_driver
+ * @{
+ */
+
+
+/******************************************************************************
+ * Definitions
+ *****************************************************************************/
+
+/*! @name Driver version */
+/*@{*/
+/*! @brief FlexCAN driver version 2.1.0. */
+#define FLEXCAN_DRIVER_VERSION (MAKE_VERSION(2, 1, 0))
+/*@}*/
+
+/*! @brief FlexCAN Frame ID helper macro. */
+#define FLEXCAN_ID_STD(id) \
+ (((uint32_t)(((uint32_t)(id)) << CAN_ID_STD_SHIFT)) & CAN_ID_STD_MASK) /*!< Standard Frame ID helper macro. */
+#define FLEXCAN_ID_EXT(id) \
+ (((uint32_t)(((uint32_t)(id)) << CAN_ID_EXT_SHIFT)) & \
+ (CAN_ID_EXT_MASK | CAN_ID_STD_MASK)) /*!< Extend Frame ID helper macro. */
+
+/*! @brief FlexCAN Rx Message Buffer Mask helper macro. */
+#define FLEXCAN_RX_MB_STD_MASK(id, rtr, ide) \
+ (((uint32_t)((uint32_t)(rtr) << 31) | (uint32_t)((uint32_t)(ide) << 30)) | \
+ FLEXCAN_ID_STD(id)) /*!< Standard Rx Message Buffer Mask helper macro. */
+#define FLEXCAN_RX_MB_EXT_MASK(id, rtr, ide) \
+ (((uint32_t)((uint32_t)(rtr) << 31) | (uint32_t)((uint32_t)(ide) << 30)) | \
+ FLEXCAN_ID_EXT(id)) /*!< Extend Rx Message Buffer Mask helper macro. */
+
+/*! @brief FlexCAN Rx FIFO Mask helper macro. */
+#define FLEXCAN_RX_FIFO_STD_MASK_TYPE_A(id, rtr, ide) \
+ (((uint32_t)((uint32_t)(rtr) << 31) | (uint32_t)((uint32_t)(ide) << 30)) | \
+ (FLEXCAN_ID_STD(id) << 1)) /*!< Standard Rx FIFO Mask helper macro Type A helper macro. */
+#define FLEXCAN_RX_FIFO_STD_MASK_TYPE_B_HIGH(id, rtr, ide) \
+ (((uint32_t)((uint32_t)(rtr) << 31) | (uint32_t)((uint32_t)(ide) << 30)) | \
+ (FLEXCAN_ID_STD(id) << 16)) /*!< Standard Rx FIFO Mask helper macro Type B upper part helper macro. */
+#define FLEXCAN_RX_FIFO_STD_MASK_TYPE_B_LOW(id, rtr, ide) \
+ (((uint32_t)((uint32_t)(rtr) << 15) | (uint32_t)((uint32_t)(ide) << 14)) | \
+ FLEXCAN_ID_STD(id)) /*!< Standard Rx FIFO Mask helper macro Type B lower part helper macro. */
+#define FLEXCAN_RX_FIFO_STD_MASK_TYPE_C_HIGH(id) \
+ ((FLEXCAN_ID_STD(id) & 0x7F8) << 21) /*!< Standard Rx FIFO Mask helper macro Type C upper part helper macro. */
+#define FLEXCAN_RX_FIFO_STD_MASK_TYPE_C_MID_HIGH(id) \
+ ((FLEXCAN_ID_STD(id) & 0x7F8) << 13) /*!< Standard Rx FIFO Mask helper macro Type C mid-upper part helper macro. \
+ */
+#define FLEXCAN_RX_FIFO_STD_MASK_TYPE_C_MID_LOW(id) \
+ ((FLEXCAN_ID_STD(id) & 0x7F8) << 5) /*!< Standard Rx FIFO Mask helper macro Type C mid-lower part helper macro. */
+#define FLEXCAN_RX_FIFO_STD_MASK_TYPE_C_LOW(id) \
+ ((FLEXCAN_ID_STD(id) & 0x7F8) >> 3) /*!< Standard Rx FIFO Mask helper macro Type C lower part helper macro. */
+#define FLEXCAN_RX_FIFO_EXT_MASK_TYPE_A(id, rtr, ide) \
+ (((uint32_t)((uint32_t)(rtr) << 31) | (uint32_t)((uint32_t)(ide) << 30)) | \
+ (FLEXCAN_ID_EXT(id) << 1)) /*!< Extend Rx FIFO Mask helper macro Type A helper macro. */
+#define FLEXCAN_RX_FIFO_EXT_MASK_TYPE_B_HIGH(id, rtr, ide) \
+ ( \
+ ((uint32_t)((uint32_t)(rtr) << 31) | (uint32_t)((uint32_t)(ide) << 30)) | \
+ ((FLEXCAN_ID_EXT(id) & 0x1FFF8000) \
+ << 1)) /*!< Extend Rx FIFO Mask helper macro Type B upper part helper macro. */
+#define FLEXCAN_RX_FIFO_EXT_MASK_TYPE_B_LOW(id, rtr, ide) \
+ (((uint32_t)((uint32_t)(rtr) << 15) | (uint32_t)((uint32_t)(ide) << 14)) | \
+ ((FLEXCAN_ID_EXT(id) & 0x1FFF8000) >> \
+ 15)) /*!< Extend Rx FIFO Mask helper macro Type B lower part helper macro. */
+#define FLEXCAN_RX_FIFO_EXT_MASK_TYPE_C_HIGH(id) \
+ ((FLEXCAN_ID_EXT(id) & 0x1FE00000) << 3) /*!< Extend Rx FIFO Mask helper macro Type C upper part helper macro. */
+#define FLEXCAN_RX_FIFO_EXT_MASK_TYPE_C_MID_HIGH(id) \
+ ((FLEXCAN_ID_EXT(id) & 0x1FE00000) >> \
+ 5) /*!< Extend Rx FIFO Mask helper macro Type C mid-upper part helper macro. */
+#define FLEXCAN_RX_FIFO_EXT_MASK_TYPE_C_MID_LOW(id) \
+ ((FLEXCAN_ID_EXT(id) & 0x1FE00000) >> \
+ 13) /*!< Extend Rx FIFO Mask helper macro Type C mid-lower part helper macro. */
+#define FLEXCAN_RX_FIFO_EXT_MASK_TYPE_C_LOW(id) \
+ ((FLEXCAN_ID_EXT(id) & 0x1FE00000) >> 21) /*!< Extend Rx FIFO Mask helper macro Type C lower part helper macro. */
+
+/*! @brief FlexCAN Rx FIFO Filter helper macro. */
+#define FLEXCAN_RX_FIFO_STD_FILTER_TYPE_A(id, rtr, ide) \
+ FLEXCAN_RX_FIFO_STD_MASK_TYPE_A(id, rtr, ide) /*!< Standard Rx FIFO Filter helper macro Type A helper macro. */
+#define FLEXCAN_RX_FIFO_STD_FILTER_TYPE_B_HIGH(id, rtr, ide) \
+ FLEXCAN_RX_FIFO_STD_MASK_TYPE_B_HIGH( \
+ id, rtr, ide) /*!< Standard Rx FIFO Filter helper macro Type B upper part helper macro. */
+#define FLEXCAN_RX_FIFO_STD_FILTER_TYPE_B_LOW(id, rtr, ide) \
+ FLEXCAN_RX_FIFO_STD_MASK_TYPE_B_LOW( \
+ id, rtr, ide) /*!< Standard Rx FIFO Filter helper macro Type B lower part helper macro. */
+#define FLEXCAN_RX_FIFO_STD_FILTER_TYPE_C_HIGH(id) \
+ FLEXCAN_RX_FIFO_STD_MASK_TYPE_C_HIGH( \
+ id) /*!< Standard Rx FIFO Filter helper macro Type C upper part helper macro. */
+#define FLEXCAN_RX_FIFO_STD_FILTER_TYPE_C_MID_HIGH(id) \
+ FLEXCAN_RX_FIFO_STD_MASK_TYPE_C_MID_HIGH( \
+ id) /*!< Standard Rx FIFO Filter helper macro Type C mid-upper part helper macro. */
+#define FLEXCAN_RX_FIFO_STD_FILTER_TYPE_C_MID_LOW(id) \
+ FLEXCAN_RX_FIFO_STD_MASK_TYPE_C_MID_LOW( \
+ id) /*!< Standard Rx FIFO Filter helper macro Type C mid-lower part helper macro. */
+#define FLEXCAN_RX_FIFO_STD_FILTER_TYPE_C_LOW(id) \
+ FLEXCAN_RX_FIFO_STD_MASK_TYPE_C_LOW(id) /*!< Standard Rx FIFO Filter helper macro Type C lower part helper macro. \
+ */
+#define FLEXCAN_RX_FIFO_EXT_FILTER_TYPE_A(id, rtr, ide) \
+ FLEXCAN_RX_FIFO_EXT_MASK_TYPE_A(id, rtr, ide) /*!< Extend Rx FIFO Filter helper macro Type A helper macro. */
+#define FLEXCAN_RX_FIFO_EXT_FILTER_TYPE_B_HIGH(id, rtr, ide) \
+ FLEXCAN_RX_FIFO_EXT_MASK_TYPE_B_HIGH( \
+ id, rtr, ide) /*!< Extend Rx FIFO Filter helper macro Type B upper part helper macro. */
+#define FLEXCAN_RX_FIFO_EXT_FILTER_TYPE_B_LOW(id, rtr, ide) \
+ FLEXCAN_RX_FIFO_EXT_MASK_TYPE_B_LOW( \
+ id, rtr, ide) /*!< Extend Rx FIFO Filter helper macro Type B lower part helper macro. */
+#define FLEXCAN_RX_FIFO_EXT_FILTER_TYPE_C_HIGH(id) \
+ FLEXCAN_RX_FIFO_EXT_MASK_TYPE_C_HIGH(id) /*!< Extend Rx FIFO Filter helper macro Type C upper part helper macro. \
+ */
+#define FLEXCAN_RX_FIFO_EXT_FILTER_TYPE_C_MID_HIGH(id) \
+ FLEXCAN_RX_FIFO_EXT_MASK_TYPE_C_MID_HIGH( \
+ id) /*!< Extend Rx FIFO Filter helper macro Type C mid-upper part helper macro. */
+#define FLEXCAN_RX_FIFO_EXT_FILTER_TYPE_C_MID_LOW(id) \
+ FLEXCAN_RX_FIFO_EXT_MASK_TYPE_C_MID_LOW( \
+ id) /*!< Extend Rx FIFO Filter helper macro Type C mid-lower part helper macro. */
+#define FLEXCAN_RX_FIFO_EXT_FILTER_TYPE_C_LOW(id) \
+ FLEXCAN_RX_FIFO_EXT_MASK_TYPE_C_LOW(id) /*!< Extend Rx FIFO Filter helper macro Type C lower part helper macro. */
+
+/*! @brief FlexCAN transfer status. */
+enum _flexcan_status
+{
+ kStatus_FLEXCAN_TxBusy = MAKE_STATUS(kStatusGroup_FLEXCAN, 0), /*!< Tx Message Buffer is Busy. */
+ kStatus_FLEXCAN_TxIdle = MAKE_STATUS(kStatusGroup_FLEXCAN, 1), /*!< Tx Message Buffer is Idle. */
+ kStatus_FLEXCAN_TxSwitchToRx = MAKE_STATUS(
+ kStatusGroup_FLEXCAN, 2), /*!< Remote Message is send out and Message buffer changed to Receive one. */
+ kStatus_FLEXCAN_RxBusy = MAKE_STATUS(kStatusGroup_FLEXCAN, 3), /*!< Rx Message Buffer is Busy. */
+ kStatus_FLEXCAN_RxIdle = MAKE_STATUS(kStatusGroup_FLEXCAN, 4), /*!< Rx Message Buffer is Idle. */
+ kStatus_FLEXCAN_RxOverflow = MAKE_STATUS(kStatusGroup_FLEXCAN, 5), /*!< Rx Message Buffer is Overflowed. */
+ kStatus_FLEXCAN_RxFifoBusy = MAKE_STATUS(kStatusGroup_FLEXCAN, 6), /*!< Rx Message FIFO is Busy. */
+ kStatus_FLEXCAN_RxFifoIdle = MAKE_STATUS(kStatusGroup_FLEXCAN, 7), /*!< Rx Message FIFO is Idle. */
+ kStatus_FLEXCAN_RxFifoOverflow = MAKE_STATUS(kStatusGroup_FLEXCAN, 8), /*!< Rx Message FIFO is overflowed. */
+ kStatus_FLEXCAN_RxFifoWarning = MAKE_STATUS(kStatusGroup_FLEXCAN, 0), /*!< Rx Message FIFO is almost overflowed. */
+ kStatus_FLEXCAN_ErrorStatus = MAKE_STATUS(kStatusGroup_FLEXCAN, 10), /*!< FlexCAN Module Error and Status. */
+ kStatus_FLEXCAN_UnHandled = MAKE_STATUS(kStatusGroup_FLEXCAN, 11), /*!< UnHadled Interrupt asserted. */
+};
+
+/*! @brief FlexCAN frame format. */
+typedef enum _flexcan_frame_format
+{
+ kFLEXCAN_FrameFormatStandard = 0x0U, /*!< Standard frame format attribute. */
+ kFLEXCAN_FrameFormatExtend = 0x1U, /*!< Extend frame format attribute. */
+} flexcan_frame_format_t;
+
+/*! @brief FlexCAN frame type. */
+typedef enum _flexcan_frame_type
+{
+ kFLEXCAN_FrameTypeData = 0x0U, /*!< Data frame type attribute. */
+ kFLEXCAN_FrameTypeRemote = 0x1U, /*!< Remote frame type attribute. */
+} flexcan_frame_type_t;
+
+/*! @brief FlexCAN clock source. */
+typedef enum _flexcan_clock_source
+{
+ kFLEXCAN_ClkSrcOsc = 0x0U, /*!< FlexCAN Protocol Engine clock from Oscillator. */
+ kFLEXCAN_ClkSrcPeri = 0x1U, /*!< FlexCAN Protocol Engine clock from Peripheral Clock. */
+} flexcan_clock_source_t;
+
+/*! @brief FlexCAN Rx Fifo Filter type. */
+typedef enum _flexcan_rx_fifo_filter_type
+{
+ kFLEXCAN_RxFifoFilterTypeA = 0x0U, /*!< One full ID (standard and extended) per ID Filter element. */
+ kFLEXCAN_RxFifoFilterTypeB =
+ 0x1U, /*!< Two full standard IDs or two partial 14-bit ID slices per ID Filter Table element. */
+ kFLEXCAN_RxFifoFilterTypeC =
+ 0x2U, /*!< Four partial 8-bit Standard or extended ID slices per ID Filter Table element. */
+ kFLEXCAN_RxFifoFilterTypeD = 0x3U, /*!< All frames rejected. */
+} flexcan_rx_fifo_filter_type_t;
+
+/*!
+ * @brief FlexCAN Rx FIFO priority
+ *
+ * The matching process starts from the Rx MB(or Rx FIFO) with higher priority.
+ * If no MB(or Rx FIFO filter) is satisfied, the matching process goes on with
+ * the Rx FIFO(or Rx MB) with lower priority.
+ */
+typedef enum _flexcan_rx_fifo_priority
+{
+ kFLEXCAN_RxFifoPrioLow = 0x0U, /*!< Matching process start from Rx Message Buffer first*/
+ kFLEXCAN_RxFifoPrioHigh = 0x1U, /*!< Matching process start from Rx FIFO first*/
+} flexcan_rx_fifo_priority_t;
+
+/*!
+ * @brief FlexCAN interrupt configuration structure, default settings all disabled.
+ *
+ * This structure contains the settings for all of the FlexCAN Module interrupt configurations.
+ * Note: FlexCAN Message Buffers and Rx FIFO have their own interrupts.
+ */
+enum _flexcan_interrupt_enable
+{
+ kFLEXCAN_BusOffInterruptEnable = CAN_CTRL1_BOFFMSK_MASK, /*!< Bus Off interrupt. */
+ kFLEXCAN_ErrorInterruptEnable = CAN_CTRL1_ERRMSK_MASK, /*!< Error interrupt. */
+ kFLEXCAN_RxWarningInterruptEnable = CAN_CTRL1_RWRNMSK_MASK, /*!< Rx Warning interrupt. */
+ kFLEXCAN_TxWarningInterruptEnable = CAN_CTRL1_TWRNMSK_MASK, /*!< Tx Warning interrupt. */
+ kFLEXCAN_WakeUpInterruptEnable = CAN_MCR_WAKMSK_MASK, /*!< Wake Up interrupt. */
+};
+
+/*!
+ * @brief FlexCAN status flags.
+ *
+ * This provides constants for the FlexCAN status flags for use in the FlexCAN functions.
+ * Note: The CPU read action clears FlEXCAN_ErrorFlag, therefore user need to
+ * read FlEXCAN_ErrorFlag and distinguish which error is occur using
+ * @ref _flexcan_error_flags enumerations.
+ */
+enum _flexcan_flags
+{
+ kFLEXCAN_SynchFlag = CAN_ESR1_SYNCH_MASK, /*!< CAN Synchronization Status. */
+ kFLEXCAN_TxWarningIntFlag = CAN_ESR1_TWRNINT_MASK, /*!< Tx Warning Interrupt Flag. */
+ kFLEXCAN_RxWarningIntFlag = CAN_ESR1_RWRNINT_MASK, /*!< Rx Warning Interrupt Flag. */
+ kFLEXCAN_TxErrorWarningFlag = CAN_ESR1_TXWRN_MASK, /*!< Tx Error Warning Status. */
+ kFLEXCAN_RxErrorWarningFlag = CAN_ESR1_RXWRN_MASK, /*!< Rx Error Warning Status. */
+ kFLEXCAN_IdleFlag = CAN_ESR1_IDLE_MASK, /*!< CAN IDLE Status Flag. */
+ kFLEXCAN_FaultConfinementFlag = CAN_ESR1_FLTCONF_MASK, /*!< Fault Confinement State Flag. */
+ kFLEXCAN_TransmittingFlag = CAN_ESR1_TX_MASK, /*!< FlexCAN In Transmission Status. */
+ kFLEXCAN_ReceivingFlag = CAN_ESR1_RX_MASK, /*!< FlexCAN In Reception Status. */
+ kFLEXCAN_BusOffIntFlag = CAN_ESR1_BOFFINT_MASK, /*!< Bus Off Interrupt Flag. */
+ kFLEXCAN_ErrorIntFlag = CAN_ESR1_ERRINT_MASK, /*!< Error Interrupt Flag. */
+ kFLEXCAN_WakeUpIntFlag = CAN_ESR1_WAKINT_MASK, /*!< Wake-Up Interrupt Flag. */
+ kFLEXCAN_ErrorFlag = CAN_ESR1_BIT1ERR_MASK | /*!< All FlexCAN Error Status. */
+ CAN_ESR1_BIT0ERR_MASK |
+ CAN_ESR1_ACKERR_MASK | CAN_ESR1_CRCERR_MASK | CAN_ESR1_FRMERR_MASK | CAN_ESR1_STFERR_MASK,
+};
+
+/*!
+ * @brief FlexCAN error status flags.
+ *
+ * The FlexCAN Error Status enumerations is used to report current error of the FlexCAN bus.
+ * This enumerations should be used with KFLEXCAN_ErrorFlag in @ref _flexcan_flags enumerations
+ * to ditermine which error is generated.
+ */
+enum _flexcan_error_flags
+{
+ kFLEXCAN_StuffingError = CAN_ESR1_STFERR_MASK, /*!< Stuffing Error. */
+ kFLEXCAN_FormError = CAN_ESR1_FRMERR_MASK, /*!< Form Error. */
+ kFLEXCAN_CrcError = CAN_ESR1_CRCERR_MASK, /*!< Cyclic Redundancy Check Error. */
+ kFLEXCAN_AckError = CAN_ESR1_ACKERR_MASK, /*!< Received no ACK on transmission. */
+ kFLEXCAN_Bit0Error = CAN_ESR1_BIT0ERR_MASK, /*!< Unable to send dominant bit. */
+ kFLEXCAN_Bit1Error = CAN_ESR1_BIT1ERR_MASK, /*!< Unable to send recessive bit. */
+};
+
+/*!
+ * @brief FlexCAN Rx FIFO status flags.
+ *
+ * The FlexCAN Rx FIFO Status enumerations are used to determine the status of the
+ * Rx FIFO. Because Rx FIFO occupy the MB0 ~ MB7 (Rx Fifo filter also occupies
+ * more Message Buffer space), Rx FIFO status flags are mapped to the corresponding
+ * Message Buffer status flags.
+ */
+enum _flexcan_rx_fifo_flags
+{
+ kFLEXCAN_RxFifoOverflowFlag = CAN_IFLAG1_BUF7I_MASK, /*!< Rx FIFO overflow flag. */
+ kFLEXCAN_RxFifoWarningFlag = CAN_IFLAG1_BUF6I_MASK, /*!< Rx FIFO almost full flag. */
+ kFLEXCAN_RxFifoFrameAvlFlag = CAN_IFLAG1_BUF5I_MASK, /*!< Frames available in Rx FIFO flag. */
+};
+
+#if defined(__CC_ARM)
+#pragma anon_unions
+#endif
+/*! @brief FlexCAN message frame structure. */
+typedef struct _flexcan_frame
+{
+ struct
+ {
+ uint32_t timestamp : 16; /*!< FlexCAN internal Free-Running Counter Time Stamp. */
+ uint32_t length : 4; /*!< CAN frame payload length in bytes(Range: 0~8). */
+ uint32_t type : 1; /*!< CAN Frame Type(DATA or REMOTE). */
+ uint32_t format : 1; /*!< CAN Frame Identifier(STD or EXT format). */
+ uint32_t reserve1 : 1; /*!< Reserved for placeholder. */
+ uint32_t idhit : 9; /*!< CAN Rx FIFO filter hit id(This value is only used in Rx FIFO receive mode). */
+ };
+ struct
+ {
+ uint32_t id : 29; /*!< CAN Frame Identifier, should be set using FLEXCAN_ID_EXT() or FLEXCAN_ID_STD() macro. */
+ uint32_t reserve2 : 3; /*!< Reserved for place holder. */
+ };
+ union
+ {
+ struct
+ {
+ uint32_t dataWord0; /*!< CAN Frame payload word0. */
+ uint32_t dataWord1; /*!< CAN Frame payload word1. */
+ };
+ struct
+ {
+ uint8_t dataByte3; /*!< CAN Frame payload byte3. */
+ uint8_t dataByte2; /*!< CAN Frame payload byte2. */
+ uint8_t dataByte1; /*!< CAN Frame payload byte1. */
+ uint8_t dataByte0; /*!< CAN Frame payload byte0. */
+ uint8_t dataByte7; /*!< CAN Frame payload byte7. */
+ uint8_t dataByte6; /*!< CAN Frame payload byte6. */
+ uint8_t dataByte5; /*!< CAN Frame payload byte5. */
+ uint8_t dataByte4; /*!< CAN Frame payload byte4. */
+ };
+ };
+} flexcan_frame_t;
+
+/*! @brief FlexCAN module configuration structure. */
+typedef struct _flexcan_config
+{
+ uint32_t baudRate; /*!< FlexCAN baud rate in bps. */
+ flexcan_clock_source_t clkSrc; /*!< Clock source for FlexCAN Protocol Engine. */
+ uint8_t maxMbNum; /*!< The maximum number of Message Buffers used by user. */
+ bool enableLoopBack; /*!< Enable or Disable Loop Back Self Test Mode. */
+ bool enableSelfWakeup; /*!< Enable or Disable Self Wakeup Mode. */
+ bool enableIndividMask; /*!< Enable or Disable Rx Individual Mask. */
+#if (defined(FSL_FEATURE_FLEXCAN_HAS_DOZE_MODE_SUPPORT) && FSL_FEATURE_FLEXCAN_HAS_DOZE_MODE_SUPPORT)
+ bool enableDoze; /*!< Enable or Disable Doze Mode. */
+#endif
+} flexcan_config_t;
+
+/*! @brief FlexCAN protocol timing characteristic configuration structure. */
+typedef struct _flexcan_timing_config
+{
+ uint8_t preDivider; /*!< Clock Pre-scaler Division Factor. */
+ uint8_t rJumpwidth; /*!< Re-sync Jump Width. */
+ uint8_t phaseSeg1; /*!< Phase Segment 1. */
+ uint8_t phaseSeg2; /*!< Phase Segment 2. */
+ uint8_t propSeg; /*!< Propagation Segment. */
+} flexcan_timing_config_t;
+
+/*!
+ * @brief FlexCAN Receive Message Buffer configuration structure
+ *
+ * This structure is used as the parameter of FLEXCAN_SetRxMbConfig() function.
+ * The FLEXCAN_SetRxMbConfig() function is used to configure FlexCAN Receive
+ * Message Buffer. The function abort previous receiving process, clean the
+ * Message Buffer and activate the Rx Message Buffer using given Message Buffer
+ * setting.
+ */
+typedef struct _flexcan_rx_mb_config
+{
+ uint32_t id; /*!< CAN Message Buffer Frame Identifier, should be set using
+ FLEXCAN_ID_EXT() or FLEXCAN_ID_STD() macro. */
+ flexcan_frame_format_t format; /*!< CAN Frame Identifier format(Standard of Extend). */
+ flexcan_frame_type_t type; /*!< CAN Frame Type(Data or Remote). */
+} flexcan_rx_mb_config_t;
+
+/*! @brief FlexCAN Rx FIFO configure structure. */
+typedef struct _flexcan_rx_fifo_config
+{
+ uint32_t *idFilterTable; /*!< Pointer to FlexCAN Rx FIFO identifier filter table. */
+ uint8_t idFilterNum; /*!< The quantity of filter elements. */
+ flexcan_rx_fifo_filter_type_t idFilterType; /*!< The FlexCAN Rx FIFO Filter type. */
+ flexcan_rx_fifo_priority_t priority; /*!< The FlexCAN Rx FIFO receive priority. */
+} flexcan_rx_fifo_config_t;
+
+/*! @brief FlexCAN Message Buffer transfer. */
+typedef struct _flexcan_mb_transfer
+{
+ flexcan_frame_t *frame; /*!< The buffer of CAN Message to be transfer. */
+ uint8_t mbIdx; /*!< The index of Message buffer used to transfer Message. */
+} flexcan_mb_transfer_t;
+
+/*! @brief FlexCAN Rx FIFO transfer. */
+typedef struct _flexcan_fifo_transfer
+{
+ flexcan_frame_t *frame; /*!< The buffer of CAN Message to be received from Rx FIFO. */
+} flexcan_fifo_transfer_t;
+
+/*! @brief FlexCAN handle structure definition. */
+typedef struct _flexcan_handle flexcan_handle_t;
+
+/*! @brief FlexCAN transfer callback function.
+ *
+ * The FlexCAN transfer callback returns a value from the underlying layer.
+ * If the status equals to kStatus_FLEXCAN_ErrorStatus, the result parameter is the Content of
+ * FlexCAN status register which can be used to get the working status(or error status) of FlexCAN module.
+ * If the status equals to other FlexCAN Message Buffer transfer status, the result is the index of
+ * Message Buffer that generate transfer event.
+ * If the status equals to other FlexCAN Message Buffer transfer status, the result is meaningless and should be
+ * Ignored.
+ */
+typedef void (*flexcan_transfer_callback_t)(
+ CAN_Type *base, flexcan_handle_t *handle, status_t status, uint32_t result, void *userData);
+
+/*! @brief FlexCAN handle structure. */
+struct _flexcan_handle
+{
+ flexcan_transfer_callback_t callback; /*!< Callback function. */
+ void *userData; /*!< FlexCAN callback function parameter.*/
+ flexcan_frame_t *volatile mbFrameBuf[CAN_WORD1_COUNT];
+ /*!< The buffer for received data from Message Buffers. */
+ flexcan_frame_t *volatile rxFifoFrameBuf; /*!< The buffer for received data from Rx FIFO. */
+ volatile uint8_t mbState[CAN_WORD1_COUNT]; /*!< Message Buffer transfer state. */
+ volatile uint8_t rxFifoState; /*!< Rx FIFO transfer state. */
+};
+
+/******************************************************************************
+ * API
+ *****************************************************************************/
+
+#if defined(__cplusplus)
+extern "C" {
+#endif
+
+/*!
+ * @name Initialization and deinitialization
+ * @{
+ */
+
+/*!
+ * @brief Initializes a FlexCAN instance.
+ *
+ * This function initializes the FlexCAN module with user-defined settings.
+ * This example shows how to set up the flexcan_config_t parameters and how
+ * to call the FLEXCAN_Init function by passing in these parameters:
+ * @code
+ * flexcan_config_t flexcanConfig;
+ * flexcanConfig.clkSrc = KFLEXCAN_ClkSrcOsc;
+ * flexcanConfig.baudRate = 125000U;
+ * flexcanConfig.maxMbNum = 16;
+ * flexcanConfig.enableLoopBack = false;
+ * flexcanConfig.enableSelfWakeup = false;
+ * flexcanConfig.enableIndividMask = false;
+ * flexcanConfig.enableDoze = false;
+ * FLEXCAN_Init(CAN0, &flexcanConfig, 8000000UL);
+ * @endcode
+ *
+ * @param base FlexCAN peripheral base address.
+ * @param config Pointer to user-defined configuration structure.
+ * @param sourceClock_Hz FlexCAN Protocol Engine clock source frequency in Hz.
+ */
+void FLEXCAN_Init(CAN_Type *base, const flexcan_config_t *config, uint32_t sourceClock_Hz);
+
+/*!
+ * @brief De-initializes a FlexCAN instance.
+ *
+ * This function disable the FlexCAN module clock and set all register value
+ * to reset value.
+ *
+ * @param base FlexCAN peripheral base address.
+ */
+void FLEXCAN_Deinit(CAN_Type *base);
+
+/*!
+ * @brief Get the default configuration structure.
+ *
+ * This function initializes the FlexCAN configure structure to default value. The default
+ * value are:
+ * flexcanConfig->clkSrc = KFLEXCAN_ClkSrcOsc;
+ * flexcanConfig->baudRate = 125000U;
+ * flexcanConfig->maxMbNum = 16;
+ * flexcanConfig->enableLoopBack = false;
+ * flexcanConfig->enableSelfWakeup = false;
+ * flexcanConfig->enableIndividMask = false;
+ * flexcanConfig->enableDoze = false;
+ *
+ * @param config Pointer to FlexCAN configuration structure.
+ */
+void FLEXCAN_GetDefaultConfig(flexcan_config_t *config);
+
+/* @} */
+
+/*!
+ * @name Configuration.
+ * @{
+ */
+
+/*!
+ * @brief Sets the FlexCAN protocol timing characteristic.
+ *
+ * This function gives user settings to CAN bus timing characteristic.
+ * The function is for an experienced user. For less experienced users, call
+ * the FLEXCAN_Init() and fill the baud rate field with a desired value.
+ * This provides the default timing characteristics to the module.
+ *
+ * Note that calling FLEXCAN_SetTimingConfig() overrides the baud rate set
+ * in FLEXCAN_Init().
+ *
+ * @param base FlexCAN peripheral base address.
+ * @param config Pointer to the timing configuration structure.
+ */
+void FLEXCAN_SetTimingConfig(CAN_Type *base, const flexcan_timing_config_t *config);
+
+/*!
+ * @brief Sets the FlexCAN receive message buffer global mask.
+ *
+ * This function sets the global mask for FlexCAN message buffer in a matching process.
+ * The configuration is only effective when the Rx individual mask is disabled in the FLEXCAN_Init().
+ *
+ * @param base FlexCAN peripheral base address.
+ * @param mask Rx Message Buffer Global Mask value.
+ */
+void FLEXCAN_SetRxMbGlobalMask(CAN_Type *base, uint32_t mask);
+
+/*!
+ * @brief Sets the FlexCAN receive FIFO global mask.
+ *
+ * This function sets the global mask for FlexCAN FIFO in a matching process.
+ *
+ * @param base FlexCAN peripheral base address.
+ * @param mask Rx Fifo Global Mask value.
+ */
+void FLEXCAN_SetRxFifoGlobalMask(CAN_Type *base, uint32_t mask);
+
+/*!
+ * @brief Sets the FlexCAN receive individual mask.
+ *
+ * This function sets the individual mask for FlexCAN matching process.
+ * The configuration is only effective when the Rx individual mask is enabled in FLEXCAN_Init().
+ * If Rx FIFO is disabled, the individual mask is applied to the corresponding Message Buffer.
+ * If Rx FIFO is enabled, the individual mask for Rx FIFO occupied Message Buffer is applied to
+ * the Rx Filter with same index. What calls for special attention is that only the first 32
+ * individual masks can be used as Rx FIFO filter mask.
+ *
+ * @param base FlexCAN peripheral base address.
+ * @param maskIdx The Index of individual Mask.
+ * @param mask Rx Individual Mask value.
+ */
+void FLEXCAN_SetRxIndividualMask(CAN_Type *base, uint8_t maskIdx, uint32_t mask);
+
+/*!
+ * @brief Configures a FlexCAN transmit message buffer.
+ *
+ * This function aborts the previous transmission, cleans the Message Buffer, and
+ * configures it as a Transmit Message Buffer.
+ *
+ * @param base FlexCAN peripheral base address.
+ * @param mbIdx The Message Buffer index.
+ * @param enable Enable/Disable Tx Message Buffer.
+ * - true: Enable Tx Message Buffer.
+ * - false: Disable Tx Message Buffer.
+ */
+void FLEXCAN_SetTxMbConfig(CAN_Type *base, uint8_t mbIdx, bool enable);
+
+/*!
+ * @brief Configures a FlexCAN Receive Message Buffer.
+ *
+ * This function cleans a FlexCAN build-in Message Buffer and configures it
+ * as a Receive Message Buffer.
+ *
+ * @param base FlexCAN peripheral base address.
+ * @param mbIdx The Message Buffer index.
+ * @param config Pointer to FlexCAN Message Buffer configuration structure.
+ * @param enable Enable/Disable Rx Message Buffer.
+ * - true: Enable Rx Message Buffer.
+ * - false: Disable Rx Message Buffer.
+ */
+void FLEXCAN_SetRxMbConfig(CAN_Type *base, uint8_t mbIdx, const flexcan_rx_mb_config_t *config, bool enable);
+
+/*!
+ * @brief Configures the FlexCAN Rx FIFO.
+ *
+ * This function configures the Rx FIFO with given Rx FIFO configuration.
+ *
+ * @param base FlexCAN peripheral base address.
+ * @param config Pointer to FlexCAN Rx FIFO configuration structure.
+ * @param enable Enable/Disable Rx FIFO.
+ * - true: Enable Rx FIFO.
+ * - false: Disable Rx FIFO.
+ */
+void FLEXCAN_SetRxFifoConfig(CAN_Type *base, const flexcan_rx_fifo_config_t *config, bool enable);
+
+/* @} */
+
+/*!
+ * @name Status
+ * @{
+ */
+
+/*!
+ * @brief Gets the FlexCAN module interrupt flags.
+ *
+ * This function gets all FlexCAN status flags. The flags are returned as the logical
+ * OR value of the enumerators @ref _flexcan_flags. To check the specific status,
+ * compare the return value with enumerators in @ref _flexcan_flags.
+ *
+ * @param base FlexCAN peripheral base address.
+ * @return FlexCAN status flags which are ORed by the enumerators in the _flexcan_flags.
+ */
+static inline uint32_t FLEXCAN_GetStatusFlags(CAN_Type *base)
+{
+ return base->ESR1;
+}
+
+/*!
+ * @brief Clears status flags with the provided mask.
+ *
+ * This function clears the FlexCAN status flags with a provided mask. An automatically cleared flag
+ * can't be cleared by this function.
+ *
+ * @param base FlexCAN peripheral base address.
+ * @param mask The status flags to be cleared, it is logical OR value of @ref _flexcan_flags.
+ */
+static inline void FLEXCAN_ClearStatusFlags(CAN_Type *base, uint32_t mask)
+{
+ /* Write 1 to clear status flag. */
+ base->ESR1 = mask;
+}
+
+/*!
+ * @brief Gets the FlexCAN Bus Error Counter value.
+ *
+ * This function gets the FlexCAN Bus Error Counter value for both Tx and
+ * Rx direction. These values may be needed in the upper layer error handling.
+ *
+ * @param base FlexCAN peripheral base address.
+ * @param txErrBuf Buffer to store Tx Error Counter value.
+ * @param rxErrBuf Buffer to store Rx Error Counter value.
+ */
+static inline void FLEXCAN_GetBusErrCount(CAN_Type *base, uint8_t *txErrBuf, uint8_t *rxErrBuf)
+{
+ if (txErrBuf)
+ {
+ *txErrBuf = (uint8_t)((base->ECR & CAN_ECR_TXERRCNT_MASK) >> CAN_ECR_TXERRCNT_SHIFT);
+ }
+
+ if (rxErrBuf)
+ {
+ *rxErrBuf = (uint8_t)((base->ECR & CAN_ECR_RXERRCNT_MASK) >> CAN_ECR_RXERRCNT_SHIFT);
+ }
+}
+
+/*!
+ * @brief Gets the FlexCAN Message Buffer interrupt flags.
+ *
+ * This function gets the interrupt flags of a given Message Buffers.
+ *
+ * @param base FlexCAN peripheral base address.
+ * @param mask The ORed FlexCAN Message Buffer mask.
+ * @return The status of given Message Buffers.
+ */
+#if (defined(FSL_FEATURE_FLEXCAN_HAS_EXTENDED_FLAG_REGISTER)) && (FSL_FEATURE_FLEXCAN_HAS_EXTENDED_FLAG_REGISTER > 0)
+static inline uint64_t FLEXCAN_GetMbStatusFlags(CAN_Type *base, uint64_t mask)
+#else
+static inline uint32_t FLEXCAN_GetMbStatusFlags(CAN_Type *base, uint32_t mask)
+#endif
+{
+#if (defined(FSL_FEATURE_FLEXCAN_HAS_EXTENDED_FLAG_REGISTER)) && (FSL_FEATURE_FLEXCAN_HAS_EXTENDED_FLAG_REGISTER > 0)
+ return ((((uint64_t)base->IFLAG1) & mask) | ((((uint64_t)base->IFLAG2) << 32) & mask));
+#else
+ return (base->IFLAG1 & mask);
+#endif
+}
+
+/*!
+ * @brief Clears the FlexCAN Message Buffer interrupt flags.
+ *
+ * This function clears the interrupt flags of a given Message Buffers.
+ *
+ * @param base FlexCAN peripheral base address.
+ * @param mask The ORed FlexCAN Message Buffer mask.
+ */
+#if (defined(FSL_FEATURE_FLEXCAN_HAS_EXTENDED_FLAG_REGISTER)) && (FSL_FEATURE_FLEXCAN_HAS_EXTENDED_FLAG_REGISTER > 0)
+static inline void FLEXCAN_ClearMbStatusFlags(CAN_Type *base, uint64_t mask)
+#else
+static inline void FLEXCAN_ClearMbStatusFlags(CAN_Type *base, uint32_t mask)
+#endif
+{
+#if (defined(FSL_FEATURE_FLEXCAN_HAS_EXTENDED_FLAG_REGISTER)) && (FSL_FEATURE_FLEXCAN_HAS_EXTENDED_FLAG_REGISTER > 0)
+ base->IFLAG1 = (uint32_t)(mask & 0xFFFFFFFF);
+ base->IFLAG2 = (uint32_t)(mask >> 32);
+#else
+ base->IFLAG1 = mask;
+#endif
+}
+
+/* @} */
+
+/*!
+ * @name Interrupts
+ * @{
+ */
+
+/*!
+ * @brief Enables FlexCAN interrupts according to provided mask.
+ *
+ * This function enables the FlexCAN interrupts according to provided mask. The mask
+ * is a logical OR of enumeration members, see @ref _flexcan_interrupt_enable.
+ *
+ * @param base FlexCAN peripheral base address.
+ * @param mask The interrupts to enable. Logical OR of @ref _flexcan_interrupt_enable.
+ */
+static inline void FLEXCAN_EnableInterrupts(CAN_Type *base, uint32_t mask)
+{
+ /* Solve Wake Up Interrupt. */
+ if (mask & kFLEXCAN_WakeUpInterruptEnable)
+ {
+ base->MCR |= CAN_MCR_WAKMSK_MASK;
+ }
+
+ /* Solve others. */
+ base->CTRL1 |= (mask & (~((uint32_t)kFLEXCAN_WakeUpInterruptEnable)));
+}
+
+/*!
+ * @brief Disables FlexCAN interrupts according to provided mask.
+ *
+ * This function disables the FlexCAN interrupts according to provided mask. The mask
+ * is a logical OR of enumeration members, see @ref _flexcan_interrupt_enable.
+ *
+ * @param base FlexCAN peripheral base address.
+ * @param mask The interrupts to disable. Logical OR of @ref _flexcan_interrupt_enable.
+ */
+static inline void FLEXCAN_DisableInterrupts(CAN_Type *base, uint32_t mask)
+{
+ /* Solve Wake Up Interrupt. */
+ if (mask & kFLEXCAN_WakeUpInterruptEnable)
+ {
+ base->MCR &= ~CAN_MCR_WAKMSK_MASK;
+ }
+
+ /* Solve others. */
+ base->CTRL1 &= ~(mask & (~((uint32_t)kFLEXCAN_WakeUpInterruptEnable)));
+}
+
+/*!
+ * @brief Enables FlexCAN Message Buffer interrupts.
+ *
+ * This function enables the interrupts of given Message Buffers
+ *
+ * @param base FlexCAN peripheral base address.
+ * @param mask The ORed FlexCAN Message Buffer mask.
+ */
+#if (defined(FSL_FEATURE_FLEXCAN_HAS_EXTENDED_FLAG_REGISTER)) && (FSL_FEATURE_FLEXCAN_HAS_EXTENDED_FLAG_REGISTER > 0)
+static inline void FLEXCAN_EnableMbInterrupts(CAN_Type *base, uint64_t mask)
+#else
+static inline void FLEXCAN_EnableMbInterrupts(CAN_Type *base, uint32_t mask)
+#endif
+{
+#if (defined(FSL_FEATURE_FLEXCAN_HAS_EXTENDED_FLAG_REGISTER)) && (FSL_FEATURE_FLEXCAN_HAS_EXTENDED_FLAG_REGISTER > 0)
+ base->IMASK1 |= (uint32_t)(mask & 0xFFFFFFFF);
+ base->IMASK2 |= (uint32_t)(mask >> 32);
+#else
+ base->IMASK1 |= mask;
+#endif
+}
+
+/*!
+ * @brief Disables FlexCAN Message Buffer interrupts.
+ *
+ * This function disables the interrupts of given Message Buffers
+ *
+ * @param base FlexCAN peripheral base address.
+ * @param mask The ORed FlexCAN Message Buffer mask.
+ */
+#if (defined(FSL_FEATURE_FLEXCAN_HAS_EXTENDED_FLAG_REGISTER)) && (FSL_FEATURE_FLEXCAN_HAS_EXTENDED_FLAG_REGISTER > 0)
+static inline void FLEXCAN_DisableMbInterrupts(CAN_Type *base, uint64_t mask)
+#else
+static inline void FLEXCAN_DisableMbInterrupts(CAN_Type *base, uint32_t mask)
+#endif
+{
+#if (defined(FSL_FEATURE_FLEXCAN_HAS_EXTENDED_FLAG_REGISTER)) && (FSL_FEATURE_FLEXCAN_HAS_EXTENDED_FLAG_REGISTER > 0)
+ base->IMASK1 &= ~((uint32_t)(mask & 0xFFFFFFFF));
+ base->IMASK2 &= ~((uint32_t)(mask >> 32));
+#else
+ base->IMASK1 &= ~mask;
+#endif
+}
+
+/* @} */
+
+#if (defined(FSL_FEATURE_FLEXCAN_HAS_RX_FIFO_DMA) && FSL_FEATURE_FLEXCAN_HAS_RX_FIFO_DMA)
+/*!
+ * @name DMA Control
+ * @{
+ */
+
+/*!
+ * @brief Enables or disables the FlexCAN Rx FIFO DMA request.
+ *
+ * This function enables or disables the DMA feature of FlexCAN build-in Rx FIFO.
+ *
+ * @param base FlexCAN peripheral base address.
+ * @param enable true to enable, false to disable.
+ */
+void FLEXCAN_EnableRxFifoDMA(CAN_Type *base, bool enable);
+
+/*!
+ * @brief Gets the Rx FIFO Head address.
+ *
+ * This function returns the FlexCAN Rx FIFO Head address, which is mainly used for the DMA/eDMA use case.
+ *
+ * @param base FlexCAN peripheral base address.
+ * @return FlexCAN Rx FIFO Head address.
+ */
+static inline uint32_t FLEXCAN_GetRxFifoHeadAddr(CAN_Type *base)
+{
+ return (uint32_t) & (base->MB[0].CS);
+}
+
+/* @} */
+#endif /* FSL_FEATURE_FLEXCAN_HAS_RX_FIFO_DMA */
+
+/*!
+ * @name Bus Operations
+ * @{
+ */
+
+/*!
+ * @brief Enables or disables the FlexCAN module operation.
+ *
+ * This function enables or disables the FlexCAN module.
+ *
+ * @param base FlexCAN base pointer.
+ * @param enable true to enable, false to disable.
+ */
+static inline void FLEXCAN_Enable(CAN_Type *base, bool enable)
+{
+ if (enable)
+ {
+ base->MCR &= ~CAN_MCR_MDIS_MASK;
+
+ /* Wait FlexCAN exit from low-power mode. */
+ while (base->MCR & CAN_MCR_LPMACK_MASK)
+ {
+ }
+ }
+ else
+ {
+ base->MCR |= CAN_MCR_MDIS_MASK;
+
+ /* Wait FlexCAN enter low-power mode. */
+ while (!(base->MCR & CAN_MCR_LPMACK_MASK))
+ {
+ }
+ }
+}
+
+/*!
+ * @brief Writes a FlexCAN Message to Transmit Message Buffer.
+ *
+ * This function writes a CAN Message to the specified Transmit Message Buffer
+ * and changes the Message Buffer state to start CAN Message transmit. After
+ * that the function returns immediately.
+ *
+ * @param base FlexCAN peripheral base address.
+ * @param mbIdx The FlexCAN Message Buffer index.
+ * @param txFrame Pointer to CAN message frame to be sent.
+ * @retval kStatus_Success - Write Tx Message Buffer Successfully.
+ * @retval kStatus_Fail - Tx Message Buffer is currently in use.
+ */
+status_t FLEXCAN_WriteTxMb(CAN_Type *base, uint8_t mbIdx, const flexcan_frame_t *txFrame);
+
+/*!
+ * @brief Reads a FlexCAN Message from Receive Message Buffer.
+ *
+ * This function reads a CAN message from a specified Receive Message Buffer.
+ * The function fills a receive CAN message frame structure with
+ * just received data and activates the Message Buffer again.
+ * The function returns immediately.
+ *
+ * @param base FlexCAN peripheral base address.
+ * @param mbIdx The FlexCAN Message Buffer index.
+ * @param rxFrame Pointer to CAN message frame structure for reception.
+ * @retval kStatus_Success - Rx Message Buffer is full and has been read successfully.
+ * @retval kStatus_FLEXCAN_RxOverflow - Rx Message Buffer is already overflowed and has been read successfully.
+ * @retval kStatus_Fail - Rx Message Buffer is empty.
+ */
+status_t FLEXCAN_ReadRxMb(CAN_Type *base, uint8_t mbIdx, flexcan_frame_t *rxFrame);
+
+/*!
+ * @brief Reads a FlexCAN Message from Rx FIFO.
+ *
+ * This function reads a CAN message from the FlexCAN build-in Rx FIFO.
+ *
+ * @param base FlexCAN peripheral base address.
+ * @param rxFrame Pointer to CAN message frame structure for reception.
+ * @retval kStatus_Success - Read Message from Rx FIFO successfully.
+ * @retval kStatus_Fail - Rx FIFO is not enabled.
+ */
+status_t FLEXCAN_ReadRxFifo(CAN_Type *base, flexcan_frame_t *rxFrame);
+
+/* @} */
+
+/*!
+ * @name Transactional
+ * @{
+ */
+
+/*!
+ * @brief Performs a polling send transaction on the CAN bus.
+ *
+ * Note that a transfer handle does not need to be created before calling this API.
+ *
+ * @param base FlexCAN peripheral base pointer.
+ * @param mbIdx The FlexCAN Message Buffer index.
+ * @param txFrame Pointer to CAN message frame to be sent.
+ * @retval kStatus_Success - Write Tx Message Buffer Successfully.
+ * @retval kStatus_Fail - Tx Message Buffer is currently in use.
+ */
+status_t FLEXCAN_TransferSendBlocking(CAN_Type *base, uint8_t mbIdx, flexcan_frame_t *txFrame);
+
+/*!
+ * @brief Performs a polling receive transaction on the CAN bus.
+ *
+ * Note that a transfer handle does not need to be created before calling this API.
+ *
+ * @param base FlexCAN peripheral base pointer.
+ * @param mbIdx The FlexCAN Message Buffer index.
+ * @param rxFrame Pointer to CAN message frame structure for reception.
+ * @retval kStatus_Success - Rx Message Buffer is full and has been read successfully.
+ * @retval kStatus_FLEXCAN_RxOverflow - Rx Message Buffer is already overflowed and has been read successfully.
+ * @retval kStatus_Fail - Rx Message Buffer is empty.
+ */
+status_t FLEXCAN_TransferReceiveBlocking(CAN_Type *base, uint8_t mbIdx, flexcan_frame_t *rxFrame);
+
+/*!
+ * @brief Performs a polling receive transaction from Rx FIFO on the CAN bus.
+ *
+ * Note that a transfer handle does not need to be created before calling this API.
+ *
+ * @param base FlexCAN peripheral base pointer.
+ * @param rxFrame Pointer to CAN message frame structure for reception.
+ * @retval kStatus_Success - Read Message from Rx FIFO successfully.
+ * @retval kStatus_Fail - Rx FIFO is not enabled.
+ */
+status_t FLEXCAN_TransferReceiveFifoBlocking(CAN_Type *base, flexcan_frame_t *rxFrame);
+
+/*!
+ * @brief Initializes the FlexCAN handle.
+ *
+ * This function initializes the FlexCAN handle which can be used for other FlexCAN
+ * transactional APIs. Usually, for a specified FlexCAN instance,
+ * call this API once to get the initialized handle.
+ *
+ * @param base FlexCAN peripheral base address.
+ * @param handle FlexCAN handle pointer.
+ * @param callback The callback function.
+ * @param userData The parameter of the callback function.
+ */
+void FLEXCAN_TransferCreateHandle(CAN_Type *base,
+ flexcan_handle_t *handle,
+ flexcan_transfer_callback_t callback,
+ void *userData);
+
+/*!
+ * @brief Sends a message using IRQ.
+ *
+ * This function sends a message using IRQ. This is a non-blocking function, which returns
+ * right away. When messages have been sent out, the send callback function is called.
+ *
+ * @param base FlexCAN peripheral base address.
+ * @param handle FlexCAN handle pointer.
+ * @param xfer FlexCAN Message Buffer transfer structure. See the #flexcan_mb_transfer_t.
+ * @retval kStatus_Success Start Tx Message Buffer sending process successfully.
+ * @retval kStatus_Fail Write Tx Message Buffer failed.
+ * @retval kStatus_FLEXCAN_TxBusy Tx Message Buffer is in use.
+ */
+status_t FLEXCAN_TransferSendNonBlocking(CAN_Type *base, flexcan_handle_t *handle, flexcan_mb_transfer_t *xfer);
+
+/*!
+ * @brief Receives a message using IRQ.
+ *
+ * This function receives a message using IRQ. This is non-blocking function, which returns
+ * right away. When the message has been received, the receive callback function is called.
+ *
+ * @param base FlexCAN peripheral base address.
+ * @param handle FlexCAN handle pointer.
+ * @param xfer FlexCAN Message Buffer transfer structure. See the #flexcan_mb_transfer_t.
+ * @retval kStatus_Success - Start Rx Message Buffer receiving process successfully.
+ * @retval kStatus_FLEXCAN_RxBusy - Rx Message Buffer is in use.
+ */
+status_t FLEXCAN_TransferReceiveNonBlocking(CAN_Type *base, flexcan_handle_t *handle, flexcan_mb_transfer_t *xfer);
+
+/*!
+ * @brief Receives a message from Rx FIFO using IRQ.
+ *
+ * This function receives a message using IRQ. This is a non-blocking function, which returns
+ * right away. When all messages have been received, the receive callback function is called.
+ *
+ * @param base FlexCAN peripheral base address.
+ * @param handle FlexCAN handle pointer.
+ * @param xfer FlexCAN Rx FIFO transfer structure. See the @ref flexcan_fifo_transfer_t.
+ * @retval kStatus_Success - Start Rx FIFO receiving process successfully.
+ * @retval kStatus_FLEXCAN_RxFifoBusy - Rx FIFO is currently in use.
+ */
+status_t FLEXCAN_TransferReceiveFifoNonBlocking(CAN_Type *base,
+ flexcan_handle_t *handle,
+ flexcan_fifo_transfer_t *xfer);
+
+/*!
+ * @brief Aborts the interrupt driven message send process.
+ *
+ * This function aborts the interrupt driven message send process.
+ *
+ * @param base FlexCAN peripheral base address.
+ * @param handle FlexCAN handle pointer.
+ * @param mbIdx The FlexCAN Message Buffer index.
+ */
+void FLEXCAN_TransferAbortSend(CAN_Type *base, flexcan_handle_t *handle, uint8_t mbIdx);
+
+/*!
+ * @brief Aborts the interrupt driven message receive process.
+ *
+ * This function aborts the interrupt driven message receive process.
+ *
+ * @param base FlexCAN peripheral base address.
+ * @param handle FlexCAN handle pointer.
+ * @param mbIdx The FlexCAN Message Buffer index.
+ */
+void FLEXCAN_TransferAbortReceive(CAN_Type *base, flexcan_handle_t *handle, uint8_t mbIdx);
+
+/*!
+ * @brief Aborts the interrupt driven message receive from Rx FIFO process.
+ *
+ * This function aborts the interrupt driven message receive from Rx FIFO process.
+ *
+ * @param base FlexCAN peripheral base address.
+ * @param handle FlexCAN handle pointer.
+ */
+void FLEXCAN_TransferAbortReceiveFifo(CAN_Type *base, flexcan_handle_t *handle);
+
+/*!
+ * @brief FlexCAN IRQ handle function.
+ *
+ * This function handles the FlexCAN Error, the Message Buffer, and the Rx FIFO IRQ request.
+ *
+ * @param base FlexCAN peripheral base address.
+ * @param handle FlexCAN handle pointer.
+ */
+void FLEXCAN_TransferHandleIRQ(CAN_Type *base, flexcan_handle_t *handle);
+
+/* @} */
+
+#if defined(__cplusplus)
+}
+#endif
+
+/*! @}*/
+
+#endif /* _FSL_FLEXCAN_H_ */
diff --git a/drivers/fsl_ftm.c b/drivers/fsl_ftm.c
new file mode 100644
index 0000000..85dc219
--- /dev/null
+++ b/drivers/fsl_ftm.c
@@ -0,0 +1,896 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_ftm.h"
+
+/*******************************************************************************
+ * Prototypes
+ ******************************************************************************/
+/*!
+ * @brief Gets the instance from the base address
+ *
+ * @param base FTM peripheral base address
+ *
+ * @return The FTM instance
+ */
+static uint32_t FTM_GetInstance(FTM_Type *base);
+
+/*!
+ * @brief Sets the FTM register PWM synchronization method
+ *
+ * This function will set the necessary bits for the PWM synchronization mode that
+ * user wishes to use.
+ *
+ * @param base FTM peripheral base address
+ * @param syncMethod Syncronization methods to use to update buffered registers. This is a logical
+ * OR of members of the enumeration ::ftm_pwm_sync_method_t
+ */
+static void FTM_SetPwmSync(FTM_Type *base, uint32_t syncMethod);
+
+/*!
+ * @brief Sets the reload points used as loading points for register update
+ *
+ * This function will set the necessary bits based on what the user wishes to use as loading
+ * points for FTM register update. When using this it is not required to use PWM synchnronization.
+ *
+ * @param base FTM peripheral base address
+ * @param reloadPoints FTM reload points. This is a logical OR of members of the
+ * enumeration ::ftm_reload_point_t
+ */
+static void FTM_SetReloadPoints(FTM_Type *base, uint32_t reloadPoints);
+
+/*******************************************************************************
+ * Variables
+ ******************************************************************************/
+/*! @brief Pointers to FTM bases for each instance. */
+static FTM_Type *const s_ftmBases[] = FTM_BASE_PTRS;
+
+/*! @brief Pointers to FTM clocks for each instance. */
+static const clock_ip_name_t s_ftmClocks[] = FTM_CLOCKS;
+
+/*******************************************************************************
+ * Code
+ ******************************************************************************/
+static uint32_t FTM_GetInstance(FTM_Type *base)
+{
+ uint32_t instance;
+ uint32_t ftmArrayCount = (sizeof(s_ftmBases) / sizeof(s_ftmBases[0]));
+
+ /* Find the instance index from base address mappings. */
+ for (instance = 0; instance < ftmArrayCount; instance++)
+ {
+ if (s_ftmBases[instance] == base)
+ {
+ break;
+ }
+ }
+
+ assert(instance < ftmArrayCount);
+
+ return instance;
+}
+
+static void FTM_SetPwmSync(FTM_Type *base, uint32_t syncMethod)
+{
+ uint8_t chnlNumber = 0;
+ uint32_t reg = 0, syncReg = 0;
+
+ syncReg = base->SYNC;
+ /* Enable PWM synchronization of output mask register */
+ syncReg |= FTM_SYNC_SYNCHOM_MASK;
+
+ reg = base->COMBINE;
+ for (chnlNumber = 0; chnlNumber < (FSL_FEATURE_FTM_CHANNEL_COUNTn(base) / 2); chnlNumber++)
+ {
+ /* Enable PWM synchronization of registers C(n)V and C(n+1)V */
+ reg |= (1U << (FTM_COMBINE_SYNCEN0_SHIFT + (FTM_COMBINE_COMBINE1_SHIFT * chnlNumber)));
+ }
+ base->COMBINE = reg;
+
+ reg = base->SYNCONF;
+
+ /* Use enhanced PWM synchronization method. Use PWM sync to update register values */
+ reg |= (FTM_SYNCONF_SYNCMODE_MASK | FTM_SYNCONF_CNTINC_MASK | FTM_SYNCONF_INVC_MASK | FTM_SYNCONF_SWOC_MASK);
+
+ if (syncMethod & FTM_SYNC_SWSYNC_MASK)
+ {
+ /* Enable needed bits for software trigger to update registers with its buffer value */
+ reg |= (FTM_SYNCONF_SWRSTCNT_MASK | FTM_SYNCONF_SWWRBUF_MASK | FTM_SYNCONF_SWINVC_MASK |
+ FTM_SYNCONF_SWSOC_MASK | FTM_SYNCONF_SWOM_MASK);
+ }
+
+ if (syncMethod & (FTM_SYNC_TRIG0_MASK | FTM_SYNC_TRIG1_MASK | FTM_SYNC_TRIG2_MASK))
+ {
+ /* Enable needed bits for hardware trigger to update registers with its buffer value */
+ reg |= (FTM_SYNCONF_HWRSTCNT_MASK | FTM_SYNCONF_HWWRBUF_MASK | FTM_SYNCONF_HWINVC_MASK |
+ FTM_SYNCONF_HWSOC_MASK | FTM_SYNCONF_HWOM_MASK);
+
+ /* Enable the appropriate hardware trigger that is used for PWM sync */
+ if (syncMethod & FTM_SYNC_TRIG0_MASK)
+ {
+ syncReg |= FTM_SYNC_TRIG0_MASK;
+ }
+ if (syncMethod & FTM_SYNC_TRIG1_MASK)
+ {
+ syncReg |= FTM_SYNC_TRIG1_MASK;
+ }
+ if (syncMethod & FTM_SYNC_TRIG2_MASK)
+ {
+ syncReg |= FTM_SYNC_TRIG2_MASK;
+ }
+ }
+
+ /* Write back values to the SYNC register */
+ base->SYNC = syncReg;
+
+ /* Write the PWM synch values to the SYNCONF register */
+ base->SYNCONF = reg;
+}
+
+static void FTM_SetReloadPoints(FTM_Type *base, uint32_t reloadPoints)
+{
+ uint32_t chnlNumber = 0;
+ uint32_t reg = 0;
+
+ /* Need CNTINC bit to be 1 for CNTIN register to update with its buffer value on reload */
+ base->SYNCONF |= FTM_SYNCONF_CNTINC_MASK;
+
+ reg = base->COMBINE;
+ for (chnlNumber = 0; chnlNumber < (FSL_FEATURE_FTM_CHANNEL_COUNTn(base) / 2); chnlNumber++)
+ {
+ /* Need SYNCEN bit to be 1 for CnV reg to update with its buffer value on reload */
+ reg |= (1U << (FTM_COMBINE_SYNCEN0_SHIFT + (FTM_COMBINE_COMBINE1_SHIFT * chnlNumber)));
+ }
+ base->COMBINE = reg;
+
+ /* Set the reload points */
+ reg = base->PWMLOAD;
+
+ /* Enable the selected channel match reload points */
+ reg &= ~((1U << FSL_FEATURE_FTM_CHANNEL_COUNTn(base)) - 1);
+ reg |= (reloadPoints & ((1U << FSL_FEATURE_FTM_CHANNEL_COUNTn(base)) - 1));
+
+#if defined(FSL_FEATURE_FTM_HAS_HALFCYCLE_RELOAD) && (FSL_FEATURE_FTM_HAS_HALFCYCLE_RELOAD)
+ /* Enable half cycle match as a reload point */
+ if (reloadPoints & kFTM_HalfCycMatch)
+ {
+ reg |= FTM_PWMLOAD_HCSEL_MASK;
+ }
+ else
+ {
+ reg &= ~FTM_PWMLOAD_HCSEL_MASK;
+ }
+#endif /* FSL_FEATURE_FTM_HAS_HALFCYCLE_RELOAD */
+
+ base->PWMLOAD = reg;
+
+ /* These reload points are used when counter is in up-down counting mode */
+ reg = base->SYNC;
+ if (reloadPoints & kFTM_CntMax)
+ {
+ /* Reload when counter turns from up to down */
+ reg |= FTM_SYNC_CNTMAX_MASK;
+ }
+ else
+ {
+ reg &= ~FTM_SYNC_CNTMAX_MASK;
+ }
+
+ if (reloadPoints & kFTM_CntMin)
+ {
+ /* Reload when counter turns from down to up */
+ reg |= FTM_SYNC_CNTMIN_MASK;
+ }
+ else
+ {
+ reg &= ~FTM_SYNC_CNTMIN_MASK;
+ }
+ base->SYNC = reg;
+}
+
+status_t FTM_Init(FTM_Type *base, const ftm_config_t *config)
+{
+ assert(config);
+
+ uint32_t reg;
+
+ if (!(config->pwmSyncMode &
+ (FTM_SYNC_TRIG0_MASK | FTM_SYNC_TRIG1_MASK | FTM_SYNC_TRIG2_MASK | FTM_SYNC_SWSYNC_MASK)))
+ {
+ /* Invalid PWM sync mode */
+ return kStatus_Fail;
+ }
+
+ /* Ungate the FTM clock*/
+ CLOCK_EnableClock(s_ftmClocks[FTM_GetInstance(base)]);
+
+ /* Configure the fault mode, enable FTM mode and disable write protection */
+ base->MODE = FTM_MODE_FAULTM(config->faultMode) | FTM_MODE_FTMEN_MASK | FTM_MODE_WPDIS_MASK;
+
+ /* Configure the update mechanism for buffered registers */
+ FTM_SetPwmSync(base, config->pwmSyncMode);
+
+ /* Setup intermediate register reload points */
+ FTM_SetReloadPoints(base, config->reloadPoints);
+
+ /* Set the clock prescale factor */
+ base->SC = FTM_SC_PS(config->prescale);
+
+ /* Setup the counter operation */
+ base->CONF = (FTM_CONF_BDMMODE(config->bdmMode) | FTM_CONF_GTBEEN(config->useGlobalTimeBase));
+
+ /* Initial state of channel output */
+ base->OUTINIT = config->chnlInitState;
+
+ /* Channel polarity */
+ base->POL = config->chnlPolarity;
+
+ /* Set the external trigger sources */
+ base->EXTTRIG = config->extTriggers;
+#if defined(FSL_FEATURE_FTM_HAS_RELOAD_INITIALIZATION_TRIGGER) && (FSL_FEATURE_FTM_HAS_RELOAD_INITIALIZATION_TRIGGER)
+ if (config->extTriggers & kFTM_ReloadInitTrigger)
+ {
+ base->CONF |= FTM_CONF_ITRIGR_MASK;
+ }
+ else
+ {
+ base->CONF &= ~FTM_CONF_ITRIGR_MASK;
+ }
+#endif /* FSL_FEATURE_FTM_HAS_RELOAD_INITIALIZATION_TRIGGER */
+
+ /* FTM deadtime insertion control */
+ base->DEADTIME = (FTM_DEADTIME_DTPS(config->deadTimePrescale) | FTM_DEADTIME_DTVAL(config->deadTimeValue));
+
+ /* FTM fault filter value */
+ reg = base->FLTCTRL;
+ reg &= ~FTM_FLTCTRL_FFVAL_MASK;
+ reg |= FTM_FLTCTRL_FFVAL(config->faultFilterValue);
+ base->FLTCTRL = reg;
+
+ return kStatus_Success;
+}
+
+void FTM_Deinit(FTM_Type *base)
+{
+ /* Set clock source to none to disable counter */
+ base->SC &= ~(FTM_SC_CLKS_MASK);
+
+ /* Gate the FTM clock */
+ CLOCK_DisableClock(s_ftmClocks[FTM_GetInstance(base)]);
+}
+
+void FTM_GetDefaultConfig(ftm_config_t *config)
+{
+ assert(config);
+
+ /* Divide FTM clock by 1 */
+ config->prescale = kFTM_Prescale_Divide_1;
+ /* FTM behavior in BDM mode */
+ config->bdmMode = kFTM_BdmMode_0;
+ /* Software trigger will be used to update registers */
+ config->pwmSyncMode = kFTM_SoftwareTrigger;
+ /* No intermediate register load */
+ config->reloadPoints = 0;
+ /* Fault control disabled for all channels */
+ config->faultMode = kFTM_Fault_Disable;
+ /* Disable the fault filter */
+ config->faultFilterValue = 0;
+ /* Divide the system clock by 1 */
+ config->deadTimePrescale = kFTM_Deadtime_Prescale_1;
+ /* No counts are inserted */
+ config->deadTimeValue = 0;
+ /* No external trigger */
+ config->extTriggers = 0;
+ /* Initialization value is 0 for all channels */
+ config->chnlInitState = 0;
+ /* Active high polarity for all channels */
+ config->chnlPolarity = 0;
+ /* Use internal FTM counter as timebase */
+ config->useGlobalTimeBase = false;
+}
+
+status_t FTM_SetupPwm(FTM_Type *base,
+ const ftm_chnl_pwm_signal_param_t *chnlParams,
+ uint8_t numOfChnls,
+ ftm_pwm_mode_t mode,
+ uint32_t pwmFreq_Hz,
+ uint32_t srcClock_Hz)
+{
+ assert(chnlParams);
+ assert(srcClock_Hz);
+ assert(pwmFreq_Hz);
+ assert(numOfChnls);
+
+ uint32_t mod, reg;
+ uint32_t ftmClock = (srcClock_Hz / (1U << (base->SC & FTM_SC_PS_MASK)));
+ uint16_t cnv, cnvFirstEdge;
+ uint8_t i;
+
+ switch (mode)
+ {
+ case kFTM_EdgeAlignedPwm:
+ case kFTM_CombinedPwm:
+ base->SC &= ~FTM_SC_CPWMS_MASK;
+ mod = (ftmClock / pwmFreq_Hz) - 1;
+ break;
+ case kFTM_CenterAlignedPwm:
+ base->SC |= FTM_SC_CPWMS_MASK;
+ mod = ftmClock / (pwmFreq_Hz * 2);
+ break;
+ default:
+ return kStatus_Fail;
+ }
+
+ /* Return an error in case we overflow the registers, probably would require changing
+ * clock source to get the desired frequency */
+ if (mod > 65535U)
+ {
+ return kStatus_Fail;
+ }
+ /* Set the PWM period */
+ base->MOD = mod;
+
+ /* Setup each FTM channel */
+ for (i = 0; i < numOfChnls; i++)
+ {
+ /* Return error if requested dutycycle is greater than the max allowed */
+ if (chnlParams->dutyCyclePercent > 100)
+ {
+ return kStatus_Fail;
+ }
+
+ if ((mode == kFTM_EdgeAlignedPwm) || (mode == kFTM_CenterAlignedPwm))
+ {
+ /* Clear the current mode and edge level bits */
+ reg = base->CONTROLS[chnlParams->chnlNumber].CnSC;
+ reg &= ~(FTM_CnSC_MSA_MASK | FTM_CnSC_MSB_MASK | FTM_CnSC_ELSA_MASK | FTM_CnSC_ELSB_MASK);
+
+ /* Setup the active level */
+ reg |= (uint32_t)(chnlParams->level << FTM_CnSC_ELSA_SHIFT);
+
+ /* Edge-aligned mode needs MSB to be 1, don't care for Center-aligned mode */
+ reg |= FTM_CnSC_MSB(1U);
+
+ /* Update the mode and edge level */
+ base->CONTROLS[chnlParams->chnlNumber].CnSC = reg;
+
+ if (chnlParams->dutyCyclePercent == 0)
+ {
+ /* Signal stays low */
+ cnv = 0;
+ }
+ else
+ {
+ cnv = (mod * chnlParams->dutyCyclePercent) / 100;
+ /* For 100% duty cycle */
+ if (cnv >= mod)
+ {
+ cnv = mod + 1;
+ }
+ }
+
+ base->CONTROLS[chnlParams->chnlNumber].CnV = cnv;
+#if defined(FSL_FEATURE_FTM_HAS_ENABLE_PWM_OUTPUT) && (FSL_FEATURE_FTM_HAS_ENABLE_PWM_OUTPUT)
+ /* Set to output mode */
+ FTM_SetPwmOutputEnable(base, chnlParams->chnlNumber, true);
+#endif
+ }
+ else
+ {
+ /* This check is added for combined mode as the channel number should be the pair number */
+ if (chnlParams->chnlNumber >= (FSL_FEATURE_FTM_CHANNEL_COUNTn(base) / 2))
+ {
+ return kStatus_Fail;
+ }
+
+ /* Return error if requested value is greater than the max allowed */
+ if (chnlParams->firstEdgeDelayPercent > 100)
+ {
+ return kStatus_Fail;
+ }
+
+ /* Configure delay of the first edge */
+ if (chnlParams->firstEdgeDelayPercent == 0)
+ {
+ /* No delay for the first edge */
+ cnvFirstEdge = 0;
+ }
+ else
+ {
+ cnvFirstEdge = (mod * chnlParams->firstEdgeDelayPercent) / 100;
+ }
+
+ /* Configure dutycycle */
+ if (chnlParams->dutyCyclePercent == 0)
+ {
+ /* Signal stays low */
+ cnv = 0;
+ cnvFirstEdge = 0;
+ }
+ else
+ {
+ cnv = (mod * chnlParams->dutyCyclePercent) / 100;
+ /* For 100% duty cycle */
+ if (cnv >= mod)
+ {
+ cnv = mod + 1;
+ }
+ }
+
+ /* Clear the current mode and edge level bits for channel n */
+ reg = base->CONTROLS[chnlParams->chnlNumber * 2].CnSC;
+ reg &= ~(FTM_CnSC_MSA_MASK | FTM_CnSC_MSB_MASK | FTM_CnSC_ELSA_MASK | FTM_CnSC_ELSB_MASK);
+
+ /* Setup the active level for channel n */
+ reg |= (uint32_t)(chnlParams->level << FTM_CnSC_ELSA_SHIFT);
+
+ /* Update the mode and edge level for channel n */
+ base->CONTROLS[chnlParams->chnlNumber * 2].CnSC = reg;
+
+ /* Clear the current mode and edge level bits for channel n + 1 */
+ reg = base->CONTROLS[(chnlParams->chnlNumber * 2) + 1].CnSC;
+ reg &= ~(FTM_CnSC_MSA_MASK | FTM_CnSC_MSB_MASK | FTM_CnSC_ELSA_MASK | FTM_CnSC_ELSB_MASK);
+
+ /* Setup the active level for channel n + 1 */
+ reg |= (uint32_t)(chnlParams->level << FTM_CnSC_ELSA_SHIFT);
+
+ /* Update the mode and edge level for channel n + 1*/
+ base->CONTROLS[(chnlParams->chnlNumber * 2) + 1].CnSC = reg;
+
+ /* Set the combine bit for the channel pair */
+ base->COMBINE |=
+ (1U << (FTM_COMBINE_COMBINE0_SHIFT + (FTM_COMBINE_COMBINE1_SHIFT * chnlParams->chnlNumber)));
+
+ /* Set the channel pair values */
+ base->CONTROLS[chnlParams->chnlNumber * 2].CnV = cnvFirstEdge;
+ base->CONTROLS[(chnlParams->chnlNumber * 2) + 1].CnV = cnvFirstEdge + cnv;
+
+#if defined(FSL_FEATURE_FTM_HAS_ENABLE_PWM_OUTPUT) && (FSL_FEATURE_FTM_HAS_ENABLE_PWM_OUTPUT)
+ /* Set to output mode */
+ FTM_SetPwmOutputEnable(base, (ftm_chnl_t)((uint8_t)chnlParams->chnlNumber * 2), true);
+ FTM_SetPwmOutputEnable(base, (ftm_chnl_t)((uint8_t)chnlParams->chnlNumber * 2 + 1), true);
+#endif
+ }
+ chnlParams++;
+ }
+
+ return kStatus_Success;
+}
+
+void FTM_UpdatePwmDutycycle(FTM_Type *base,
+ ftm_chnl_t chnlNumber,
+ ftm_pwm_mode_t currentPwmMode,
+ uint8_t dutyCyclePercent)
+{
+ uint16_t cnv, cnvFirstEdge = 0, mod;
+
+ mod = base->MOD;
+ if ((currentPwmMode == kFTM_EdgeAlignedPwm) || (currentPwmMode == kFTM_CenterAlignedPwm))
+ {
+ cnv = (mod * dutyCyclePercent) / 100;
+ /* For 100% duty cycle */
+ if (cnv >= mod)
+ {
+ cnv = mod + 1;
+ }
+ base->CONTROLS[chnlNumber].CnV = cnv;
+ }
+ else
+ {
+ /* This check is added for combined mode as the channel number should be the pair number */
+ if (chnlNumber >= (FSL_FEATURE_FTM_CHANNEL_COUNTn(base) / 2))
+ {
+ return;
+ }
+
+ cnv = (mod * dutyCyclePercent) / 100;
+ cnvFirstEdge = base->CONTROLS[chnlNumber * 2].CnV;
+ /* For 100% duty cycle */
+ if (cnv >= mod)
+ {
+ cnv = mod + 1;
+ }
+ base->CONTROLS[(chnlNumber * 2) + 1].CnV = cnvFirstEdge + cnv;
+ }
+}
+
+void FTM_UpdateChnlEdgeLevelSelect(FTM_Type *base, ftm_chnl_t chnlNumber, uint8_t level)
+{
+ uint32_t reg = base->CONTROLS[chnlNumber].CnSC;
+
+ /* Clear the field and write the new level value */
+ reg &= ~(FTM_CnSC_ELSA_MASK | FTM_CnSC_ELSB_MASK);
+ reg |= ((uint32_t)level << FTM_CnSC_ELSA_SHIFT) & (FTM_CnSC_ELSA_MASK | FTM_CnSC_ELSB_MASK);
+
+ base->CONTROLS[chnlNumber].CnSC = reg;
+}
+
+void FTM_SetupInputCapture(FTM_Type *base,
+ ftm_chnl_t chnlNumber,
+ ftm_input_capture_edge_t captureMode,
+ uint32_t filterValue)
+{
+ uint32_t reg;
+
+ /* Clear the combine bit for the channel pair */
+ base->COMBINE &= ~(1U << (FTM_COMBINE_COMBINE0_SHIFT + (FTM_COMBINE_COMBINE1_SHIFT * (chnlNumber >> 1))));
+ /* Clear the dual edge capture mode because it's it's higher priority */
+ base->COMBINE &= ~(1U << (FTM_COMBINE_DECAPEN0_SHIFT + (FTM_COMBINE_COMBINE1_SHIFT * (chnlNumber >> 1))));
+ /* Clear the quadrature decoder mode beacause it's higher priority */
+ base->QDCTRL &= ~FTM_QDCTRL_QUADEN_MASK;
+
+ reg = base->CONTROLS[chnlNumber].CnSC;
+ reg &= ~(FTM_CnSC_MSA_MASK | FTM_CnSC_MSB_MASK | FTM_CnSC_ELSA_MASK | FTM_CnSC_ELSB_MASK);
+ reg |= captureMode;
+
+ /* Set the requested input capture mode */
+ base->CONTROLS[chnlNumber].CnSC = reg;
+ /* Input filter available only for channels 0, 1, 2, 3 */
+ if (chnlNumber < kFTM_Chnl_4)
+ {
+ reg = base->FILTER;
+ reg &= ~(FTM_FILTER_CH0FVAL_MASK << (FTM_FILTER_CH1FVAL_SHIFT * chnlNumber));
+ reg |= (filterValue << (FTM_FILTER_CH1FVAL_SHIFT * chnlNumber));
+ base->FILTER = reg;
+ }
+#if defined(FSL_FEATURE_FTM_HAS_ENABLE_PWM_OUTPUT) && (FSL_FEATURE_FTM_HAS_ENABLE_PWM_OUTPUT)
+ /* Set to input mode */
+ FTM_SetPwmOutputEnable(base, chnlNumber, false);
+#endif
+}
+
+void FTM_SetupOutputCompare(FTM_Type *base,
+ ftm_chnl_t chnlNumber,
+ ftm_output_compare_mode_t compareMode,
+ uint32_t compareValue)
+{
+ uint32_t reg;
+
+ /* Clear the combine bit for the channel pair */
+ base->COMBINE &= ~(1U << (FTM_COMBINE_COMBINE0_SHIFT + (FTM_COMBINE_COMBINE1_SHIFT * (chnlNumber >> 1))));
+ /* Clear the dual edge capture mode because it's it's higher priority */
+ base->COMBINE &= ~(1U << (FTM_COMBINE_DECAPEN0_SHIFT + (FTM_COMBINE_COMBINE1_SHIFT * (chnlNumber >> 1))));
+ /* Clear the quadrature decoder mode beacause it's higher priority */
+ base->QDCTRL &= ~FTM_QDCTRL_QUADEN_MASK;
+
+ reg = base->CONTROLS[chnlNumber].CnSC;
+ reg &= ~(FTM_CnSC_MSA_MASK | FTM_CnSC_MSB_MASK | FTM_CnSC_ELSA_MASK | FTM_CnSC_ELSB_MASK);
+ reg |= compareMode;
+ /* Setup the channel output behaviour when a match occurs with the compare value */
+ base->CONTROLS[chnlNumber].CnSC = reg;
+
+ /* Set output on match to the requested level */
+ base->CONTROLS[chnlNumber].CnV = compareValue;
+
+#if defined(FSL_FEATURE_FTM_HAS_ENABLE_PWM_OUTPUT) && (FSL_FEATURE_FTM_HAS_ENABLE_PWM_OUTPUT)
+ /* Set to output mode */
+ FTM_SetPwmOutputEnable(base, chnlNumber, true);
+#endif
+}
+
+void FTM_SetupDualEdgeCapture(FTM_Type *base,
+ ftm_chnl_t chnlPairNumber,
+ const ftm_dual_edge_capture_param_t *edgeParam,
+ uint32_t filterValue)
+{
+ assert(edgeParam);
+
+ uint32_t reg;
+
+ reg = base->COMBINE;
+ /* Clear the combine bit for the channel pair */
+ reg &= ~(1U << (FTM_COMBINE_COMBINE0_SHIFT + (FTM_COMBINE_COMBINE1_SHIFT * chnlPairNumber)));
+ /* Enable the DECAPEN bit */
+ reg |= (1U << (FTM_COMBINE_DECAPEN0_SHIFT + (FTM_COMBINE_COMBINE1_SHIFT * chnlPairNumber)));
+ reg |= (1U << (FTM_COMBINE_DECAP0_SHIFT + (FTM_COMBINE_COMBINE1_SHIFT * chnlPairNumber)));
+ base->COMBINE = reg;
+
+ /* Setup the edge detection from channel n and n + 1 */
+ reg = base->CONTROLS[chnlPairNumber * 2].CnSC;
+ reg &= ~(FTM_CnSC_MSA_MASK | FTM_CnSC_MSB_MASK | FTM_CnSC_ELSA_MASK | FTM_CnSC_ELSB_MASK);
+ reg |= ((uint32_t)edgeParam->mode | (uint32_t)edgeParam->currChanEdgeMode);
+ base->CONTROLS[chnlPairNumber * 2].CnSC = reg;
+
+ reg = base->CONTROLS[(chnlPairNumber * 2) + 1].CnSC;
+ reg &= ~(FTM_CnSC_MSA_MASK | FTM_CnSC_MSB_MASK | FTM_CnSC_ELSA_MASK | FTM_CnSC_ELSB_MASK);
+ reg |= ((uint32_t)edgeParam->mode | (uint32_t)edgeParam->nextChanEdgeMode);
+ base->CONTROLS[(chnlPairNumber * 2) + 1].CnSC = reg;
+
+ /* Input filter available only for channels 0, 1, 2, 3 */
+ if (chnlPairNumber < kFTM_Chnl_4)
+ {
+ reg = base->FILTER;
+ reg &= ~(FTM_FILTER_CH0FVAL_MASK << (FTM_FILTER_CH1FVAL_SHIFT * chnlPairNumber));
+ reg |= (filterValue << (FTM_FILTER_CH1FVAL_SHIFT * chnlPairNumber));
+ base->FILTER = reg;
+ }
+
+#if defined(FSL_FEATURE_FTM_HAS_ENABLE_PWM_OUTPUT) && (FSL_FEATURE_FTM_HAS_ENABLE_PWM_OUTPUT)
+ /* Set to input mode */
+ FTM_SetPwmOutputEnable(base, chnlPairNumber, false);
+#endif
+}
+
+void FTM_SetupQuadDecode(FTM_Type *base,
+ const ftm_phase_params_t *phaseAParams,
+ const ftm_phase_params_t *phaseBParams,
+ ftm_quad_decode_mode_t quadMode)
+{
+ assert(phaseAParams);
+ assert(phaseBParams);
+
+ uint32_t reg;
+
+ /* Set Phase A filter value if phase filter is enabled */
+ if (phaseAParams->enablePhaseFilter)
+ {
+ reg = base->FILTER;
+ reg &= ~(FTM_FILTER_CH0FVAL_MASK);
+ reg |= FTM_FILTER_CH0FVAL(phaseAParams->phaseFilterVal);
+ base->FILTER = reg;
+ }
+
+ /* Set Phase B filter value if phase filter is enabled */
+ if (phaseBParams->enablePhaseFilter)
+ {
+ reg = base->FILTER;
+ reg &= ~(FTM_FILTER_CH1FVAL_MASK);
+ reg |= FTM_FILTER_CH1FVAL(phaseBParams->phaseFilterVal);
+ base->FILTER = reg;
+ }
+
+ /* Set Quadrature decode properties */
+ reg = base->QDCTRL;
+ reg &= ~(FTM_QDCTRL_QUADMODE_MASK | FTM_QDCTRL_PHAFLTREN_MASK | FTM_QDCTRL_PHBFLTREN_MASK | FTM_QDCTRL_PHAPOL_MASK |
+ FTM_QDCTRL_PHBPOL_MASK);
+ reg |= (FTM_QDCTRL_QUADMODE(quadMode) | FTM_QDCTRL_PHAFLTREN(phaseAParams->enablePhaseFilter) |
+ FTM_QDCTRL_PHBFLTREN(phaseBParams->enablePhaseFilter) | FTM_QDCTRL_PHAPOL(phaseAParams->phasePolarity) |
+ FTM_QDCTRL_PHBPOL(phaseBParams->phasePolarity));
+ base->QDCTRL = reg;
+ /* Enable Quad decode */
+ base->QDCTRL |= FTM_QDCTRL_QUADEN_MASK;
+}
+
+void FTM_SetupFault(FTM_Type *base, ftm_fault_input_t faultNumber, const ftm_fault_param_t *faultParams)
+{
+ assert(faultParams);
+
+ uint32_t reg;
+
+ reg = base->FLTCTRL;
+ if (faultParams->enableFaultInput)
+ {
+ /* Enable the fault input */
+ reg |= (FTM_FLTCTRL_FAULT0EN_MASK << faultNumber);
+ }
+ else
+ {
+ /* Disable the fault input */
+ reg &= ~(FTM_FLTCTRL_FAULT0EN_MASK << faultNumber);
+ }
+
+ if (faultParams->useFaultFilter)
+ {
+ /* Enable the fault filter */
+ reg |= (FTM_FLTCTRL_FFLTR0EN_MASK << (FTM_FLTCTRL_FFLTR0EN_SHIFT + faultNumber));
+ }
+ else
+ {
+ /* Disable the fault filter */
+ reg &= ~(FTM_FLTCTRL_FFLTR0EN_MASK << (FTM_FLTCTRL_FFLTR0EN_SHIFT + faultNumber));
+ }
+ base->FLTCTRL = reg;
+
+ if (faultParams->faultLevel)
+ {
+ /* Active low polarity for the fault input pin */
+ base->FLTPOL |= (1U << faultNumber);
+ }
+ else
+ {
+ /* Active high polarity for the fault input pin */
+ base->FLTPOL &= ~(1U << faultNumber);
+ }
+}
+
+void FTM_EnableInterrupts(FTM_Type *base, uint32_t mask)
+{
+ uint32_t chnlInts = (mask & 0xFFU);
+ uint8_t chnlNumber = 0;
+
+ /* Enable the timer overflow interrupt */
+ if (mask & kFTM_TimeOverflowInterruptEnable)
+ {
+ base->SC |= FTM_SC_TOIE_MASK;
+ }
+
+ /* Enable the fault interrupt */
+ if (mask & kFTM_FaultInterruptEnable)
+ {
+ base->MODE |= FTM_MODE_FAULTIE_MASK;
+ }
+
+#if defined(FSL_FEATURE_FTM_HAS_RELOAD_INTERRUPT) && (FSL_FEATURE_FTM_HAS_RELOAD_INTERRUPT)
+ /* Enable the reload interrupt available only on certain SoC's */
+ if (mask & kFTM_ReloadInterruptEnable)
+ {
+ base->SC |= FTM_SC_RIE_MASK;
+ }
+#endif
+
+ /* Enable the channel interrupts */
+ while (chnlInts)
+ {
+ if (chnlInts & 0x1)
+ {
+ base->CONTROLS[chnlNumber].CnSC |= FTM_CnSC_CHIE_MASK;
+ }
+ chnlNumber++;
+ chnlInts = chnlInts >> 1U;
+ }
+}
+
+void FTM_DisableInterrupts(FTM_Type *base, uint32_t mask)
+{
+ uint32_t chnlInts = (mask & 0xFF);
+ uint8_t chnlNumber = 0;
+
+ /* Disable the timer overflow interrupt */
+ if (mask & kFTM_TimeOverflowInterruptEnable)
+ {
+ base->SC &= ~FTM_SC_TOIE_MASK;
+ }
+ /* Disable the fault interrupt */
+ if (mask & kFTM_FaultInterruptEnable)
+ {
+ base->MODE &= ~FTM_MODE_FAULTIE_MASK;
+ }
+
+#if defined(FSL_FEATURE_FTM_HAS_RELOAD_INTERRUPT) && (FSL_FEATURE_FTM_HAS_RELOAD_INTERRUPT)
+ /* Disable the reload interrupt available only on certain SoC's */
+ if (mask & kFTM_ReloadInterruptEnable)
+ {
+ base->SC &= ~FTM_SC_RIE_MASK;
+ }
+#endif
+
+ /* Disable the channel interrupts */
+ while (chnlInts)
+ {
+ if (chnlInts & 0x1)
+ {
+ base->CONTROLS[chnlNumber].CnSC &= ~FTM_CnSC_CHIE_MASK;
+ }
+ chnlNumber++;
+ chnlInts = chnlInts >> 1U;
+ }
+}
+
+uint32_t FTM_GetEnabledInterrupts(FTM_Type *base)
+{
+ uint32_t enabledInterrupts = 0;
+ int8_t chnlCount = FSL_FEATURE_FTM_CHANNEL_COUNTn(base);
+
+ /* The CHANNEL_COUNT macro returns -1 if it cannot match the FTM instance */
+ assert(chnlCount != -1);
+
+ /* Check if timer overflow interrupt is enabled */
+ if (base->SC & FTM_SC_TOIE_MASK)
+ {
+ enabledInterrupts |= kFTM_TimeOverflowInterruptEnable;
+ }
+ /* Check if fault interrupt is enabled */
+ if (base->MODE & FTM_MODE_FAULTIE_MASK)
+ {
+ enabledInterrupts |= kFTM_FaultInterruptEnable;
+ }
+
+#if defined(FSL_FEATURE_FTM_HAS_RELOAD_INTERRUPT) && (FSL_FEATURE_FTM_HAS_RELOAD_INTERRUPT)
+ /* Check if the reload interrupt is enabled */
+ if (base->SC & FTM_SC_RIE_MASK)
+ {
+ enabledInterrupts |= kFTM_ReloadInterruptEnable;
+ }
+#endif
+
+ /* Check if the channel interrupts are enabled */
+ while (chnlCount > 0)
+ {
+ chnlCount--;
+ if (base->CONTROLS[chnlCount].CnSC & FTM_CnSC_CHIE_MASK)
+ {
+ enabledInterrupts |= (1U << chnlCount);
+ }
+ }
+
+ return enabledInterrupts;
+}
+
+uint32_t FTM_GetStatusFlags(FTM_Type *base)
+{
+ uint32_t statusFlags = 0;
+
+ /* Check the timer flag */
+ if (base->SC & FTM_SC_TOF_MASK)
+ {
+ statusFlags |= kFTM_TimeOverflowFlag;
+ }
+ /* Check fault flag */
+ if (base->FMS & FTM_FMS_FAULTF_MASK)
+ {
+ statusFlags |= kFTM_FaultFlag;
+ }
+ /* Check channel trigger flag */
+ if (base->EXTTRIG & FTM_EXTTRIG_TRIGF_MASK)
+ {
+ statusFlags |= kFTM_ChnlTriggerFlag;
+ }
+#if defined(FSL_FEATURE_FTM_HAS_RELOAD_INTERRUPT) && (FSL_FEATURE_FTM_HAS_RELOAD_INTERRUPT)
+ /* Check reload flag */
+ if (base->SC & FTM_SC_RF_MASK)
+ {
+ statusFlags |= kFTM_ReloadFlag;
+ }
+#endif
+
+ /* Lower 8 bits contain the channel status flags */
+ statusFlags |= (base->STATUS & 0xFFU);
+
+ return statusFlags;
+}
+
+void FTM_ClearStatusFlags(FTM_Type *base, uint32_t mask)
+{
+ /* Clear the timer overflow flag by writing a 0 to the bit while it is set */
+ if (mask & kFTM_TimeOverflowFlag)
+ {
+ base->SC &= ~FTM_SC_TOF_MASK;
+ }
+ /* Clear fault flag by writing a 0 to the bit while it is set */
+ if (mask & kFTM_FaultFlag)
+ {
+ base->FMS &= ~FTM_FMS_FAULTF_MASK;
+ }
+ /* Clear channel trigger flag */
+ if (mask & kFTM_ChnlTriggerFlag)
+ {
+ base->EXTTRIG &= ~FTM_EXTTRIG_TRIGF_MASK;
+ }
+
+#if defined(FSL_FEATURE_FTM_HAS_RELOAD_INTERRUPT) && (FSL_FEATURE_FTM_HAS_RELOAD_INTERRUPT)
+ /* Check reload flag by writing a 0 to the bit while it is set */
+ if (mask & kFTM_ReloadFlag)
+ {
+ base->SC &= ~FTM_SC_RF_MASK;
+ }
+#endif
+ /* Clear the channel status flags by writing a 0 to the bit */
+ base->STATUS &= ~(mask & 0xFFU);
+}
diff --git a/drivers/fsl_ftm.h b/drivers/fsl_ftm.h
new file mode 100644
index 0000000..7643635
--- /dev/null
+++ b/drivers/fsl_ftm.h
@@ -0,0 +1,861 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_FTM_H_
+#define _FSL_FTM_H_
+
+#include "fsl_common.h"
+
+/*!
+ * @addtogroup ftm
+ * @{
+ */
+
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+/*! @name Driver version */
+/*@{*/
+#define FSL_FTM_DRIVER_VERSION (MAKE_VERSION(2, 0, 0)) /*!< Version 2.0.0 */
+/*@}*/
+
+/*!
+ * @brief List of FTM channels
+ * @note Actual number of available channels is SoC dependent
+ */
+typedef enum _ftm_chnl
+{
+ kFTM_Chnl_0 = 0U, /*!< FTM channel number 0*/
+ kFTM_Chnl_1, /*!< FTM channel number 1 */
+ kFTM_Chnl_2, /*!< FTM channel number 2 */
+ kFTM_Chnl_3, /*!< FTM channel number 3 */
+ kFTM_Chnl_4, /*!< FTM channel number 4 */
+ kFTM_Chnl_5, /*!< FTM channel number 5 */
+ kFTM_Chnl_6, /*!< FTM channel number 6 */
+ kFTM_Chnl_7 /*!< FTM channel number 7 */
+} ftm_chnl_t;
+
+/*! @brief List of FTM faults */
+typedef enum _ftm_fault_input
+{
+ kFTM_Fault_0 = 0U, /*!< FTM fault 0 input pin */
+ kFTM_Fault_1, /*!< FTM fault 1 input pin */
+ kFTM_Fault_2, /*!< FTM fault 2 input pin */
+ kFTM_Fault_3 /*!< FTM fault 3 input pin */
+} ftm_fault_input_t;
+
+/*! @brief FTM PWM operation modes */
+typedef enum _ftm_pwm_mode
+{
+ kFTM_EdgeAlignedPwm = 0U, /*!< Edge-aligned PWM */
+ kFTM_CenterAlignedPwm, /*!< Center-aligned PWM */
+ kFTM_CombinedPwm /*!< Combined PWM */
+} ftm_pwm_mode_t;
+
+/*! @brief FTM PWM output pulse mode: high-true, low-true or no output */
+typedef enum _ftm_pwm_level_select
+{
+ kFTM_NoPwmSignal = 0U, /*!< No PWM output on pin */
+ kFTM_LowTrue, /*!< Low true pulses */
+ kFTM_HighTrue /*!< High true pulses */
+} ftm_pwm_level_select_t;
+
+/*! @brief Options to configure a FTM channel's PWM signal */
+typedef struct _ftm_chnl_pwm_signal_param
+{
+ ftm_chnl_t chnlNumber; /*!< The channel/channel pair number.
+ In combined mode, this represents the channel pair number. */
+ ftm_pwm_level_select_t level; /*!< PWM output active level select. */
+ uint8_t dutyCyclePercent; /*!< PWM pulse width, value should be between 0 to 100
+ 0 = inactive signal(0% duty cycle)...
+ 100 = always active signal (100% duty cycle).*/
+ uint8_t firstEdgeDelayPercent; /*!< Used only in combined PWM mode to generate an asymmetrical PWM.
+ Specifies the delay to the first edge in a PWM period.
+ If unsure leave as 0; Should be specified as a
+ percentage of the PWM period */
+} ftm_chnl_pwm_signal_param_t;
+
+/*! @brief FlexTimer output compare mode */
+typedef enum _ftm_output_compare_mode
+{
+ kFTM_NoOutputSignal = (1U << FTM_CnSC_MSA_SHIFT), /*!< No channel output when counter reaches CnV */
+ kFTM_ToggleOnMatch = ((1U << FTM_CnSC_MSA_SHIFT) | (1U << FTM_CnSC_ELSA_SHIFT)), /*!< Toggle output */
+ kFTM_ClearOnMatch = ((1U << FTM_CnSC_MSA_SHIFT) | (2U << FTM_CnSC_ELSA_SHIFT)), /*!< Clear output */
+ kFTM_SetOnMatch = ((1U << FTM_CnSC_MSA_SHIFT) | (3U << FTM_CnSC_ELSA_SHIFT)) /*!< Set output */
+} ftm_output_compare_mode_t;
+
+/*! @brief FlexTimer input capture edge */
+typedef enum _ftm_input_capture_edge
+{
+ kFTM_RisingEdge = (1U << FTM_CnSC_ELSA_SHIFT), /*!< Capture on rising edge only*/
+ kFTM_FallingEdge = (2U << FTM_CnSC_ELSA_SHIFT), /*!< Capture on falling edge only*/
+ kFTM_RiseAndFallEdge = (3U << FTM_CnSC_ELSA_SHIFT) /*!< Capture on rising or falling edge */
+} ftm_input_capture_edge_t;
+
+/*! @brief FlexTimer dual edge capture modes */
+typedef enum _ftm_dual_edge_capture_mode
+{
+ kFTM_OneShot = 0U, /*!< One-shot capture mode */
+ kFTM_Continuous = (1U << FTM_CnSC_MSA_SHIFT) /*!< Continuous capture mode */
+} ftm_dual_edge_capture_mode_t;
+
+/*! @brief FlexTimer dual edge capture parameters */
+typedef struct _ftm_dual_edge_capture_param
+{
+ ftm_dual_edge_capture_mode_t mode; /*!< Dual Edge Capture mode */
+ ftm_input_capture_edge_t currChanEdgeMode; /*!< Input capture edge select for channel n */
+ ftm_input_capture_edge_t nextChanEdgeMode; /*!< Input capture edge select for channel n+1 */
+} ftm_dual_edge_capture_param_t;
+
+/*! @brief FlexTimer quadrature decode modes */
+typedef enum _ftm_quad_decode_mode
+{
+ kFTM_QuadPhaseEncode = 0U, /*!< Phase A and Phase B encoding mode */
+ kFTM_QuadCountAndDir /*!< Count and direction encoding mode */
+} ftm_quad_decode_mode_t;
+
+/*! @brief FlexTimer quadrature phase polarities */
+typedef enum _ftm_phase_polarity
+{
+ kFTM_QuadPhaseNormal = 0U, /*!< Phase input signal is not inverted */
+ kFTM_QuadPhaseInvert /*!< Phase input signal is inverted */
+} ftm_phase_polarity_t;
+
+/*! @brief FlexTimer quadrature decode phase parameters */
+typedef struct _ftm_phase_param
+{
+ bool enablePhaseFilter; /*!< True: enable phase filter; false: disable filter */
+ uint32_t phaseFilterVal; /*!< Filter value, used only if phase filter is enabled */
+ ftm_phase_polarity_t phasePolarity; /*!< Phase polarity */
+} ftm_phase_params_t;
+
+/*! @brief Structure is used to hold the parameters to configure a FTM fault */
+typedef struct _ftm_fault_param
+{
+ bool enableFaultInput; /*!< True: Fault input is enabled; false: Fault input is disabled */
+ bool faultLevel; /*!< True: Fault polarity is active low i.e., '0' indicates a fault;
+ False: Fault polarity is active high */
+ bool useFaultFilter; /*!< True: Use the filtered fault signal;
+ False: Use the direct path from fault input */
+} ftm_fault_param_t;
+
+/*! @brief FlexTimer pre-scaler factor for the dead time insertion*/
+typedef enum _ftm_deadtime_prescale
+{
+ kFTM_Deadtime_Prescale_1 = 1U, /*!< Divide by 1 */
+ kFTM_Deadtime_Prescale_4, /*!< Divide by 4 */
+ kFTM_Deadtime_Prescale_16 /*!< Divide by 16 */
+} ftm_deadtime_prescale_t;
+
+/*! @brief FlexTimer clock source selection*/
+typedef enum _ftm_clock_source
+{
+ kFTM_SystemClock = 1U, /*!< System clock selected */
+ kFTM_FixedClock, /*!< Fixed frequency clock */
+ kFTM_ExternalClock /*!< External clock */
+} ftm_clock_source_t;
+
+/*! @brief FlexTimer pre-scaler factor selection for the clock source*/
+typedef enum _ftm_clock_prescale
+{
+ kFTM_Prescale_Divide_1 = 0U, /*!< Divide by 1 */
+ kFTM_Prescale_Divide_2, /*!< Divide by 2 */
+ kFTM_Prescale_Divide_4, /*!< Divide by 4 */
+ kFTM_Prescale_Divide_8, /*!< Divide by 8 */
+ kFTM_Prescale_Divide_16, /*!< Divide by 16 */
+ kFTM_Prescale_Divide_32, /*!< Divide by 32 */
+ kFTM_Prescale_Divide_64, /*!< Divide by 64 */
+ kFTM_Prescale_Divide_128 /*!< Divide by 128 */
+} ftm_clock_prescale_t;
+
+/*! @brief Options for the FlexTimer behaviour in BDM Mode */
+typedef enum _ftm_bdm_mode
+{
+ kFTM_BdmMode_0 = 0U,
+ /*!< FTM counter stopped, CH(n)F bit can be set, FTM channels in functional mode, writes to MOD,CNTIN and C(n)V
+ registers bypass the register buffers */
+ kFTM_BdmMode_1,
+ /*!< FTM counter stopped, CH(n)F bit is not set, FTM channels outputs are forced to their safe value , writes to
+ MOD,CNTIN and C(n)V registers bypass the register buffers */
+ kFTM_BdmMode_2,
+ /*!< FTM counter stopped, CH(n)F bit is not set, FTM channels outputs are frozen when chip enters in BDM mode,
+ writes to MOD,CNTIN and C(n)V registers bypass the register buffers */
+ kFTM_BdmMode_3
+ /*!< FTM counter in functional mode, CH(n)F bit can be set, FTM channels in functional mode, writes to MOD,CNTIN and
+ C(n)V registers is in fully functional mode */
+} ftm_bdm_mode_t;
+
+/*! @brief Options for the FTM fault control mode */
+typedef enum _ftm_fault_mode
+{
+ kFTM_Fault_Disable = 0U, /*!< Fault control is disabled for all channels */
+ kFTM_Fault_EvenChnls, /*!< Enabled for even channels only(0,2,4,6) with manual fault clearing */
+ kFTM_Fault_AllChnlsMan, /*!< Enabled for all channels with manual fault clearing */
+ kFTM_Fault_AllChnlsAuto /*!< Enabled for all channels with automatic fault clearing */
+} ftm_fault_mode_t;
+
+/*!
+ * @brief FTM external trigger options
+ * @note Actual available external trigger sources are SoC-specific
+ */
+typedef enum _ftm_external_trigger
+{
+ kFTM_Chnl0Trigger = (1U << 4), /*!< Generate trigger when counter equals chnl 0 CnV reg */
+ kFTM_Chnl1Trigger = (1U << 5), /*!< Generate trigger when counter equals chnl 1 CnV reg */
+ kFTM_Chnl2Trigger = (1U << 0), /*!< Generate trigger when counter equals chnl 2 CnV reg */
+ kFTM_Chnl3Trigger = (1U << 1), /*!< Generate trigger when counter equals chnl 3 CnV reg */
+ kFTM_Chnl4Trigger = (1U << 2), /*!< Generate trigger when counter equals chnl 4 CnV reg */
+ kFTM_Chnl5Trigger = (1U << 3), /*!< Generate trigger when counter equals chnl 5 CnV reg */
+ kFTM_Chnl6Trigger =
+ (1U << 8), /*!< Available on certain SoC's, generate trigger when counter equals chnl 6 CnV reg */
+ kFTM_Chnl7Trigger =
+ (1U << 9), /*!< Available on certain SoC's, generate trigger when counter equals chnl 7 CnV reg */
+ kFTM_InitTrigger = (1U << 6), /*!< Generate Trigger when counter is updated with CNTIN */
+ kFTM_ReloadInitTrigger = (1U << 7) /*!< Available on certain SoC's, trigger on reload point */
+} ftm_external_trigger_t;
+
+/*! @brief FlexTimer PWM sync options to update registers with buffer */
+typedef enum _ftm_pwm_sync_method
+{
+ kFTM_SoftwareTrigger = FTM_SYNC_SWSYNC_MASK, /*!< Software triggers PWM sync */
+ kFTM_HardwareTrigger_0 = FTM_SYNC_TRIG0_MASK, /*!< Hardware trigger 0 causes PWM sync */
+ kFTM_HardwareTrigger_1 = FTM_SYNC_TRIG1_MASK, /*!< Hardware trigger 1 causes PWM sync */
+ kFTM_HardwareTrigger_2 = FTM_SYNC_TRIG2_MASK /*!< Hardware trigger 2 causes PWM sync */
+} ftm_pwm_sync_method_t;
+
+/*!
+ * @brief FTM options available as loading point for register reload
+ * @note Actual available reload points are SoC-specific
+ */
+typedef enum _ftm_reload_point
+{
+ kFTM_Chnl0Match = (1U << 0), /*!< Channel 0 match included as a reload point */
+ kFTM_Chnl1Match = (1U << 1), /*!< Channel 1 match included as a reload point */
+ kFTM_Chnl2Match = (1U << 2), /*!< Channel 2 match included as a reload point */
+ kFTM_Chnl3Match = (1U << 3), /*!< Channel 3 match included as a reload point */
+ kFTM_Chnl4Match = (1U << 4), /*!< Channel 4 match included as a reload point */
+ kFTM_Chnl5Match = (1U << 5), /*!< Channel 5 match included as a reload point */
+ kFTM_Chnl6Match = (1U << 6), /*!< Channel 6 match included as a reload point */
+ kFTM_Chnl7Match = (1U << 7), /*!< Channel 7 match included as a reload point */
+ kFTM_CntMax = (1U << 8), /*!< Use in up-down count mode only, reload when counter reaches the maximum value */
+ kFTM_CntMin = (1U << 9), /*!< Use in up-down count mode only, reload when counter reaches the minimum value */
+ kFTM_HalfCycMatch = (1U << 10) /*!< Available on certain SoC's, half cycle match reload point */
+} ftm_reload_point_t;
+
+/*!
+ * @brief List of FTM interrupts
+ * @note Actual available interrupts are SoC-specific
+ */
+typedef enum _ftm_interrupt_enable
+{
+ kFTM_Chnl0InterruptEnable = (1U << 0), /*!< Channel 0 interrupt */
+ kFTM_Chnl1InterruptEnable = (1U << 1), /*!< Channel 1 interrupt */
+ kFTM_Chnl2InterruptEnable = (1U << 2), /*!< Channel 2 interrupt */
+ kFTM_Chnl3InterruptEnable = (1U << 3), /*!< Channel 3 interrupt */
+ kFTM_Chnl4InterruptEnable = (1U << 4), /*!< Channel 4 interrupt */
+ kFTM_Chnl5InterruptEnable = (1U << 5), /*!< Channel 5 interrupt */
+ kFTM_Chnl6InterruptEnable = (1U << 6), /*!< Channel 6 interrupt */
+ kFTM_Chnl7InterruptEnable = (1U << 7), /*!< Channel 7 interrupt */
+ kFTM_FaultInterruptEnable = (1U << 8), /*!< Fault interrupt */
+ kFTM_TimeOverflowInterruptEnable = (1U << 9), /*!< Time overflow interrupt */
+ kFTM_ReloadInterruptEnable = (1U << 10) /*!< Reload interrupt; Available only on certain SoC's */
+} ftm_interrupt_enable_t;
+
+/*!
+ * @brief List of FTM flags
+ * @note Actual available flags are SoC-specific
+ */
+typedef enum _ftm_status_flags
+{
+ kFTM_Chnl0Flag = (1U << 0), /*!< Channel 0 Flag */
+ kFTM_Chnl1Flag = (1U << 1), /*!< Channel 1 Flag */
+ kFTM_Chnl2Flag = (1U << 2), /*!< Channel 2 Flag */
+ kFTM_Chnl3Flag = (1U << 3), /*!< Channel 3 Flag */
+ kFTM_Chnl4Flag = (1U << 4), /*!< Channel 4 Flag */
+ kFTM_Chnl5Flag = (1U << 5), /*!< Channel 5 Flag */
+ kFTM_Chnl6Flag = (1U << 6), /*!< Channel 6 Flag */
+ kFTM_Chnl7Flag = (1U << 7), /*!< Channel 7 Flag */
+ kFTM_FaultFlag = (1U << 8), /*!< Fault Flag */
+ kFTM_TimeOverflowFlag = (1U << 9), /*!< Time overflow Flag */
+ kFTM_ChnlTriggerFlag = (1U << 10), /*!< Channel trigger Flag */
+ kFTM_ReloadFlag = (1U << 11) /*!< Reload Flag; Available only on certain SoC's */
+} ftm_status_flags_t;
+
+/*!
+ * @brief FTM configuration structure
+ *
+ * This structure holds the configuration settings for the FTM peripheral. To initialize this
+ * structure to reasonable defaults, call the FTM_GetDefaultConfig() function and pass a
+ * pointer to the configuration structure instance.
+ *
+ * The configuration structure can be made constant so as to reside in flash.
+ */
+typedef struct _ftm_config
+{
+ ftm_clock_prescale_t prescale; /*!< FTM clock prescale value */
+ ftm_bdm_mode_t bdmMode; /*!< FTM behavior in BDM mode */
+ uint32_t pwmSyncMode; /*!< Synchronization methods to use to update buffered registers; Multiple
+ update modes can be used by providing an OR'ed list of options
+ available in enumeration ::ftm_pwm_sync_method_t. */
+ uint32_t reloadPoints; /*!< FTM reload points; When using this, the PWM
+ synchronization is not required. Multiple reload points can be used by providing
+ an OR'ed list of options available in
+ enumeration ::ftm_reload_point_t. */
+ ftm_fault_mode_t faultMode; /*!< FTM fault control mode */
+ uint8_t faultFilterValue; /*!< Fault input filter value */
+ ftm_deadtime_prescale_t deadTimePrescale; /*!< The dead time prescalar value */
+ uint8_t deadTimeValue; /*!< The dead time value */
+ uint32_t extTriggers; /*!< External triggers to enable. Multiple trigger sources can be
+ enabled by providing an OR'ed list of options available in
+ enumeration ::ftm_external_trigger_t. */
+ uint8_t chnlInitState; /*!< Defines the initialization value of the channels in OUTINT register */
+ uint8_t chnlPolarity; /*!< Defines the output polarity of the channels in POL register */
+ bool useGlobalTimeBase; /*!< True: Use of an external global time base is enabled;
+ False: disabled */
+} ftm_config_t;
+
+/*******************************************************************************
+ * API
+ ******************************************************************************/
+
+#if defined(__cplusplus)
+extern "C" {
+#endif
+
+/*!
+ * @name Initialization and deinitialization
+ * @{
+ */
+
+/*!
+ * @brief Ungates the FTM clock and configures the peripheral for basic operation.
+ *
+ * @note This API should be called at the beginning of the application using the FTM driver.
+ *
+ * @param base FTM peripheral base address
+ * @param config Pointer to the user configuration structure.
+ *
+ * @return kStatus_Success indicates success; Else indicates failure.
+ */
+status_t FTM_Init(FTM_Type *base, const ftm_config_t *config);
+
+/*!
+ * @brief Gates the FTM clock.
+ *
+ * @param base FTM peripheral base address
+ */
+void FTM_Deinit(FTM_Type *base);
+
+/*!
+ * @brief Fills in the FTM configuration structure with the default settings.
+ *
+ * The default values are:
+ * @code
+ * config->prescale = kFTM_Prescale_Divide_1;
+ * config->bdmMode = kFTM_BdmMode_0;
+ * config->pwmSyncMode = kFTM_SoftwareTrigger;
+ * config->reloadPoints = 0;
+ * config->faultMode = kFTM_Fault_Disable;
+ * config->faultFilterValue = 0;
+ * config->deadTimePrescale = kFTM_Deadtime_Prescale_1;
+ * config->deadTimeValue = 0;
+ * config->extTriggers = 0;
+ * config->chnlInitState = 0;
+ * config->chnlPolarity = 0;
+ * config->useGlobalTimeBase = false;
+ * @endcode
+ * @param config Pointer to the user configuration structure.
+ */
+void FTM_GetDefaultConfig(ftm_config_t *config);
+
+/*! @}*/
+
+/*!
+ * @name Channel mode operations
+ * @{
+ */
+
+/*!
+ * @brief Configures the PWM signal parameters.
+ *
+ * Call this function to configure the PWM signal period, mode, duty cycle, and edge. Use this
+ * function to configure all FTM channels that are used to output a PWM signal.
+ *
+ * @param base FTM peripheral base address
+ * @param chnlParams Array of PWM channel parameters to configure the channel(s)
+ * @param numOfChnls Number of channels to configure; This should be the size of the array passed in
+ * @param mode PWM operation mode, options available in enumeration ::ftm_pwm_mode_t
+ * @param pwmFreq_Hz PWM signal frequency in Hz
+ * @param srcClock_Hz FTM counter clock in Hz
+ *
+ * @return kStatus_Success if the PWM setup was successful
+ * kStatus_Error on failure
+ */
+status_t FTM_SetupPwm(FTM_Type *base,
+ const ftm_chnl_pwm_signal_param_t *chnlParams,
+ uint8_t numOfChnls,
+ ftm_pwm_mode_t mode,
+ uint32_t pwmFreq_Hz,
+ uint32_t srcClock_Hz);
+
+/*!
+ * @brief Updates the duty cycle of an active PWM signal.
+ *
+ * @param base FTM peripheral base address
+ * @param chnlNumber The channel/channel pair number. In combined mode, this represents
+ * the channel pair number
+ * @param currentPwmMode The current PWM mode set during PWM setup
+ * @param dutyCyclePercent New PWM pulse width; The value should be between 0 to 100
+ * 0=inactive signal(0% duty cycle)...
+ * 100=active signal (100% duty cycle)
+ */
+void FTM_UpdatePwmDutycycle(FTM_Type *base,
+ ftm_chnl_t chnlNumber,
+ ftm_pwm_mode_t currentPwmMode,
+ uint8_t dutyCyclePercent);
+
+/*!
+ * @brief Updates the edge level selection for a channel.
+ *
+ * @param base FTM peripheral base address
+ * @param chnlNumber The channel number
+ * @param level The level to be set to the ELSnB:ELSnA field; Valid values are 00, 01, 10, 11.
+ * See the Kinetis SoC reference manual for details about this field.
+ */
+void FTM_UpdateChnlEdgeLevelSelect(FTM_Type *base, ftm_chnl_t chnlNumber, uint8_t level);
+
+/*!
+ * @brief Enables capturing an input signal on the channel using the function parameters.
+ *
+ * When the edge specified in the captureMode argument occurs on the channel, the FTM counter is
+ * captured into the CnV register. The user has to read the CnV register separately to get this
+ * value. The filter function is disabled if the filterVal argument passed in is 0. The filter
+ * function is available only for channels 0, 1, 2, 3.
+ *
+ * @param base FTM peripheral base address
+ * @param chnlNumber The channel number
+ * @param captureMode Specifies which edge to capture
+ * @param filterValue Filter value, specify 0 to disable filter. Available only for channels 0-3.
+ */
+void FTM_SetupInputCapture(FTM_Type *base,
+ ftm_chnl_t chnlNumber,
+ ftm_input_capture_edge_t captureMode,
+ uint32_t filterValue);
+
+/*!
+ * @brief Configures the FTM to generate timed pulses.
+ *
+ * When the FTM counter matches the value of compareVal argument (this is written into CnV reg),
+ * the channel output is changed based on what is specified in the compareMode argument.
+ *
+ * @param base FTM peripheral base address
+ * @param chnlNumber The channel number
+ * @param compareMode Action to take on the channel output when the compare condition is met
+ * @param compareValue Value to be programmed in the CnV register.
+ */
+void FTM_SetupOutputCompare(FTM_Type *base,
+ ftm_chnl_t chnlNumber,
+ ftm_output_compare_mode_t compareMode,
+ uint32_t compareValue);
+
+/*!
+ * @brief Configures the dual edge capture mode of the FTM.
+ *
+ * This function sets up the dual edge capture mode on a channel pair. The capture edge for the
+ * channel pair and the capture mode (one-shot or continuous) is specified in the parameter
+ * argument. The filter function is disabled if the filterVal argument passed is zero. The filter
+ * function is available only on channels 0 and 2. The user has to read the channel CnV registers
+ * separately to get the capture values.
+ *
+ * @param base FTM peripheral base address
+ * @param chnlPairNumber The FTM channel pair number; options are 0, 1, 2, 3
+ * @param edgeParam Sets up the dual edge capture function
+ * @param filterValue Filter value, specify 0 to disable filter. Available only for channel pair 0 and 1.
+ */
+void FTM_SetupDualEdgeCapture(FTM_Type *base,
+ ftm_chnl_t chnlPairNumber,
+ const ftm_dual_edge_capture_param_t *edgeParam,
+ uint32_t filterValue);
+
+/*! @}*/
+
+/*!
+ * @brief Configures the parameters and activates the quadrature decoder mode.
+ *
+ * @param base FTM peripheral base address
+ * @param phaseAParams Phase A configuration parameters
+ * @param phaseBParams Phase B configuration parameters
+ * @param quadMode Selects encoding mode used in quadrature decoder mode
+ */
+void FTM_SetupQuadDecode(FTM_Type *base,
+ const ftm_phase_params_t *phaseAParams,
+ const ftm_phase_params_t *phaseBParams,
+ ftm_quad_decode_mode_t quadMode);
+
+/*!
+ * @brief Sets up the working of the FTM fault protection.
+ *
+ * FTM can have up to 4 fault inputs. This function sets up fault parameters, fault level, and a filter.
+ *
+ * @param base FTM peripheral base address
+ * @param faultNumber FTM fault to configure.
+ * @param faultParams Parameters passed in to set up the fault
+ */
+void FTM_SetupFault(FTM_Type *base, ftm_fault_input_t faultNumber, const ftm_fault_param_t *faultParams);
+
+/*!
+ * @name Interrupt Interface
+ * @{
+ */
+
+/*!
+ * @brief Enables the selected FTM interrupts.
+ *
+ * @param base FTM peripheral base address
+ * @param mask The interrupts to enable. This is a logical OR of members of the
+ * enumeration ::ftm_interrupt_enable_t
+ */
+void FTM_EnableInterrupts(FTM_Type *base, uint32_t mask);
+
+/*!
+ * @brief Disables the selected FTM interrupts.
+ *
+ * @param base FTM peripheral base address
+ * @param mask The interrupts to enable. This is a logical OR of members of the
+ * enumeration ::ftm_interrupt_enable_t
+ */
+void FTM_DisableInterrupts(FTM_Type *base, uint32_t mask);
+
+/*!
+ * @brief Gets the enabled FTM interrupts.
+ *
+ * @param base FTM peripheral base address
+ *
+ * @return The enabled interrupts. This is the logical OR of members of the
+ * enumeration ::ftm_interrupt_enable_t
+ */
+uint32_t FTM_GetEnabledInterrupts(FTM_Type *base);
+
+/*! @}*/
+
+/*!
+ * @name Status Interface
+ * @{
+ */
+
+/*!
+ * @brief Gets the FTM status flags.
+ *
+ * @param base FTM peripheral base address
+ *
+ * @return The status flags. This is the logical OR of members of the
+ * enumeration ::ftm_status_flags_t
+ */
+uint32_t FTM_GetStatusFlags(FTM_Type *base);
+
+/*!
+ * @brief Clears the FTM status flags.
+ *
+ * @param base FTM peripheral base address
+ * @param mask The status flags to clear. This is a logical OR of members of the
+ * enumeration ::ftm_status_flags_t
+ */
+void FTM_ClearStatusFlags(FTM_Type *base, uint32_t mask);
+
+/*! @}*/
+
+/*!
+ * @name Timer Start and Stop
+ * @{
+ */
+
+/*!
+ * @brief Starts the FTM counter.
+ *
+ * @param base FTM peripheral base address
+ * @param clockSource FTM clock source; After the clock source is set, the counter starts running.
+ */
+static inline void FTM_StartTimer(FTM_Type *base, ftm_clock_source_t clockSource)
+{
+ uint32_t reg = base->SC;
+
+ reg &= ~(FTM_SC_CLKS_MASK);
+ reg |= FTM_SC_CLKS(clockSource);
+ base->SC = reg;
+}
+
+/*!
+ * @brief Stops the FTM counter.
+ *
+ * @param base FTM peripheral base address
+ */
+static inline void FTM_StopTimer(FTM_Type *base)
+{
+ /* Set clock source to none to disable counter */
+ base->SC &= ~(FTM_SC_CLKS_MASK);
+}
+
+/*! @}*/
+
+/*!
+ * @name Software output control
+ * @{
+ */
+
+/*!
+ * @brief Enables or disables the channel software output control.
+ *
+ * @param base FTM peripheral base address
+ * @param chnlNumber Channel to be enabled or disabled
+ * @param value true: channel output is affected by software output control
+ false: channel output is unaffected by software output control
+ */
+static inline void FTM_SetSoftwareCtrlEnable(FTM_Type *base, ftm_chnl_t chnlNumber, bool value)
+{
+ if (value)
+ {
+ base->SWOCTRL |= (1U << chnlNumber);
+ }
+ else
+ {
+ base->SWOCTRL &= ~(1U << chnlNumber);
+ }
+}
+
+/*!
+ * @brief Sets the channel software output control value.
+ *
+ * @param base FTM peripheral base address.
+ * @param chnlNumber Channel to be configured
+ * @param value true to set 1, false to set 0
+ */
+static inline void FTM_SetSoftwareCtrlVal(FTM_Type *base, ftm_chnl_t chnlNumber, bool value)
+{
+ if (value)
+ {
+ base->SWOCTRL |= (1U << (chnlNumber + FTM_SWOCTRL_CH0OCV_SHIFT));
+ }
+ else
+ {
+ base->SWOCTRL &= ~(1U << (chnlNumber + FTM_SWOCTRL_CH0OCV_SHIFT));
+ }
+}
+
+/*! @}*/
+
+/*!
+ * @brief Enables or disables the FTM global time base signal generation to other FTMs.
+ *
+ * @param base FTM peripheral base address
+ * @param enable true to enable, false to disable
+ */
+static inline void FTM_SetGlobalTimeBaseOutputEnable(FTM_Type *base, bool enable)
+{
+ if (enable)
+ {
+ base->CONF |= FTM_CONF_GTBEOUT_MASK;
+ }
+ else
+ {
+ base->CONF &= ~FTM_CONF_GTBEOUT_MASK;
+ }
+}
+
+/*!
+ * @brief Sets the FTM peripheral timer channel output mask.
+ *
+ * @param base FTM peripheral base address
+ * @param chnlNumber Channel to be configured
+ * @param mask true: masked, channel is forced to its inactive state; false: unmasked
+ */
+static inline void FTM_SetOutputMask(FTM_Type *base, ftm_chnl_t chnlNumber, bool mask)
+{
+ if (mask)
+ {
+ base->OUTMASK |= (1U << chnlNumber);
+ }
+ else
+ {
+ base->OUTMASK &= ~(1U << chnlNumber);
+ }
+}
+
+#if defined(FSL_FEATURE_FTM_HAS_ENABLE_PWM_OUTPUT) && (FSL_FEATURE_FTM_HAS_ENABLE_PWM_OUTPUT)
+/*!
+ * @brief Allows user to enable an output on an FTM channel.
+ *
+ * To enable the PWM channel output call this function with val=true. For input mode,
+ * call this function with val=false.
+ *
+ * @param base FTM peripheral base address
+ * @param chnlNumber Channel to be configured
+ * @param value true: enable output; false: output is disabled, used in input mode
+ */
+static inline void FTM_SetPwmOutputEnable(FTM_Type *base, ftm_chnl_t chnlNumber, bool value)
+{
+ if (value)
+ {
+ base->SC |= (1U << (chnlNumber + FTM_SC_PWMEN0_SHIFT));
+ }
+ else
+ {
+ base->SC &= ~(1U << (chnlNumber + FTM_SC_PWMEN0_SHIFT));
+ }
+}
+#endif
+
+/*!
+ * @name Channel pair operations
+ * @{
+ */
+
+/*!
+ * @brief This function enables/disables the fault control in a channel pair.
+ *
+ * @param base FTM peripheral base address
+ * @param chnlPairNumber The FTM channel pair number; options are 0, 1, 2, 3
+ * @param value true: Enable fault control for this channel pair; false: No fault control
+ */
+static inline void FTM_SetFaultControlEnable(FTM_Type *base, ftm_chnl_t chnlPairNumber, bool value)
+{
+ if (value)
+ {
+ base->COMBINE |= (1U << (FTM_COMBINE_FAULTEN0_SHIFT + (FTM_COMBINE_COMBINE1_SHIFT * chnlPairNumber)));
+ }
+ else
+ {
+ base->COMBINE &= ~(1U << (FTM_COMBINE_FAULTEN0_SHIFT + (FTM_COMBINE_COMBINE1_SHIFT * chnlPairNumber)));
+ }
+}
+
+/*!
+ * @brief This function enables/disables the dead time insertion in a channel pair.
+ *
+ * @param base FTM peripheral base address
+ * @param chnlPairNumber The FTM channel pair number; options are 0, 1, 2, 3
+ * @param value true: Insert dead time in this channel pair; false: No dead time inserted
+ */
+static inline void FTM_SetDeadTimeEnable(FTM_Type *base, ftm_chnl_t chnlPairNumber, bool value)
+{
+ if (value)
+ {
+ base->COMBINE |= (1U << (FTM_COMBINE_DTEN0_SHIFT + (FTM_COMBINE_COMBINE1_SHIFT * chnlPairNumber)));
+ }
+ else
+ {
+ base->COMBINE &= ~(1U << (FTM_COMBINE_DTEN0_SHIFT + (FTM_COMBINE_COMBINE1_SHIFT * chnlPairNumber)));
+ }
+}
+
+/*!
+ * @brief This function enables/disables complementary mode in a channel pair.
+ *
+ * @param base FTM peripheral base address
+ * @param chnlPairNumber The FTM channel pair number; options are 0, 1, 2, 3
+ * @param value true: enable complementary mode; false: disable complementary mode
+ */
+static inline void FTM_SetComplementaryEnable(FTM_Type *base, ftm_chnl_t chnlPairNumber, bool value)
+{
+ if (value)
+ {
+ base->COMBINE |= (1U << (FTM_COMBINE_COMP0_SHIFT + (FTM_COMBINE_COMBINE1_SHIFT * chnlPairNumber)));
+ }
+ else
+ {
+ base->COMBINE &= ~(1U << (FTM_COMBINE_COMP0_SHIFT + (FTM_COMBINE_COMBINE1_SHIFT * chnlPairNumber)));
+ }
+}
+
+/*!
+ * @brief This function enables/disables inverting control in a channel pair.
+ *
+ * @param base FTM peripheral base address
+ * @param chnlPairNumber The FTM channel pair number; options are 0, 1, 2, 3
+ * @param value true: enable inverting; false: disable inverting
+ */
+static inline void FTM_SetInvertEnable(FTM_Type *base, ftm_chnl_t chnlPairNumber, bool value)
+{
+ if (value)
+ {
+ base->INVCTRL |= (1U << chnlPairNumber);
+ }
+ else
+ {
+ base->INVCTRL &= ~(1U << chnlPairNumber);
+ }
+}
+
+/*! @}*/
+
+/*!
+ * @brief Enables or disables the FTM software trigger for PWM synchronization.
+ *
+ * @param base FTM peripheral base address
+ * @param enable true: software trigger is selected, false: software trigger is not selected
+ */
+static inline void FTM_SetSoftwareTrigger(FTM_Type *base, bool enable)
+{
+ if (enable)
+ {
+ base->SYNC |= FTM_SYNC_SWSYNC_MASK;
+ }
+ else
+ {
+ base->SYNC &= ~FTM_SYNC_SWSYNC_MASK;
+ }
+}
+
+/*!
+ * @brief Enables or disables the FTM write protection.
+ *
+ * @param base FTM peripheral base address
+ * @param enable true: Write-protection is enabled, false: Write-protection is disabled
+ */
+static inline void FTM_SetWriteProtection(FTM_Type *base, bool enable)
+{
+ /* Configure write protection */
+ if (enable)
+ {
+ base->FMS |= FTM_FMS_WPEN_MASK;
+ }
+ else
+ {
+ base->MODE |= FTM_MODE_WPDIS_MASK;
+ }
+}
+
+#if defined(__cplusplus)
+}
+#endif
+
+/*! @}*/
+
+#endif /* _FSL_FTM_H_*/
diff --git a/drivers/fsl_gpio.c b/drivers/fsl_gpio.c
new file mode 100644
index 0000000..8fc068f
--- /dev/null
+++ b/drivers/fsl_gpio.c
@@ -0,0 +1,179 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_gpio.h"
+
+/*******************************************************************************
+ * Variables
+ ******************************************************************************/
+static PORT_Type *const s_portBases[] = PORT_BASE_PTRS;
+static GPIO_Type *const s_gpioBases[] = GPIO_BASE_PTRS;
+
+/*******************************************************************************
+* Prototypes
+******************************************************************************/
+
+/*!
+* @brief Gets the GPIO instance according to the GPIO base
+*
+* @param base GPIO peripheral base pointer(PTA, PTB, PTC, etc.)
+* @retval GPIO instance
+*/
+static uint32_t GPIO_GetInstance(GPIO_Type *base);
+
+/*******************************************************************************
+ * Code
+ ******************************************************************************/
+
+static uint32_t GPIO_GetInstance(GPIO_Type *base)
+{
+ uint32_t instance;
+
+ /* Find the instance index from base address mappings. */
+ for (instance = 0; instance < FSL_FEATURE_SOC_GPIO_COUNT; instance++)
+ {
+ if (s_gpioBases[instance] == base)
+ {
+ break;
+ }
+ }
+
+ assert(instance < FSL_FEATURE_SOC_GPIO_COUNT);
+
+ return instance;
+}
+
+void GPIO_PinInit(GPIO_Type *base, uint32_t pin, const gpio_pin_config_t *config)
+{
+ assert(config);
+
+ if (config->pinDirection == kGPIO_DigitalInput)
+ {
+ base->PDDR &= ~(1U << pin);
+ }
+ else
+ {
+ GPIO_WritePinOutput(base, pin, config->outputLogic);
+ base->PDDR |= (1U << pin);
+ }
+}
+
+uint32_t GPIO_GetPinsInterruptFlags(GPIO_Type *base)
+{
+ uint8_t instance;
+ PORT_Type *portBase;
+ instance = GPIO_GetInstance(base);
+ portBase = s_portBases[instance];
+ return portBase->ISFR;
+}
+
+void GPIO_ClearPinsInterruptFlags(GPIO_Type *base, uint32_t mask)
+{
+ uint8_t instance;
+ PORT_Type *portBase;
+ instance = GPIO_GetInstance(base);
+ portBase = s_portBases[instance];
+ portBase->ISFR = mask;
+}
+
+#if defined(FSL_FEATURE_SOC_FGPIO_COUNT) && FSL_FEATURE_SOC_FGPIO_COUNT
+
+/*******************************************************************************
+ * Variables
+ ******************************************************************************/
+static FGPIO_Type *const s_fgpioBases[] = FGPIO_BASE_PTRS;
+
+/*******************************************************************************
+* Prototypes
+******************************************************************************/
+/*!
+* @brief Gets the FGPIO instance according to the GPIO base
+*
+* @param base FGPIO peripheral base pointer(PTA, PTB, PTC, etc.)
+* @retval FGPIO instance
+*/
+static uint32_t FGPIO_GetInstance(FGPIO_Type *base);
+
+/*******************************************************************************
+ * Code
+ ******************************************************************************/
+
+static uint32_t FGPIO_GetInstance(FGPIO_Type *base)
+{
+ uint32_t instance;
+
+ /* Find the instance index from base address mappings. */
+ for (instance = 0; instance < FSL_FEATURE_SOC_FGPIO_COUNT; instance++)
+ {
+ if (s_fgpioBases[instance] == base)
+ {
+ break;
+ }
+ }
+
+ assert(instance < FSL_FEATURE_SOC_FGPIO_COUNT);
+
+ return instance;
+}
+
+void FGPIO_PinInit(FGPIO_Type *base, uint32_t pin, const gpio_pin_config_t *config)
+{
+ assert(config);
+
+ if (config->pinDirection == kGPIO_DigitalInput)
+ {
+ base->PDDR &= ~(1U << pin);
+ }
+ else
+ {
+ FGPIO_WritePinOutput(base, pin, config->outputLogic);
+ base->PDDR |= (1U << pin);
+ }
+}
+
+uint32_t FGPIO_GetPinsInterruptFlags(FGPIO_Type *base)
+{
+ uint8_t instance;
+ instance = FGPIO_GetInstance(base);
+ PORT_Type *portBase;
+ portBase = s_portBases[instance];
+ return portBase->ISFR;
+}
+
+void FGPIO_ClearPinsInterruptFlags(FGPIO_Type *base, uint32_t mask)
+{
+ uint8_t instance;
+ instance = FGPIO_GetInstance(base);
+ PORT_Type *portBase;
+ portBase = s_portBases[instance];
+ portBase->ISFR = mask;
+}
+
+#endif /* FSL_FEATURE_SOC_FGPIO_COUNT */
diff --git a/drivers/fsl_gpio.h b/drivers/fsl_gpio.h
new file mode 100644
index 0000000..d62545f
--- /dev/null
+++ b/drivers/fsl_gpio.h
@@ -0,0 +1,389 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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 SDRVL 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_GPIO_H_
+#define _FSL_GPIO_H_
+
+#include "fsl_common.h"
+
+/*!
+ * @addtogroup gpio
+ * @{
+ */
+
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+/*! @name Driver version */
+/*@{*/
+/*! @brief GPIO driver version 2.1.0. */
+#define FSL_GPIO_DRIVER_VERSION (MAKE_VERSION(2, 1, 0))
+/*@}*/
+
+/*! @brief GPIO direction definition*/
+typedef enum _gpio_pin_direction
+{
+ kGPIO_DigitalInput = 0U, /*!< Set current pin as digital input*/
+ kGPIO_DigitalOutput = 1U, /*!< Set current pin as digital output*/
+} gpio_pin_direction_t;
+
+/*!
+ * @brief The GPIO pin configuration structure.
+ *
+ * Every pin can only be configured as either output pin or input pin at a time.
+ * If configured as a input pin, then leave the outputConfig unused
+ * Note : In some use cases, the corresponding port property should be configured in advance
+ * with the PORT_SetPinConfig()
+ */
+typedef struct _gpio_pin_config
+{
+ gpio_pin_direction_t pinDirection; /*!< GPIO direction, input or output */
+ /* Output configurations, please ignore if configured as a input one */
+ uint8_t outputLogic; /*!< Set default output logic, no use in input */
+} gpio_pin_config_t;
+
+/*! @} */
+
+/*******************************************************************************
+ * API
+ ******************************************************************************/
+
+#if defined(__cplusplus)
+extern "C" {
+#endif
+
+/*!
+ * @addtogroup gpio_driver
+ * @{
+ */
+
+/*! @name GPIO Configuration */
+/*@{*/
+
+/*!
+ * @brief Initializes a GPIO pin used by the board.
+ *
+ * To initialize the GPIO, define a pin configuration, either input or output, in the user file.
+ * Then, call the GPIO_PinInit() function.
+ *
+ * This is an example to define an input pin or output pin configuration:
+ * @code
+ * // Define a digital input pin configuration,
+ * gpio_pin_config_t config =
+ * {
+ * kGPIO_DigitalInput,
+ * 0,
+ * }
+ * //Define a digital output pin configuration,
+ * gpio_pin_config_t config =
+ * {
+ * kGPIO_DigitalOutput,
+ * 0,
+ * }
+ * @endcode
+ *
+ * @param base GPIO peripheral base pointer(GPIOA, GPIOB, GPIOC, and so on.)
+ * @param pin GPIO port pin number
+ * @param config GPIO pin configuration pointer
+ */
+void GPIO_PinInit(GPIO_Type *base, uint32_t pin, const gpio_pin_config_t *config);
+
+/*@}*/
+
+/*! @name GPIO Output Operations */
+/*@{*/
+
+/*!
+ * @brief Sets the output level of the multiple GPIO pins to the logic 1 or 0.
+ *
+ * @param base GPIO peripheral base pointer(GPIOA, GPIOB, GPIOC, and so on.)
+ * @param pin GPIO pin number
+ * @param output GPIO pin output logic level.
+ * - 0: corresponding pin output low-logic level.
+ * - 1: corresponding pin output high-logic level.
+ */
+static inline void GPIO_WritePinOutput(GPIO_Type *base, uint32_t pin, uint8_t output)
+{
+ if (output == 0U)
+ {
+ base->PCOR = 1 << pin;
+ }
+ else
+ {
+ base->PSOR = 1 << pin;
+ }
+}
+
+/*!
+ * @brief Sets the output level of the multiple GPIO pins to the logic 1.
+ *
+ * @param base GPIO peripheral base pointer(GPIOA, GPIOB, GPIOC, and so on.)
+ * @param mask GPIO pin number macro
+ */
+static inline void GPIO_SetPinsOutput(GPIO_Type *base, uint32_t mask)
+{
+ base->PSOR = mask;
+}
+
+/*!
+ * @brief Sets the output level of the multiple GPIO pins to the logic 0.
+ *
+ * @param base GPIO peripheral base pointer(GPIOA, GPIOB, GPIOC, and so on.)
+ * @param mask GPIO pin number macro
+ */
+static inline void GPIO_ClearPinsOutput(GPIO_Type *base, uint32_t mask)
+{
+ base->PCOR = mask;
+}
+
+/*!
+ * @brief Reverses current output logic of the multiple GPIO pins.
+ *
+ * @param base GPIO peripheral base pointer(GPIOA, GPIOB, GPIOC, and so on.)
+ * @param mask GPIO pin number macro
+ */
+static inline void GPIO_TogglePinsOutput(GPIO_Type *base, uint32_t mask)
+{
+ base->PTOR = mask;
+}
+/*@}*/
+
+/*! @name GPIO Input Operations */
+/*@{*/
+
+/*!
+ * @brief Reads the current input value of the whole GPIO port.
+ *
+ * @param base GPIO peripheral base pointer(GPIOA, GPIOB, GPIOC, and so on.)
+ * @param pin GPIO pin number
+ * @retval GPIO port input value
+ * - 0: corresponding pin input low-logic level.
+ * - 1: corresponding pin input high-logic level.
+ */
+static inline uint32_t GPIO_ReadPinInput(GPIO_Type *base, uint32_t pin)
+{
+ return (((base->PDIR) >> pin) & 0x01U);
+}
+/*@}*/
+
+/*! @name GPIO Interrupt */
+/*@{*/
+
+/*!
+ * @brief Reads whole GPIO port interrupt status flag.
+ *
+ * If a pin is configured to generate the DMA request, the corresponding flag
+ * is cleared automatically at the completion of the requested DMA transfer.
+ * Otherwise, the flag remains set until a logic one is written to that flag.
+ * If configured for a level sensitive interrupt that remains asserted, the flag
+ * is set again immediately.
+ *
+ * @param base GPIO peripheral base pointer(GPIOA, GPIOB, GPIOC, and so on.)
+ * @retval Current GPIO port interrupt status flag, for example, 0x00010001 means the
+ * pin 0 and 17 have the interrupt.
+ */
+uint32_t GPIO_GetPinsInterruptFlags(GPIO_Type *base);
+
+/*!
+ * @brief Clears multiple GPIO pin interrupt status flag.
+ *
+ * @param base GPIO peripheral base pointer(GPIOA, GPIOB, GPIOC, and so on.)
+ * @param mask GPIO pin number macro
+ */
+void GPIO_ClearPinsInterruptFlags(GPIO_Type *base, uint32_t mask);
+
+/*@}*/
+/*! @} */
+
+/*!
+ * @addtogroup fgpio_driver
+ * @{
+ */
+
+/*
+ * Introduce the FGPIO feature.
+ *
+ * The FGPIO features are only support on some of Kinetis chips. The FGPIO registers are aliased to the IOPORT
+ * interface. Accesses via the IOPORT interface occur in parallel with any instruction fetches and will therefore
+ * complete in a single cycle. This aliased Fast GPIO memory map is called FGPIO.
+ */
+
+#if defined(FSL_FEATURE_SOC_FGPIO_COUNT) && FSL_FEATURE_SOC_FGPIO_COUNT
+
+/*! @name FGPIO Configuration */
+/*@{*/
+
+/*!
+ * @brief Initializes a FGPIO pin used by the board.
+ *
+ * To initialize the FGPIO driver, define a pin configuration, either input or output, in the user file.
+ * Then, call the FGPIO_PinInit() function.
+ *
+ * This is an example to define an input pin or output pin configuration:
+ * @code
+ * // Define a digital input pin configuration,
+ * gpio_pin_config_t config =
+ * {
+ * kGPIO_DigitalInput,
+ * 0,
+ * }
+ * //Define a digital output pin configuration,
+ * gpio_pin_config_t config =
+ * {
+ * kGPIO_DigitalOutput,
+ * 0,
+ * }
+ * @endcode
+ *
+ * @param base FGPIO peripheral base pointer(GPIOA, GPIOB, GPIOC, and so on.)
+ * @param pin FGPIO port pin number
+ * @param config FGPIO pin configuration pointer
+ */
+void FGPIO_PinInit(FGPIO_Type *base, uint32_t pin, const gpio_pin_config_t *config);
+
+/*@}*/
+
+/*! @name FGPIO Output Operations */
+/*@{*/
+
+/*!
+ * @brief Sets the output level of the multiple FGPIO pins to the logic 1 or 0.
+ *
+ * @param base FGPIO peripheral base pointer(GPIOA, GPIOB, GPIOC, and so on.)
+ * @param pin FGPIO pin number
+ * @param output FGPIOpin output logic level.
+ * - 0: corresponding pin output low-logic level.
+ * - 1: corresponding pin output high-logic level.
+ */
+static inline void FGPIO_WritePinOutput(FGPIO_Type *base, uint32_t pin, uint8_t output)
+{
+ if (output == 0U)
+ {
+ base->PCOR = 1 << pin;
+ }
+ else
+ {
+ base->PSOR = 1 << pin;
+ }
+}
+
+/*!
+ * @brief Sets the output level of the multiple FGPIO pins to the logic 1.
+ *
+ * @param base FGPIO peripheral base pointer(GPIOA, GPIOB, GPIOC, and so on.)
+ * @param mask FGPIO pin number macro
+ */
+static inline void FGPIO_SetPinsOutput(FGPIO_Type *base, uint32_t mask)
+{
+ base->PSOR = mask;
+}
+
+/*!
+ * @brief Sets the output level of the multiple FGPIO pins to the logic 0.
+ *
+ * @param base FGPIO peripheral base pointer(GPIOA, GPIOB, GPIOC, and so on.)
+ * @param mask FGPIO pin number macro
+ */
+static inline void FGPIO_ClearPinsOutput(FGPIO_Type *base, uint32_t mask)
+{
+ base->PCOR = mask;
+}
+
+/*!
+ * @brief Reverses current output logic of the multiple FGPIO pins.
+ *
+ * @param base FGPIO peripheral base pointer(GPIOA, GPIOB, GPIOC, and so on.)
+ * @param mask FGPIO pin number macro
+ */
+static inline void FGPIO_TogglePinsOutput(FGPIO_Type *base, uint32_t mask)
+{
+ base->PTOR = mask;
+}
+/*@}*/
+
+/*! @name FGPIO Input Operations */
+/*@{*/
+
+/*!
+ * @brief Reads the current input value of the whole FGPIO port.
+ *
+ * @param base FGPIO peripheral base pointer(GPIOA, GPIOB, GPIOC, and so on.)
+ * @param pin FGPIO pin number
+ * @retval FGPIO port input value
+ * - 0: corresponding pin input low-logic level.
+ * - 1: corresponding pin input high-logic level.
+ */
+static inline uint32_t FGPIO_ReadPinInput(FGPIO_Type *base, uint32_t pin)
+{
+ return (((base->PDIR) >> pin) & 0x01U);
+}
+/*@}*/
+
+/*! @name FGPIO Interrupt */
+/*@{*/
+
+/*!
+ * @brief Reads the whole FGPIO port interrupt status flag.
+ *
+ * If a pin is configured to generate the DMA request, the corresponding flag
+ * is cleared automatically at the completion of the requested DMA transfer.
+ * Otherwise, the flag remains set until a logic one is written to that flag.
+ * If configured for a level sensitive interrupt that remains asserted, the flag
+ * is set again immediately.
+ *
+ * @param base FGPIO peripheral base pointer(GPIOA, GPIOB, GPIOC, and so on.)
+ * @retval Current FGPIO port interrupt status flags, for example, 0x00010001 means the
+ * pin 0 and 17 have the interrupt.
+ */
+uint32_t FGPIO_GetPinsInterruptFlags(FGPIO_Type *base);
+
+/*!
+ * @brief Clears the multiple FGPIO pin interrupt status flag.
+ *
+ * @param base FGPIO peripheral base pointer(GPIOA, GPIOB, GPIOC, and so on.)
+ * @param mask FGPIO pin number macro
+ */
+void FGPIO_ClearPinsInterruptFlags(FGPIO_Type *base, uint32_t mask);
+
+/*@}*/
+
+#endif /* FSL_FEATURE_SOC_FGPIO_COUNT */
+
+#if defined(__cplusplus)
+}
+#endif
+
+/*!
+ * @}
+ */
+
+#endif /* _FSL_GPIO_H_*/
diff --git a/drivers/fsl_i2c.c b/drivers/fsl_i2c.c
new file mode 100644
index 0000000..b51fc07
--- /dev/null
+++ b/drivers/fsl_i2c.c
@@ -0,0 +1,1633 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_i2c.h"
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+/*! @brief i2c transfer state. */
+enum _i2c_transfer_states
+{
+ kIdleState = 0x0U, /*!< I2C bus idle. */
+ kCheckAddressState = 0x1U, /*!< 7-bit address check state. */
+ kSendCommandState = 0x2U, /*!< Send command byte phase. */
+ kSendDataState = 0x3U, /*!< Send data transfer phase. */
+ kReceiveDataBeginState = 0x4U, /*!< Receive data transfer phase begin. */
+ kReceiveDataState = 0x5U, /*!< Receive data transfer phase. */
+};
+
+/*! @brief Common sets of flags used by the driver. */
+enum _i2c_flag_constants
+{
+/*! All flags which are cleared by the driver upon starting a transfer. */
+#if defined(FSL_FEATURE_I2C_HAS_START_STOP_DETECT) && FSL_FEATURE_I2C_HAS_START_STOP_DETECT
+ kClearFlags = kI2C_ArbitrationLostFlag | kI2C_IntPendingFlag | kI2C_StartDetectFlag | kI2C_StopDetectFlag,
+ kIrqFlags = kI2C_GlobalInterruptEnable | kI2C_StartStopDetectInterruptEnable,
+#elif defined(FSL_FEATURE_I2C_HAS_STOP_DETECT) && FSL_FEATURE_I2C_HAS_STOP_DETECT
+ kClearFlags = kI2C_ArbitrationLostFlag | kI2C_IntPendingFlag | kI2C_StopDetectFlag,
+ kIrqFlags = kI2C_GlobalInterruptEnable | kI2C_StopDetectInterruptEnable,
+#else
+ kClearFlags = kI2C_ArbitrationLostFlag | kI2C_IntPendingFlag,
+ kIrqFlags = kI2C_GlobalInterruptEnable,
+#endif
+
+};
+
+/*! @brief Typedef for interrupt handler. */
+typedef void (*i2c_isr_t)(I2C_Type *base, void *i2cHandle);
+
+/*******************************************************************************
+ * Prototypes
+ ******************************************************************************/
+
+/*!
+ * @brief Get instance number for I2C module.
+ *
+ * @param base I2C peripheral base address.
+ */
+uint32_t I2C_GetInstance(I2C_Type *base);
+
+/*!
+ * @brief Set up master transfer, send slave address and decide the initial
+ * transfer state.
+ *
+ * @param base I2C peripheral base address.
+ * @param handle pointer to i2c_master_handle_t structure which stores the transfer state.
+ * @param xfer pointer to i2c_master_transfer_t structure.
+ */
+static status_t I2C_InitTransferStateMachine(I2C_Type *base, i2c_master_handle_t *handle, i2c_master_transfer_t *xfer);
+
+/*!
+ * @brief Check and clear status operation.
+ *
+ * @param base I2C peripheral base address.
+ * @param status current i2c hardware status.
+ * @retval kStatus_Success No error found.
+ * @retval kStatus_I2C_ArbitrationLost Transfer error, arbitration lost.
+ * @retval kStatus_I2C_Nak Received Nak error.
+ */
+static status_t I2C_CheckAndClearError(I2C_Type *base, uint32_t status);
+
+/*!
+ * @brief Master run transfer state machine to perform a byte of transfer.
+ *
+ * @param base I2C peripheral base address.
+ * @param handle pointer to i2c_master_handle_t structure which stores the transfer state
+ * @param isDone input param to get whether the thing is done, true is done
+ * @retval kStatus_Success No error found.
+ * @retval kStatus_I2C_ArbitrationLost Transfer error, arbitration lost.
+ * @retval kStatus_I2C_Nak Received Nak error.
+ * @retval kStatus_I2C_Timeout Transfer error, wait signal timeout.
+ */
+static status_t I2C_MasterTransferRunStateMachine(I2C_Type *base, i2c_master_handle_t *handle, bool *isDone);
+
+/*!
+ * @brief I2C common interrupt handler.
+ *
+ * @param base I2C peripheral base address.
+ * @param handle pointer to i2c_master_handle_t structure which stores the transfer state
+ */
+static void I2C_TransferCommonIRQHandler(I2C_Type *base, void *handle);
+
+/*******************************************************************************
+ * Variables
+ ******************************************************************************/
+
+/*! @brief Pointers to i2c handles for each instance. */
+static void *s_i2cHandle[FSL_FEATURE_SOC_I2C_COUNT] = {NULL};
+
+/*! @brief SCL clock divider used to calculate baudrate. */
+static const uint16_t s_i2cDividerTable[] = {
+ 20, 22, 24, 26, 28, 30, 34, 40, 28, 32, 36, 40, 44, 48, 56, 68,
+ 48, 56, 64, 72, 80, 88, 104, 128, 80, 96, 112, 128, 144, 160, 192, 240,
+ 160, 192, 224, 256, 288, 320, 384, 480, 320, 384, 448, 512, 576, 640, 768, 960,
+ 640, 768, 896, 1024, 1152, 1280, 1536, 1920, 1280, 1536, 1792, 2048, 2304, 2560, 3072, 3840};
+
+/*! @brief Pointers to i2c bases for each instance. */
+static I2C_Type *const s_i2cBases[] = I2C_BASE_PTRS;
+
+/*! @brief Pointers to i2c IRQ number for each instance. */
+static const IRQn_Type s_i2cIrqs[] = I2C_IRQS;
+
+/*! @brief Pointers to i2c clocks for each instance. */
+static const clock_ip_name_t s_i2cClocks[] = I2C_CLOCKS;
+
+/*! @brief Pointer to master IRQ handler for each instance. */
+static i2c_isr_t s_i2cMasterIsr;
+
+/*! @brief Pointer to slave IRQ handler for each instance. */
+static i2c_isr_t s_i2cSlaveIsr;
+
+/*******************************************************************************
+ * Codes
+ ******************************************************************************/
+
+uint32_t I2C_GetInstance(I2C_Type *base)
+{
+ uint32_t instance;
+
+ /* Find the instance index from base address mappings. */
+ for (instance = 0; instance < FSL_FEATURE_SOC_I2C_COUNT; instance++)
+ {
+ if (s_i2cBases[instance] == base)
+ {
+ break;
+ }
+ }
+
+ assert(instance < FSL_FEATURE_SOC_I2C_COUNT);
+
+ return instance;
+}
+
+static status_t I2C_InitTransferStateMachine(I2C_Type *base, i2c_master_handle_t *handle, i2c_master_transfer_t *xfer)
+{
+ status_t result = kStatus_Success;
+ i2c_direction_t direction = xfer->direction;
+ uint16_t timeout = UINT16_MAX;
+
+ /* Initialize the handle transfer information. */
+ handle->transfer = *xfer;
+
+ /* Save total transfer size. */
+ handle->transferSize = xfer->dataSize;
+
+ /* Initial transfer state. */
+ if (handle->transfer.subaddressSize > 0)
+ {
+ handle->state = kSendCommandState;
+ if (xfer->direction == kI2C_Read)
+ {
+ direction = kI2C_Write;
+ }
+ }
+ else
+ {
+ handle->state = kCheckAddressState;
+ }
+
+ /* Wait until the data register is ready for transmit. */
+ while ((!(base->S & kI2C_TransferCompleteFlag)) && (--timeout))
+ {
+ }
+
+ /* Failed to start the transfer. */
+ if (timeout == 0)
+ {
+ return kStatus_I2C_Timeout;
+ }
+
+ /* Clear all status before transfer. */
+ I2C_MasterClearStatusFlags(base, kClearFlags);
+
+ /* If repeated start is requested, send repeated start. */
+ if (handle->transfer.flags & kI2C_TransferRepeatedStartFlag)
+ {
+ result = I2C_MasterRepeatedStart(base, handle->transfer.slaveAddress, direction);
+ }
+ else /* For normal transfer, send start. */
+ {
+ result = I2C_MasterStart(base, handle->transfer.slaveAddress, direction);
+ }
+
+ return result;
+}
+
+static status_t I2C_CheckAndClearError(I2C_Type *base, uint32_t status)
+{
+ status_t result = kStatus_Success;
+
+ /* Check arbitration lost. */
+ if (status & kI2C_ArbitrationLostFlag)
+ {
+ /* Clear arbitration lost flag. */
+ base->S = kI2C_ArbitrationLostFlag;
+ result = kStatus_I2C_ArbitrationLost;
+ }
+ /* Check NAK */
+ else if (status & kI2C_ReceiveNakFlag)
+ {
+ result = kStatus_I2C_Nak;
+ }
+ else
+ {
+ }
+
+ return result;
+}
+
+static status_t I2C_MasterTransferRunStateMachine(I2C_Type *base, i2c_master_handle_t *handle, bool *isDone)
+{
+ status_t result = kStatus_Success;
+ uint32_t statusFlags = base->S;
+ *isDone = false;
+ volatile uint8_t dummy = 0;
+ bool ignoreNak = ((handle->state == kSendDataState) && (handle->transfer.dataSize == 0U)) ||
+ ((handle->state == kReceiveDataState) && (handle->transfer.dataSize == 1U));
+
+ /* Add this to avoid build warning. */
+ dummy++;
+
+ /* Check & clear error flags. */
+ result = I2C_CheckAndClearError(base, statusFlags);
+
+ /* Ignore Nak when it's appeared for last byte. */
+ if ((result == kStatus_I2C_Nak) && ignoreNak)
+ {
+ result = kStatus_Success;
+ }
+
+ if (result)
+ {
+ return result;
+ }
+
+ /* Handle Check address state to check the slave address is Acked in slave
+ probe application. */
+ if (handle->state == kCheckAddressState)
+ {
+ if (statusFlags & kI2C_ReceiveNakFlag)
+ {
+ return kStatus_I2C_Nak;
+ }
+ else
+ {
+ if (handle->transfer.direction == kI2C_Write)
+ {
+ /* Next state, send data. */
+ handle->state = kSendDataState;
+ }
+ else
+ {
+ /* Next state, receive data begin. */
+ handle->state = kReceiveDataBeginState;
+ }
+ }
+ }
+
+ /* Run state machine. */
+ switch (handle->state)
+ {
+ /* Send I2C command. */
+ case kSendCommandState:
+ if (handle->transfer.subaddressSize)
+ {
+ handle->transfer.subaddressSize--;
+ base->D = ((handle->transfer.subaddress) >> (8 * handle->transfer.subaddressSize));
+ }
+ else
+ {
+ if (handle->transfer.direction == kI2C_Write)
+ {
+ /* Next state, send data. */
+ handle->state = kSendDataState;
+
+ /* Send first byte of data. */
+ if (handle->transfer.dataSize > 0)
+ {
+ base->D = *handle->transfer.data;
+ handle->transfer.data++;
+ handle->transfer.dataSize--;
+ }
+ }
+ else
+ {
+ /* Send repeated start and slave address. */
+ result = I2C_MasterRepeatedStart(base, handle->transfer.slaveAddress, kI2C_Read);
+
+ /* Next state, receive data begin. */
+ handle->state = kReceiveDataBeginState;
+ }
+ }
+ break;
+
+ /* Send I2C data. */
+ case kSendDataState:
+ /* Send one byte of data. */
+ if (handle->transfer.dataSize > 0)
+ {
+ base->D = *handle->transfer.data;
+ handle->transfer.data++;
+ handle->transfer.dataSize--;
+ }
+ else
+ {
+ *isDone = true;
+ }
+ break;
+
+ /* Start I2C data receive. */
+ case kReceiveDataBeginState:
+ base->C1 &= ~(I2C_C1_TX_MASK | I2C_C1_TXAK_MASK);
+
+ /* Send nak at the last receive byte. */
+ if (handle->transfer.dataSize == 1)
+ {
+ base->C1 |= I2C_C1_TXAK_MASK;
+ }
+
+ /* Read dummy to release the bus. */
+ dummy = base->D;
+
+ /* Next state, receive data. */
+ handle->state = kReceiveDataState;
+ break;
+
+ /* Receive I2C data. */
+ case kReceiveDataState:
+ /* Receive one byte of data. */
+ if (handle->transfer.dataSize--)
+ {
+ if (handle->transfer.dataSize == 0)
+ {
+ *isDone = true;
+
+ /* Send stop if kI2C_TransferNoStop is not asserted. */
+ if (!(handle->transfer.flags & kI2C_TransferNoStopFlag))
+ {
+ result = I2C_MasterStop(base);
+ }
+ }
+
+ /* Send NAK at the last receive byte. */
+ if (handle->transfer.dataSize == 1)
+ {
+ base->C1 |= I2C_C1_TXAK_MASK;
+ }
+
+ /* Read the data byte into the transfer buffer. */
+ *handle->transfer.data = base->D;
+ handle->transfer.data++;
+ }
+ break;
+
+ default:
+ break;
+ }
+
+ return result;
+}
+
+static void I2C_TransferCommonIRQHandler(I2C_Type *base, void *handle)
+{
+ /* Check if master interrupt. */
+ if ((base->S & kI2C_ArbitrationLostFlag) || (base->C1 & I2C_C1_MST_MASK))
+ {
+ s_i2cMasterIsr(base, handle);
+ }
+ else
+ {
+ s_i2cSlaveIsr(base, handle);
+ }
+}
+
+void I2C_MasterInit(I2C_Type *base, const i2c_master_config_t *masterConfig, uint32_t srcClock_Hz)
+{
+ assert(masterConfig && srcClock_Hz);
+
+ /* Temporary register for filter read. */
+ uint8_t fltReg;
+#if defined(FSL_FEATURE_I2C_HAS_HIGH_DRIVE_SELECTION) && FSL_FEATURE_I2C_HAS_HIGH_DRIVE_SELECTION
+ uint8_t c2Reg;
+#endif
+#if defined(FSL_FEATURE_I2C_HAS_DOUBLE_BUFFER_ENABLE) && FSL_FEATURE_I2C_HAS_DOUBLE_BUFFER_ENABLE
+ uint8_t s2Reg;
+#endif
+ /* Enable I2C clock. */
+ CLOCK_EnableClock(s_i2cClocks[I2C_GetInstance(base)]);
+
+ /* Disable I2C prior to configuring it. */
+ base->C1 &= ~(I2C_C1_IICEN_MASK);
+
+ /* Clear all flags. */
+ I2C_MasterClearStatusFlags(base, kClearFlags);
+
+ /* Configure baud rate. */
+ I2C_MasterSetBaudRate(base, masterConfig->baudRate_Bps, srcClock_Hz);
+
+#if defined(FSL_FEATURE_I2C_HAS_HIGH_DRIVE_SELECTION) && FSL_FEATURE_I2C_HAS_HIGH_DRIVE_SELECTION
+ /* Configure high drive feature. */
+ c2Reg = base->C2;
+ c2Reg &= ~(I2C_C2_HDRS_MASK);
+ c2Reg |= I2C_C2_HDRS(masterConfig->enableHighDrive);
+ base->C2 = c2Reg;
+#endif
+
+ /* Read out the FLT register. */
+ fltReg = base->FLT;
+
+#if defined(FSL_FEATURE_I2C_HAS_STOP_HOLD_OFF) && FSL_FEATURE_I2C_HAS_STOP_HOLD_OFF
+ /* Configure the stop / hold enable. */
+ fltReg &= ~(I2C_FLT_SHEN_MASK);
+ fltReg |= I2C_FLT_SHEN(masterConfig->enableStopHold);
+#endif
+
+ /* Configure the glitch filter value. */
+ fltReg &= ~(I2C_FLT_FLT_MASK);
+ fltReg |= I2C_FLT_FLT(masterConfig->glitchFilterWidth);
+
+ /* Write the register value back to the filter register. */
+ base->FLT = fltReg;
+
+/* Enable/Disable double buffering. */
+#if defined(FSL_FEATURE_I2C_HAS_DOUBLE_BUFFER_ENABLE) && FSL_FEATURE_I2C_HAS_DOUBLE_BUFFER_ENABLE
+ s2Reg = base->S2 & (~I2C_S2_DFEN_MASK);
+ base->S2 = s2Reg | I2C_S2_DFEN(masterConfig->enableDoubleBuffering);
+#endif
+
+ /* Enable the I2C peripheral based on the configuration. */
+ base->C1 = I2C_C1_IICEN(masterConfig->enableMaster);
+}
+
+void I2C_MasterDeinit(I2C_Type *base)
+{
+ /* Disable I2C module. */
+ I2C_Enable(base, false);
+
+ /* Disable I2C clock. */
+ CLOCK_DisableClock(s_i2cClocks[I2C_GetInstance(base)]);
+}
+
+void I2C_MasterGetDefaultConfig(i2c_master_config_t *masterConfig)
+{
+ assert(masterConfig);
+
+ /* Default baud rate at 100kbps. */
+ masterConfig->baudRate_Bps = 100000U;
+
+/* Default pin high drive is disabled. */
+#if defined(FSL_FEATURE_I2C_HAS_HIGH_DRIVE_SELECTION) && FSL_FEATURE_I2C_HAS_HIGH_DRIVE_SELECTION
+ masterConfig->enableHighDrive = false;
+#endif
+
+/* Default stop hold enable is disabled. */
+#if defined(FSL_FEATURE_I2C_HAS_STOP_HOLD_OFF) && FSL_FEATURE_I2C_HAS_STOP_HOLD_OFF
+ masterConfig->enableStopHold = false;
+#endif
+
+ /* Default glitch filter value is no filter. */
+ masterConfig->glitchFilterWidth = 0U;
+
+/* Default enable double buffering. */
+#if defined(FSL_FEATURE_I2C_HAS_DOUBLE_BUFFER_ENABLE) && FSL_FEATURE_I2C_HAS_DOUBLE_BUFFER_ENABLE
+ masterConfig->enableDoubleBuffering = true;
+#endif
+
+ /* Enable the I2C peripheral. */
+ masterConfig->enableMaster = true;
+}
+
+void I2C_EnableInterrupts(I2C_Type *base, uint32_t mask)
+{
+#ifdef I2C_HAS_STOP_DETECT
+ uint8_t fltReg;
+#endif
+
+ if (mask & kI2C_GlobalInterruptEnable)
+ {
+ base->C1 |= I2C_C1_IICIE_MASK;
+ }
+
+#if defined(FSL_FEATURE_I2C_HAS_STOP_DETECT) && FSL_FEATURE_I2C_HAS_STOP_DETECT
+ if (mask & kI2C_StopDetectInterruptEnable)
+ {
+ fltReg = base->FLT;
+
+ /* Keep STOPF flag. */
+ fltReg &= ~I2C_FLT_STOPF_MASK;
+
+ /* Stop detect enable. */
+ fltReg |= I2C_FLT_STOPIE_MASK;
+ base->FLT = fltReg;
+ }
+#endif /* FSL_FEATURE_I2C_HAS_STOP_DETECT */
+
+#if defined(FSL_FEATURE_I2C_HAS_START_STOP_DETECT) && FSL_FEATURE_I2C_HAS_START_STOP_DETECT
+ if (mask & kI2C_StartStopDetectInterruptEnable)
+ {
+ fltReg = base->FLT;
+
+ /* Keep STARTF and STOPF flags. */
+ fltReg &= ~(I2C_FLT_STOPF_MASK | I2C_FLT_STARTF_MASK);
+
+ /* Start and stop detect enable. */
+ fltReg |= I2C_FLT_SSIE_MASK;
+ base->FLT = fltReg;
+ }
+#endif /* FSL_FEATURE_I2C_HAS_START_STOP_DETECT */
+}
+
+void I2C_DisableInterrupts(I2C_Type *base, uint32_t mask)
+{
+ if (mask & kI2C_GlobalInterruptEnable)
+ {
+ base->C1 &= ~I2C_C1_IICIE_MASK;
+ }
+
+#if defined(FSL_FEATURE_I2C_HAS_STOP_DETECT) && FSL_FEATURE_I2C_HAS_STOP_DETECT
+ if (mask & kI2C_StopDetectInterruptEnable)
+ {
+ base->FLT &= ~(I2C_FLT_STOPIE_MASK | I2C_FLT_STOPF_MASK);
+ }
+#endif /* FSL_FEATURE_I2C_HAS_STOP_DETECT */
+
+#if defined(FSL_FEATURE_I2C_HAS_START_STOP_DETECT) && FSL_FEATURE_I2C_HAS_START_STOP_DETECT
+ if (mask & kI2C_StartStopDetectInterruptEnable)
+ {
+ base->FLT &= ~(I2C_FLT_SSIE_MASK | I2C_FLT_STOPF_MASK | I2C_FLT_STARTF_MASK);
+ }
+#endif /* FSL_FEATURE_I2C_HAS_START_STOP_DETECT */
+}
+
+void I2C_MasterSetBaudRate(I2C_Type *base, uint32_t baudRate_Bps, uint32_t srcClock_Hz)
+{
+ uint32_t multiplier;
+ uint32_t computedRate;
+ uint32_t absError;
+ uint32_t bestError = UINT32_MAX;
+ uint32_t bestMult = 0u;
+ uint32_t bestIcr = 0u;
+ uint8_t mult;
+ uint8_t i;
+
+ /* Search for the settings with the lowest error. Mult is the MULT field of the I2C_F register,
+ * and ranges from 0-2. It selects the multiplier factor for the divider. */
+ for (mult = 0u; (mult <= 2u) && (bestError != 0); ++mult)
+ {
+ multiplier = 1u << mult;
+
+ /* Scan table to find best match. */
+ for (i = 0u; i < sizeof(s_i2cDividerTable) / sizeof(uint16_t); ++i)
+ {
+ computedRate = srcClock_Hz / (multiplier * s_i2cDividerTable[i]);
+ absError = baudRate_Bps > computedRate ? (baudRate_Bps - computedRate) : (computedRate - baudRate_Bps);
+
+ if (absError < bestError)
+ {
+ bestMult = mult;
+ bestIcr = i;
+ bestError = absError;
+
+ /* If the error is 0, then we can stop searching because we won't find a better match. */
+ if (absError == 0)
+ {
+ break;
+ }
+ }
+ }
+ }
+
+ /* Set frequency register based on best settings. */
+ base->F = I2C_F_MULT(bestMult) | I2C_F_ICR(bestIcr);
+}
+
+status_t I2C_MasterStart(I2C_Type *base, uint8_t address, i2c_direction_t direction)
+{
+ status_t result = kStatus_Success;
+ uint32_t statusFlags = I2C_MasterGetStatusFlags(base);
+
+ /* Return an error if the bus is already in use. */
+ if (statusFlags & kI2C_BusBusyFlag)
+ {
+ result = kStatus_I2C_Busy;
+ }
+ else
+ {
+ /* Send the START signal. */
+ base->C1 |= I2C_C1_MST_MASK | I2C_C1_TX_MASK;
+
+#if defined(FSL_FEATURE_I2C_HAS_DOUBLE_BUFFERING) && FSL_FEATURE_I2C_HAS_DOUBLE_BUFFERING
+ while (!(base->S2 & I2C_S2_EMPTY_MASK))
+ {
+ }
+#endif /* FSL_FEATURE_I2C_HAS_DOUBLE_BUFFERING */
+
+ base->D = (((uint32_t)address) << 1U | ((direction == kI2C_Read) ? 1U : 0U));
+ }
+
+ return result;
+}
+
+status_t I2C_MasterRepeatedStart(I2C_Type *base, uint8_t address, i2c_direction_t direction)
+{
+ status_t result = kStatus_Success;
+ uint8_t savedMult;
+ uint32_t statusFlags = I2C_MasterGetStatusFlags(base);
+ uint8_t timeDelay = 6;
+
+ /* Return an error if the bus is already in use, but not by us. */
+ if ((statusFlags & kI2C_BusBusyFlag) && ((base->C1 & I2C_C1_MST_MASK) == 0))
+ {
+ result = kStatus_I2C_Busy;
+ }
+ else
+ {
+ savedMult = base->F;
+ base->F = savedMult & (~I2C_F_MULT_MASK);
+
+ /* We are already in a transfer, so send a repeated start. */
+ base->C1 |= I2C_C1_RSTA_MASK;
+
+ /* Restore the multiplier factor. */
+ base->F = savedMult;
+
+ /* Add some delay to wait the Re-Start signal. */
+ while (timeDelay--)
+ {
+ __NOP();
+ }
+
+#if defined(FSL_FEATURE_I2C_HAS_DOUBLE_BUFFERING) && FSL_FEATURE_I2C_HAS_DOUBLE_BUFFERING
+ while (!(base->S2 & I2C_S2_EMPTY_MASK))
+ {
+ }
+#endif /* FSL_FEATURE_I2C_HAS_DOUBLE_BUFFERING */
+
+ base->D = (((uint32_t)address) << 1U | ((direction == kI2C_Read) ? 1U : 0U));
+ }
+
+ return result;
+}
+
+status_t I2C_MasterStop(I2C_Type *base)
+{
+ status_t result = kStatus_Success;
+ uint16_t timeout = UINT16_MAX;
+
+ /* Issue the STOP command on the bus. */
+ base->C1 &= ~(I2C_C1_MST_MASK | I2C_C1_TX_MASK | I2C_C1_TXAK_MASK);
+
+ /* Wait until data transfer complete. */
+ while ((base->S & kI2C_BusBusyFlag) && (--timeout))
+ {
+ }
+
+ if (timeout == 0)
+ {
+ result = kStatus_I2C_Timeout;
+ }
+
+ return result;
+}
+
+uint32_t I2C_MasterGetStatusFlags(I2C_Type *base)
+{
+ uint32_t statusFlags = base->S;
+
+#ifdef I2C_HAS_STOP_DETECT
+ /* Look up the STOPF bit from the filter register. */
+ if (base->FLT & I2C_FLT_STOPF_MASK)
+ {
+ statusFlags |= kI2C_StopDetectFlag;
+ }
+#endif
+
+#if defined(FSL_FEATURE_I2C_HAS_START_STOP_DETECT) && FSL_FEATURE_I2C_HAS_START_STOP_DETECT
+ /* Look up the STARTF bit from the filter register. */
+ if (base->FLT & I2C_FLT_STARTF_MASK)
+ {
+ statusFlags |= kI2C_StartDetectFlag;
+ }
+#endif /* FSL_FEATURE_I2C_HAS_START_STOP_DETECT */
+
+ return statusFlags;
+}
+
+status_t I2C_MasterWriteBlocking(I2C_Type *base, const uint8_t *txBuff, size_t txSize)
+{
+ status_t result = kStatus_Success;
+ uint8_t statusFlags = 0;
+
+ /* Wait until the data register is ready for transmit. */
+ while (!(base->S & kI2C_TransferCompleteFlag))
+ {
+ }
+
+ /* Clear the IICIF flag. */
+ base->S = kI2C_IntPendingFlag;
+
+ /* Setup the I2C peripheral to transmit data. */
+ base->C1 |= I2C_C1_TX_MASK;
+
+ while (txSize--)
+ {
+ /* Send a byte of data. */
+ base->D = *txBuff++;
+
+ /* Wait until data transfer complete. */
+ while (!(base->S & kI2C_IntPendingFlag))
+ {
+ }
+
+ statusFlags = base->S;
+
+ /* Clear the IICIF flag. */
+ base->S = kI2C_IntPendingFlag;
+
+ /* Check if arbitration lost or no acknowledgement (NAK), return failure status. */
+ if (statusFlags & kI2C_ArbitrationLostFlag)
+ {
+ base->S = kI2C_ArbitrationLostFlag;
+ result = kStatus_I2C_ArbitrationLost;
+ }
+
+ if ((statusFlags & kI2C_ReceiveNakFlag) && txSize)
+ {
+ base->S = kI2C_ReceiveNakFlag;
+ result = kStatus_I2C_Nak;
+ }
+
+ if (result != kStatus_Success)
+ {
+ /* Breaking out of the send loop. */
+ break;
+ }
+ }
+
+ return result;
+}
+
+status_t I2C_MasterReadBlocking(I2C_Type *base, uint8_t *rxBuff, size_t rxSize)
+{
+ status_t result = kStatus_Success;
+ volatile uint8_t dummy = 0;
+
+ /* Add this to avoid build warning. */
+ dummy++;
+
+ /* Wait until the data register is ready for transmit. */
+ while (!(base->S & kI2C_TransferCompleteFlag))
+ {
+ }
+
+ /* Clear the IICIF flag. */
+ base->S = kI2C_IntPendingFlag;
+
+ /* Setup the I2C peripheral to receive data. */
+ base->C1 &= ~(I2C_C1_TX_MASK | I2C_C1_TXAK_MASK);
+
+ /* If rxSize equals 1, configure to send NAK. */
+ if (rxSize == 1)
+ {
+ /* Issue NACK on read. */
+ base->C1 |= I2C_C1_TXAK_MASK;
+ }
+
+ /* Do dummy read. */
+ dummy = base->D;
+
+ while ((rxSize--))
+ {
+ /* Wait until data transfer complete. */
+ while (!(base->S & kI2C_IntPendingFlag))
+ {
+ }
+
+ /* Clear the IICIF flag. */
+ base->S = kI2C_IntPendingFlag;
+
+ /* Single byte use case. */
+ if (rxSize == 0)
+ {
+ /* Read the final byte. */
+ result = I2C_MasterStop(base);
+ }
+
+ if (rxSize == 1)
+ {
+ /* Issue NACK on read. */
+ base->C1 |= I2C_C1_TXAK_MASK;
+ }
+
+ /* Read from the data register. */
+ *rxBuff++ = base->D;
+ }
+
+ return result;
+}
+
+status_t I2C_MasterTransferBlocking(I2C_Type *base, i2c_master_transfer_t *xfer)
+{
+ assert(xfer);
+
+ i2c_direction_t direction = xfer->direction;
+ status_t result = kStatus_Success;
+
+ /* Clear all status before transfer. */
+ I2C_MasterClearStatusFlags(base, kClearFlags);
+
+ /* Wait until ready to complete. */
+ while (!(base->S & kI2C_TransferCompleteFlag))
+ {
+ }
+
+ /* Change to send write address when it's a read operation with command. */
+ if ((xfer->subaddressSize > 0) && (xfer->direction == kI2C_Read))
+ {
+ direction = kI2C_Write;
+ }
+
+ /* If repeated start is requested, send repeated start. */
+ if (xfer->flags & kI2C_TransferRepeatedStartFlag)
+ {
+ result = I2C_MasterRepeatedStart(base, xfer->slaveAddress, direction);
+ }
+ else /* For normal transfer, send start. */
+ {
+ result = I2C_MasterStart(base, xfer->slaveAddress, direction);
+ }
+
+ /* Return if error. */
+ if (result)
+ {
+ return result;
+ }
+
+ /* Send subaddress. */
+ if (xfer->subaddressSize)
+ {
+ do
+ {
+ /* Wait until data transfer complete. */
+ while (!(base->S & kI2C_IntPendingFlag))
+ {
+ }
+
+ /* Clear interrupt pending flag. */
+ base->S = kI2C_IntPendingFlag;
+
+ /* Check if there's transfer error. */
+ result = I2C_CheckAndClearError(base, base->S);
+
+ if (result)
+ {
+ if (result == kStatus_I2C_Nak)
+ {
+ I2C_MasterStop(base);
+ }
+
+ return result;
+ }
+
+ xfer->subaddressSize--;
+ base->D = ((xfer->subaddress) >> (8 * xfer->subaddressSize));
+
+ } while ((xfer->subaddressSize > 0) && (result == kStatus_Success));
+
+ if (xfer->direction == kI2C_Read)
+ {
+ /* Wait until data transfer complete. */
+ while (!(base->S & kI2C_IntPendingFlag))
+ {
+ }
+
+ /* Clear pending flag. */
+ base->S = kI2C_IntPendingFlag;
+
+ /* Check if there's transfer error. */
+ result = I2C_CheckAndClearError(base, base->S);
+
+ if (result)
+ {
+ if (result == kStatus_I2C_Nak)
+ {
+ I2C_MasterStop(base);
+ }
+
+ return result;
+ }
+
+ /* Send repeated start and slave address. */
+ result = I2C_MasterRepeatedStart(base, xfer->slaveAddress, kI2C_Read);
+
+ /* Return if error. */
+ if (result)
+ {
+ return result;
+ }
+ }
+ }
+
+ /* Wait until address + command transfer complete. */
+ while (!(base->S & kI2C_IntPendingFlag))
+ {
+ }
+
+ /* Check if there's transfer error. */
+ result = I2C_CheckAndClearError(base, base->S);
+
+ /* Return if error. */
+ if (result)
+ {
+ if (result == kStatus_I2C_Nak)
+ {
+ I2C_MasterStop(base);
+ }
+
+ return result;
+ }
+
+ /* Transmit data. */
+ if ((xfer->direction == kI2C_Write) && (xfer->dataSize > 0))
+ {
+ /* Send Data. */
+ result = I2C_MasterWriteBlocking(base, xfer->data, xfer->dataSize);
+
+ if (((result == kStatus_Success) && (!(xfer->flags & kI2C_TransferNoStopFlag))) || (result == kStatus_I2C_Nak))
+ {
+ /* Clear the IICIF flag. */
+ base->S = kI2C_IntPendingFlag;
+
+ /* Send stop. */
+ result = I2C_MasterStop(base);
+ }
+ }
+
+ /* Receive Data. */
+ if ((xfer->direction == kI2C_Read) && (xfer->dataSize > 0))
+ {
+ result = I2C_MasterReadBlocking(base, xfer->data, xfer->dataSize);
+ }
+
+ return result;
+}
+
+void I2C_MasterTransferCreateHandle(I2C_Type *base,
+ i2c_master_handle_t *handle,
+ i2c_master_transfer_callback_t callback,
+ void *userData)
+{
+ assert(handle);
+
+ uint32_t instance = I2C_GetInstance(base);
+
+ /* Zero handle. */
+ memset(handle, 0, sizeof(*handle));
+
+ /* Set callback and userData. */
+ handle->completionCallback = callback;
+ handle->userData = userData;
+
+ /* Save the context in global variables to support the double weak mechanism. */
+ s_i2cHandle[instance] = handle;
+
+ /* Save master interrupt handler. */
+ s_i2cMasterIsr = I2C_MasterTransferHandleIRQ;
+
+ /* Enable NVIC interrupt. */
+ EnableIRQ(s_i2cIrqs[instance]);
+}
+
+status_t I2C_MasterTransferNonBlocking(I2C_Type *base, i2c_master_handle_t *handle, i2c_master_transfer_t *xfer)
+{
+ assert(handle);
+ assert(xfer);
+
+ status_t result = kStatus_Success;
+
+ /* Check if the I2C bus is idle - if not return busy status. */
+ if (handle->state != kIdleState)
+ {
+ result = kStatus_I2C_Busy;
+ }
+ else
+ {
+ /* Start up the master transfer state machine. */
+ result = I2C_InitTransferStateMachine(base, handle, xfer);
+
+ if (result == kStatus_Success)
+ {
+ /* Enable the I2C interrupts. */
+ I2C_EnableInterrupts(base, kI2C_GlobalInterruptEnable);
+ }
+ }
+
+ return result;
+}
+
+void I2C_MasterTransferAbort(I2C_Type *base, i2c_master_handle_t *handle)
+{
+ assert(handle);
+
+ /* Disable interrupt. */
+ I2C_DisableInterrupts(base, kI2C_GlobalInterruptEnable);
+
+ /* Reset the state to idle. */
+ handle->state = kIdleState;
+}
+
+status_t I2C_MasterTransferGetCount(I2C_Type *base, i2c_master_handle_t *handle, size_t *count)
+{
+ assert(handle);
+
+ if (!count)
+ {
+ return kStatus_InvalidArgument;
+ }
+
+ *count = handle->transferSize - handle->transfer.dataSize;
+
+ return kStatus_Success;
+}
+
+void I2C_MasterTransferHandleIRQ(I2C_Type *base, void *i2cHandle)
+{
+ assert(i2cHandle);
+
+ i2c_master_handle_t *handle = (i2c_master_handle_t *)i2cHandle;
+ status_t result = kStatus_Success;
+ bool isDone;
+
+ /* Clear the interrupt flag. */
+ base->S = kI2C_IntPendingFlag;
+
+ /* Check transfer complete flag. */
+ result = I2C_MasterTransferRunStateMachine(base, handle, &isDone);
+
+ if (isDone || result)
+ {
+ /* Send stop command if transfer done or received Nak. */
+ if ((!(handle->transfer.flags & kI2C_TransferNoStopFlag)) || (result == kStatus_I2C_Nak))
+ {
+ /* Ensure stop command is a need. */
+ if ((base->C1 & I2C_C1_MST_MASK))
+ {
+ if (I2C_MasterStop(base) != kStatus_Success)
+ {
+ result = kStatus_I2C_Timeout;
+ }
+ }
+ }
+
+ /* Restore handle to idle state. */
+ handle->state = kIdleState;
+
+ /* Disable interrupt. */
+ I2C_DisableInterrupts(base, kI2C_GlobalInterruptEnable);
+
+ /* Call the callback function after the function has completed. */
+ if (handle->completionCallback)
+ {
+ handle->completionCallback(base, handle, result, handle->userData);
+ }
+ }
+}
+
+void I2C_SlaveInit(I2C_Type *base, const i2c_slave_config_t *slaveConfig)
+{
+ assert(slaveConfig);
+
+ uint8_t tmpReg;
+
+ CLOCK_EnableClock(s_i2cClocks[I2C_GetInstance(base)]);
+
+ /* Configure addressing mode. */
+ switch (slaveConfig->addressingMode)
+ {
+ case kI2C_Address7bit:
+ base->A1 = ((uint32_t)(slaveConfig->slaveAddress)) << 1U;
+ break;
+
+ case kI2C_RangeMatch:
+ assert(slaveConfig->slaveAddress < slaveConfig->upperAddress);
+ base->A1 = ((uint32_t)(slaveConfig->slaveAddress)) << 1U;
+ base->RA = ((uint32_t)(slaveConfig->upperAddress)) << 1U;
+ base->C2 |= I2C_C2_RMEN_MASK;
+ break;
+
+ default:
+ break;
+ }
+
+ /* Configure low power wake up feature. */
+ tmpReg = base->C1;
+ tmpReg &= ~I2C_C1_WUEN_MASK;
+ base->C1 = tmpReg | I2C_C1_WUEN(slaveConfig->enableWakeUp) | I2C_C1_IICEN(slaveConfig->enableSlave);
+
+ /* Configure general call & baud rate control & high drive feature. */
+ tmpReg = base->C2;
+ tmpReg &= ~(I2C_C2_SBRC_MASK | I2C_C2_GCAEN_MASK);
+ tmpReg |= I2C_C2_SBRC(slaveConfig->enableBaudRateCtl) | I2C_C2_GCAEN(slaveConfig->enableGeneralCall);
+#if defined(FSL_FEATURE_I2C_HAS_HIGH_DRIVE_SELECTION) && FSL_FEATURE_I2C_HAS_HIGH_DRIVE_SELECTION
+ tmpReg &= ~I2C_C2_HDRS_MASK;
+ tmpReg |= I2C_C2_HDRS(slaveConfig->enableHighDrive);
+#endif
+ base->C2 = tmpReg;
+
+/* Enable/Disable double buffering. */
+#if defined(FSL_FEATURE_I2C_HAS_DOUBLE_BUFFER_ENABLE) && FSL_FEATURE_I2C_HAS_DOUBLE_BUFFER_ENABLE
+ tmpReg = base->S2 & (~I2C_S2_DFEN_MASK);
+ base->S2 = tmpReg | I2C_S2_DFEN(slaveConfig->enableDoubleBuffering);
+#endif
+}
+
+void I2C_SlaveDeinit(I2C_Type *base)
+{
+ /* Disable I2C module. */
+ I2C_Enable(base, false);
+
+ /* Disable I2C clock. */
+ CLOCK_DisableClock(s_i2cClocks[I2C_GetInstance(base)]);
+}
+
+void I2C_SlaveGetDefaultConfig(i2c_slave_config_t *slaveConfig)
+{
+ assert(slaveConfig);
+
+ /* By default slave is addressed with 7-bit address. */
+ slaveConfig->addressingMode = kI2C_Address7bit;
+
+ /* General call mode is disabled by default. */
+ slaveConfig->enableGeneralCall = false;
+
+ /* Slave address match waking up MCU from low power mode is disabled. */
+ slaveConfig->enableWakeUp = false;
+
+#if defined(FSL_FEATURE_I2C_HAS_HIGH_DRIVE_SELECTION) && FSL_FEATURE_I2C_HAS_HIGH_DRIVE_SELECTION
+ /* Default pin high drive is disabled. */
+ slaveConfig->enableHighDrive = false;
+#endif
+
+ /* Independent slave mode baud rate at maximum frequency is disabled. */
+ slaveConfig->enableBaudRateCtl = false;
+
+/* Default enable double buffering. */
+#if defined(FSL_FEATURE_I2C_HAS_DOUBLE_BUFFER_ENABLE) && FSL_FEATURE_I2C_HAS_DOUBLE_BUFFER_ENABLE
+ slaveConfig->enableDoubleBuffering = true;
+#endif
+
+ /* Enable the I2C peripheral. */
+ slaveConfig->enableSlave = true;
+}
+
+status_t I2C_SlaveWriteBlocking(I2C_Type *base, const uint8_t *txBuff, size_t txSize)
+{
+ status_t result = kStatus_Success;
+ volatile uint8_t dummy = 0;
+
+ /* Add this to avoid build warning. */
+ dummy++;
+
+#if defined(FSL_FEATURE_I2C_HAS_START_STOP_DETECT) && FSL_FEATURE_I2C_HAS_START_STOP_DETECT
+ /* Check start flag. */
+ while (!(base->FLT & I2C_FLT_STARTF_MASK))
+ {
+ }
+ /* Clear STARTF flag. */
+ base->FLT |= I2C_FLT_STARTF_MASK;
+ /* Clear the IICIF flag. */
+ base->S = kI2C_IntPendingFlag;
+#endif /* FSL_FEATURE_I2C_HAS_START_STOP_DETECT */
+
+ /* Wait for address match flag. */
+ while (!(base->S & kI2C_AddressMatchFlag))
+ {
+ }
+
+ /* Read dummy to release bus. */
+ dummy = base->D;
+
+ result = I2C_MasterWriteBlocking(base, txBuff, txSize);
+
+ /* Switch to receive mode. */
+ base->C1 &= ~(I2C_C1_TX_MASK | I2C_C1_TXAK_MASK);
+
+ /* Read dummy to release bus. */
+ dummy = base->D;
+
+ return result;
+}
+
+void I2C_SlaveReadBlocking(I2C_Type *base, uint8_t *rxBuff, size_t rxSize)
+{
+ volatile uint8_t dummy = 0;
+
+ /* Add this to avoid build warning. */
+ dummy++;
+
+/* Wait until address match. */
+#if defined(FSL_FEATURE_I2C_HAS_START_STOP_DETECT) && FSL_FEATURE_I2C_HAS_START_STOP_DETECT
+ /* Check start flag. */
+ while (!(base->FLT & I2C_FLT_STARTF_MASK))
+ {
+ }
+ /* Clear STARTF flag. */
+ base->FLT |= I2C_FLT_STARTF_MASK;
+ /* Clear the IICIF flag. */
+ base->S = kI2C_IntPendingFlag;
+#endif /* FSL_FEATURE_I2C_HAS_START_STOP_DETECT */
+
+ /* Wait for address match and int pending flag. */
+ while (!(base->S & kI2C_AddressMatchFlag))
+ {
+ }
+ while (!(base->S & kI2C_IntPendingFlag))
+ {
+ }
+
+ /* Read dummy to release bus. */
+ dummy = base->D;
+
+ /* Clear the IICIF flag. */
+ base->S = kI2C_IntPendingFlag;
+
+ /* Setup the I2C peripheral to receive data. */
+ base->C1 &= ~(I2C_C1_TX_MASK);
+
+ while (rxSize--)
+ {
+ /* Wait until data transfer complete. */
+ while (!(base->S & kI2C_IntPendingFlag))
+ {
+ }
+ /* Clear the IICIF flag. */
+ base->S = kI2C_IntPendingFlag;
+
+ /* Read from the data register. */
+ *rxBuff++ = base->D;
+ }
+}
+
+void I2C_SlaveTransferCreateHandle(I2C_Type *base,
+ i2c_slave_handle_t *handle,
+ i2c_slave_transfer_callback_t callback,
+ void *userData)
+{
+ assert(handle);
+
+ uint32_t instance = I2C_GetInstance(base);
+
+ /* Zero handle. */
+ memset(handle, 0, sizeof(*handle));
+
+ /* Set callback and userData. */
+ handle->callback = callback;
+ handle->userData = userData;
+
+ /* Save the context in global variables to support the double weak mechanism. */
+ s_i2cHandle[instance] = handle;
+
+ /* Save slave interrupt handler. */
+ s_i2cSlaveIsr = I2C_SlaveTransferHandleIRQ;
+
+ /* Enable NVIC interrupt. */
+ EnableIRQ(s_i2cIrqs[instance]);
+}
+
+status_t I2C_SlaveTransferNonBlocking(I2C_Type *base, i2c_slave_handle_t *handle, uint32_t eventMask)
+{
+ assert(handle);
+
+ /* Check if the I2C bus is idle - if not return busy status. */
+ if (handle->isBusy)
+ {
+ return kStatus_I2C_Busy;
+ }
+ else
+ {
+ /* Disable LPI2C IRQ sources while we configure stuff. */
+ I2C_DisableInterrupts(base, kIrqFlags);
+
+ /* Clear transfer in handle. */
+ memset(&handle->transfer, 0, sizeof(handle->transfer));
+
+ /* Record that we're busy. */
+ handle->isBusy = true;
+
+ /* Set up event mask. tx and rx are always enabled. */
+ handle->eventMask = eventMask | kI2C_SlaveTransmitEvent | kI2C_SlaveReceiveEvent;
+
+ /* Clear all flags. */
+ I2C_SlaveClearStatusFlags(base, kClearFlags);
+
+ /* Enable I2C internal IRQ sources. NVIC IRQ was enabled in CreateHandle() */
+ I2C_EnableInterrupts(base, kIrqFlags);
+ }
+
+ return kStatus_Success;
+}
+
+void I2C_SlaveTransferAbort(I2C_Type *base, i2c_slave_handle_t *handle)
+{
+ assert(handle);
+
+ if (handle->isBusy)
+ {
+ /* Disable interrupts. */
+ I2C_DisableInterrupts(base, kIrqFlags);
+
+ /* Reset transfer info. */
+ memset(&handle->transfer, 0, sizeof(handle->transfer));
+
+ /* Reset the state to idle. */
+ handle->isBusy = false;
+ }
+}
+
+status_t I2C_SlaveTransferGetCount(I2C_Type *base, i2c_slave_handle_t *handle, size_t *count)
+{
+ assert(handle);
+
+ if (!count)
+ {
+ return kStatus_InvalidArgument;
+ }
+
+ /* Catch when there is not an active transfer. */
+ if (!handle->isBusy)
+ {
+ *count = 0;
+ return kStatus_NoTransferInProgress;
+ }
+
+ /* For an active transfer, just return the count from the handle. */
+ *count = handle->transfer.transferredCount;
+
+ return kStatus_Success;
+}
+
+void I2C_SlaveTransferHandleIRQ(I2C_Type *base, void *i2cHandle)
+{
+ assert(i2cHandle);
+
+ uint16_t status;
+ bool doTransmit = false;
+ i2c_slave_handle_t *handle = (i2c_slave_handle_t *)i2cHandle;
+ i2c_slave_transfer_t *xfer;
+ volatile uint8_t dummy = 0;
+
+ /* Add this to avoid build warning. */
+ dummy++;
+
+ status = I2C_SlaveGetStatusFlags(base);
+ xfer = &(handle->transfer);
+
+#ifdef I2C_HAS_STOP_DETECT
+ /* Check stop flag. */
+ if (status & kI2C_StopDetectFlag)
+ {
+ I2C_MasterClearStatusFlags(base, kI2C_StopDetectFlag);
+
+ /* Clear the interrupt flag. */
+ base->S = kI2C_IntPendingFlag;
+
+ /* Call slave callback if this is the STOP of the transfer. */
+ if (handle->isBusy)
+ {
+ xfer->event = kI2C_SlaveCompletionEvent;
+ xfer->completionStatus = kStatus_Success;
+ handle->isBusy = false;
+
+ if ((handle->eventMask & xfer->event) && (handle->callback))
+ {
+ handle->callback(base, xfer, handle->userData);
+ }
+ }
+
+ return;
+ }
+#endif /* I2C_HAS_STOP_DETECT */
+
+#if defined(FSL_FEATURE_I2C_HAS_START_STOP_DETECT) && FSL_FEATURE_I2C_HAS_START_STOP_DETECT
+ /* Check start flag. */
+ if (status & kI2C_StartDetectFlag)
+ {
+ I2C_MasterClearStatusFlags(base, kI2C_StartDetectFlag);
+
+ /* Clear the interrupt flag. */
+ base->S = kI2C_IntPendingFlag;
+
+ xfer->event = kI2C_SlaveStartEvent;
+
+ if ((handle->eventMask & xfer->event) && (handle->callback))
+ {
+ handle->callback(base, xfer, handle->userData);
+ }
+
+ if (!(status & kI2C_AddressMatchFlag))
+ {
+ return;
+ }
+ }
+#endif /* FSL_FEATURE_I2C_HAS_START_STOP_DETECT */
+
+ /* Clear the interrupt flag. */
+ base->S = kI2C_IntPendingFlag;
+
+ /* Check NAK */
+ if (status & kI2C_ReceiveNakFlag)
+ {
+ /* Set receive mode. */
+ base->C1 &= ~(I2C_C1_TX_MASK | I2C_C1_TXAK_MASK);
+
+ /* Read dummy. */
+ dummy = base->D;
+
+ if (handle->transfer.dataSize != 0)
+ {
+ xfer->event = kI2C_SlaveCompletionEvent;
+ xfer->completionStatus = kStatus_I2C_Nak;
+ handle->isBusy = false;
+
+ if ((handle->eventMask & xfer->event) && (handle->callback))
+ {
+ handle->callback(base, xfer, handle->userData);
+ }
+ }
+ else
+ {
+#ifndef I2C_HAS_STOP_DETECT
+ xfer->event = kI2C_SlaveCompletionEvent;
+ xfer->completionStatus = kStatus_Success;
+ handle->isBusy = false;
+
+ if ((handle->eventMask & xfer->event) && (handle->callback))
+ {
+ handle->callback(base, xfer, handle->userData);
+ }
+#endif /* !FSL_FEATURE_I2C_HAS_START_STOP_DETECT or !FSL_FEATURE_I2C_HAS_STOP_DETECT */
+ }
+ }
+ /* Check address match. */
+ else if (status & kI2C_AddressMatchFlag)
+ {
+ handle->isBusy = true;
+ xfer->event = kI2C_SlaveAddressMatchEvent;
+
+ if ((handle->eventMask & xfer->event) && (handle->callback))
+ {
+ handle->callback(base, xfer, handle->userData);
+ }
+
+ /* Slave transmit, master reading from slave. */
+ if (status & kI2C_TransferDirectionFlag)
+ {
+ /* Change direction to send data. */
+ base->C1 |= I2C_C1_TX_MASK;
+
+ doTransmit = true;
+ }
+ else
+ {
+ /* Slave receive, master writing to slave. */
+ base->C1 &= ~(I2C_C1_TX_MASK | I2C_C1_TXAK_MASK);
+
+ /* Read dummy to release the bus. */
+ dummy = base->D;
+ }
+ }
+ /* Check transfer complete flag. */
+ else if (status & kI2C_TransferCompleteFlag)
+ {
+ /* Slave transmit, master reading from slave. */
+ if (status & kI2C_TransferDirectionFlag)
+ {
+ doTransmit = true;
+ }
+ else
+ {
+ /* If we're out of data, invoke callback to get more. */
+ if ((!xfer->data) || (!xfer->dataSize))
+ {
+ xfer->event = kI2C_SlaveReceiveEvent;
+
+ if (handle->callback)
+ {
+ handle->callback(base, xfer, handle->userData);
+ }
+
+ /* Clear the transferred count now that we have a new buffer. */
+ xfer->transferredCount = 0;
+ }
+
+ /* Slave receive, master writing to slave. */
+ uint8_t data = base->D;
+
+ if (handle->transfer.dataSize)
+ {
+ /* Receive data. */
+ *handle->transfer.data++ = data;
+ handle->transfer.dataSize--;
+ xfer->transferredCount++;
+ if (!handle->transfer.dataSize)
+ {
+#ifndef I2C_HAS_STOP_DETECT
+ xfer->event = kI2C_SlaveCompletionEvent;
+ xfer->completionStatus = kStatus_Success;
+ handle->isBusy = false;
+
+ /* Proceed receive complete event. */
+ if ((handle->eventMask & xfer->event) && (handle->callback))
+ {
+ handle->callback(base, xfer, handle->userData);
+ }
+#endif /* !FSL_FEATURE_I2C_HAS_START_STOP_DETECT or !FSL_FEATURE_I2C_HAS_STOP_DETECT */
+ }
+ }
+ }
+ }
+ else
+ {
+ /* Read dummy to release bus. */
+ dummy = base->D;
+ }
+
+ /* Send data if there is the need. */
+ if (doTransmit)
+ {
+ /* If we're out of data, invoke callback to get more. */
+ if ((!xfer->data) || (!xfer->dataSize))
+ {
+ xfer->event = kI2C_SlaveTransmitEvent;
+
+ if (handle->callback)
+ {
+ handle->callback(base, xfer, handle->userData);
+ }
+
+ /* Clear the transferred count now that we have a new buffer. */
+ xfer->transferredCount = 0;
+ }
+
+ if (handle->transfer.dataSize)
+ {
+ /* Send data. */
+ base->D = *handle->transfer.data++;
+ handle->transfer.dataSize--;
+ xfer->transferredCount++;
+ }
+ else
+ {
+ /* Switch to receive mode. */
+ base->C1 &= ~(I2C_C1_TX_MASK | I2C_C1_TXAK_MASK);
+
+ /* Read dummy to release bus. */
+ dummy = base->D;
+
+#ifndef I2C_HAS_STOP_DETECT
+ xfer->event = kI2C_SlaveCompletionEvent;
+ xfer->completionStatus = kStatus_Success;
+ handle->isBusy = false;
+
+ /* Proceed txdone event. */
+ if ((handle->eventMask & xfer->event) && (handle->callback))
+ {
+ handle->callback(base, xfer, handle->userData);
+ }
+#endif /* !FSL_FEATURE_I2C_HAS_START_STOP_DETECT or !FSL_FEATURE_I2C_HAS_STOP_DETECT */
+ }
+ }
+}
+
+void I2C0_DriverIRQHandler(void)
+{
+ I2C_TransferCommonIRQHandler(I2C0, s_i2cHandle[0]);
+}
+
+#if (FSL_FEATURE_SOC_I2C_COUNT > 1)
+void I2C1_DriverIRQHandler(void)
+{
+ I2C_TransferCommonIRQHandler(I2C1, s_i2cHandle[1]);
+}
+#endif /* I2C COUNT > 1 */
+
+#if (FSL_FEATURE_SOC_I2C_COUNT > 2)
+void I2C2_DriverIRQHandler(void)
+{
+ I2C_TransferCommonIRQHandler(I2C2, s_i2cHandle[2]);
+}
+#endif /* I2C COUNT > 2 */
+#if (FSL_FEATURE_SOC_I2C_COUNT > 3)
+void I2C3_DriverIRQHandler(void)
+{
+ I2C_TransferCommonIRQHandler(I2C3, s_i2cHandle[3]);
+}
+#endif /* I2C COUNT > 3 */
diff --git a/drivers/fsl_i2c.h b/drivers/fsl_i2c.h
new file mode 100644
index 0000000..7117fd5
--- /dev/null
+++ b/drivers/fsl_i2c.h
@@ -0,0 +1,788 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_I2C_H_
+#define _FSL_I2C_H_
+
+#include "fsl_common.h"
+
+/*!
+ * @addtogroup i2c_driver
+ * @{
+ */
+
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+/*! @name Driver version */
+/*@{*/
+/*! @brief I2C driver version 2.0.1. */
+#define FSL_I2C_DRIVER_VERSION (MAKE_VERSION(2, 0, 1))
+/*@}*/
+
+#if (defined(FSL_FEATURE_I2C_HAS_START_STOP_DETECT) && FSL_FEATURE_I2C_HAS_START_STOP_DETECT || \
+ defined(FSL_FEATURE_I2C_HAS_STOP_DETECT) && FSL_FEATURE_I2C_HAS_STOP_DETECT)
+#define I2C_HAS_STOP_DETECT
+#endif /* FSL_FEATURE_I2C_HAS_START_STOP_DETECT / FSL_FEATURE_I2C_HAS_STOP_DETECT */
+
+/*! @brief I2C status return codes. */
+enum _i2c_status
+{
+ kStatus_I2C_Busy = MAKE_STATUS(kStatusGroup_I2C, 0), /*!< I2C is busy with current transfer. */
+ kStatus_I2C_Idle = MAKE_STATUS(kStatusGroup_I2C, 1), /*!< Bus is Idle. */
+ kStatus_I2C_Nak = MAKE_STATUS(kStatusGroup_I2C, 2), /*!< NAK received during transfer. */
+ kStatus_I2C_ArbitrationLost = MAKE_STATUS(kStatusGroup_I2C, 3), /*!< Arbitration lost during transfer. */
+ kStatus_I2C_Timeout = MAKE_STATUS(kStatusGroup_I2C, 4), /*!< Wait event timeout. */
+};
+
+/*!
+ * @brief I2C peripheral flags
+ *
+ * The following status register flags can be cleared:
+ * - #kI2C_ArbitrationLostFlag
+ * - #kI2C_IntPendingFlag
+ * - #kI2C_StartDetectFlag
+ * - #kI2C_StopDetectFlag
+ *
+ * @note These enumerations are meant to be OR'd together to form a bit mask.
+ *
+ */
+enum _i2c_flags
+{
+ kI2C_ReceiveNakFlag = I2C_S_RXAK_MASK, /*!< I2C receive NAK flag. */
+ kI2C_IntPendingFlag = I2C_S_IICIF_MASK, /*!< I2C interrupt pending flag. */
+ kI2C_TransferDirectionFlag = I2C_S_SRW_MASK, /*!< I2C transfer direction flag. */
+ kI2C_RangeAddressMatchFlag = I2C_S_RAM_MASK, /*!< I2C range address match flag. */
+ kI2C_ArbitrationLostFlag = I2C_S_ARBL_MASK, /*!< I2C arbitration lost flag. */
+ kI2C_BusBusyFlag = I2C_S_BUSY_MASK, /*!< I2C bus busy flag. */
+ kI2C_AddressMatchFlag = I2C_S_IAAS_MASK, /*!< I2C address match flag. */
+ kI2C_TransferCompleteFlag = I2C_S_TCF_MASK, /*!< I2C transfer complete flag. */
+#ifdef I2C_HAS_STOP_DETECT
+ kI2C_StopDetectFlag = I2C_FLT_STOPF_MASK << 8, /*!< I2C stop detect flag. */
+#endif /* FSL_FEATURE_I2C_HAS_START_STOP_DETECT / FSL_FEATURE_I2C_HAS_STOP_DETECT */
+
+#if defined(FSL_FEATURE_I2C_HAS_START_STOP_DETECT) && FSL_FEATURE_I2C_HAS_START_STOP_DETECT
+ kI2C_StartDetectFlag = I2C_FLT_STARTF_MASK << 8, /*!< I2C start detect flag. */
+#endif /* FSL_FEATURE_I2C_HAS_START_STOP_DETECT */
+};
+
+/*! @brief I2C feature interrupt source. */
+enum _i2c_interrupt_enable
+{
+ kI2C_GlobalInterruptEnable = I2C_C1_IICIE_MASK, /*!< I2C global interrupt. */
+
+#if defined(FSL_FEATURE_I2C_HAS_STOP_DETECT) && FSL_FEATURE_I2C_HAS_STOP_DETECT
+ kI2C_StopDetectInterruptEnable = I2C_FLT_STOPIE_MASK, /*!< I2C stop detect interrupt. */
+#endif /* FSL_FEATURE_I2C_HAS_STOP_DETECT */
+
+#if defined(FSL_FEATURE_I2C_HAS_START_STOP_DETECT) && FSL_FEATURE_I2C_HAS_START_STOP_DETECT
+ kI2C_StartStopDetectInterruptEnable = I2C_FLT_SSIE_MASK, /*!< I2C start&stop detect interrupt. */
+#endif /* FSL_FEATURE_I2C_HAS_START_STOP_DETECT */
+};
+
+/*! @brief Direction of master and slave transfers. */
+typedef enum _i2c_direction
+{
+ kI2C_Write = 0x0U, /*!< Master transmit to slave. */
+ kI2C_Read = 0x1U, /*!< Master receive from slave. */
+} i2c_direction_t;
+
+/*! @brief Addressing mode. */
+typedef enum _i2c_slave_address_mode
+{
+ kI2C_Address7bit = 0x0U, /*!< 7-bit addressing mode. */
+ kI2C_RangeMatch = 0X2U, /*!< Range address match addressing mode. */
+} i2c_slave_address_mode_t;
+
+/*! @brief I2C transfer control flag. */
+enum _i2c_master_transfer_flags
+{
+ kI2C_TransferDefaultFlag = 0x0U, /*!< Transfer starts with a start signal, stops with a stop signal. */
+ kI2C_TransferNoStartFlag = 0x1U, /*!< Transfer starts without a start signal. */
+ kI2C_TransferRepeatedStartFlag = 0x2U, /*!< Transfer starts with a repeated start signal. */
+ kI2C_TransferNoStopFlag = 0x4U, /*!< Transfer ends without a stop signal. */
+};
+
+/*!
+ * @brief Set of events sent to the callback for nonblocking slave transfers.
+ *
+ * These event enumerations are used for two related purposes. First, a bit mask created by OR'ing together
+ * events is passed to I2C_SlaveTransferNonBlocking() in order to specify which events to enable.
+ * Then, when the slave callback is invoked, it is passed the current event through its @a transfer
+ * parameter.
+ *
+ * @note These enumerations are meant to be OR'd together to form a bit mask of events.
+ */
+typedef enum _i2c_slave_transfer_event
+{
+ kI2C_SlaveAddressMatchEvent = 0x01U, /*!< Received the slave address after a start or repeated start. */
+ kI2C_SlaveTransmitEvent = 0x02U, /*!< Callback is requested to provide data to transmit
+ (slave-transmitter role). */
+ kI2C_SlaveReceiveEvent = 0x04U, /*!< Callback is requested to provide a buffer in which to place received
+ data (slave-receiver role). */
+ kI2C_SlaveTransmitAckEvent = 0x08U, /*!< Callback needs to either transmit an ACK or NACK. */
+#if defined(FSL_FEATURE_I2C_HAS_START_STOP_DETECT) && FSL_FEATURE_I2C_HAS_START_STOP_DETECT
+ kI2C_SlaveStartEvent = 0x10U, /*!< A start/repeated start was detected. */
+#endif
+ kI2C_SlaveCompletionEvent = 0x20U, /*!< A stop was detected or finished transfer, completing the transfer. */
+
+ /*! Bit mask of all available events. */
+ kI2C_SlaveAllEvents = kI2C_SlaveAddressMatchEvent | kI2C_SlaveTransmitEvent | kI2C_SlaveReceiveEvent |
+#if defined(FSL_FEATURE_I2C_HAS_START_STOP_DETECT) && FSL_FEATURE_I2C_HAS_START_STOP_DETECT
+ kI2C_SlaveStartEvent |
+#endif
+ kI2C_SlaveCompletionEvent,
+} i2c_slave_transfer_event_t;
+
+/*! @brief I2C master user configuration. */
+typedef struct _i2c_master_config
+{
+ bool enableMaster; /*!< Enables the I2C peripheral at initialization time. */
+#if defined(FSL_FEATURE_I2C_HAS_HIGH_DRIVE_SELECTION) && FSL_FEATURE_I2C_HAS_HIGH_DRIVE_SELECTION
+ bool enableHighDrive; /*!< Controls the drive capability of the I2C pads. */
+#endif
+#if defined(FSL_FEATURE_I2C_HAS_STOP_HOLD_OFF) && FSL_FEATURE_I2C_HAS_STOP_HOLD_OFF
+ bool enableStopHold; /*!< Controls the stop hold enable. */
+#endif
+#if defined(FSL_FEATURE_I2C_HAS_DOUBLE_BUFFER_ENABLE) && FSL_FEATURE_I2C_HAS_DOUBLE_BUFFER_ENABLE
+ bool enableDoubleBuffering; /*!< Controls double buffer enable, notice that
+ enabling the double buffer disables the clock stretch. */
+#endif
+ uint32_t baudRate_Bps; /*!< Baud rate configuration of I2C peripheral. */
+ uint8_t glitchFilterWidth; /*!< Controls the width of the glitch. */
+} i2c_master_config_t;
+
+/*! @brief I2C slave user configuration. */
+typedef struct _i2c_slave_config
+{
+ bool enableSlave; /*!< Enables the I2C peripheral at initialization time. */
+ bool enableGeneralCall; /*!< Enable general call addressing mode. */
+ bool enableWakeUp; /*!< Enables/disables waking up MCU from low-power mode. */
+#if defined(FSL_FEATURE_I2C_HAS_HIGH_DRIVE_SELECTION) && FSL_FEATURE_I2C_HAS_HIGH_DRIVE_SELECTION
+ bool enableHighDrive; /*!< Controls the drive capability of the I2C pads. */
+#endif
+#if defined(FSL_FEATURE_I2C_HAS_DOUBLE_BUFFER_ENABLE) && FSL_FEATURE_I2C_HAS_DOUBLE_BUFFER_ENABLE
+ bool enableDoubleBuffering; /*!< Controls double buffer enable, notice that
+ enabling the double buffer disables the clock stretch. */
+#endif
+ bool enableBaudRateCtl; /*!< Enables/disables independent slave baud rate on SCL in very fast I2C modes. */
+ uint16_t slaveAddress; /*!< Slave address configuration. */
+ uint16_t upperAddress; /*!< Maximum boundary slave address used in range matching mode. */
+ i2c_slave_address_mode_t addressingMode; /*!< Addressing mode configuration of i2c_slave_address_mode_config_t. */
+} i2c_slave_config_t;
+
+/*! @brief I2C master handle typedef. */
+typedef struct _i2c_master_handle i2c_master_handle_t;
+
+/*! @brief I2C master transfer callback typedef. */
+typedef void (*i2c_master_transfer_callback_t)(I2C_Type *base,
+ i2c_master_handle_t *handle,
+ status_t status,
+ void *userData);
+
+/*! @brief I2C slave handle typedef. */
+typedef struct _i2c_slave_handle i2c_slave_handle_t;
+
+/*! @brief I2C master transfer structure. */
+typedef struct _i2c_master_transfer
+{
+ uint32_t flags; /*!< Transfer flag which controls the transfer. */
+ uint8_t slaveAddress; /*!< 7-bit slave address. */
+ i2c_direction_t direction; /*!< Transfer direction, read or write. */
+ uint32_t subaddress; /*!< Sub address. Transferred MSB first. */
+ uint8_t subaddressSize; /*!< Size of command buffer. */
+ uint8_t *volatile data; /*!< Transfer buffer. */
+ volatile size_t dataSize; /*!< Transfer size. */
+} i2c_master_transfer_t;
+
+/*! @brief I2C master handle structure. */
+struct _i2c_master_handle
+{
+ i2c_master_transfer_t transfer; /*!< I2C master transfer copy. */
+ size_t transferSize; /*!< Total bytes to be transferred. */
+ uint8_t state; /*!< Transfer state maintained during transfer. */
+ i2c_master_transfer_callback_t completionCallback; /*!< Callback function called when transfer finished. */
+ void *userData; /*!< Callback parameter passed to callback function. */
+};
+
+/*! @brief I2C slave transfer structure. */
+typedef struct _i2c_slave_transfer
+{
+ i2c_slave_transfer_event_t event; /*!< Reason the callback is being invoked. */
+ uint8_t *volatile data; /*!< Transfer buffer. */
+ volatile size_t dataSize; /*!< Transfer size. */
+ status_t completionStatus; /*!< Success or error code describing how the transfer completed. Only applies for
+ #kI2C_SlaveCompletionEvent. */
+ size_t transferredCount; /*!< Number of bytes actually transferred since start or last repeated start. */
+} i2c_slave_transfer_t;
+
+/*! @brief I2C slave transfer callback typedef. */
+typedef void (*i2c_slave_transfer_callback_t)(I2C_Type *base, i2c_slave_transfer_t *xfer, void *userData);
+
+/*! @brief I2C slave handle structure. */
+struct _i2c_slave_handle
+{
+ bool isBusy; /*!< Whether transfer is busy. */
+ i2c_slave_transfer_t transfer; /*!< I2C slave transfer copy. */
+ uint32_t eventMask; /*!< Mask of enabled events. */
+ i2c_slave_transfer_callback_t callback; /*!< Callback function called at transfer event. */
+ void *userData; /*!< Callback parameter passed to callback. */
+};
+
+/*******************************************************************************
+ * API
+ ******************************************************************************/
+
+#if defined(__cplusplus)
+extern "C" {
+#endif /*_cplusplus. */
+
+/*!
+ * @name Initialization and deinitialization
+ * @{
+ */
+
+/*!
+ * @brief Initializes the I2C peripheral. Call this API to ungate the I2C clock
+ * and configure the I2C with master configuration.
+ *
+ * @note This API should be called at the beginning of the application to use
+ * the I2C driver, or any operation to the I2C module may cause a hard fault
+ * because clock is not enabled. The configuration structure can be filled by user
+ * from scratch, or be set with default values by I2C_MasterGetDefaultConfig().
+ * After calling this API, the master is ready to transfer.
+ * Example:
+ * @code
+ * i2c_master_config_t config = {
+ * .enableMaster = true,
+ * .enableStopHold = false,
+ * .highDrive = false,
+ * .baudRate_Bps = 100000,
+ * .glitchFilterWidth = 0
+ * };
+ * I2C_MasterInit(I2C0, &config, 12000000U);
+ * @endcode
+ *
+ * @param base I2C base pointer
+ * @param masterConfig pointer to master configuration structure
+ * @param srcClock_Hz I2C peripheral clock frequency in Hz
+ */
+void I2C_MasterInit(I2C_Type *base, const i2c_master_config_t *masterConfig, uint32_t srcClock_Hz);
+
+/*!
+ * @brief Initializes the I2C peripheral. Call this API to ungate the I2C clock
+ * and initializes the I2C with slave configuration.
+ *
+ * @note This API should be called at the beginning of the application to use
+ * the I2C driver, or any operation to the I2C module can cause a hard fault
+ * because the clock is not enabled. The configuration structure can partly be set
+ * with default values by I2C_SlaveGetDefaultConfig(), or can be filled by the user.
+ * Example
+ * @code
+ * i2c_slave_config_t config = {
+ * .enableSlave = true,
+ * .enableGeneralCall = false,
+ * .addressingMode = kI2C_Address7bit,
+ * .slaveAddress = 0x1DU,
+ * .enableWakeUp = false,
+ * .enablehighDrive = false,
+ * .enableBaudRateCtl = false
+ * };
+ * I2C_SlaveInit(I2C0, &config);
+ * @endcode
+ *
+ * @param base I2C base pointer
+ * @param slaveConfig pointer to slave configuration structure
+ */
+void I2C_SlaveInit(I2C_Type *base, const i2c_slave_config_t *slaveConfig);
+
+/*!
+ * @brief De-initializes the I2C master peripheral. Call this API to gate the I2C clock.
+ * The I2C master module can't work unless the I2C_MasterInit is called.
+ * @param base I2C base pointer
+ */
+void I2C_MasterDeinit(I2C_Type *base);
+
+/*!
+ * @brief De-initializes the I2C slave peripheral. Calling this API gates the I2C clock.
+ * The I2C slave module can't work unless the I2C_SlaveInit is called to enable the clock.
+ * @param base I2C base pointer
+ */
+void I2C_SlaveDeinit(I2C_Type *base);
+
+/*!
+ * @brief Sets the I2C master configuration structure to default values.
+ *
+ * The purpose of this API is to get the configuration structure initialized for use in the I2C_MasterConfigure().
+ * Use the initialized structure unchanged in I2C_MasterConfigure(), or modify some fields of
+ * the structure before calling I2C_MasterConfigure().
+ * Example:
+ * @code
+ * i2c_master_config_t config;
+ * I2C_MasterGetDefaultConfig(&config);
+ * @endcode
+ * @param masterConfig Pointer to the master configuration structure.
+*/
+void I2C_MasterGetDefaultConfig(i2c_master_config_t *masterConfig);
+
+/*!
+ * @brief Sets the I2C slave configuration structure to default values.
+ *
+ * The purpose of this API is to get the configuration structure initialized for use in I2C_SlaveConfigure().
+ * Modify fields of the structure before calling the I2C_SlaveConfigure().
+ * Example:
+ * @code
+ * i2c_slave_config_t config;
+ * I2C_SlaveGetDefaultConfig(&config);
+ * @endcode
+ * @param slaveConfig Pointer to the slave configuration structure.
+ */
+void I2C_SlaveGetDefaultConfig(i2c_slave_config_t *slaveConfig);
+
+/*!
+ * @brief Enables or disabless the I2C peripheral operation.
+ *
+ * @param base I2C base pointer
+ * @param enable pass true to enable module, false to disable module
+ */
+static inline void I2C_Enable(I2C_Type *base, bool enable)
+{
+ if (enable)
+ {
+ base->C1 |= I2C_C1_IICEN_MASK;
+ }
+ else
+ {
+ base->C1 &= ~I2C_C1_IICEN_MASK;
+ }
+}
+
+/* @} */
+
+/*!
+ * @name Status
+ * @{
+ */
+
+/*!
+ * @brief Gets the I2C status flags.
+ *
+ * @param base I2C base pointer
+ * @return status flag, use status flag to AND #_i2c_flags to get the related status.
+ */
+uint32_t I2C_MasterGetStatusFlags(I2C_Type *base);
+
+/*!
+ * @brief Gets the I2C status flags.
+ *
+ * @param base I2C base pointer
+ * @return status flag, use status flag to AND #_i2c_flags to get the related status.
+ */
+static inline uint32_t I2C_SlaveGetStatusFlags(I2C_Type *base)
+{
+ return I2C_MasterGetStatusFlags(base);
+}
+
+/*!
+ * @brief Clears the I2C status flag state.
+ *
+ * The following status register flags can be cleared: kI2C_ArbitrationLostFlag and kI2C_IntPendingFlag
+ *
+ * @param base I2C base pointer
+ * @param statusMask The status flag mask, defined in type i2c_status_flag_t.
+ * The parameter can be any combination of the following values:
+ * @arg kI2C_StartDetectFlag (if available)
+ * @arg kI2C_StopDetectFlag (if available)
+ * @arg kI2C_ArbitrationLostFlag
+ * @arg kI2C_IntPendingFlagFlag
+ */
+static inline void I2C_MasterClearStatusFlags(I2C_Type *base, uint32_t statusMask)
+{
+/* Must clear the STARTF / STOPF bits prior to clearing IICIF */
+#if defined(FSL_FEATURE_I2C_HAS_START_STOP_DETECT) && FSL_FEATURE_I2C_HAS_START_STOP_DETECT
+ if (statusMask & kI2C_StartDetectFlag)
+ {
+ /* Shift the odd-ball flags back into place. */
+ base->FLT |= (uint8_t)(statusMask >> 8U);
+ }
+#endif
+
+#ifdef I2C_HAS_STOP_DETECT
+ if (statusMask & kI2C_StopDetectFlag)
+ {
+ /* Shift the odd-ball flags back into place. */
+ base->FLT |= (uint8_t)(statusMask >> 8U);
+ }
+#endif
+
+ base->S = (uint8_t)statusMask;
+}
+
+/*!
+ * @brief Clears the I2C status flag state.
+ *
+ * The following status register flags can be cleared: kI2C_ArbitrationLostFlag and kI2C_IntPendingFlag
+ *
+ * @param base I2C base pointer
+ * @param statusMask The status flag mask, defined in type i2c_status_flag_t.
+ * The parameter can be any combination of the following values:
+ * @arg kI2C_StartDetectFlag (if available)
+ * @arg kI2C_StopDetectFlag (if available)
+ * @arg kI2C_ArbitrationLostFlag
+ * @arg kI2C_IntPendingFlagFlag
+ */
+static inline void I2C_SlaveClearStatusFlags(I2C_Type *base, uint32_t statusMask)
+{
+ I2C_MasterClearStatusFlags(base, statusMask);
+}
+
+/* @} */
+
+/*!
+ * @name Interrupts
+ * @{
+ */
+
+/*!
+ * @brief Enables I2C interrupt requests.
+ *
+ * @param base I2C base pointer
+ * @param mask interrupt source
+ * The parameter can be combination of the following source if defined:
+ * @arg kI2C_GlobalInterruptEnable
+ * @arg kI2C_StopDetectInterruptEnable/kI2C_StartDetectInterruptEnable
+ * @arg kI2C_SdaTimeoutInterruptEnable
+ */
+void I2C_EnableInterrupts(I2C_Type *base, uint32_t mask);
+
+/*!
+ * @brief Disables I2C interrupt requests.
+ *
+ * @param base I2C base pointer
+ * @param mask interrupt source
+ * The parameter can be combination of the following source if defined:
+ * @arg kI2C_GlobalInterruptEnable
+ * @arg kI2C_StopDetectInterruptEnable/kI2C_StartDetectInterruptEnable
+ * @arg kI2C_SdaTimeoutInterruptEnable
+ */
+void I2C_DisableInterrupts(I2C_Type *base, uint32_t mask);
+
+/*!
+ * @name DMA Control
+ * @{
+ */
+#if defined(FSL_FEATURE_I2C_HAS_DMA_SUPPORT) && FSL_FEATURE_I2C_HAS_DMA_SUPPORT
+/*!
+ * @brief Enables/disables the I2C DMA interrupt.
+ *
+ * @param base I2C base pointer
+ * @param enable true to enable, false to disable
+*/
+static inline void I2C_EnableDMA(I2C_Type *base, bool enable)
+{
+ if (enable)
+ {
+ base->C1 |= I2C_C1_DMAEN_MASK;
+ }
+ else
+ {
+ base->C1 &= ~I2C_C1_DMAEN_MASK;
+ }
+}
+
+#endif /* FSL_FEATURE_I2C_HAS_DMA_SUPPORT */
+
+/*!
+ * @brief Gets the I2C tx/rx data register address. This API is used to provide a transfer address
+ * for I2C DMA transfer configuration.
+ *
+ * @param base I2C base pointer
+ * @return data register address
+ */
+static inline uint32_t I2C_GetDataRegAddr(I2C_Type *base)
+{
+ return (uint32_t)(&(base->D));
+}
+
+/* @} */
+/*!
+ * @name Bus Operations
+ * @{
+ */
+
+/*!
+ * @brief Sets the I2C master transfer baud rate.
+ *
+ * @param base I2C base pointer
+ * @param baudRate_Bps the baud rate value in bps
+ * @param srcClock_Hz Source clock
+ */
+void I2C_MasterSetBaudRate(I2C_Type *base, uint32_t baudRate_Bps, uint32_t srcClock_Hz);
+
+/*!
+ * @brief Sends a START on the I2C bus.
+ *
+ * This function is used to initiate a new master mode transfer by sending the START signal.
+ * The slave address is sent following the I2C START signal.
+ *
+ * @param base I2C peripheral base pointer
+ * @param address 7-bit slave device address.
+ * @param direction Master transfer directions(transmit/receive).
+ * @retval kStatus_Success Successfully send the start signal.
+ * @retval kStatus_I2C_Busy Current bus is busy.
+ */
+status_t I2C_MasterStart(I2C_Type *base, uint8_t address, i2c_direction_t direction);
+
+/*!
+ * @brief Sends a STOP signal on the I2C bus.
+ *
+ * @retval kStatus_Success Successfully send the stop signal.
+ * @retval kStatus_I2C_Timeout Send stop signal failed, timeout.
+ */
+status_t I2C_MasterStop(I2C_Type *base);
+
+/*!
+ * @brief Sends a REPEATED START on the I2C bus.
+ *
+ * @param base I2C peripheral base pointer
+ * @param address 7-bit slave device address.
+ * @param direction Master transfer directions(transmit/receive).
+ * @retval kStatus_Success Successfully send the start signal.
+ * @retval kStatus_I2C_Busy Current bus is busy but not occupied by current I2C master.
+ */
+status_t I2C_MasterRepeatedStart(I2C_Type *base, uint8_t address, i2c_direction_t direction);
+
+/*!
+ * @brief Performs a polling send transaction on the I2C bus without a STOP signal.
+ *
+ * @param base The I2C peripheral base pointer.
+ * @param txBuff The pointer to the data to be transferred.
+ * @param txSize The length in bytes of the data to be transferred.
+ * @retval kStatus_Success Successfully complete the data transmission.
+ * @retval kStatus_I2C_ArbitrationLost Transfer error, arbitration lost.
+ * @retval kStataus_I2C_Nak Transfer error, receive NAK during transfer.
+ */
+status_t I2C_MasterWriteBlocking(I2C_Type *base, const uint8_t *txBuff, size_t txSize);
+
+/*!
+ * @brief Performs a polling receive transaction on the I2C bus with a STOP signal.
+ *
+ * @note The I2C_MasterReadBlocking function stops the bus before reading the final byte.
+ * Without stopping the bus prior for the final read, the bus issues another read, resulting
+ * in garbage data being read into the data register.
+ *
+ * @param base I2C peripheral base pointer.
+ * @param rxBuff The pointer to the data to store the received data.
+ * @param rxSize The length in bytes of the data to be received.
+ * @retval kStatus_Success Successfully complete the data transmission.
+ * @retval kStatus_I2C_Timeout Send stop signal failed, timeout.
+ */
+status_t I2C_MasterReadBlocking(I2C_Type *base, uint8_t *rxBuff, size_t rxSize);
+
+/*!
+ * @brief Performs a polling send transaction on the I2C bus.
+ *
+ * @param base The I2C peripheral base pointer.
+ * @param txBuff The pointer to the data to be transferred.
+ * @param txSize The length in bytes of the data to be transferred.
+ * @retval kStatus_Success Successfully complete the data transmission.
+ * @retval kStatus_I2C_ArbitrationLost Transfer error, arbitration lost.
+ * @retval kStataus_I2C_Nak Transfer error, receive NAK during transfer.
+ */
+status_t I2C_SlaveWriteBlocking(I2C_Type *base, const uint8_t *txBuff, size_t txSize);
+
+/*!
+ * @brief Performs a polling receive transaction on the I2C bus.
+ *
+ * @param base I2C peripheral base pointer.
+ * @param rxBuff The pointer to the data to store the received data.
+ * @param rxSize The length in bytes of the data to be received.
+ */
+void I2C_SlaveReadBlocking(I2C_Type *base, uint8_t *rxBuff, size_t rxSize);
+
+/*!
+ * @brief Performs a master polling transfer on the I2C bus.
+ *
+ * @note The API does not return until the transfer succeeds or fails due
+ * to arbitration lost or receiving a NAK.
+ *
+ * @param base I2C peripheral base address.
+ * @param xfer Pointer to the transfer structure.
+ * @retval kStatus_Success Successfully complete the data transmission.
+ * @retval kStatus_I2C_Busy Previous transmission still not finished.
+ * @retval kStatus_I2C_Timeout Transfer error, wait signal timeout.
+ * @retval kStatus_I2C_ArbitrationLost Transfer error, arbitration lost.
+ * @retval kStataus_I2C_Nak Transfer error, receive NAK during transfer.
+ */
+status_t I2C_MasterTransferBlocking(I2C_Type *base, i2c_master_transfer_t *xfer);
+
+/* @} */
+
+/*!
+ * @name Transactional
+ * @{
+ */
+
+/*!
+ * @brief Initializes the I2C handle which is used in transactional functions.
+ *
+ * @param base I2C base pointer.
+ * @param handle pointer to i2c_master_handle_t structure to store the transfer state.
+ * @param callback pointer to user callback function.
+ * @param userData user parameter passed to the callback function.
+ */
+void I2C_MasterTransferCreateHandle(I2C_Type *base,
+ i2c_master_handle_t *handle,
+ i2c_master_transfer_callback_t callback,
+ void *userData);
+
+/*!
+ * @brief Performs a master interrupt non-blocking transfer on the I2C bus.
+ *
+ * @note Calling the API returns immediately after transfer initiates. The user needs
+ * to call I2C_MasterGetTransferCount to poll the transfer status to check whether
+ * the transfer is finished. If the return status is not kStatus_I2C_Busy, the transfer
+ * is finished.
+ *
+ * @param base I2C base pointer.
+ * @param handle pointer to i2c_master_handle_t structure which stores the transfer state.
+ * @param xfer pointer to i2c_master_transfer_t structure.
+ * @retval kStatus_Success Successfully start the data transmission.
+ * @retval kStatus_I2C_Busy Previous transmission still not finished.
+ * @retval kStatus_I2C_Timeout Transfer error, wait signal timeout.
+ */
+status_t I2C_MasterTransferNonBlocking(I2C_Type *base, i2c_master_handle_t *handle, i2c_master_transfer_t *xfer);
+
+/*!
+ * @brief Gets the master transfer status during a interrupt non-blocking transfer.
+ *
+ * @param base I2C base pointer.
+ * @param handle pointer to i2c_master_handle_t structure which stores the transfer state.
+ * @param count Number of bytes transferred so far by the non-blocking transaction.
+ * @retval kStatus_InvalidArgument count is Invalid.
+ * @retval kStatus_Success Successfully return the count.
+ */
+status_t I2C_MasterTransferGetCount(I2C_Type *base, i2c_master_handle_t *handle, size_t *count);
+
+/*!
+ * @brief Aborts an interrupt non-blocking transfer early.
+ *
+ * @note This API can be called at any time when an interrupt non-blocking transfer initiates
+ * to abort the transfer early.
+ *
+ * @param base I2C base pointer.
+ * @param handle pointer to i2c_master_handle_t structure which stores the transfer state
+ */
+void I2C_MasterTransferAbort(I2C_Type *base, i2c_master_handle_t *handle);
+
+/*!
+ * @brief Master interrupt handler.
+ *
+ * @param base I2C base pointer.
+ * @param i2cHandle pointer to i2c_master_handle_t structure.
+ */
+void I2C_MasterTransferHandleIRQ(I2C_Type *base, void *i2cHandle);
+
+/*!
+ * @brief Initializes the I2C handle which is used in transactional functions.
+ *
+ * @param base I2C base pointer.
+ * @param handle pointer to i2c_slave_handle_t structure to store the transfer state.
+ * @param callback pointer to user callback function.
+ * @param userData user parameter passed to the callback function.
+ */
+void I2C_SlaveTransferCreateHandle(I2C_Type *base,
+ i2c_slave_handle_t *handle,
+ i2c_slave_transfer_callback_t callback,
+ void *userData);
+
+/*!
+ * @brief Starts accepting slave transfers.
+ *
+ * Call this API after calling the I2C_SlaveInit() and I2C_SlaveTransferCreateHandle() to start processing
+ * transactions driven by an I2C master. The slave monitors the I2C bus and passes events to the
+ * callback that was passed into the call to I2C_SlaveTransferCreateHandle(). The callback is always invoked
+ * from the interrupt context.
+ *
+ * The set of events received by the callback is customizable. To do so, set the @a eventMask parameter to
+ * the OR'd combination of #i2c_slave_transfer_event_t enumerators for the events you wish to receive.
+ * The #kI2C_SlaveTransmitEvent and #kLPI2C_SlaveReceiveEvent events are always enabled and do not need
+ * to be included in the mask. Alternatively, pass 0 to get a default set of only the transmit and
+ * receive events that are always enabled. In addition, the #kI2C_SlaveAllEvents constant is provided as
+ * a convenient way to enable all events.
+ *
+ * @param base The I2C peripheral base address.
+ * @param handle Pointer to #i2c_slave_handle_t structure which stores the transfer state.
+ * @param eventMask Bit mask formed by OR'ing together #i2c_slave_transfer_event_t enumerators to specify
+ * which events to send to the callback. Other accepted values are 0 to get a default set of
+ * only the transmit and receive events, and #kI2C_SlaveAllEvents to enable all events.
+ *
+ * @retval #kStatus_Success Slave transfers were successfully started.
+ * @retval #kStatus_I2C_Busy Slave transfers have already been started on this handle.
+ */
+status_t I2C_SlaveTransferNonBlocking(I2C_Type *base, i2c_slave_handle_t *handle, uint32_t eventMask);
+
+/*!
+ * @brief Aborts the slave transfer.
+ *
+ * @note This API can be called at any time to stop slave for handling the bus events.
+ *
+ * @param base I2C base pointer.
+ * @param handle pointer to i2c_slave_handle_t structure which stores the transfer state.
+ */
+void I2C_SlaveTransferAbort(I2C_Type *base, i2c_slave_handle_t *handle);
+
+/*!
+ * @brief Gets the slave transfer remaining bytes during a interrupt non-blocking transfer.
+ *
+ * @param base I2C base pointer.
+ * @param handle pointer to i2c_slave_handle_t structure.
+ * @param count Number of bytes transferred so far by the non-blocking transaction.
+ * @retval kStatus_InvalidArgument count is Invalid.
+ * @retval kStatus_Success Successfully return the count.
+ */
+status_t I2C_SlaveTransferGetCount(I2C_Type *base, i2c_slave_handle_t *handle, size_t *count);
+
+/*!
+ * @brief Slave interrupt handler.
+ *
+ * @param base I2C base pointer.
+ * @param i2cHandle pointer to i2c_slave_handle_t structure which stores the transfer state
+ */
+void I2C_SlaveTransferHandleIRQ(I2C_Type *base, void *i2cHandle);
+
+/* @} */
+#if defined(__cplusplus)
+}
+#endif /*_cplusplus. */
+/*@}*/
+
+#endif /* _FSL_I2C_H_*/
diff --git a/drivers/fsl_i2c_edma.c b/drivers/fsl_i2c_edma.c
new file mode 100644
index 0000000..c8f7c20
--- /dev/null
+++ b/drivers/fsl_i2c_edma.c
@@ -0,0 +1,526 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_i2c_edma.h"
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+/*<! @breif Structure definition for i2c_master_edma_private_handle_t. The structure is private. */
+typedef struct _i2c_master_edma_private_handle
+{
+ I2C_Type *base;
+ i2c_master_edma_handle_t *handle;
+} i2c_master_edma_private_handle_t;
+
+/*! @brief i2c master DMA transfer state. */
+enum _i2c_master_dma_transfer_states
+{
+ kIdleState = 0x0U, /*!< I2C bus idle. */
+ kTransferDataState = 0x1U, /*!< 7-bit address check state. */
+};
+
+/*! @brief Common sets of flags used by the driver. */
+enum _i2c_flag_constants
+{
+/*! All flags which are cleared by the driver upon starting a transfer. */
+#if defined(FSL_FEATURE_I2C_HAS_START_STOP_DETECT) && FSL_FEATURE_I2C_HAS_START_STOP_DETECT
+ kClearFlags = kI2C_ArbitrationLostFlag | kI2C_IntPendingFlag | kI2C_StartDetectFlag | kI2C_StopDetectFlag,
+#elif defined(FSL_FEATURE_I2C_HAS_STOP_DETECT) && FSL_FEATURE_I2C_HAS_STOP_DETECT
+ kClearFlags = kI2C_ArbitrationLostFlag | kI2C_IntPendingFlag | kI2C_StopDetectFlag,
+#else
+ kClearFlags = kI2C_ArbitrationLostFlag | kI2C_IntPendingFlag,
+#endif
+};
+
+/*******************************************************************************
+ * Prototypes
+ ******************************************************************************/
+
+/*!
+ * @brief EDMA callback for I2C master EDMA driver.
+ *
+ * @param handle EDMA handler for I2C master EDMA driver
+ * @param userData user param passed to the callback function
+ */
+static void I2C_MasterTransferCallbackEDMA(edma_handle_t *handle, void *userData, bool transferDone, uint32_t tcds);
+
+/*!
+ * @brief Check and clear status operation.
+ *
+ * @param base I2C peripheral base address.
+ * @param status current i2c hardware status.
+ * @retval kStatus_Success No error found.
+ * @retval kStatus_I2C_ArbitrationLost Transfer error, arbitration lost.
+ * @retval kStatus_I2C_Nak Received Nak error.
+ */
+static status_t I2C_CheckAndClearError(I2C_Type *base, uint32_t status);
+
+/*!
+ * @brief EDMA config for I2C master driver.
+ *
+ * @param base I2C peripheral base address.
+ * @param handle pointer to i2c_master_edma_handle_t structure which stores the transfer state
+ */
+static void I2C_MasterTransferEDMAConfig(I2C_Type *base, i2c_master_edma_handle_t *handle);
+
+/*!
+ * @brief Set up master transfer, send slave address and sub address(if any), wait until the
+ * wait until address sent status return.
+ *
+ * @param base I2C peripheral base address.
+ * @param handle pointer to i2c_master_edma_handle_t structure which stores the transfer state
+ * @param xfer pointer to i2c_master_transfer_t structure
+ */
+static status_t I2C_InitTransferStateMachineEDMA(I2C_Type *base,
+ i2c_master_edma_handle_t *handle,
+ i2c_master_transfer_t *xfer);
+
+/*!
+ * @brief Get the I2C instance from peripheral base address.
+ *
+ * @param base I2C peripheral base address.
+ * @return I2C instance.
+ */
+extern uint32_t I2C_GetInstance(I2C_Type *base);
+
+/*******************************************************************************
+ * Variables
+ ******************************************************************************/
+
+/*<! Private handle only used for internally. */
+static i2c_master_edma_private_handle_t s_edmaPrivateHandle[FSL_FEATURE_SOC_I2C_COUNT];
+
+/*******************************************************************************
+ * Codes
+ ******************************************************************************/
+
+static void I2C_MasterTransferCallbackEDMA(edma_handle_t *handle, void *userData, bool transferDone, uint32_t tcds)
+{
+ i2c_master_edma_private_handle_t *i2cPrivateHandle = (i2c_master_edma_private_handle_t *)userData;
+ status_t result = kStatus_Success;
+
+ /* Disable DMA. */
+ I2C_EnableDMA(i2cPrivateHandle->base, false);
+
+ /* Send stop if kI2C_TransferNoStop flag is not asserted. */
+ if (!(i2cPrivateHandle->handle->transfer.flags & kI2C_TransferNoStopFlag))
+ {
+ if (i2cPrivateHandle->handle->transfer.direction == kI2C_Read)
+ {
+ /* Change to send NAK at the last byte. */
+ i2cPrivateHandle->base->C1 |= I2C_C1_TXAK_MASK;
+
+ /* Wait the last data to be received. */
+ while (!(i2cPrivateHandle->base->S & kI2C_TransferCompleteFlag))
+ {
+ }
+
+ /* Send stop signal. */
+ result = I2C_MasterStop(i2cPrivateHandle->base);
+
+ /* Read the last data byte. */
+ *(i2cPrivateHandle->handle->transfer.data + i2cPrivateHandle->handle->transfer.dataSize - 1) =
+ i2cPrivateHandle->base->D;
+ }
+ else
+ {
+ /* Wait the last data to be sent. */
+ while (!(i2cPrivateHandle->base->S & kI2C_TransferCompleteFlag))
+ {
+ }
+
+ /* Send stop signal. */
+ result = I2C_MasterStop(i2cPrivateHandle->base);
+ }
+ }
+
+ i2cPrivateHandle->handle->state = kIdleState;
+
+ if (i2cPrivateHandle->handle->completionCallback)
+ {
+ i2cPrivateHandle->handle->completionCallback(i2cPrivateHandle->base, i2cPrivateHandle->handle, result,
+ i2cPrivateHandle->handle->userData);
+ }
+}
+
+static status_t I2C_CheckAndClearError(I2C_Type *base, uint32_t status)
+{
+ status_t result = kStatus_Success;
+
+ /* Check arbitration lost. */
+ if (status & kI2C_ArbitrationLostFlag)
+ {
+ /* Clear arbitration lost flag. */
+ base->S = kI2C_ArbitrationLostFlag;
+ result = kStatus_I2C_ArbitrationLost;
+ }
+ /* Check NAK */
+ else if (status & kI2C_ReceiveNakFlag)
+ {
+ result = kStatus_I2C_Nak;
+ }
+ else
+ {
+ }
+
+ return result;
+}
+
+static status_t I2C_InitTransferStateMachineEDMA(I2C_Type *base,
+ i2c_master_edma_handle_t *handle,
+ i2c_master_transfer_t *xfer)
+{
+ assert(handle);
+ assert(xfer);
+
+ status_t result = kStatus_Success;
+ uint16_t timeout = UINT16_MAX;
+
+ if (handle->state != kIdleState)
+ {
+ return kStatus_I2C_Busy;
+ }
+ else
+ {
+ i2c_direction_t direction = xfer->direction;
+
+ /* Init the handle member. */
+ handle->transfer = *xfer;
+
+ /* Save total transfer size. */
+ handle->transferSize = xfer->dataSize;
+
+ handle->state = kTransferDataState;
+
+ /* Wait until ready to complete. */
+ while ((!(base->S & kI2C_TransferCompleteFlag)) && (--timeout))
+ {
+ }
+
+ /* Failed to start the transfer. */
+ if (timeout == 0)
+ {
+ return kStatus_I2C_Timeout;
+ }
+ /* Clear all status before transfer. */
+ I2C_MasterClearStatusFlags(base, kClearFlags);
+
+ /* Change to send write address when it's a read operation with command. */
+ if ((xfer->subaddressSize > 0) && (xfer->direction == kI2C_Read))
+ {
+ direction = kI2C_Write;
+ }
+
+ /* If repeated start is requested, send repeated start. */
+ if (handle->transfer.flags & kI2C_TransferRepeatedStartFlag)
+ {
+ result = I2C_MasterRepeatedStart(base, handle->transfer.slaveAddress, direction);
+ }
+ else /* For normal transfer, send start. */
+ {
+ result = I2C_MasterStart(base, handle->transfer.slaveAddress, direction);
+ }
+
+ /* Send subaddress. */
+ if (handle->transfer.subaddressSize)
+ {
+ do
+ {
+ /* Wait until data transfer complete. */
+ while (!(base->S & kI2C_IntPendingFlag))
+ {
+ }
+
+ /* Clear interrupt pending flag. */
+ base->S = kI2C_IntPendingFlag;
+
+ handle->transfer.subaddressSize--;
+ base->D = ((handle->transfer.subaddress) >> (8 * handle->transfer.subaddressSize));
+
+ /* Check if there's transfer error. */
+ result = I2C_CheckAndClearError(base, base->S);
+
+ if (result)
+ {
+ return result;
+ }
+
+ } while ((handle->transfer.subaddressSize > 0) && (result == kStatus_Success));
+
+ if (handle->transfer.direction == kI2C_Read)
+ {
+ /* Wait until data transfer complete. */
+ while (!(base->S & kI2C_IntPendingFlag))
+ {
+ }
+
+ /* Clear pending flag. */
+ base->S = kI2C_IntPendingFlag;
+
+ /* Send repeated start and slave address. */
+ result = I2C_MasterRepeatedStart(base, handle->transfer.slaveAddress, kI2C_Read);
+ }
+ }
+
+ if (result)
+ {
+ return result;
+ }
+
+ /* Wait until data transfer complete. */
+ while (!(base->S & kI2C_IntPendingFlag))
+ {
+ }
+
+ /* Clear pending flag. */
+ base->S = kI2C_IntPendingFlag;
+
+ /* Check if there's transfer error. */
+ result = I2C_CheckAndClearError(base, base->S);
+ }
+
+ return result;
+}
+
+static void I2C_MasterTransferEDMAConfig(I2C_Type *base, i2c_master_edma_handle_t *handle)
+{
+ edma_transfer_config_t transfer_config;
+
+ if (handle->transfer.direction == kI2C_Read)
+ {
+ transfer_config.srcAddr = (uint32_t)I2C_GetDataRegAddr(base);
+ transfer_config.destAddr = (uint32_t)(handle->transfer.data);
+
+ /* Send stop if kI2C_TransferNoStop flag is not asserted. */
+ if (!(handle->transfer.flags & kI2C_TransferNoStopFlag))
+ {
+ transfer_config.majorLoopCounts = (handle->transfer.dataSize - 1);
+ }
+ else
+ {
+ transfer_config.majorLoopCounts = handle->transfer.dataSize;
+ }
+
+ transfer_config.srcTransferSize = kEDMA_TransferSize1Bytes;
+ transfer_config.srcOffset = 0;
+ transfer_config.destTransferSize = kEDMA_TransferSize1Bytes;
+ transfer_config.destOffset = 1;
+ transfer_config.minorLoopBytes = 1;
+ }
+ else
+ {
+ transfer_config.srcAddr = (uint32_t)(handle->transfer.data + 1);
+ transfer_config.destAddr = (uint32_t)I2C_GetDataRegAddr(base);
+ transfer_config.majorLoopCounts = (handle->transfer.dataSize - 1);
+ transfer_config.srcTransferSize = kEDMA_TransferSize1Bytes;
+ transfer_config.srcOffset = 1;
+ transfer_config.destTransferSize = kEDMA_TransferSize1Bytes;
+ transfer_config.destOffset = 0;
+ transfer_config.minorLoopBytes = 1;
+ }
+
+ EDMA_SubmitTransfer(handle->dmaHandle, &transfer_config);
+ EDMA_StartTransfer(handle->dmaHandle);
+}
+
+void I2C_MasterCreateEDMAHandle(I2C_Type *base,
+ i2c_master_edma_handle_t *handle,
+ i2c_master_edma_transfer_callback_t callback,
+ void *userData,
+ edma_handle_t *edmaHandle)
+{
+ assert(handle);
+ assert(edmaHandle);
+
+ uint32_t instance = I2C_GetInstance(base);
+
+ /* Zero handle. */
+ memset(handle, 0, sizeof(*handle));
+
+ /* Set the user callback and userData. */
+ handle->completionCallback = callback;
+ handle->userData = userData;
+
+ /* Set the base for the handle. */
+ base = base;
+
+ /* Set the handle for EDMA. */
+ handle->dmaHandle = edmaHandle;
+
+ s_edmaPrivateHandle[instance].base = base;
+ s_edmaPrivateHandle[instance].handle = handle;
+
+ EDMA_SetCallback(edmaHandle, (edma_callback)I2C_MasterTransferCallbackEDMA, &s_edmaPrivateHandle[instance]);
+}
+
+status_t I2C_MasterTransferEDMA(I2C_Type *base, i2c_master_edma_handle_t *handle, i2c_master_transfer_t *xfer)
+{
+ assert(handle);
+ assert(xfer);
+
+ status_t result;
+ uint8_t tmpReg;
+ volatile uint8_t dummy = 0;
+
+ /* Add this to avoid build warning. */
+ dummy++;
+
+ /* Disable dma xfer. */
+ I2C_EnableDMA(base, false);
+
+ /* Send address and command buffer(if there is), until senddata phase or receive data phase. */
+ result = I2C_InitTransferStateMachineEDMA(base, handle, xfer);
+
+ if (result)
+ {
+ /* Send stop if received Nak. */
+ if (result == kStatus_I2C_Nak)
+ {
+ if (I2C_MasterStop(base) != kStatus_Success)
+ {
+ result = kStatus_I2C_Timeout;
+ }
+ }
+
+ /* Reset the state to idle state. */
+ handle->state = kIdleState;
+
+ return result;
+ }
+
+ /* Configure dma transfer. */
+ /* For i2c send, need to send 1 byte first to trigger the dma, for i2c read,
+ need to send stop before reading the last byte, so the dma transfer size should
+ be (xSize - 1). */
+ if (handle->transfer.dataSize > 1)
+ {
+ I2C_MasterTransferEDMAConfig(base, handle);
+ if (handle->transfer.direction == kI2C_Read)
+ {
+ /* Change direction for receive. */
+ base->C1 &= ~I2C_C1_TX_MASK;
+
+ /* Read dummy to release the bus. */
+ dummy = base->D;
+
+ /* Enabe dma transfer. */
+ I2C_EnableDMA(base, true);
+ }
+ else
+ {
+ /* Enabe dma transfer. */
+ I2C_EnableDMA(base, true);
+
+ /* Send the first data. */
+ base->D = *handle->transfer.data;
+ }
+ }
+ else /* If transfer size is 1, use polling method. */
+ {
+ if (handle->transfer.direction == kI2C_Read)
+ {
+ tmpReg = base->C1;
+
+ /* Change direction to Rx. */
+ tmpReg &= ~I2C_C1_TX_MASK;
+
+ /* Configure send NAK */
+ tmpReg |= I2C_C1_TXAK_MASK;
+
+ base->C1 = tmpReg;
+
+ /* Read dummy to release the bus. */
+ dummy = base->D;
+ }
+ else
+ {
+ base->D = *handle->transfer.data;
+ }
+
+ /* Wait until data transfer complete. */
+ while (!(base->S & kI2C_IntPendingFlag))
+ {
+ }
+
+ /* Clear pending flag. */
+ base->S = kI2C_IntPendingFlag;
+
+ /* Send stop if kI2C_TransferNoStop flag is not asserted. */
+ if (!(handle->transfer.flags & kI2C_TransferNoStopFlag))
+ {
+ result = I2C_MasterStop(base);
+ }
+
+ /* Read the last byte of data. */
+ if (handle->transfer.direction == kI2C_Read)
+ {
+ *handle->transfer.data = base->D;
+ }
+
+ /* Reset the state to idle. */
+ handle->state = kIdleState;
+ }
+
+ return result;
+}
+
+status_t I2C_MasterTransferGetCountEDMA(I2C_Type *base, i2c_master_edma_handle_t *handle, size_t *count)
+{
+ assert(handle->dmaHandle);
+
+ if (!count)
+ {
+ return kStatus_InvalidArgument;
+ }
+
+ if (kIdleState != handle->state)
+ {
+ *count = (handle->transferSize - EDMA_GetRemainingBytes(handle->dmaHandle->base, handle->dmaHandle->channel));
+ }
+ else
+ {
+ *count = handle->transferSize;
+ }
+
+ return kStatus_Success;
+}
+
+void I2C_MasterTransferAbortEDMA(I2C_Type *base, i2c_master_edma_handle_t *handle)
+{
+ EDMA_AbortTransfer(handle->dmaHandle);
+
+ /* Disable dma transfer. */
+ I2C_EnableDMA(base, false);
+
+ /* Reset the state to idle. */
+ handle->state = kIdleState;
+}
diff --git a/drivers/fsl_i2c_edma.h b/drivers/fsl_i2c_edma.h
new file mode 100644
index 0000000..c95d6ad
--- /dev/null
+++ b/drivers/fsl_i2c_edma.h
@@ -0,0 +1,132 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_I2C_DMA_H_
+#define _FSL_I2C_DMA_H_
+
+#include "fsl_i2c.h"
+#include "fsl_dmamux.h"
+#include "fsl_edma.h"
+
+/*!
+ * @addtogroup i2c_edma_driver
+ * @{
+ */
+
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+/*! @brief I2C master eDMA handle typedef. */
+typedef struct _i2c_master_edma_handle i2c_master_edma_handle_t;
+
+/*! @brief I2C master eDMA transfer callback typedef. */
+typedef void (*i2c_master_edma_transfer_callback_t)(I2C_Type *base,
+ i2c_master_edma_handle_t *handle,
+ status_t status,
+ void *userData);
+
+/*! @brief I2C master eDMA transfer structure. */
+struct _i2c_master_edma_handle
+{
+ i2c_master_transfer_t transfer; /*!< I2C master transfer struct. */
+ size_t transferSize; /*!< Total bytes to be transferred. */
+ uint8_t state; /*!< I2C master transfer status. */
+ edma_handle_t *dmaHandle; /*!< The eDMA handler used. */
+ i2c_master_edma_transfer_callback_t
+ completionCallback; /*!< Callback function called after eDMA transfer finished. */
+ void *userData; /*!< Callback parameter passed to callback function. */
+};
+
+/*******************************************************************************
+ * API
+ ******************************************************************************/
+
+#if defined(__cplusplus)
+extern "C" {
+#endif /*_cplusplus. */
+
+/*!
+ * @name I2C Block eDMA Transfer Operation
+ * @{
+ */
+
+/*!
+ * @brief Init the I2C handle which is used in transcational functions.
+ *
+ * @param base I2C peripheral base address.
+ * @param handle pointer to i2c_master_edma_handle_t structure.
+ * @param callback pointer to user callback function.
+ * @param userData user param passed to the callback function.
+ * @param edmaHandle eDMA handle pointer.
+ */
+void I2C_MasterCreateEDMAHandle(I2C_Type *base,
+ i2c_master_edma_handle_t *handle,
+ i2c_master_edma_transfer_callback_t callback,
+ void *userData,
+ edma_handle_t *edmaHandle);
+
+/*!
+ * @brief Performs a master eDMA non-blocking transfer on the I2C bus.
+ *
+ * @param base I2C peripheral base address.
+ * @param handle pointer to i2c_master_edma_handle_t structure.
+ * @param xfer pointer to transfer structure of i2c_master_transfer_t.
+ * @retval kStatus_Success Sucessully complete the data transmission.
+ * @retval kStatus_I2C_Busy Previous transmission still not finished.
+ * @retval kStatus_I2C_Timeout Transfer error, wait signal timeout.
+ * @retval kStatus_I2C_ArbitrationLost Transfer error, arbitration lost.
+ * @retval kStataus_I2C_Nak Transfer error, receive Nak during transfer.
+ */
+status_t I2C_MasterTransferEDMA(I2C_Type *base, i2c_master_edma_handle_t *handle, i2c_master_transfer_t *xfer);
+
+/*!
+ * @brief Get master transfer status during a eDMA non-blocking transfer.
+ *
+ * @param base I2C peripheral base address.
+ * @param handle pointer to i2c_master_edma_handle_t structure.
+ * @param count Number of bytes transferred so far by the non-blocking transaction.
+ */
+status_t I2C_MasterTransferGetCountEDMA(I2C_Type *base, i2c_master_edma_handle_t *handle, size_t *count);
+
+/*!
+ * @brief Abort a master eDMA non-blocking transfer in a early time.
+ *
+ * @param base I2C peripheral base address.
+ * @param handle pointer to i2c_master_edma_handle_t structure.
+ */
+void I2C_MasterTransferAbortEDMA(I2C_Type *base, i2c_master_edma_handle_t *handle);
+
+/* @} */
+#if defined(__cplusplus)
+}
+#endif /*_cplusplus. */
+/*@}*/
+#endif /*_FSL_I2C_DMA_H_*/
diff --git a/drivers/fsl_llwu.c b/drivers/fsl_llwu.c
new file mode 100644
index 0000000..c27b91e
--- /dev/null
+++ b/drivers/fsl_llwu.c
@@ -0,0 +1,404 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_llwu.h"
+
+#if (defined(FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN) && FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN)
+void LLWU_SetExternalWakeupPinMode(LLWU_Type *base, uint32_t pinIndex, llwu_external_pin_mode_t pinMode)
+{
+#if (defined(FSL_FEATURE_LLWU_REG_BITWIDTH) && (FSL_FEATURE_LLWU_REG_BITWIDTH == 32))
+ volatile uint32_t *regBase;
+ uint32_t regOffset;
+ uint32_t reg;
+
+ switch (pinIndex >> 4U)
+ {
+ case 0U:
+ regBase = &base->PE1;
+ break;
+#if (defined(FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN) && (FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN > 16))
+ case 1U:
+ regBase = &base->PE2;
+ break;
+#endif
+ default:
+ regBase = NULL;
+ break;
+ }
+#else
+ volatile uint8_t *regBase;
+ uint8_t regOffset;
+ uint8_t reg;
+ switch (pinIndex >> 2U)
+ {
+ case 0U:
+ regBase = &base->PE1;
+ break;
+ case 1U:
+ regBase = &base->PE2;
+ break;
+#if (defined(FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN) && (FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN > 8))
+ case 2U:
+ regBase = &base->PE3;
+ break;
+#endif
+#if (defined(FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN) && (FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN > 12))
+ case 3U:
+ regBase = &base->PE4;
+ break;
+#endif
+#if (defined(FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN) && (FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN > 16))
+ case 4U:
+ regBase = &base->PE5;
+ break;
+#endif
+#if (defined(FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN) && (FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN > 20))
+ case 5U:
+ regBase = &base->PE6;
+ break;
+#endif
+#if (defined(FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN) && (FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN > 24))
+ case 6U:
+ regBase = &base->PE7;
+ break;
+#endif
+#if (defined(FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN) && (FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN > 28))
+ case 7U:
+ regBase = &base->PE8;
+ break;
+#endif
+ default:
+ regBase = NULL;
+ break;
+ }
+#endif /* FSL_FEATURE_LLWU_REG_BITWIDTH == 32 */
+
+ if (regBase)
+ {
+ reg = *regBase;
+#if (defined(FSL_FEATURE_LLWU_REG_BITWIDTH) && (FSL_FEATURE_LLWU_REG_BITWIDTH == 32))
+ regOffset = ((pinIndex & 0x0FU) << 1U);
+#else
+ regOffset = ((pinIndex & 0x03U) << 1U);
+#endif
+ reg &= ~(0x3U << regOffset);
+ reg |= ((uint32_t)pinMode << regOffset);
+ *regBase = reg;
+ }
+}
+
+bool LLWU_GetExternalWakeupPinFlag(LLWU_Type *base, uint32_t pinIndex)
+{
+#if (defined(FSL_FEATURE_LLWU_REG_BITWIDTH) && (FSL_FEATURE_LLWU_REG_BITWIDTH == 32))
+ return (bool)(base->PF & (1U << pinIndex));
+#else
+ volatile uint8_t *regBase;
+
+ switch (pinIndex >> 3U)
+ {
+#if (defined(FSL_FEATURE_LLWU_HAS_PF) && FSL_FEATURE_LLWU_HAS_PF)
+ case 0U:
+ regBase = &base->PF1;
+ break;
+#if (defined(FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN) && (FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN > 8))
+ case 1U:
+ regBase = &base->PF2;
+ break;
+#endif /* FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN */
+#if (defined(FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN) && (FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN > 16))
+ case 2U:
+ regBase = &base->PF3;
+ break;
+#endif /* FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN */
+#if (defined(FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN) && (FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN > 24))
+ case 3U:
+ regBase = &base->PF4;
+ break;
+#endif /* FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN */
+#else
+ case 0U:
+ regBase = &base->F1;
+ break;
+#if (defined(FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN) && (FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN > 8))
+ case 1U:
+ regBase = &base->F2;
+ break;
+#endif /* FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN */
+#if (defined(FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN) && (FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN > 16))
+ case 2U:
+ regBase = &base->F3;
+ break;
+#endif /* FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN */
+#if (defined(FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN) && (FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN > 24))
+ case 3U:
+ regBase = &base->F4;
+ break;
+#endif /* FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN */
+#endif /* FSL_FEATURE_LLWU_HAS_PF */
+ default:
+ regBase = NULL;
+ break;
+ }
+
+ if (regBase)
+ {
+ return (bool)(*regBase & (1U << pinIndex % 8));
+ }
+ else
+ {
+ return false;
+ }
+#endif /* FSL_FEATURE_LLWU_REG_BITWIDTH */
+}
+
+void LLWU_ClearExternalWakeupPinFlag(LLWU_Type *base, uint32_t pinIndex)
+{
+#if (defined(FSL_FEATURE_LLWU_REG_BITWIDTH) && (FSL_FEATURE_LLWU_REG_BITWIDTH == 32))
+ base->PF = (1U << pinIndex);
+#else
+ volatile uint8_t *regBase;
+ switch (pinIndex >> 3U)
+ {
+#if (defined(FSL_FEATURE_LLWU_HAS_PF) && FSL_FEATURE_LLWU_HAS_PF)
+ case 0U:
+ regBase = &base->PF1;
+ break;
+#if (defined(FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN) && (FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN > 8))
+ case 1U:
+ regBase = &base->PF2;
+ break;
+#endif /* FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN */
+#if (defined(FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN) && (FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN > 16))
+ case 2U:
+ regBase = &base->PF3;
+ break;
+#endif /* FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN */
+#if (defined(FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN) && (FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN > 24))
+ case 3U:
+ regBase = &base->PF4;
+ break;
+#endif /* FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN */
+#else
+ case 0U:
+ regBase = &base->F1;
+ break;
+#if (defined(FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN) && (FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN > 8))
+ case 1U:
+ regBase = &base->F2;
+ break;
+#endif /* FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN */
+#if (defined(FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN) && (FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN > 16))
+ case 2U:
+ regBase = &base->F3;
+ break;
+#endif /* FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN */
+#if (defined(FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN) && (FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN > 24))
+ case 3U:
+ regBase = &base->F4;
+ break;
+#endif /* FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN */
+#endif /* FSL_FEATURE_LLWU_HAS_PF */
+ default:
+ regBase = NULL;
+ break;
+ }
+ if (regBase)
+ {
+ *regBase = (1U << pinIndex % 8U);
+ }
+#endif /* FSL_FEATURE_LLWU_REG_BITWIDTH */
+}
+#endif /* FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN */
+
+#if (defined(FSL_FEATURE_LLWU_HAS_PIN_FILTER) && FSL_FEATURE_LLWU_HAS_PIN_FILTER)
+void LLWU_SetPinFilterMode(LLWU_Type *base, uint32_t filterIndex, llwu_external_pin_filter_mode_t filterMode)
+{
+#if (defined(FSL_FEATURE_LLWU_REG_BITWIDTH) && (FSL_FEATURE_LLWU_REG_BITWIDTH == 32))
+ uint32_t reg;
+
+ reg = base->FILT;
+ reg &= ~((LLWU_FILT_FILTSEL1_MASK | LLWU_FILT_FILTE1_MASK) << (filterIndex * 8U - 1U));
+ reg |= (((filterMode.pinIndex << LLWU_FILT_FILTSEL1_SHIFT) | (filterMode.filterMode << LLWU_FILT_FILTE1_SHIFT)
+ /* Clear the Filter Detect Flag */
+ | LLWU_FILT_FILTF1_MASK)
+ << (filterIndex * 8U - 1U));
+ base->FILT = reg;
+#else
+ volatile uint8_t *regBase;
+ uint8_t reg;
+
+ switch (filterIndex)
+ {
+ case 1:
+ regBase = &base->FILT1;
+ break;
+#if (defined(FSL_FEATURE_LLWU_HAS_PIN_FILTER) && (FSL_FEATURE_LLWU_HAS_PIN_FILTER > 1))
+ case 2:
+ regBase = &base->FILT2;
+ break;
+#endif /* FSL_FEATURE_LLWU_HAS_PIN_FILTER */
+#if (defined(FSL_FEATURE_LLWU_HAS_PIN_FILTER) && (FSL_FEATURE_LLWU_HAS_PIN_FILTER > 2))
+ case 3:
+ regBase = &base->FILT3;
+ break;
+#endif /* FSL_FEATURE_LLWU_HAS_PIN_FILTER */
+#if (defined(FSL_FEATURE_LLWU_HAS_PIN_FILTER) && (FSL_FEATURE_LLWU_HAS_PIN_FILTER > 3))
+ case 4:
+ regBase = &base->FILT4;
+ break;
+#endif /* FSL_FEATURE_LLWU_HAS_PIN_FILTER */
+ default:
+ regBase = NULL;
+ break;
+ }
+
+ if (regBase)
+ {
+ reg = *regBase;
+ reg &= ~(LLWU_FILT1_FILTSEL_MASK | LLWU_FILT1_FILTE_MASK);
+ reg |= ((uint32_t)filterMode.pinIndex << LLWU_FILT1_FILTSEL_SHIFT);
+ reg |= ((uint32_t)filterMode.filterMode << LLWU_FILT1_FILTE_SHIFT);
+ /* Clear the Filter Detect Flag */
+ reg |= LLWU_FILT1_FILTF_MASK;
+ *regBase = reg;
+ }
+#endif /* FSL_FEATURE_LLWU_REG_BITWIDTH */
+}
+
+bool LLWU_GetPinFilterFlag(LLWU_Type *base, uint32_t filterIndex)
+{
+#if (defined(FSL_FEATURE_LLWU_REG_BITWIDTH) && (FSL_FEATURE_LLWU_REG_BITWIDTH == 32))
+ return (bool)(base->FILT & (1U << (filterIndex * 8U - 1)));
+#else
+ bool status = false;
+
+ switch (filterIndex)
+ {
+ case 1:
+ status = (base->FILT1 & LLWU_FILT1_FILTF_MASK);
+ break;
+#if (defined(FSL_FEATURE_LLWU_HAS_PIN_FILTER) && (FSL_FEATURE_LLWU_HAS_PIN_FILTER > 1))
+ case 2:
+ status = (base->FILT2 & LLWU_FILT2_FILTF_MASK);
+ break;
+#endif /* FSL_FEATURE_LLWU_HAS_PIN_FILTER */
+#if (defined(FSL_FEATURE_LLWU_HAS_PIN_FILTER) && (FSL_FEATURE_LLWU_HAS_PIN_FILTER > 2))
+ case 3:
+ status = (base->FILT3 & LLWU_FILT3_FILTF_MASK);
+ break;
+#endif /* FSL_FEATURE_LLWU_HAS_PIN_FILTER */
+#if (defined(FSL_FEATURE_LLWU_HAS_PIN_FILTER) && (FSL_FEATURE_LLWU_HAS_PIN_FILTER > 3))
+ case 4:
+ status = (base->FILT4 & LLWU_FILT4_FILTF_MASK);
+ break;
+#endif /* FSL_FEATURE_LLWU_HAS_PIN_FILTER */
+ default:
+ break;
+ }
+
+ return status;
+#endif /* FSL_FEATURE_LLWU_REG_BITWIDTH */
+}
+
+void LLWU_ClearPinFilterFlag(LLWU_Type *base, uint32_t filterIndex)
+{
+#if (defined(FSL_FEATURE_LLWU_REG_BITWIDTH) && (FSL_FEATURE_LLWU_REG_BITWIDTH == 32))
+ uint32_t reg;
+
+ reg = base->FILT;
+ switch (filterIndex)
+ {
+ case 1:
+ reg |= LLWU_FILT_FILTF1_MASK;
+ break;
+ case 2:
+ reg |= LLWU_FILT_FILTF2_MASK;
+ break;
+ case 3:
+ reg |= LLWU_FILT_FILTF3_MASK;
+ break;
+ case 4:
+ reg |= LLWU_FILT_FILTF4_MASK;
+ break;
+ default:
+ break;
+ }
+ base->FILT = reg;
+#else
+ volatile uint8_t *regBase;
+ uint8_t reg;
+
+ switch (filterIndex)
+ {
+ case 1:
+ regBase = &base->FILT1;
+ break;
+#if (defined(FSL_FEATURE_LLWU_HAS_PIN_FILTER) && (FSL_FEATURE_LLWU_HAS_PIN_FILTER > 1))
+ case 2:
+ regBase = &base->FILT2;
+ break;
+#endif /* FSL_FEATURE_LLWU_HAS_PIN_FILTER */
+#if (defined(FSL_FEATURE_LLWU_HAS_PIN_FILTER) && (FSL_FEATURE_LLWU_HAS_PIN_FILTER > 2))
+ case 3:
+ regBase = &base->FILT3;
+ break;
+#endif /* FSL_FEATURE_LLWU_HAS_PIN_FILTER */
+#if (defined(FSL_FEATURE_LLWU_HAS_PIN_FILTER) && (FSL_FEATURE_LLWU_HAS_PIN_FILTER > 3))
+ case 4:
+ regBase = &base->FILT4;
+ break;
+#endif /* FSL_FEATURE_LLWU_HAS_PIN_FILTER */
+ default:
+ regBase = NULL;
+ break;
+ }
+
+ if (regBase)
+ {
+ reg = *regBase;
+ reg |= LLWU_FILT1_FILTF_MASK;
+ *regBase = reg;
+ }
+#endif /* FSL_FEATURE_LLWU_REG_BITWIDTH */
+}
+#endif /* FSL_FEATURE_LLWU_HAS_PIN_FILTER */
+
+#if (defined(FSL_FEATURE_LLWU_HAS_RESET_ENABLE) && FSL_FEATURE_LLWU_HAS_RESET_ENABLE)
+void LLWU_SetResetPinMode(LLWU_Type *base, bool pinEnable, bool enableInLowLeakageMode)
+{
+ uint8_t reg;
+
+ reg = base->RST;
+ reg &= ~(LLWU_RST_LLRSTE_MASK | LLWU_RST_RSTFILT_MASK);
+ reg |=
+ (((uint32_t)pinEnable << LLWU_RST_LLRSTE_SHIFT) | ((uint32_t)enableInLowLeakageMode << LLWU_RST_RSTFILT_SHIFT));
+ base->RST = reg;
+}
+#endif /* FSL_FEATURE_LLWU_HAS_RESET_ENABLE */
diff --git a/drivers/fsl_llwu.h b/drivers/fsl_llwu.h
new file mode 100644
index 0000000..1384d51
--- /dev/null
+++ b/drivers/fsl_llwu.h
@@ -0,0 +1,320 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_LLWU_H_
+#define _FSL_LLWU_H_
+
+#include "fsl_common.h"
+
+/*! @addtogroup llwu */
+/*! @{ */
+
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+/*! @name Driver version */
+/*@{*/
+/*! @brief LLWU driver version 2.0.1. */
+#define FSL_LLWU_DRIVER_VERSION (MAKE_VERSION(2, 0, 1))
+/*@}*/
+
+/*!
+ * @brief External input pin control modes
+ */
+typedef enum _llwu_external_pin_mode
+{
+ kLLWU_ExternalPinDisable = 0U, /*!< Pin disabled as wakeup input. */
+ kLLWU_ExternalPinRisingEdge = 1U, /*!< Pin enabled with rising edge detection. */
+ kLLWU_ExternalPinFallingEdge = 2U, /*!< Pin enabled with falling edge detection.*/
+ kLLWU_ExternalPinAnyEdge = 3U /*!< Pin enabled with any change detection. */
+} llwu_external_pin_mode_t;
+
+/*!
+ * @brief Digital filter control modes
+ */
+typedef enum _llwu_pin_filter_mode
+{
+ kLLWU_PinFilterDisable = 0U, /*!< Filter disabled. */
+ kLLWU_PinFilterRisingEdge = 1U, /*!< Filter positive edge detection.*/
+ kLLWU_PinFilterFallingEdge = 2U, /*!< Filter negative edge detection.*/
+ kLLWU_PinFilterAnyEdge = 3U /*!< Filter any edge detection. */
+} llwu_pin_filter_mode_t;
+
+#if (defined(FSL_FEATURE_LLWU_HAS_VERID) && FSL_FEATURE_LLWU_HAS_VERID)
+/*!
+ * @brief IP version ID definition.
+ */
+typedef struct _llwu_version_id
+{
+ uint16_t feature; /*!< Feature Specification Number. */
+ uint8_t minor; /*!< Minor version number. */
+ uint8_t major; /*!< Major version number. */
+} llwu_version_id_t;
+#endif /* FSL_FEATURE_LLWU_HAS_VERID */
+
+#if (defined(FSL_FEATURE_LLWU_HAS_PARAM) && FSL_FEATURE_LLWU_HAS_PARAM)
+/*!
+ * @brief IP parameter definition.
+ */
+typedef struct _llwu_param
+{
+ uint8_t filters; /*!< Number of pin filter. */
+ uint8_t dmas; /*!< Number of wakeup DMA. */
+ uint8_t modules; /*!< Number of wakeup module. */
+ uint8_t pins; /*!< Number of wake up pin. */
+} llwu_param_t;
+#endif /* FSL_FEATURE_LLWU_HAS_PARAM */
+
+#if (defined(FSL_FEATURE_LLWU_HAS_PIN_FILTER) && FSL_FEATURE_LLWU_HAS_PIN_FILTER)
+/*!
+ * @brief External input pin filter control structure
+ */
+typedef struct _llwu_external_pin_filter_mode
+{
+ uint32_t pinIndex; /*!< Pin number */
+ llwu_pin_filter_mode_t filterMode; /*!< Filter mode */
+} llwu_external_pin_filter_mode_t;
+#endif /* FSL_FEATURE_LLWU_HAS_PIN_FILTER */
+
+/*******************************************************************************
+ * API
+ ******************************************************************************/
+
+#if defined(__cplusplus)
+extern "C" {
+#endif
+
+/*!
+ * @name Low-Leakage Wakeup Unit Control APIs
+ * @{
+ */
+
+#if (defined(FSL_FEATURE_LLWU_HAS_VERID) && FSL_FEATURE_LLWU_HAS_VERID)
+/*!
+ * @brief Gets the LLWU version ID.
+ *
+ * This function gets the LLWU version ID, including major version number,
+ * minor version number, and feature specification number.
+ *
+ * @param base LLWU peripheral base address.
+ * @param versionId Pointer to version ID structure.
+ */
+static inline void LLWU_GetVersionId(LLWU_Type *base, llwu_version_id_t *versionId)
+{
+ *((uint32_t *)versionId) = base->VERID;
+}
+#endif /* FSL_FEATURE_LLWU_HAS_VERID */
+
+#if (defined(FSL_FEATURE_LLWU_HAS_PARAM) && FSL_FEATURE_LLWU_HAS_PARAM)
+/*!
+ * @brief Gets the LLWU parameter.
+ *
+ * This function gets the LLWU parameter, including wakeup pin number, module
+ * number, DMA number, and pin filter number.
+ *
+ * @param base LLWU peripheral base address.
+ * @param param Pointer to LLWU param structure.
+ */
+static inline void LLWU_GetParam(LLWU_Type *base, llwu_param_t *param)
+{
+ *((uint32_t *)param) = base->PARAM;
+}
+#endif /* FSL_FEATURE_LLWU_HAS_PARAM */
+
+#if (defined(FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN) && FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN)
+/*!
+ * @brief Sets the external input pin source mode.
+ *
+ * This function sets the external input pin source mode that is used
+ * as a wake up source.
+ *
+ * @param base LLWU peripheral base address.
+ * @param pinIndex pin index which to be enabled as external wakeup source, start from 1.
+ * @param pinMode pin configuration mode defined in llwu_external_pin_modes_t
+ */
+void LLWU_SetExternalWakeupPinMode(LLWU_Type *base, uint32_t pinIndex, llwu_external_pin_mode_t pinMode);
+
+/*!
+ * @brief Gets the external wakeup source flag.
+ *
+ * This function checks the external pin flag to detect whether the MCU is
+ * woke up by the specific pin.
+ *
+ * @param base LLWU peripheral base address.
+ * @param pinIndex pin index, start from 1.
+ * @return true if the specific pin is wake up source.
+ */
+bool LLWU_GetExternalWakeupPinFlag(LLWU_Type *base, uint32_t pinIndex);
+
+/*!
+ * @brief Clears the external wakeup source flag.
+ *
+ * This function clears the external wakeup source flag for a specific pin.
+ *
+ * @param base LLWU peripheral base address.
+ * @param pinIndex pin index, start from 1.
+ */
+void LLWU_ClearExternalWakeupPinFlag(LLWU_Type *base, uint32_t pinIndex);
+#endif /* FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN */
+
+#if (defined(FSL_FEATURE_LLWU_HAS_INTERNAL_MODULE) && FSL_FEATURE_LLWU_HAS_INTERNAL_MODULE)
+/*!
+ * @brief Enables/disables the internal module source.
+ *
+ * This function enables/disables the internal module source mode that is used
+ * as a wake up source.
+ *
+ * @param base LLWU peripheral base address.
+ * @param moduleIndex module index which to be enabled as internal wakeup source, start from 1.
+ * @param enable enable or disable setting
+ */
+static inline void LLWU_EnableInternalModuleInterruptWakup(LLWU_Type *base, uint32_t moduleIndex, bool enable)
+{
+ if (enable)
+ {
+ base->ME |= 1U << moduleIndex;
+ }
+ else
+ {
+ base->ME &= ~(1U << moduleIndex);
+ }
+}
+
+/*!
+ * @brief Gets the external wakeup source flag.
+ *
+ * This function checks the external pin flag to detect whether the system is
+ * woke up by the specific pin.
+ *
+ * @param base LLWU peripheral base address.
+ * @param moduleIndex module index, start from 1.
+ * @return true if the specific pin is wake up source.
+ */
+static inline bool LLWU_GetInternalWakeupModuleFlag(LLWU_Type *base, uint32_t moduleIndex)
+{
+#if (defined(FSL_FEATURE_LLWU_HAS_MF) && FSL_FEATURE_LLWU_HAS_MF)
+#if (defined(FSL_FEATURE_LLWU_REG_BITWIDTH) && (FSL_FEATURE_LLWU_REG_BITWIDTH == 32))
+ return (bool)(base->MF & (1U << moduleIndex));
+#else
+ return (bool)(base->MF5 & (1U << moduleIndex));
+#endif /* FSL_FEATURE_LLWU_REG_BITWIDTH */
+#else
+#if (defined(FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN) && (FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN > 16))
+ return (bool)(base->F5 & (1U << moduleIndex));
+#else
+#if (defined(FSL_FEATURE_LLWU_HAS_PF) && FSL_FEATURE_LLWU_HAS_PF)
+ return (bool)(base->PF3 & (1U << moduleIndex));
+#else
+ return (bool)(base->F3 & (1U << moduleIndex));
+#endif /* FSL_FEATURE_LLWU_HAS_PF */
+#endif /* FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN */
+#endif /* FSL_FEATURE_LLWU_HAS_MF */
+}
+#endif /* FSL_FEATURE_LLWU_HAS_INTERNAL_MODULE */
+
+#if (defined(FSL_FEATURE_LLWU_HAS_DMA_ENABLE_REG) && FSL_FEATURE_LLWU_HAS_DMA_ENABLE_REG)
+/*!
+ * @brief Enables/disables the internal module DMA wakeup source.
+ *
+ * This function enables/disables the internal DMA that is used as a wake up source.
+ *
+ * @param base LLWU peripheral base address.
+ * @param moduleIndex Internal module index which used as DMA request source, start from 1.
+ * @param enable Enable or disable DMA request source
+ */
+static inline void LLWU_EnableInternalModuleDmaRequestWakup(LLWU_Type *base, uint32_t moduleIndex, bool enable)
+{
+ if (enable)
+ {
+ base->DE |= 1U << moduleIndex;
+ }
+ else
+ {
+ base->DE &= ~(1U << moduleIndex);
+ }
+}
+#endif /* FSL_FEATURE_LLWU_HAS_DMA_ENABLE_REG */
+
+#if (defined(FSL_FEATURE_LLWU_HAS_PIN_FILTER) && FSL_FEATURE_LLWU_HAS_PIN_FILTER)
+/*!
+ * @brief Sets the pin filter configuration.
+ *
+ * This function sets the pin filter configuration.
+ *
+ * @param base LLWU peripheral base address.
+ * @param filterIndex pin filter index which used to enable/disable the digital filter, start from 1.
+ * @param filterMode filter mode configuration
+ */
+void LLWU_SetPinFilterMode(LLWU_Type *base, uint32_t filterIndex, llwu_external_pin_filter_mode_t filterMode);
+
+/*!
+ * @brief Gets the pin filter configuration.
+ *
+ * This function gets the pin filter flag.
+ *
+ * @param base LLWU peripheral base address.
+ * @param filterIndex pin filter index, start from 1.
+ * @return true if the flag is a source of existing a low-leakage power mode.
+ */
+bool LLWU_GetPinFilterFlag(LLWU_Type *base, uint32_t filterIndex);
+
+/*!
+ * @brief Clear the pin filter configuration.
+ *
+ * This function clear the pin filter flag.
+ *
+ * @param base LLWU peripheral base address.
+ * @param filterIndex pin filter index which to be clear the flag, start from 1.
+ */
+void LLWU_ClearPinFilterFlag(LLWU_Type *base, uint32_t filterIndex);
+
+#endif /* FSL_FEATURE_LLWU_HAS_PIN_FILTER */
+
+#if (defined(FSL_FEATURE_LLWU_HAS_RESET_ENABLE) && FSL_FEATURE_LLWU_HAS_RESET_ENABLE)
+/*!
+ * @brief Sets the reset pin mode.
+ *
+ * This function sets how the reset pin is used as a low leakage mode exit source.
+ *
+ * @param pinEnable Enable reset pin filter
+ * @param pinFilterEnable Specify whether pin filter is enabled in Low-Leakage power mode.
+ */
+void LLWU_SetResetPinMode(LLWU_Type *base, bool pinEnable, bool enableInLowLeakageMode);
+#endif /* FSL_FEATURE_LLWU_HAS_RESET_ENABLE */
+
+/*@}*/
+
+#if defined(__cplusplus)
+}
+#endif
+
+/*! @}*/
+#endif /* _FSL_LLWU_H_*/
diff --git a/drivers/fsl_lptmr.c b/drivers/fsl_lptmr.c
new file mode 100644
index 0000000..b3dcc89
--- /dev/null
+++ b/drivers/fsl_lptmr.c
@@ -0,0 +1,117 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_lptmr.h"
+
+/*******************************************************************************
+ * Prototypes
+ ******************************************************************************/
+/*!
+ * @brief Gets the instance from the base address to be used to gate or ungate the module clock
+ *
+ * @param base LPTMR peripheral base address
+ *
+ * @return The LPTMR instance
+ */
+static uint32_t LPTMR_GetInstance(LPTMR_Type *base);
+
+/*******************************************************************************
+ * Variables
+ ******************************************************************************/
+/*! @brief Pointers to LPTMR bases for each instance. */
+static LPTMR_Type *const s_lptmrBases[] = LPTMR_BASE_PTRS;
+
+/*! @brief Pointers to LPTMR clocks for each instance. */
+static const clock_ip_name_t s_lptmrClocks[] = LPTMR_CLOCKS;
+
+/*******************************************************************************
+ * Code
+ ******************************************************************************/
+static uint32_t LPTMR_GetInstance(LPTMR_Type *base)
+{
+ uint32_t instance;
+
+ /* Find the instance index from base address mappings. */
+ for (instance = 0; instance < FSL_FEATURE_SOC_LPTMR_COUNT; instance++)
+ {
+ if (s_lptmrBases[instance] == base)
+ {
+ break;
+ }
+ }
+
+ assert(instance < FSL_FEATURE_SOC_LPTMR_COUNT);
+
+ return instance;
+}
+
+void LPTMR_Init(LPTMR_Type *base, const lptmr_config_t *config)
+{
+ assert(config);
+
+ /* Ungate the LPTMR clock*/
+ CLOCK_EnableClock(s_lptmrClocks[LPTMR_GetInstance(base)]);
+
+ /* Configure the timers operation mode and input pin setup */
+ base->CSR = (LPTMR_CSR_TMS(config->timerMode) | LPTMR_CSR_TFC(config->enableFreeRunning) |
+ LPTMR_CSR_TPP(config->pinPolarity) | LPTMR_CSR_TPS(config->pinSelect));
+
+ /* Configure the prescale value and clock source */
+ base->PSR = (LPTMR_PSR_PRESCALE(config->value) | LPTMR_PSR_PBYP(config->bypassPrescaler) |
+ LPTMR_PSR_PCS(config->prescalerClockSource));
+}
+
+void LPTMR_Deinit(LPTMR_Type *base)
+{
+ /* Disable the LPTMR and reset the internal logic */
+ base->CSR &= ~LPTMR_CSR_TEN_MASK;
+ /* Gate the LPTMR clock*/
+ CLOCK_DisableClock(s_lptmrClocks[LPTMR_GetInstance(base)]);
+}
+
+void LPTMR_GetDefaultConfig(lptmr_config_t *config)
+{
+ assert(config);
+
+ /* Use time counter mode */
+ config->timerMode = kLPTMR_TimerModeTimeCounter;
+ /* Use input 0 as source in pulse counter mode */
+ config->pinSelect = kLPTMR_PinSelectInput_0;
+ /* Pulse input pin polarity is active-high */
+ config->pinPolarity = kLPTMR_PinPolarityActiveHigh;
+ /* Counter resets whenever TCF flag is set */
+ config->enableFreeRunning = false;
+ /* Bypass the prescaler */
+ config->bypassPrescaler = true;
+ /* LPTMR clock source */
+ config->prescalerClockSource = kLPTMR_PrescalerClock_1;
+ /* Divide the prescaler clock by 2 */
+ config->value = kLPTMR_Prescale_Glitch_0;
+}
diff --git a/drivers/fsl_lptmr.h b/drivers/fsl_lptmr.h
new file mode 100644
index 0000000..d022cbb
--- /dev/null
+++ b/drivers/fsl_lptmr.h
@@ -0,0 +1,370 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_LPTMR_H_
+#define _FSL_LPTMR_H_
+
+#include "fsl_common.h"
+
+/*!
+ * @addtogroup lptmr
+ * @{
+ */
+
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+/*! @name Driver version */
+/*@{*/
+#define FSL_LPTMR_DRIVER_VERSION (MAKE_VERSION(2, 0, 0)) /*!< Version 2.0.0 */
+/*@}*/
+
+/*! @brief LPTMR pin selection, used in pulse counter mode.*/
+typedef enum _lptmr_pin_select
+{
+ kLPTMR_PinSelectInput_0 = 0x0U, /*!< Pulse counter input 0 is selected */
+ kLPTMR_PinSelectInput_1 = 0x1U, /*!< Pulse counter input 1 is selected */
+ kLPTMR_PinSelectInput_2 = 0x2U, /*!< Pulse counter input 2 is selected */
+ kLPTMR_PinSelectInput_3 = 0x3U /*!< Pulse counter input 3 is selected */
+} lptmr_pin_select_t;
+
+/*! @brief LPTMR pin polarity, used in pulse counter mode.*/
+typedef enum _lptmr_pin_polarity
+{
+ kLPTMR_PinPolarityActiveHigh = 0x0U, /*!< Pulse Counter input source is active-high */
+ kLPTMR_PinPolarityActiveLow = 0x1U /*!< Pulse Counter input source is active-low */
+} lptmr_pin_polarity_t;
+
+/*! @brief LPTMR timer mode selection.*/
+typedef enum _lptmr_timer_mode
+{
+ kLPTMR_TimerModeTimeCounter = 0x0U, /*!< Time Counter mode */
+ kLPTMR_TimerModePulseCounter = 0x1U /*!< Pulse Counter mode */
+} lptmr_timer_mode_t;
+
+/*! @brief LPTMR prescaler/glitch filter values*/
+typedef enum _lptmr_prescaler_glitch_value
+{
+ kLPTMR_Prescale_Glitch_0 = 0x0U, /*!< Prescaler divide 2, glitch filter does not support this setting */
+ kLPTMR_Prescale_Glitch_1 = 0x1U, /*!< Prescaler divide 4, glitch filter 2 */
+ kLPTMR_Prescale_Glitch_2 = 0x2U, /*!< Prescaler divide 8, glitch filter 4 */
+ kLPTMR_Prescale_Glitch_3 = 0x3U, /*!< Prescaler divide 16, glitch filter 8 */
+ kLPTMR_Prescale_Glitch_4 = 0x4U, /*!< Prescaler divide 32, glitch filter 16 */
+ kLPTMR_Prescale_Glitch_5 = 0x5U, /*!< Prescaler divide 64, glitch filter 32 */
+ kLPTMR_Prescale_Glitch_6 = 0x6U, /*!< Prescaler divide 128, glitch filter 64 */
+ kLPTMR_Prescale_Glitch_7 = 0x7U, /*!< Prescaler divide 256, glitch filter 128 */
+ kLPTMR_Prescale_Glitch_8 = 0x8U, /*!< Prescaler divide 512, glitch filter 256 */
+ kLPTMR_Prescale_Glitch_9 = 0x9U, /*!< Prescaler divide 1024, glitch filter 512*/
+ kLPTMR_Prescale_Glitch_10 = 0xAU, /*!< Prescaler divide 2048 glitch filter 1024 */
+ kLPTMR_Prescale_Glitch_11 = 0xBU, /*!< Prescaler divide 4096, glitch filter 2048 */
+ kLPTMR_Prescale_Glitch_12 = 0xCU, /*!< Prescaler divide 8192, glitch filter 4096 */
+ kLPTMR_Prescale_Glitch_13 = 0xDU, /*!< Prescaler divide 16384, glitch filter 8192 */
+ kLPTMR_Prescale_Glitch_14 = 0xEU, /*!< Prescaler divide 32768, glitch filter 16384 */
+ kLPTMR_Prescale_Glitch_15 = 0xFU /*!< Prescaler divide 65536, glitch filter 32768 */
+} lptmr_prescaler_glitch_value_t;
+
+/*!
+ * @brief LPTMR prescaler/glitch filter clock select.
+ * @note Clock connections are SoC-specific
+ */
+typedef enum _lptmr_prescaler_clock_select
+{
+ kLPTMR_PrescalerClock_0 = 0x0U, /*!< Prescaler/glitch filter clock 0 selected. */
+ kLPTMR_PrescalerClock_1 = 0x1U, /*!< Prescaler/glitch filter clock 1 selected. */
+ kLPTMR_PrescalerClock_2 = 0x2U, /*!< Prescaler/glitch filter clock 2 selected. */
+ kLPTMR_PrescalerClock_3 = 0x3U, /*!< Prescaler/glitch filter clock 3 selected. */
+} lptmr_prescaler_clock_select_t;
+
+/*! @brief List of LPTMR interrupts */
+typedef enum _lptmr_interrupt_enable
+{
+ kLPTMR_TimerInterruptEnable = LPTMR_CSR_TIE_MASK, /*!< Timer interrupt enable */
+} lptmr_interrupt_enable_t;
+
+/*! @brief List of LPTMR status flags */
+typedef enum _lptmr_status_flags
+{
+ kLPTMR_TimerCompareFlag = LPTMR_CSR_TCF_MASK, /*!< Timer compare flag */
+} lptmr_status_flags_t;
+
+/*!
+ * @brief LPTMR config structure
+ *
+ * This structure holds the configuration settings for the LPTMR peripheral. To initialize this
+ * structure to reasonable defaults, call the LPTMR_GetDefaultConfig() function and pass a
+ * pointer to your config structure instance.
+ *
+ * The config struct can be made const so it resides in flash
+ */
+typedef struct _lptmr_config
+{
+ lptmr_timer_mode_t timerMode; /*!< Time counter mode or pulse counter mode */
+ lptmr_pin_select_t pinSelect; /*!< LPTMR pulse input pin select; used only in pulse counter mode */
+ lptmr_pin_polarity_t pinPolarity; /*!< LPTMR pulse input pin polarity; used only in pulse counter mode */
+ bool enableFreeRunning; /*!< true: enable free running, counter is reset on overflow
+ false: counter is reset when the compare flag is set */
+ bool bypassPrescaler; /*!< true: bypass prescaler; false: use clock from prescaler */
+ lptmr_prescaler_clock_select_t prescalerClockSource; /*!< LPTMR clock source */
+ lptmr_prescaler_glitch_value_t value; /*!< Prescaler or glitch filter value */
+} lptmr_config_t;
+
+/*******************************************************************************
+ * API
+ ******************************************************************************/
+
+#if defined(__cplusplus)
+extern "C" {
+#endif
+
+/*!
+ * @name Initialization and deinitialization
+ * @{
+ */
+
+/*!
+ * @brief Ungate the LPTMR clock and configures the peripheral for basic operation.
+ *
+ * @note This API should be called at the beginning of the application using the LPTMR driver.
+ *
+ * @param base LPTMR peripheral base address
+ * @param config Pointer to user's LPTMR config structure.
+ */
+void LPTMR_Init(LPTMR_Type *base, const lptmr_config_t *config);
+
+/*!
+ * @brief Gate the LPTMR clock
+ *
+ * @param base LPTMR peripheral base address
+ */
+void LPTMR_Deinit(LPTMR_Type *base);
+
+/*!
+ * @brief Fill in the LPTMR config struct with the default settings
+ *
+ * The default values are:
+ * @code
+ * config->timerMode = kLPTMR_TimerModeTimeCounter;
+ * config->pinSelect = kLPTMR_PinSelectInput_0;
+ * config->pinPolarity = kLPTMR_PinPolarityActiveHigh;
+ * config->enableFreeRunning = false;
+ * config->bypassPrescaler = true;
+ * config->prescalerClockSource = kLPTMR_PrescalerClock_1;
+ * config->value = kLPTMR_Prescale_Glitch_0;
+ * @endcode
+ * @param config Pointer to user's LPTMR config structure.
+ */
+void LPTMR_GetDefaultConfig(lptmr_config_t *config);
+
+/*! @}*/
+
+/*!
+ * @name Interrupt Interface
+ * @{
+ */
+
+/*!
+ * @brief Enables the selected LPTMR interrupts.
+ *
+ * @param base LPTMR peripheral base address
+ * @param mask The interrupts to enable. This is a logical OR of members of the
+ * enumeration ::lptmr_interrupt_enable_t
+ */
+static inline void LPTMR_EnableInterrupts(LPTMR_Type *base, uint32_t mask)
+{
+ uint32_t reg = base->CSR;
+
+ /* Clear the TCF bit so that we don't clear this w1c bit when writing back */
+ reg &= ~(LPTMR_CSR_TCF_MASK);
+ reg |= mask;
+ base->CSR = reg;
+}
+
+/*!
+ * @brief Disables the selected LPTMR interrupts.
+ *
+ * @param base LPTMR peripheral base address
+ * @param mask The interrupts to disable. This is a logical OR of members of the
+ * enumeration ::lptmr_interrupt_enable_t
+ */
+static inline void LPTMR_DisableInterrupts(LPTMR_Type *base, uint32_t mask)
+{
+ uint32_t reg = base->CSR;
+
+ /* Clear the TCF bit so that we don't clear this w1c bit when writing back */
+ reg &= ~(LPTMR_CSR_TCF_MASK);
+ reg &= ~mask;
+ base->CSR = reg;
+}
+
+/*!
+ * @brief Gets the enabled LPTMR interrupts.
+ *
+ * @param base LPTMR peripheral base address
+ *
+ * @return The enabled interrupts. This is the logical OR of members of the
+ * enumeration ::lptmr_interrupt_enable_t
+ */
+static inline uint32_t LPTMR_GetEnabledInterrupts(LPTMR_Type *base)
+{
+ return (base->CSR & LPTMR_CSR_TIE_MASK);
+}
+
+/*! @}*/
+
+/*!
+ * @name Status Interface
+ * @{
+ */
+
+/*!
+ * @brief Gets the LPTMR status flags
+ *
+ * @param base LPTMR peripheral base address
+ *
+ * @return The status flags. This is the logical OR of members of the
+ * enumeration ::lptmr_status_flags_t
+ */
+static inline uint32_t LPTMR_GetStatusFlags(LPTMR_Type *base)
+{
+ return (base->CSR & LPTMR_CSR_TCF_MASK);
+}
+
+/*!
+ * @brief Clears the LPTMR status flags
+ *
+ * @param base LPTMR peripheral base address
+ * @param mask The status flags to clear. This is a logical OR of members of the
+ * enumeration ::lptmr_status_flags_t
+ */
+static inline void LPTMR_ClearStatusFlags(LPTMR_Type *base, uint32_t mask)
+{
+ base->CSR |= mask;
+}
+
+/*! @}*/
+
+/*!
+ * @name Read and Write the timer period
+ * @{
+ */
+
+/*!
+ * @brief Sets the timer period in units of count.
+ *
+ * Timers counts from 0 till it equals the count value set here. The count value is written to
+ * the CMR register.
+ *
+ * @note
+ * 1. The TCF flag is set with the CNR equals the count provided here and then increments.
+ * 2. User can call the utility macros provided in fsl_common.h to convert to ticks
+ *
+ * @param base LPTMR peripheral base address
+ * @param ticks Timer period in units of ticks
+ */
+static inline void LPTMR_SetTimerPeriod(LPTMR_Type *base, uint16_t ticks)
+{
+ base->CMR = ticks;
+}
+
+/*!
+ * @brief Reads the current timer counting value.
+ *
+ * This function returns the real-time timer counting value, in a range from 0 to a
+ * timer period.
+ *
+ * @note User can call the utility macros provided in fsl_common.h to convert ticks to usec or msec
+ *
+ * @param base LPTMR peripheral base address
+ *
+ * @return Current counter value in ticks
+ */
+static inline uint16_t LPTMR_GetCurrentTimerCount(LPTMR_Type *base)
+{
+ /* Must first write any value to the CNR. This synchronizes and registers the current value
+ * of the CNR into a temporary register which can then be read
+ */
+ base->CNR = 0U;
+ return (uint16_t)base->CNR;
+}
+
+/*! @}*/
+
+/*!
+ * @name Timer Start and Stop
+ * @{
+ */
+
+/*!
+ * @brief Starts the timer counting.
+ *
+ * After calling this function, the timer counts up to the CMR register value.
+ * Each time the timer reaches CMR value and then increments, it generates a
+ * trigger pulse and sets the timeout interrupt flag. An interrupt is also
+ * triggered if the timer interrupt is enabled.
+ *
+ * @param base LPTMR peripheral base address
+ */
+static inline void LPTMR_StartTimer(LPTMR_Type *base)
+{
+ uint32_t reg = base->CSR;
+
+ /* Clear the TCF bit so that we don't clear this w1c bit when writing back */
+ reg &= ~(LPTMR_CSR_TCF_MASK);
+ reg |= LPTMR_CSR_TEN_MASK;
+ base->CSR = reg;
+}
+
+/*!
+ * @brief Stops the timer counting.
+ *
+ * This function stops the timer counting and resets the timer's counter register
+ *
+ * @param base LPTMR peripheral base address
+ */
+static inline void LPTMR_StopTimer(LPTMR_Type *base)
+{
+ uint32_t reg = base->CSR;
+
+ /* Clear the TCF bit so that we don't clear this w1c bit when writing back */
+ reg &= ~(LPTMR_CSR_TCF_MASK);
+ reg &= ~LPTMR_CSR_TEN_MASK;
+ base->CSR = reg;
+}
+
+/*! @}*/
+
+#if defined(__cplusplus)
+}
+#endif
+
+/*! @}*/
+
+#endif /* _FSL_LPTMR_H_ */
diff --git a/drivers/fsl_mpu.c b/drivers/fsl_mpu.c
new file mode 100644
index 0000000..8e0e77d
--- /dev/null
+++ b/drivers/fsl_mpu.c
@@ -0,0 +1,239 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_mpu.h"
+
+/*******************************************************************************
+ * Variables
+ ******************************************************************************/
+
+const clock_ip_name_t g_mpuClock[FSL_FEATURE_SOC_MPU_COUNT] = MPU_CLOCKS;
+
+/*******************************************************************************
+ * Codes
+ ******************************************************************************/
+
+void MPU_Init(MPU_Type *base, const mpu_config_t *config)
+{
+ assert(config);
+ uint8_t count;
+
+ /* Un-gate MPU clock */
+ CLOCK_EnableClock(g_mpuClock[0]);
+
+ /* Initializes the regions. */
+ for (count = 1; count < FSL_FEATURE_MPU_DESCRIPTOR_COUNT; count++)
+ {
+ base->WORD[count][3] = 0; /* VLD/VID+PID. */
+ base->WORD[count][0] = 0; /* Start address. */
+ base->WORD[count][1] = 0; /* End address. */
+ base->WORD[count][2] = 0; /* Access rights. */
+ base->RGDAAC[count] = 0; /* Alternate access rights. */
+ }
+
+ /* MPU configure. */
+ while (config)
+ {
+ MPU_SetRegionConfig(base, &(config->regionConfig));
+ config = config->next;
+ }
+ /* Enable MPU. */
+ MPU_Enable(base, true);
+}
+
+void MPU_Deinit(MPU_Type *base)
+{
+ /* Disable MPU. */
+ MPU_Enable(base, false);
+
+ /* Gate the clock. */
+ CLOCK_DisableClock(g_mpuClock[0]);
+}
+
+void MPU_GetHardwareInfo(MPU_Type *base, mpu_hardware_info_t *hardwareInform)
+{
+ assert(hardwareInform);
+
+ uint32_t cesReg = base->CESR;
+
+ hardwareInform->hardwareRevisionLevel = (cesReg & MPU_CESR_HRL_MASK) >> MPU_CESR_HRL_SHIFT;
+ hardwareInform->slavePortsNumbers = (cesReg & MPU_CESR_NSP_MASK) >> MPU_CESR_NSP_SHIFT;
+ hardwareInform->regionsNumbers = (mpu_region_total_num_t)((cesReg & MPU_CESR_NRGD_MASK) >> MPU_CESR_NRGD_SHIFT);
+}
+
+void MPU_SetRegionConfig(MPU_Type *base, const mpu_region_config_t *regionConfig)
+{
+ assert(regionConfig);
+ assert(regionConfig->regionNum < FSL_FEATURE_MPU_DESCRIPTOR_COUNT);
+
+ uint32_t wordReg = 0;
+ uint8_t msPortNum;
+ uint8_t regNumber = regionConfig->regionNum;
+
+ /* The start and end address of the region descriptor. */
+ base->WORD[regNumber][0] = regionConfig->startAddress;
+ base->WORD[regNumber][1] = regionConfig->endAddress;
+
+ /* Set the privilege rights for master 0 ~ master 3. */
+ for (msPortNum = 0; msPortNum <= FSL_FEATURE_MPU_PRIVILEGED_RIGHTS_MASTER_MAX_INDEX; msPortNum++)
+ {
+ wordReg |= MPU_REGION_RWXRIGHTS_MASTER(
+ msPortNum, (((uint32_t)regionConfig->accessRights1[msPortNum].superAccessRights << 3U) |
+ (uint32_t)regionConfig->accessRights1[msPortNum].userAccessRights));
+
+#if FSL_FEATURE_MPU_HAS_PROCESS_IDENTIFIER
+ wordReg |=
+ MPU_REGION_RWXRIGHTS_MASTER_PE(msPortNum, regionConfig->accessRights1[msPortNum].processIdentifierEnable);
+#endif /* FSL_FEATURE_MPU_HAS_PROCESS_IDENTIFIER */
+ }
+
+ /* Set the normal read write rights for master 4 ~ master 7. */
+ for (msPortNum = FSL_FEATURE_MPU_PRIVILEGED_RIGHTS_MASTER_COUNT; msPortNum < FSL_FEATURE_MPU_MASTER_COUNT;
+ msPortNum++)
+ {
+ wordReg |= MPU_REGION_RWRIGHTS_MASTER(msPortNum,
+ ((uint32_t)regionConfig->accessRights2[msPortNum - FSL_FEATURE_MPU_PRIVILEGED_RIGHTS_MASTER_COUNT].readEnable << 1U |
+ (uint32_t)regionConfig->accessRights2[msPortNum - FSL_FEATURE_MPU_PRIVILEGED_RIGHTS_MASTER_COUNT].writeEnable));
+ }
+
+ /* Set region descriptor access rights. */
+ base->WORD[regNumber][2] = wordReg;
+
+ wordReg = MPU_WORD_VLD(1);
+#if FSL_FEATURE_MPU_HAS_PROCESS_IDENTIFIER
+ wordReg |= MPU_WORD_PID(regionConfig->processIdentifier) | MPU_WORD_PIDMASK(regionConfig->processIdMask);
+#endif /* FSL_FEATURE_MPU_HAS_PROCESS_IDENTIFIER */
+
+ base->WORD[regNumber][3] = wordReg;
+}
+
+void MPU_SetRegionAddr(MPU_Type *base, uint32_t regionNum, uint32_t startAddr, uint32_t endAddr)
+{
+ assert(regionNum < FSL_FEATURE_MPU_DESCRIPTOR_COUNT);
+
+ base->WORD[regionNum][0] = startAddr;
+ base->WORD[regionNum][1] = endAddr;
+}
+
+void MPU_SetRegionRwxMasterAccessRights(MPU_Type *base,
+ uint32_t regionNum,
+ uint32_t masterNum,
+ const mpu_rwxrights_master_access_control_t *accessRights)
+{
+ assert(accessRights);
+ assert(regionNum < FSL_FEATURE_MPU_DESCRIPTOR_COUNT);
+ assert(masterNum <= FSL_FEATURE_MPU_PRIVILEGED_RIGHTS_MASTER_MAX_INDEX);
+
+ uint32_t mask = MPU_REGION_RWXRIGHTS_MASTER_MASK(masterNum);
+ uint32_t right = base->RGDAAC[regionNum];
+
+#if FSL_FEATURE_MPU_HAS_PROCESS_IDENTIFIER
+ mask |= MPU_REGION_RWXRIGHTS_MASTER_PE_MASK(masterNum);
+#endif
+
+ /* Build rights control value. */
+ right &= ~mask;
+ right |= MPU_REGION_RWXRIGHTS_MASTER(
+ masterNum, ((uint32_t)(accessRights->superAccessRights << 3U) | accessRights->userAccessRights));
+#if FSL_FEATURE_MPU_HAS_PROCESS_IDENTIFIER
+ right |= MPU_REGION_RWXRIGHTS_MASTER_PE(masterNum, accessRights->processIdentifierEnable);
+#endif /* FSL_FEATURE_MPU_HAS_PROCESS_IDENTIFIER */
+
+ /* Set low master region access rights. */
+ base->RGDAAC[regionNum] = right;
+}
+
+void MPU_SetRegionRwMasterAccessRights(MPU_Type *base,
+ uint32_t regionNum,
+ uint32_t masterNum,
+ const mpu_rwrights_master_access_control_t *accessRights)
+{
+ assert(accessRights);
+ assert(regionNum < FSL_FEATURE_MPU_DESCRIPTOR_COUNT);
+ assert(masterNum > FSL_FEATURE_MPU_PRIVILEGED_RIGHTS_MASTER_MAX_INDEX);
+ assert(masterNum <= FSL_FEATURE_MPU_MASTER_MAX_INDEX);
+
+ uint32_t mask = MPU_REGION_RWRIGHTS_MASTER_MASK(masterNum);
+ uint32_t right = base->RGDAAC[regionNum];
+
+ /* Build rights control value. */
+ right &= ~mask;
+ right |=
+ MPU_REGION_RWRIGHTS_MASTER(masterNum, (((uint32_t)accessRights->readEnable << 1U) | accessRights->writeEnable));
+ /* Set low master region access rights. */
+ base->RGDAAC[regionNum] = right;
+}
+
+bool MPU_GetSlavePortErrorStatus(MPU_Type *base, mpu_slave_t slaveNum)
+{
+ uint8_t sperr;
+
+ sperr = ((base->CESR & MPU_CESR_SPERR_MASK) >> MPU_CESR_SPERR_SHIFT) & (0x1U << slaveNum);
+
+ return (sperr != 0) ? true : false;
+}
+
+void MPU_GetDetailErrorAccessInfo(MPU_Type *base, mpu_slave_t slaveNum, mpu_access_err_info_t *errInform)
+{
+ assert(errInform);
+
+ uint16_t value;
+ uint32_t cesReg;
+
+ /* Error address. */
+ errInform->address = base->SP[slaveNum].EAR;
+
+ /* Error detail information. */
+ value = (base->SP[slaveNum].EDR & MPU_EDR_EACD_MASK) >> MPU_EDR_EACD_SHIFT;
+ if (!value)
+ {
+ errInform->accessControl = kMPU_NoRegionHit;
+ }
+ else if (!(value & (uint16_t)(value - 1)))
+ {
+ errInform->accessControl = kMPU_NoneOverlappRegion;
+ }
+ else
+ {
+ errInform->accessControl = kMPU_OverlappRegion;
+ }
+
+ value = base->SP[slaveNum].EDR;
+ errInform->master = (uint32_t)((value & MPU_EDR_EMN_MASK) >> MPU_EDR_EMN_SHIFT);
+ errInform->attributes = (mpu_err_attributes_t)((value & MPU_EDR_EATTR_MASK) >> MPU_EDR_EATTR_SHIFT);
+ errInform->accessType = (mpu_err_access_type_t)((value & MPU_EDR_ERW_MASK) >> MPU_EDR_ERW_SHIFT);
+#if FSL_FEATURE_MPU_HAS_PROCESS_IDENTIFIER
+ errInform->processorIdentification = (uint8_t)((value & MPU_EDR_EPID_MASK) >> MPU_EDR_EPID_SHIFT);
+#endif
+
+ /* Clears error slave port bit. */
+ cesReg = (base->CESR & ~MPU_CESR_SPERR_MASK) | ((0x1U << slaveNum) << MPU_CESR_SPERR_SHIFT);
+ base->CESR = cesReg;
+}
diff --git a/drivers/fsl_mpu.h b/drivers/fsl_mpu.h
new file mode 100644
index 0000000..d39d78a
--- /dev/null
+++ b/drivers/fsl_mpu.h
@@ -0,0 +1,422 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_MPU_H_
+#define _FSL_MPU_H_
+
+#include "fsl_common.h"
+
+/*!
+ * @addtogroup mpu
+ * @{
+ */
+
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+/*! @name Driver version */
+/*@{*/
+/*! @brief MPU driver version 2.1.0. */
+#define FSL_MPU_DRIVER_VERSION (MAKE_VERSION(2, 1, 0))
+/*@}*/
+
+/*! @brief MPU the bit shift for masters with privilege rights: read write and execute. */
+#define MPU_REGION_RWXRIGHTS_MASTER_SHIFT(n) (n * 6)
+
+/*! @brief MPU masters with read, write and execute rights bit mask. */
+#define MPU_REGION_RWXRIGHTS_MASTER_MASK(n) (0x1Fu << MPU_REGION_RWXRIGHTS_MASTER_SHIFT(n))
+
+/*! @brief MPU masters with read, write and execute rights bit width. */
+#define MPU_REGION_RWXRIGHTS_MASTER_WIDTH 5
+
+/*! @brief MPU masters with read, write and execute rights priority setting. */
+#define MPU_REGION_RWXRIGHTS_MASTER(n, x) \
+ (((uint32_t)(((uint32_t)(x)) << MPU_REGION_RWXRIGHTS_MASTER_SHIFT(n))) & MPU_REGION_RWXRIGHTS_MASTER_MASK(n))
+
+/*! @brief MPU masters with read, write and execute rights process enable bit shift. */
+#define MPU_REGION_RWXRIGHTS_MASTER_PE_SHIFT(n) (n * 6 + MPU_REGION_RWXRIGHTS_MASTER_WIDTH)
+
+/*! @brief MPU masters with read, write and execute rights process enable bit mask. */
+#define MPU_REGION_RWXRIGHTS_MASTER_PE_MASK(n) (0x1u << MPU_REGION_RWXRIGHTS_MASTER_PE_SHIFT(n))
+
+/*! @brief MPU masters with read, write and execute rights process enable setting. */
+#define MPU_REGION_RWXRIGHTS_MASTER_PE(n, x) \
+ (((uint32_t)(((uint32_t)(x)) << MPU_REGION_RWXRIGHTS_MASTER_PE_SHIFT(n))) & MPU_REGION_RWXRIGHTS_MASTER_PE_MASK(n))
+
+/*! @brief MPU masters with normal read write permission bit shift. */
+#define MPU_REGION_RWRIGHTS_MASTER_SHIFT(n) ((n - FSL_FEATURE_MPU_PRIVILEGED_RIGHTS_MASTER_COUNT) * 2 + 24)
+
+/*! @brief MPU masters with normal read write rights bit mask. */
+#define MPU_REGION_RWRIGHTS_MASTER_MASK(n) (0x3u << MPU_REGION_RWRIGHTS_MASTER_SHIFT(n))
+
+/*! @brief MPU masters with normal read write rights priority setting. */
+#define MPU_REGION_RWRIGHTS_MASTER(n, x) \
+ (((uint32_t)(((uint32_t)(x)) << MPU_REGION_RWRIGHTS_MASTER_SHIFT(n))) & MPU_REGION_RWRIGHTS_MASTER_MASK(n))
+
+/*! @brief Describes the number of MPU regions. */
+typedef enum _mpu_region_total_num
+{
+ kMPU_8Regions = 0x0U, /*!< MPU supports 8 regions. */
+ kMPU_12Regions = 0x1U, /*!< MPU supports 12 regions. */
+ kMPU_16Regions = 0x2U /*!< MPU supports 16 regions. */
+} mpu_region_total_num_t;
+
+/*! @brief MPU slave port number. */
+typedef enum _mpu_slave
+{
+ kMPU_Slave0 = 4U, /*!< MPU slave port 0. */
+ kMPU_Slave1 = 3U, /*!< MPU slave port 1. */
+ kMPU_Slave2 = 2U, /*!< MPU slave port 2. */
+ kMPU_Slave3 = 1U, /*!< MPU slave port 3. */
+ kMPU_Slave4 = 0U /*!< MPU slave port 4. */
+} mpu_slave_t;
+
+/*! @brief MPU error access control detail. */
+typedef enum _mpu_err_access_control
+{
+ kMPU_NoRegionHit = 0U, /*!< No region hit error. */
+ kMPU_NoneOverlappRegion = 1U, /*!< Access single region error. */
+ kMPU_OverlappRegion = 2U /*!< Access overlapping region error. */
+} mpu_err_access_control_t;
+
+/*! @brief MPU error access type. */
+typedef enum _mpu_err_access_type
+{
+ kMPU_ErrTypeRead = 0U, /*!< MPU error access type --- read. */
+ kMPU_ErrTypeWrite = 1U /*!< MPU error access type --- write. */
+} mpu_err_access_type_t;
+
+/*! @brief MPU access error attributes.*/
+typedef enum _mpu_err_attributes
+{
+ kMPU_InstructionAccessInUserMode = 0U, /*!< Access instruction error in user mode. */
+ kMPU_DataAccessInUserMode = 1U, /*!< Access data error in user mode. */
+ kMPU_InstructionAccessInSupervisorMode = 2U, /*!< Access instruction error in supervisor mode. */
+ kMPU_DataAccessInSupervisorMode = 3U /*!< Access data error in supervisor mode. */
+} mpu_err_attributes_t;
+
+/*! @brief MPU access rights in supervisor mode for bus master 0 ~ 3. */
+typedef enum _mpu_supervisor_access_rights
+{
+ kMPU_SupervisorReadWriteExecute = 0U, /*!< Read write and execute operations are allowed in supervisor mode. */
+ kMPU_SupervisorReadExecute = 1U, /*!< Read and execute operations are allowed in supervisor mode. */
+ kMPU_SupervisorReadWrite = 2U, /*!< Read write operations are allowed in supervisor mode. */
+ kMPU_SupervisorEqualToUsermode = 3U /*!< Access permission equal to user mode. */
+} mpu_supervisor_access_rights_t;
+
+/*! @brief MPU access rights in user mode for bus master 0 ~ 3. */
+typedef enum _mpu_user_access_rights
+{
+ kMPU_UserNoAccessRights = 0U, /*!< No access allowed in user mode. */
+ kMPU_UserExecute = 1U, /*!< Execute operation is allowed in user mode. */
+ kMPU_UserWrite = 2U, /*!< Write operation is allowed in user mode. */
+ kMPU_UserWriteExecute = 3U, /*!< Write and execute operations are allowed in user mode. */
+ kMPU_UserRead = 4U, /*!< Read is allowed in user mode. */
+ kMPU_UserReadExecute = 5U, /*!< Read and execute operations are allowed in user mode. */
+ kMPU_UserReadWrite = 6U, /*!< Read and write operations are allowed in user mode. */
+ kMPU_UserReadWriteExecute = 7U /*!< Read write and execute operations are allowed in user mode. */
+} mpu_user_access_rights_t;
+
+/*! @brief MPU hardware basic information. */
+typedef struct _mpu_hardware_info
+{
+ uint8_t hardwareRevisionLevel; /*!< Specifies the MPU's hardware and definition reversion level. */
+ uint8_t slavePortsNumbers; /*!< Specifies the number of slave ports connected to MPU. */
+ mpu_region_total_num_t regionsNumbers; /*!< Indicates the number of region descriptors implemented. */
+} mpu_hardware_info_t;
+
+/*! @brief MPU detail error access information. */
+typedef struct _mpu_access_err_info
+{
+ uint32_t master; /*!< Access error master. */
+ mpu_err_attributes_t attributes; /*!< Access error attributes. */
+ mpu_err_access_type_t accessType; /*!< Access error type. */
+ mpu_err_access_control_t accessControl; /*!< Access error control. */
+ uint32_t address; /*!< Access error address. */
+#if FSL_FEATURE_MPU_HAS_PROCESS_IDENTIFIER
+ uint8_t processorIdentification; /*!< Access error processor identification. */
+#endif /* FSL_FEATURE_MPU_HAS_PROCESS_IDENTIFIER */
+} mpu_access_err_info_t;
+
+/*! @brief MPU read/write/execute rights control for bus master 0 ~ 3. */
+typedef struct _mpu_rwxrights_master_access_control
+{
+ mpu_supervisor_access_rights_t superAccessRights; /*!< Master access rights in supervisor mode. */
+ mpu_user_access_rights_t userAccessRights; /*!< Master access rights in user mode. */
+#if FSL_FEATURE_MPU_HAS_PROCESS_IDENTIFIER
+ bool processIdentifierEnable; /*!< Enables or disables process identifier. */
+#endif /* FSL_FEATURE_MPU_HAS_PROCESS_IDENTIFIER */
+} mpu_rwxrights_master_access_control_t;
+
+/*! @brief MPU read/write access control for bus master 4 ~ 7. */
+typedef struct _mpu_rwrights_master_access_control
+{
+ bool writeEnable; /*!< Enables or disables write permission. */
+ bool readEnable; /*!< Enables or disables read permission. */
+} mpu_rwrights_master_access_control_t;
+
+/*!
+ * @brief MPU region configuration structure.
+ *
+ * This structure is used to configure the regionNum region.
+ * The accessRights1[0] ~ accessRights1[3] are used to configure the bus master
+ * 0 ~ 3 with the privilege rights setting. The accessRights2[0] ~ accessRights2[3]
+ * are used to configure the high master 4 ~ 7 with the normal read write permission.
+ * The master port assignment is the chip configuration. Normally, the core is the
+ * master 0, debugger is the master 1.
+ * Note: MPU assigns a priority scheme where the debugger is treated as the highest
+ * priority master followed by the core and then all the remaining masters.
+ * MPU protection does not allow writes from the core to affect the "regionNum 0" start
+ * and end address nor the permissions associated with the debugger. It can only write
+ * the permission fields associated with the other masters. This protection guarantee
+ * the debugger always has access to the entire address space and those rights can't
+ * be changed by the core or any other bus master. Prepare
+ * the region configuration when regionNum is 0.
+ */
+typedef struct _mpu_region_config
+{
+ uint32_t regionNum; /*!< MPU region number, range form 0 ~ FSL_FEATURE_MPU_DESCRIPTOR_COUNT - 1. */
+ uint32_t startAddress; /*!< Memory region start address. Note: bit0 ~ bit4 always be marked as 0 by MPU. The actual
+ start address is 0-modulo-32 byte address. */
+ uint32_t endAddress; /*!< Memory region end address. Note: bit0 ~ bit4 always be marked as 1 by MPU. The actual end
+ address is 31-modulo-32 byte address. */
+ mpu_rwxrights_master_access_control_t accessRights1[4]; /*!< Masters with read, write and execute rights setting. */
+ mpu_rwrights_master_access_control_t accessRights2[4]; /*!< Masters with normal read write rights setting. */
+#if FSL_FEATURE_MPU_HAS_PROCESS_IDENTIFIER
+ uint8_t processIdentifier; /*!< Process identifier used when "processIdentifierEnable" set with true. */
+ uint8_t
+ processIdMask; /*!< Process identifier mask. The setting bit will ignore the same bit in process identifier. */
+#endif /* FSL_FEATURE_MPU_HAS_PROCESS_IDENTIFIER */
+} mpu_region_config_t;
+
+/*!
+ * @brief The configuration structure for the MPU initialization.
+ *
+ * This structure is used when calling the MPU_Init function.
+ */
+typedef struct _mpu_config
+{
+ mpu_region_config_t regionConfig; /*!< region access permission. */
+ struct _mpu_config *next; /*!< pointer to the next structure. */
+} mpu_config_t;
+
+/*******************************************************************************
+ * API
+ ******************************************************************************/
+
+#if defined(__cplusplus)
+extern "C" {
+#endif /* _cplusplus */
+
+/*!
+ * @name Initialization and deinitialization
+ * @{
+ */
+
+/*!
+ * @brief Initializes the MPU with the user configuration structure.
+ *
+ * This function configures the MPU module with the user-defined configuration.
+ *
+ * @param base MPU peripheral base address.
+ * @param config The pointer to the configuration structure.
+ */
+void MPU_Init(MPU_Type *base, const mpu_config_t *config);
+
+/*!
+ * @brief Deinitializes the MPU regions.
+ *
+ * @param base MPU peripheral base address.
+ */
+void MPU_Deinit(MPU_Type *base);
+
+/* @}*/
+
+/*!
+ * @name Basic Control Operations
+ * @{
+ */
+
+/*!
+ * @brief Enables/disables the MPU globally.
+ *
+ * Call this API to enable or disable the MPU module.
+ *
+ * @param base MPU peripheral base address.
+ * @param enable True enable MPU, false disable MPU.
+ */
+static inline void MPU_Enable(MPU_Type *base, bool enable)
+{
+ if (enable)
+ {
+ /* Enable the MPU globally. */
+ base->CESR |= MPU_CESR_VLD_MASK;
+ }
+ else
+ { /* Disable the MPU globally. */
+ base->CESR &= ~MPU_CESR_VLD_MASK;
+ }
+}
+
+/*!
+ * @brief Enables/disables the MPU for a special region.
+ *
+ * When MPU is enabled, call this API to disable an unused region
+ * of an enabled MPU. Call this API to minimize the power dissipation.
+ *
+ * @param base MPU peripheral base address.
+ * @param number MPU region number.
+ * @param enable True enable the special region MPU, false disable the special region MPU.
+ */
+static inline void MPU_RegionEnable(MPU_Type *base, uint32_t number, bool enable)
+{
+ if (enable)
+ {
+ /* Enable the #number region MPU. */
+ base->WORD[number][3] |= MPU_WORD_VLD_MASK;
+ }
+ else
+ { /* Disable the #number region MPU. */
+ base->WORD[number][3] &= ~MPU_WORD_VLD_MASK;
+ }
+}
+
+/*!
+ * @brief Gets the MPU basic hardware information.
+ *
+ * @param base MPU peripheral base address.
+ * @param hardwareInform The pointer to the MPU hardware information structure. See "mpu_hardware_info_t".
+ */
+void MPU_GetHardwareInfo(MPU_Type *base, mpu_hardware_info_t *hardwareInform);
+
+/*!
+ * @brief Sets the MPU region.
+ *
+ * Note: Due to the MPU protection, the Region number 0 does not allow writes from
+ * core to affect the start and end address nor the permissions associated with
+ * the debugger. It can only write the permission fields associated
+ * with the other masters.
+ *
+ * @param base MPU peripheral base address.
+ * @param regionConfig The pointer to the MPU user configuration structure. See "mpu_region_config_t".
+ */
+void MPU_SetRegionConfig(MPU_Type *base, const mpu_region_config_t *regionConfig);
+
+/*!
+ * @brief Sets the region start and end address.
+ *
+ * Memory region start address. Note: bit0 ~ bit4 is always marked as 0 by MPU.
+ * The actual start address by MPU is 0-modulo-32 byte address.
+ * Memory region end address. Note: bit0 ~ bit4 always be marked as 1 by MPU.
+ * The actual end address used by MPU is 31-modulo-32 byte address.
+ * Note: Due to the MPU protection, the startAddr and endAddr can't be
+ * changed by the core when regionNum is 0.
+ *
+ * @param base MPU peripheral base address.
+ * @param regionNum MPU region number. The range is from 0 to
+ * FSL_FEATURE_MPU_DESCRIPTOR_COUNT - 1.
+ * @param startAddr Region start address.
+ * @param endAddr Region end address.
+ */
+void MPU_SetRegionAddr(MPU_Type *base, uint32_t regionNum, uint32_t startAddr, uint32_t endAddr);
+
+/*!
+ * @brief Sets the MPU region access rights for masters with read, write and execute rights.
+ * The MPU access rights depend on two board classifications of bus masters.
+ * The privilege rights masters and the normal rights masters.
+ * The privilege rights masters have the read, write and execute access rights.
+ * So except the normal read and write rights, the execute rights is also
+ * allowed for these masters. The privilege rights masters are normally range from
+ * bus masters 0 - 3. However, the maximum master number is device-specific.
+ * See the "FSL_FEATURE_MPU_PRIVILEGED_RIGHTS_MASTER_MAX_INDEX".
+ * The normal rights masters access rights control see
+ * "MPU_SetRegionRwMasterAccessRights()".
+ *
+ * @param base MPU peripheral base address.
+ * @param regionNum MPU region number. Should range from 0 to
+ * FSL_FEATURE_MPU_DESCRIPTOR_COUNT - 1.
+ * @param masterNum MPU bus master number. Should range from 0 to
+ * FSL_FEATURE_MPU_PRIVILEGED_RIGHTS_MASTER_MAX_INDEX.
+ * @param accessRights The pointer to the MPU access rights configuration. See "mpu_rwxrights_master_access_control_t".
+ */
+void MPU_SetRegionRwxMasterAccessRights(MPU_Type *base,
+ uint32_t regionNum,
+ uint32_t masterNum,
+ const mpu_rwxrights_master_access_control_t *accessRights);
+
+/*!
+ * @brief Sets the MPU region access rights for masters with read and write rights.
+ * The MPU access rights depend on two board classifications of bus masters.
+ * The privilege rights masters and the normal rights masters.
+ * The normal rights masters only have the read and write access permissions.
+ * The privilege rights access control see "MPU_SetRegionRwxMasterAccessRights".
+ *
+ * @param base MPU peripheral base address.
+ * @param regionNum MPU region number. The range is from 0 to
+ * FSL_FEATURE_MPU_DESCRIPTOR_COUNT - 1.
+ * @param masterNum MPU bus master number. Should range from FSL_FEATURE_MPU_PRIVILEGED_RIGHTS_MASTER_COUNT
+ * to ~ FSL_FEATURE_MPU_MASTER_MAX_INDEX.
+ * @param accessRights The pointer to the MPU access rights configuration. See "mpu_rwrights_master_access_control_t".
+ */
+void MPU_SetRegionRwMasterAccessRights(MPU_Type *base,
+ uint32_t regionNum,
+ uint32_t masterNum,
+ const mpu_rwrights_master_access_control_t *accessRights);
+
+/*!
+ * @brief Gets the numbers of slave ports where errors occur.
+ *
+ * @param base MPU peripheral base address.
+ * @param slaveNum MPU slave port number.
+ * @return The slave ports error status.
+ * true - error happens in this slave port.
+ * false - error didn't happen in this slave port.
+ */
+bool MPU_GetSlavePortErrorStatus(MPU_Type *base, mpu_slave_t slaveNum);
+
+/*!
+ * @brief Gets the MPU detailed error access information.
+ *
+ * @param base MPU peripheral base address.
+ * @param slaveNum MPU slave port number.
+ * @param errInform The pointer to the MPU access error information. See "mpu_access_err_info_t".
+ */
+void MPU_GetDetailErrorAccessInfo(MPU_Type *base, mpu_slave_t slaveNum, mpu_access_err_info_t *errInform);
+
+/* @} */
+
+#if defined(__cplusplus)
+}
+#endif
+
+/*! @}*/
+
+#endif /* _FSL_MPU_H_ */
diff --git a/drivers/fsl_pdb.c b/drivers/fsl_pdb.c
new file mode 100644
index 0000000..dcc03ba
--- /dev/null
+++ b/drivers/fsl_pdb.c
@@ -0,0 +1,135 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_pdb.h"
+
+/*******************************************************************************
+ * Prototypes
+ ******************************************************************************/
+/*!
+ * @brief Get instance number for PDB module.
+ *
+ * @param base PDB peripheral base address
+ */
+static uint32_t PDB_GetInstance(PDB_Type *base);
+
+/*******************************************************************************
+ * Variables
+ ******************************************************************************/
+/*! @brief Pointers to PDB bases for each instance. */
+static PDB_Type *const s_pdbBases[] = PDB_BASE_PTRS;
+/*! @brief Pointers to PDB clocks for each instance. */
+static const clock_ip_name_t s_pdbClocks[] = PDB_CLOCKS;
+
+/*******************************************************************************
+ * Codes
+ ******************************************************************************/
+static uint32_t PDB_GetInstance(PDB_Type *base)
+{
+ uint32_t instance;
+
+ /* Find the instance index from base address mappings. */
+ for (instance = 0; instance < FSL_FEATURE_SOC_PDB_COUNT; instance++)
+ {
+ if (s_pdbBases[instance] == base)
+ {
+ break;
+ }
+ }
+
+ assert(instance < FSL_FEATURE_SOC_PDB_COUNT);
+
+ return instance;
+}
+
+void PDB_Init(PDB_Type *base, const pdb_config_t *config)
+{
+ assert(NULL != config);
+
+ uint32_t tmp32;
+
+ /* Enable the clock. */
+ CLOCK_EnableClock(s_pdbClocks[PDB_GetInstance(base)]);
+
+ /* Configure. */
+ /* PDBx_SC. */
+ tmp32 = base->SC &
+ ~(PDB_SC_LDMOD_MASK | PDB_SC_PRESCALER_MASK | PDB_SC_TRGSEL_MASK | PDB_SC_MULT_MASK | PDB_SC_CONT_MASK);
+
+ tmp32 |= PDB_SC_LDMOD(config->loadValueMode) | PDB_SC_PRESCALER(config->prescalerDivider) |
+ PDB_SC_TRGSEL(config->triggerInputSource) | PDB_SC_MULT(config->dividerMultiplicationFactor);
+ if (config->enableContinuousMode)
+ {
+ tmp32 |= PDB_SC_CONT_MASK;
+ }
+ base->SC = tmp32;
+
+ PDB_Enable(base, true); /* Enable the PDB module. */
+}
+
+void PDB_Deinit(PDB_Type *base)
+{
+ PDB_Enable(base, false); /* Disable the PDB module. */
+
+ /* Disable the clock. */
+ CLOCK_DisableClock(s_pdbClocks[PDB_GetInstance(base)]);
+}
+
+void PDB_GetDefaultConfig(pdb_config_t *config)
+{
+ assert(NULL != config);
+
+ config->loadValueMode = kPDB_LoadValueImmediately;
+ config->prescalerDivider = kPDB_PrescalerDivider1;
+ config->dividerMultiplicationFactor = kPDB_DividerMultiplicationFactor1;
+ config->triggerInputSource = kPDB_TriggerSoftware;
+ config->enableContinuousMode = false;
+}
+
+#if defined(FSL_FEATURE_PDB_HAS_DAC) && FSL_FEATURE_PDB_HAS_DAC
+void PDB_SetDACTriggerConfig(PDB_Type *base, uint32_t channel, pdb_dac_trigger_config_t *config)
+{
+ assert(channel < PDB_INTC_COUNT);
+ assert(NULL != config);
+
+ uint32_t tmp32 = 0U;
+
+ /* PDBx_DACINTC. */
+ if (config->enableExternalTriggerInput)
+ {
+ tmp32 |= PDB_INTC_EXT_MASK;
+ }
+ if (config->enableIntervalTrigger)
+ {
+ tmp32 |= PDB_INTC_TOE_MASK;
+ }
+ base->DAC[channel].INTC = tmp32;
+}
+#endif /* FSL_FEATURE_PDB_HAS_DAC */
diff --git a/drivers/fsl_pdb.h b/drivers/fsl_pdb.h
new file mode 100644
index 0000000..5fed10a
--- /dev/null
+++ b/drivers/fsl_pdb.h
@@ -0,0 +1,575 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_PDB_H_
+#define _FSL_PDB_H_
+
+#include "fsl_common.h"
+
+/*!
+ * @addtogroup pdb
+ * @{
+ */
+
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+/*! @name Driver version */
+/*@{*/
+/*! @brief PDB driver version 2.0.1. */
+#define FSL_PDB_DRIVER_VERSION (MAKE_VERSION(2, 0, 1))
+/*@}*/
+
+/*!
+ * @brief PDB flags.
+ */
+enum _pdb_status_flags
+{
+ kPDB_LoadOKFlag = PDB_SC_LDOK_MASK, /*!< This flag is automatically cleared when the values in buffers are
+ loaded into the internal registers after the LDOK bit is set or the
+ PDBEN is cleared. */
+ kPDB_DelayEventFlag = PDB_SC_PDBIF_MASK, /*!< PDB timer delay event flag. */
+};
+
+/*!
+ * @brief PDB ADC PreTrigger channel flags.
+ */
+enum _pdb_adc_pretrigger_flags
+{
+ /* PDB PreTrigger channel match flags. */
+ kPDB_ADCPreTriggerChannel0Flag = PDB_S_CF(1U << 0), /*!< Pre-Trigger 0 flag. */
+ kPDB_ADCPreTriggerChannel1Flag = PDB_S_CF(1U << 1), /*!< Pre-Trigger 1 flag. */
+#if (PDB_DLY_COUNT > 2)
+ kPDB_ADCPreTriggerChannel2Flag = PDB_S_CF(1U << 2), /*!< Pre-Trigger 2 flag. */
+ kPDB_ADCPreTriggerChannel3Flag = PDB_S_CF(1U << 3), /*!< Pre-Trigger 3 flag. */
+#endif /* PDB_DLY_COUNT > 2 */
+#if (PDB_DLY_COUNT > 4)
+ kPDB_ADCPreTriggerChannel4Flag = PDB_S_CF(1U << 4), /*!< Pre-Trigger 4 flag. */
+ kPDB_ADCPreTriggerChannel5Flag = PDB_S_CF(1U << 5), /*!< Pre-Trigger 5 flag. */
+ kPDB_ADCPreTriggerChannel6Flag = PDB_S_CF(1U << 6), /*!< Pre-Trigger 6 flag. */
+ kPDB_ADCPreTriggerChannel7Flag = PDB_S_CF(1U << 7), /*!< Pre-Trigger 7 flag. */
+#endif /* PDB_DLY_COUNT > 4 */
+
+ /* PDB PreTrigger channel error flags. */
+ kPDB_ADCPreTriggerChannel0ErrorFlag = PDB_S_ERR(1U << 0), /*!< Pre-Trigger 0 Error. */
+ kPDB_ADCPreTriggerChannel1ErrorFlag = PDB_S_ERR(1U << 1), /*!< Pre-Trigger 1 Error. */
+#if (PDB_DLY_COUNT > 2)
+ kPDB_ADCPreTriggerChannel2ErrorFlag = PDB_S_ERR(1U << 2), /*!< Pre-Trigger 2 Error. */
+ kPDB_ADCPreTriggerChannel3ErrorFlag = PDB_S_ERR(1U << 3), /*!< Pre-Trigger 3 Error. */
+#endif /* PDB_DLY_COUNT > 2 */
+#if (PDB_DLY_COUNT > 4)
+ kPDB_ADCPreTriggerChannel4ErrorFlag = PDB_S_ERR(1U << 4), /*!< Pre-Trigger 4 Error. */
+ kPDB_ADCPreTriggerChannel5ErrorFlag = PDB_S_ERR(1U << 5), /*!< Pre-Trigger 5 Error. */
+ kPDB_ADCPreTriggerChannel6ErrorFlag = PDB_S_ERR(1U << 6), /*!< Pre-Trigger 6 Error. */
+ kPDB_ADCPreTriggerChannel7ErrorFlag = PDB_S_ERR(1U << 7), /*!< Pre-Trigger 7 Error. */
+#endif /* PDB_DLY_COUNT > 4 */
+};
+
+/*!
+ * @brief PDB buffer interrupts.
+ */
+enum _pdb_interrupt_enable
+{
+ kPDB_SequenceErrorInterruptEnable = PDB_SC_PDBEIE_MASK, /*!< PDB sequence error interrupt enable. */
+ kPDB_DelayInterruptEnable = PDB_SC_PDBIE_MASK, /*!< PDB delay interrupt enable. */
+};
+
+/*!
+ * @brief PDB load value mode.
+ *
+ * Selects the mode to load the internal values after doing the load operation (write 1 to PDBx_SC[LDOK]).
+ * These values are for:
+ * - PDB counter (PDBx_MOD, PDBx_IDLY)
+ * - ADC trigger (PDBx_CHnDLYm)
+ * - DAC trigger (PDBx_DACINTx)
+ * - CMP trigger (PDBx_POyDLY)
+ */
+typedef enum _pdb_load_value_mode
+{
+ kPDB_LoadValueImmediately = 0U, /*!< Load immediately after 1 is written to LDOK. */
+ kPDB_LoadValueOnCounterOverflow = 1U, /*!< Load when the PDB counter overflows (reaches the MOD
+ register value). */
+ kPDB_LoadValueOnTriggerInput = 2U, /*!< Load a trigger input event is detected. */
+ kPDB_LoadValueOnCounterOverflowOrTriggerInput = 3U, /*!< Load either when the PDB counter overflows or a trigger
+ input is detected. */
+} pdb_load_value_mode_t;
+
+/*!
+ * @brief Prescaler divider.
+ *
+ * Counting uses the peripheral clock divided by multiplication factor selected by times of MULT.
+ */
+typedef enum _pdb_prescaler_divider
+{
+ kPDB_PrescalerDivider1 = 0U, /*!< Divider x1. */
+ kPDB_PrescalerDivider2 = 1U, /*!< Divider x2. */
+ kPDB_PrescalerDivider4 = 2U, /*!< Divider x4. */
+ kPDB_PrescalerDivider8 = 3U, /*!< Divider x8. */
+ kPDB_PrescalerDivider16 = 4U, /*!< Divider x16. */
+ kPDB_PrescalerDivider32 = 5U, /*!< Divider x32. */
+ kPDB_PrescalerDivider64 = 6U, /*!< Divider x64. */
+ kPDB_PrescalerDivider128 = 7U, /*!< Divider x128. */
+} pdb_prescaler_divider_t;
+
+/*!
+ * @brief Multiplication factor select for prescaler.
+ *
+ * Selects the multiplication factor of the prescaler divider for the counter clock.
+ */
+typedef enum _pdb_divider_multiplication_factor
+{
+ kPDB_DividerMultiplicationFactor1 = 0U, /*!< Multiplication factor is 1. */
+ kPDB_DividerMultiplicationFactor10 = 1U, /*!< Multiplication factor is 10. */
+ kPDB_DividerMultiplicationFactor20 = 2U, /*!< Multiplication factor is 20. */
+ kPDB_DividerMultiplicationFactor40 = 3U, /*!< Multiplication factor is 40. */
+} pdb_divider_multiplication_factor_t;
+
+/*!
+ * @brief Trigger input source
+ *
+ * Selects the trigger input source for the PDB. The trigger input source can be internal or external (EXTRG pin), or
+ * the software trigger. See chip configuration details for the actual PDB input trigger connections.
+ */
+typedef enum _pdb_trigger_input_source
+{
+ kPDB_TriggerInput0 = 0U, /*!< Trigger-In 0. */
+ kPDB_TriggerInput1 = 1U, /*!< Trigger-In 1. */
+ kPDB_TriggerInput2 = 2U, /*!< Trigger-In 2. */
+ kPDB_TriggerInput3 = 3U, /*!< Trigger-In 3. */
+ kPDB_TriggerInput4 = 4U, /*!< Trigger-In 4. */
+ kPDB_TriggerInput5 = 5U, /*!< Trigger-In 5. */
+ kPDB_TriggerInput6 = 6U, /*!< Trigger-In 6. */
+ kPDB_TriggerInput7 = 7U, /*!< Trigger-In 7. */
+ kPDB_TriggerInput8 = 8U, /*!< Trigger-In 8. */
+ kPDB_TriggerInput9 = 9U, /*!< Trigger-In 9. */
+ kPDB_TriggerInput10 = 10U, /*!< Trigger-In 10. */
+ kPDB_TriggerInput11 = 11U, /*!< Trigger-In 11. */
+ kPDB_TriggerInput12 = 12U, /*!< Trigger-In 12. */
+ kPDB_TriggerInput13 = 13U, /*!< Trigger-In 13. */
+ kPDB_TriggerInput14 = 14U, /*!< Trigger-In 14. */
+ kPDB_TriggerSoftware = 15U, /*!< Trigger-In 15, software trigger. */
+} pdb_trigger_input_source_t;
+
+/*!
+ * @brief PDB module configuration.
+ */
+typedef struct _pdb_config
+{
+ pdb_load_value_mode_t loadValueMode; /*!< Select the load value mode. */
+ pdb_prescaler_divider_t prescalerDivider; /*!< Select the prescaler divider. */
+ pdb_divider_multiplication_factor_t dividerMultiplicationFactor; /*!< Multiplication factor select for prescaler. */
+ pdb_trigger_input_source_t triggerInputSource; /*!< Select the trigger input source. */
+ bool enableContinuousMode; /*!< Enable the PDB operation in Continuous mode.*/
+} pdb_config_t;
+
+/*!
+ * @brief PDB ADC Pre-Trigger configuration.
+ */
+typedef struct _pdb_adc_pretrigger_config
+{
+ uint32_t enablePreTriggerMask; /*!< PDB Channel Pre-Trigger Enable. */
+ uint32_t enableOutputMask; /*!< PDB Channel Pre-Trigger Output Select.
+ PDB channel's corresponding pre-trigger asserts when the counter
+ reaches the channel delay register. */
+ uint32_t enableBackToBackOperationMask; /*!< PDB Channel Pre-Trigger Back-to-Back Operation Enable.
+ Back-to-back operation enables the ADC conversions complete to trigger
+ the next PDB channel pre-trigger and trigger output, so that the ADC
+ conversions can be triggered on next set of configuration and results
+ registers.*/
+} pdb_adc_pretrigger_config_t;
+
+/*!
+ * @brief PDB DAC trigger configuration.
+ */
+typedef struct _pdb_dac_trigger_config
+{
+ bool enableExternalTriggerInput; /*!< Enables the external trigger for DAC interval counter. */
+ bool enableIntervalTrigger; /*!< Enables the DAC interval trigger. */
+} pdb_dac_trigger_config_t;
+
+/*******************************************************************************
+ * API
+ ******************************************************************************/
+#if defined(__cplusplus)
+extern "C" {
+#endif
+
+/*!
+ * @name Initialization
+ * @{
+ */
+
+/*!
+ * @brief Initializes the PDB module.
+ *
+ * This function is to make the initialization for PDB module. The operations includes are:
+ * - Enable the clock for PDB instance.
+ * - Configure the PDB module.
+ * - Enable the PDB module.
+ *
+ * @param base PDB peripheral base address.
+ * @param config Pointer to configuration structure. See "pdb_config_t".
+ */
+void PDB_Init(PDB_Type *base, const pdb_config_t *config);
+
+/*!
+ * @brief De-initializes the PDB module.
+ *
+ * @param base PDB peripheral base address.
+ */
+void PDB_Deinit(PDB_Type *base);
+
+/*!
+ * @brief Initializes the PDB user configuration structure.
+ *
+ * This function initializes the user configuration structure to default value. The default values are:
+ * @code
+ * config->loadValueMode = kPDB_LoadValueImmediately;
+ * config->prescalerDivider = kPDB_PrescalerDivider1;
+ * config->dividerMultiplicationFactor = kPDB_DividerMultiplicationFactor1;
+ * config->triggerInputSource = kPDB_TriggerSoftware;
+ * config->enableContinuousMode = false;
+ * @endcode
+ * @param config Pointer to configuration structure. See "pdb_config_t".
+ */
+void PDB_GetDefaultConfig(pdb_config_t *config);
+
+/*!
+ * @brief Enables the PDB module.
+ *
+ * @param base PDB peripheral base address.
+ * @param enable Enable the module or not.
+ */
+static inline void PDB_Enable(PDB_Type *base, bool enable)
+{
+ if (enable)
+ {
+ base->SC |= PDB_SC_PDBEN_MASK;
+ }
+ else
+ {
+ base->SC &= ~PDB_SC_PDBEN_MASK;
+ }
+}
+
+/* @} */
+
+/*!
+ * @name Basic Counter
+ * @{
+ */
+
+/*!
+ * @brief Triggers the PDB counter by software.
+ *
+ * @param base PDB peripheral base address.
+ */
+static inline void PDB_DoSoftwareTrigger(PDB_Type *base)
+{
+ base->SC |= PDB_SC_SWTRIG_MASK;
+}
+
+/*!
+ * @brief Loads the counter values.
+ *
+ * This function is to load the counter values from their internal buffer.
+ * See "pdb_load_value_mode_t" about PDB's load mode.
+ *
+ * @param base PDB peripheral base address.
+ */
+static inline void PDB_DoLoadValues(PDB_Type *base)
+{
+ base->SC |= PDB_SC_LDOK_MASK;
+}
+
+/*!
+ * @brief Enables the DMA for the PDB module.
+ *
+ * @param base PDB peripheral base address.
+ * @param enable Enable the feature or not.
+ */
+static inline void PDB_EnableDMA(PDB_Type *base, bool enable)
+{
+ if (enable)
+ {
+ base->SC |= PDB_SC_DMAEN_MASK;
+ }
+ else
+ {
+ base->SC &= ~PDB_SC_DMAEN_MASK;
+ }
+}
+
+/*!
+ * @brief Enables the interrupts for the PDB module.
+ *
+ * @param base PDB peripheral base address.
+ * @param mask Mask value for interrupts. See "_pdb_interrupt_enable".
+ */
+static inline void PDB_EnableInterrupts(PDB_Type *base, uint32_t mask)
+{
+ assert(0U == (mask & ~(PDB_SC_PDBEIE_MASK | PDB_SC_PDBIE_MASK)));
+
+ base->SC |= mask;
+}
+
+/*!
+ * @brief Disables the interrupts for the PDB module.
+ *
+ * @param base PDB peripheral base address.
+ * @param mask Mask value for interrupts. See "_pdb_interrupt_enable".
+ */
+static inline void PDB_DisableInterrupts(PDB_Type *base, uint32_t mask)
+{
+ assert(0U == (mask & ~(PDB_SC_PDBEIE_MASK | PDB_SC_PDBIE_MASK)));
+
+ base->SC &= ~mask;
+}
+
+/*!
+ * @brief Gets the status flags of the PDB module.
+ *
+ * @param base PDB peripheral base address.
+ *
+ * @return Mask value for asserted flags. See "_pdb_status_flags".
+ */
+static inline uint32_t PDB_GetStatusFlags(PDB_Type *base)
+{
+ return base->SC & (PDB_SC_PDBIF_MASK | PDB_SC_LDOK_MASK);
+}
+
+/*!
+ * @brief Clears the status flags of the PDB module.
+ *
+ * @param base PDB peripheral base address.
+ * @param mask Mask value of flags. See "_pdb_status_flags".
+ */
+static inline void PDB_ClearStatusFlags(PDB_Type *base, uint32_t mask)
+{
+ assert(0U == (mask & ~PDB_SC_PDBIF_MASK));
+
+ base->SC &= ~mask;
+}
+
+/*!
+ * @brief Specifies the period of the counter.
+ *
+ * @param base PDB peripheral base address.
+ * @param value Setting value for the modulus. 16-bit is available.
+ */
+static inline void PDB_SetModulusValue(PDB_Type *base, uint32_t value)
+{
+ base->MOD = PDB_MOD_MOD(value);
+}
+
+/*!
+ * @brief Gets the PDB counter's current value.
+ *
+ * @param base PDB peripheral base address.
+ *
+ * @return PDB counter's current value.
+ */
+static inline uint32_t PDB_GetCounterValue(PDB_Type *base)
+{
+ return base->CNT;
+}
+
+/*!
+ * @brief Sets the value for PDB counter delay event.
+ *
+ * @param base PDB peripheral base address.
+ * @param value Setting value for PDB counter delay event. 16-bit is available.
+ */
+static inline void PDB_SetCounterDelayValue(PDB_Type *base, uint32_t value)
+{
+ base->IDLY = PDB_IDLY_IDLY(value);
+}
+/* @} */
+
+/*!
+ * @name ADC Pre-Trigger
+ * @{
+ */
+
+/*!
+ * @brief Configures the ADC PreTrigger in PDB module.
+ *
+ * @param base PDB peripheral base address.
+ * @param channel Channel index for ADC instance.
+ * @param config Pointer to configuration structure. See "pdb_adc_pretrigger_config_t".
+ */
+static inline void PDB_SetADCPreTriggerConfig(PDB_Type *base, uint32_t channel, pdb_adc_pretrigger_config_t *config)
+{
+ assert(channel < PDB_C1_COUNT);
+ assert(NULL != config);
+
+ base->CH[channel].C1 = PDB_C1_BB(config->enableBackToBackOperationMask) | PDB_C1_TOS(config->enableOutputMask) |
+ PDB_C1_EN(config->enablePreTriggerMask);
+}
+
+/*!
+ * @brief Sets the value for ADC Pre-Trigger delay event.
+ *
+ * This function is to set the value for ADC Pre-Trigger delay event. IT Specifies the delay value for the channel's
+ * corresponding pre-trigger. The pre-trigger asserts when the PDB counter is equal to the setting value here.
+ *
+ * @param base PDB peripheral base address.
+ * @param channel Channel index for ADC instance.
+ * @param preChannel Channel group index for ADC instance.
+ * @param value Setting value for ADC Pre-Trigger delay event. 16-bit is available.
+ */
+static inline void PDB_SetADCPreTriggerDelayValue(PDB_Type *base, uint32_t channel, uint32_t preChannel, uint32_t value)
+{
+ assert(channel < PDB_C1_COUNT);
+ assert(preChannel < PDB_DLY_COUNT);
+
+ base->CH[channel].DLY[preChannel] = PDB_DLY_DLY(value);
+}
+
+/*!
+ * @brief Gets the ADC Pre-Trigger's status flags.
+ *
+ * @param base PDB peripheral base address.
+ * @param channel Channel index for ADC instance.
+ *
+ * @return Mask value for asserted flags. See "_pdb_adc_pretrigger_flags".
+ */
+static inline uint32_t PDB_GetADCPreTriggerStatusFlags(PDB_Type *base, uint32_t channel)
+{
+ assert(channel < PDB_C1_COUNT);
+
+ return base->CH[channel].S;
+}
+
+/*!
+ * @brief Clears the ADC Pre-Trigger's status flags.
+ *
+ * @param base PDB peripheral base address.
+ * @param channel Channel index for ADC instance.
+ * @param mask Mask value for flags. See "_pdb_adc_pretrigger_flags".
+ */
+static inline void PDB_ClearADCPreTriggerStatusFlags(PDB_Type *base, uint32_t channel, uint32_t mask)
+{
+ assert(channel < PDB_C1_COUNT);
+
+ base->CH[channel].S &= ~mask;
+}
+
+/* @} */
+
+#if defined(FSL_FEATURE_PDB_HAS_DAC) && FSL_FEATURE_PDB_HAS_DAC
+/*!
+ * @name DAC Interval Trigger
+ * @{
+ */
+
+/*!
+ * @brief Configures the DAC trigger in PDB module.
+ *
+ * @param base PDB peripheral base address.
+ * @param channel Channel index for DAC instance.
+ * @param config Pointer to configuration structure. See "pdb_dac_trigger_config_t".
+ */
+void PDB_SetDACTriggerConfig(PDB_Type *base, uint32_t channel, pdb_dac_trigger_config_t *config);
+
+/*!
+ * @brief Sets the value for the DAC interval event.
+ *
+ * This fucntion is to set the value for DAC interval event. DAC interval trigger would trigger the DAC module to update
+ * buffer when the DAC interval counter is equal to the setting value here.
+ *
+ * @param base PDB peripheral base address.
+ * @param channel Channel index for DAC instance.
+ * @param value Setting value for the DAC interval event.
+ */
+static inline void PDB_SetDACTriggerIntervalValue(PDB_Type *base, uint32_t channel, uint32_t value)
+{
+ assert(channel < PDB_INT_COUNT);
+
+ base->DAC[channel].INT = PDB_INT_INT(value);
+}
+
+/* @} */
+#endif /* FSL_FEATURE_PDB_HAS_DAC */
+
+/*!
+ * @name Pulse-Out Trigger
+ * @{
+ */
+
+/*!
+ * @brief Enables the pulse out trigger channels.
+ *
+ * @param base PDB peripheral base address.
+ * @param channelMask Channel mask value for multiple pulse out trigger channel.
+ * @param enable Enable the feature or not.
+ */
+static inline void PDB_EnablePulseOutTrigger(PDB_Type *base, uint32_t channelMask, bool enable)
+{
+ if (enable)
+ {
+ base->POEN |= PDB_POEN_POEN(channelMask);
+ }
+ else
+ {
+ base->POEN &= ~(PDB_POEN_POEN(channelMask));
+ }
+}
+
+/*!
+ * @brief Sets event values for pulse out trigger.
+ *
+ * This function is used to set event values for pulse output trigger.
+ * These pulse output trigger delay values specify the delay for the PDB Pulse-Out. Pulse-Out goes high when the PDB
+ * counter is equal to the pulse output high value (value1). Pulse-Out goes low when the PDB counter is equal to the
+ * pulse output low value (value2).
+ *
+ * @param base PDB peripheral base address.
+ * @param channel Channel index for pulse out trigger channel.
+ * @param value1 Setting value for pulse out high.
+ * @param value2 Setting value for pulse out low.
+ */
+static inline void PDB_SetPulseOutTriggerDelayValue(PDB_Type *base, uint32_t channel, uint32_t value1, uint32_t value2)
+{
+ assert(channel < PDB_PODLY_COUNT);
+
+ base->PODLY[channel] = PDB_PODLY_DLY1(value1) | PDB_PODLY_DLY2(value2);
+}
+
+/* @} */
+#if defined(__cplusplus)
+}
+#endif
+/*!
+ * @}
+ */
+#endif /* _FSL_PDB_H_ */
diff --git a/drivers/fsl_pit.c b/drivers/fsl_pit.c
new file mode 100644
index 0000000..1f2fdfe
--- /dev/null
+++ b/drivers/fsl_pit.c
@@ -0,0 +1,119 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_pit.h"
+
+/*******************************************************************************
+ * Prototypes
+ ******************************************************************************/
+/*!
+ * @brief Gets the instance from the base address to be used to gate or ungate the module clock
+ *
+ * @param base PIT peripheral base address
+ *
+ * @return The PIT instance
+ */
+static uint32_t PIT_GetInstance(PIT_Type *base);
+
+/*******************************************************************************
+ * Variables
+ ******************************************************************************/
+/*! @brief Pointers to PIT bases for each instance. */
+static PIT_Type *const s_pitBases[] = PIT_BASE_PTRS;
+
+/*! @brief Pointers to PIT clocks for each instance. */
+static const clock_ip_name_t s_pitClocks[] = PIT_CLOCKS;
+
+/*******************************************************************************
+ * Code
+ ******************************************************************************/
+static uint32_t PIT_GetInstance(PIT_Type *base)
+{
+ uint32_t instance;
+
+ /* Find the instance index from base address mappings. */
+ for (instance = 0; instance < FSL_FEATURE_SOC_PIT_COUNT; instance++)
+ {
+ if (s_pitBases[instance] == base)
+ {
+ break;
+ }
+ }
+
+ assert(instance < FSL_FEATURE_SOC_PIT_COUNT);
+
+ return instance;
+}
+
+void PIT_Init(PIT_Type *base, const pit_config_t *config)
+{
+ assert(config);
+
+ /* Ungate the PIT clock*/
+ CLOCK_EnableClock(s_pitClocks[PIT_GetInstance(base)]);
+
+ /* Enable PIT timers */
+ base->MCR &= ~PIT_MCR_MDIS_MASK;
+
+ /* Config timer operation when in debug mode */
+ if (config->enableRunInDebug)
+ {
+ base->MCR &= ~PIT_MCR_FRZ_MASK;
+ }
+ else
+ {
+ base->MCR |= PIT_MCR_FRZ_MASK;
+ }
+}
+
+void PIT_Deinit(PIT_Type *base)
+{
+ /* Disable PIT timers */
+ base->MCR |= PIT_MCR_MDIS_MASK;
+
+ /* Gate the PIT clock*/
+ CLOCK_DisableClock(s_pitClocks[PIT_GetInstance(base)]);
+}
+
+#if defined(FSL_FEATURE_PIT_HAS_LIFETIME_TIMER) && FSL_FEATURE_PIT_HAS_LIFETIME_TIMER
+
+uint64_t PIT_GetLifetimeTimerCount(PIT_Type *base)
+{
+ uint32_t valueH = 0U;
+ uint32_t valueL = 0U;
+
+ /* LTMR64H should be read before LTMR64L */
+ valueH = base->LTMR64H;
+ valueL = base->LTMR64L;
+
+ return (((uint64_t)valueH << 32U) + (uint64_t)(valueL));
+}
+
+#endif /* FSL_FEATURE_PIT_HAS_LIFETIME_TIMER */
diff --git a/drivers/fsl_pit.h b/drivers/fsl_pit.h
new file mode 100644
index 0000000..f94c14a
--- /dev/null
+++ b/drivers/fsl_pit.h
@@ -0,0 +1,354 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_PIT_H_
+#define _FSL_PIT_H_
+
+#include "fsl_common.h"
+
+/*!
+ * @addtogroup pit
+ * @{
+ */
+
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+/*! @name Driver version */
+/*@{*/
+#define FSL_PIT_DRIVER_VERSION (MAKE_VERSION(2, 0, 0)) /*!< Version 2.0.0 */
+/*@}*/
+
+/*!
+ * @brief List of PIT channels
+ * @note Actual number of available channels is SoC dependent
+ */
+typedef enum _pit_chnl
+{
+ kPIT_Chnl_0 = 0U, /*!< PIT channel number 0*/
+ kPIT_Chnl_1, /*!< PIT channel number 1 */
+ kPIT_Chnl_2, /*!< PIT channel number 2 */
+ kPIT_Chnl_3, /*!< PIT channel number 3 */
+} pit_chnl_t;
+
+/*! @brief List of PIT interrupts */
+typedef enum _pit_interrupt_enable
+{
+ kPIT_TimerInterruptEnable = PIT_TCTRL_TIE_MASK, /*!< Timer interrupt enable*/
+} pit_interrupt_enable_t;
+
+/*! @brief List of PIT status flags */
+typedef enum _pit_status_flags
+{
+ kPIT_TimerFlag = PIT_TFLG_TIF_MASK, /*!< Timer flag */
+} pit_status_flags_t;
+
+/*!
+ * @brief PIT config structure
+ *
+ * This structure holds the configuration settings for the PIT peripheral. To initialize this
+ * structure to reasonable defaults, call the PIT_GetDefaultConfig() function and pass a
+ * pointer to your config structure instance.
+ *
+ * The config struct can be made const so it resides in flash
+ */
+typedef struct _pit_config
+{
+ bool enableRunInDebug; /*!< true: Timers run in debug mode; false: Timers stop in debug mode */
+} pit_config_t;
+
+/*******************************************************************************
+ * API
+ ******************************************************************************/
+
+#if defined(__cplusplus)
+extern "C" {
+#endif
+
+/*!
+ * @name Initialization and deinitialization
+ * @{
+ */
+
+/*!
+ * @brief Ungates the PIT clock, enables the PIT module and configures the peripheral for basic operation.
+ *
+ * @note This API should be called at the beginning of the application using the PIT driver.
+ *
+ * @param base PIT peripheral base address
+ * @param config Pointer to user's PIT config structure
+ */
+void PIT_Init(PIT_Type *base, const pit_config_t *config);
+
+/*!
+ * @brief Gate the PIT clock and disable the PIT module
+ *
+ * @param base PIT peripheral base address
+ */
+void PIT_Deinit(PIT_Type *base);
+
+/*!
+ * @brief Fill in the PIT config struct with the default settings
+ *
+ * The default values are:
+ * @code
+ * config->enableRunInDebug = false;
+ * @endcode
+ * @param config Pointer to user's PIT config structure.
+ */
+static inline void PIT_GetDefaultConfig(pit_config_t *config)
+{
+ assert(config);
+
+ /* Timers are stopped in Debug mode */
+ config->enableRunInDebug = false;
+}
+
+#if defined(FSL_FEATURE_PIT_HAS_CHAIN_MODE) && FSL_FEATURE_PIT_HAS_CHAIN_MODE
+
+/*!
+ * @brief Enables or disables chaining a timer with the previous timer.
+ *
+ * When a timer has a chain mode enabled, it only counts after the previous
+ * timer has expired. If the timer n-1 has counted down to 0, counter n
+ * decrements the value by one. Each timer is 32-bits, this allows the developers
+ * to chain timers together and form a longer timer (64-bits and larger). The first timer
+ * (timer 0) cannot be chained to any other timer.
+ *
+ * @param base PIT peripheral base address
+ * @param channel Timer channel number which is chained with the previous timer
+ * @param enable Enable or disable chain.
+ * true: Current timer is chained with the previous timer.
+ * false: Timer doesn't chain with other timers.
+ */
+static inline void PIT_SetTimerChainMode(PIT_Type *base, pit_chnl_t channel, bool enable)
+{
+ if (enable)
+ {
+ base->CHANNEL[channel].TCTRL |= PIT_TCTRL_CHN_MASK;
+ }
+ else
+ {
+ base->CHANNEL[channel].TCTRL &= ~PIT_TCTRL_CHN_MASK;
+ }
+}
+
+#endif /* FSL_FEATURE_PIT_HAS_CHAIN_MODE */
+
+/*! @}*/
+
+/*!
+ * @name Interrupt Interface
+ * @{
+ */
+
+/*!
+ * @brief Enables the selected PIT interrupts.
+ *
+ * @param base PIT peripheral base address
+ * @param channel Timer channel number
+ * @param mask The interrupts to enable. This is a logical OR of members of the
+ * enumeration ::pit_interrupt_enable_t
+ */
+static inline void PIT_EnableInterrupts(PIT_Type *base, pit_chnl_t channel, uint32_t mask)
+{
+ base->CHANNEL[channel].TCTRL |= mask;
+}
+
+/*!
+ * @brief Disables the selected PIT interrupts.
+ *
+ * @param base PIT peripheral base address
+ * @param channel Timer channel number
+ * @param mask The interrupts to disable. This is a logical OR of members of the
+ * enumeration ::pit_interrupt_enable_t
+ */
+static inline void PIT_DisableInterrupts(PIT_Type *base, pit_chnl_t channel, uint32_t mask)
+{
+ base->CHANNEL[channel].TCTRL &= ~mask;
+}
+
+/*!
+ * @brief Gets the enabled PIT interrupts.
+ *
+ * @param base PIT peripheral base address
+ * @param channel Timer channel number
+ *
+ * @return The enabled interrupts. This is the logical OR of members of the
+ * enumeration ::pit_interrupt_enable_t
+ */
+static inline uint32_t PIT_GetEnabledInterrupts(PIT_Type *base, pit_chnl_t channel)
+{
+ return (base->CHANNEL[channel].TCTRL & PIT_TCTRL_TIE_MASK);
+}
+
+/*! @}*/
+
+/*!
+ * @name Status Interface
+ * @{
+ */
+
+/*!
+ * @brief Gets the PIT status flags
+ *
+ * @param base PIT peripheral base address
+ * @param channel Timer channel number
+ *
+ * @return The status flags. This is the logical OR of members of the
+ * enumeration ::pit_status_flags_t
+ */
+static inline uint32_t PIT_GetStatusFlags(PIT_Type *base, pit_chnl_t channel)
+{
+ return (base->CHANNEL[channel].TFLG & PIT_TFLG_TIF_MASK);
+}
+
+/*!
+ * @brief Clears the PIT status flags.
+ *
+ * @param base PIT peripheral base address
+ * @param channel Timer channel number
+ * @param mask The status flags to clear. This is a logical OR of members of the
+ * enumeration ::pit_status_flags_t
+ */
+static inline void PIT_ClearStatusFlags(PIT_Type *base, pit_chnl_t channel, uint32_t mask)
+{
+ base->CHANNEL[channel].TFLG = mask;
+}
+
+/*! @}*/
+
+/*!
+ * @name Read and Write the timer period
+ * @{
+ */
+
+/*!
+ * @brief Sets the timer period in units of count.
+ *
+ * Timers begin counting from the value set by this function until it reaches 0,
+ * then it generates an interrupt and load this register value again.
+ * Writing a new value to this register does not restart the timer. Instead, the value
+ * is loaded after the timer expires.
+ *
+ * @note User can call the utility macros provided in fsl_common.h to convert to ticks
+ *
+ * @param base PIT peripheral base address
+ * @param channel Timer channel number
+ * @param count Timer period in units of ticks
+ */
+static inline void PIT_SetTimerPeriod(PIT_Type *base, pit_chnl_t channel, uint32_t count)
+{
+ base->CHANNEL[channel].LDVAL = count;
+}
+
+/*!
+ * @brief Reads the current timer counting value.
+ *
+ * This function returns the real-time timer counting value, in a range from 0 to a
+ * timer period.
+ *
+ * @note User can call the utility macros provided in fsl_common.h to convert ticks to usec or msec
+ *
+ * @param base PIT peripheral base address
+ * @param channel Timer channel number
+ *
+ * @return Current timer counting value in ticks
+ */
+static inline uint32_t PIT_GetCurrentTimerCount(PIT_Type *base, pit_chnl_t channel)
+{
+ return base->CHANNEL[channel].CVAL;
+}
+
+/*! @}*/
+
+/*!
+ * @name Timer Start and Stop
+ * @{
+ */
+
+/*!
+ * @brief Starts the timer counting.
+ *
+ * After calling this function, timers load period value, count down to 0 and
+ * then load the respective start value again. Each time a timer reaches 0,
+ * it generates a trigger pulse and sets the timeout interrupt flag.
+ *
+ * @param base PIT peripheral base address
+ * @param channel Timer channel number.
+ */
+static inline void PIT_StartTimer(PIT_Type *base, pit_chnl_t channel)
+{
+ base->CHANNEL[channel].TCTRL |= PIT_TCTRL_TEN_MASK;
+}
+
+/*!
+ * @brief Stops the timer counting.
+ *
+ * This function stops every timer counting. Timers reload their periods
+ * respectively after the next time they call the PIT_DRV_StartTimer.
+ *
+ * @param base PIT peripheral base address
+ * @param channel Timer channel number.
+ */
+static inline void PIT_StopTimer(PIT_Type *base, pit_chnl_t channel)
+{
+ base->CHANNEL[channel].TCTRL &= ~PIT_TCTRL_TEN_MASK;
+}
+
+/*! @}*/
+
+#if defined(FSL_FEATURE_PIT_HAS_LIFETIME_TIMER) && FSL_FEATURE_PIT_HAS_LIFETIME_TIMER
+
+/*!
+ * @brief Reads the current lifetime counter value.
+ *
+ * The lifetime timer is a 64-bit timer which chains timer 0 and timer 1 together.
+ * Timer 0 and 1 are chained by calling the PIT_SetTimerChainMode before using this timer.
+ * The period of lifetime timer is equal to the "period of timer 0 * period of timer 1".
+ * For the 64-bit value, the higher 32-bit has the value of timer 1, and the lower 32-bit
+ * has the value of timer 0.
+ *
+ * @param base PIT peripheral base address
+ *
+ * @return Current lifetime timer value
+ */
+uint64_t PIT_GetLifetimeTimerCount(PIT_Type *base);
+
+#endif /* FSL_FEATURE_PIT_HAS_LIFETIME_TIMER */
+
+#if defined(__cplusplus)
+}
+#endif
+
+/*! @}*/
+
+#endif /* _FSL_PIT_H_ */
diff --git a/drivers/fsl_pmc.c b/drivers/fsl_pmc.c
new file mode 100644
index 0000000..82d7b7a
--- /dev/null
+++ b/drivers/fsl_pmc.c
@@ -0,0 +1,93 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_pmc.h"
+
+#if (defined(FSL_FEATURE_PMC_HAS_PARAM) && FSL_FEATURE_PMC_HAS_PARAM)
+void PMC_GetParam(PMC_Type *base, pmc_param_t *param)
+{
+ uint32_t reg = base->PARAM;
+ ;
+ param->vlpoEnable = (bool)(reg & PMC_PARAM_VLPOE_MASK);
+ param->hvdEnable = (bool)(reg & PMC_PARAM_HVDE_MASK);
+}
+#endif /* FSL_FEATURE_PMC_HAS_PARAM */
+
+void PMC_ConfigureLowVoltDetect(PMC_Type *base, const pmc_low_volt_detect_config_t *config)
+{
+ base->LVDSC1 = (0U |
+#if (defined(FSL_FEATURE_PMC_HAS_LVDV) && FSL_FEATURE_PMC_HAS_LVDV)
+ ((uint32_t)config->voltSelect << PMC_LVDSC1_LVDV_SHIFT) |
+#endif
+ ((uint32_t)config->enableInt << PMC_LVDSC1_LVDIE_SHIFT) |
+ ((uint32_t)config->enableReset << PMC_LVDSC1_LVDRE_SHIFT)
+ /* Clear the Low Voltage Detect Flag with previouse power detect setting */
+ | PMC_LVDSC1_LVDACK_MASK);
+}
+
+void PMC_ConfigureLowVoltWarning(PMC_Type *base, const pmc_low_volt_warning_config_t *config)
+{
+ base->LVDSC2 = (0U |
+#if (defined(FSL_FEATURE_PMC_HAS_LVWV) && FSL_FEATURE_PMC_HAS_LVWV)
+ ((uint32_t)config->voltSelect << PMC_LVDSC2_LVWV_SHIFT) |
+#endif
+ ((uint32_t)config->enableInt << PMC_LVDSC2_LVWIE_SHIFT)
+ /* Clear the Low Voltage Warning Flag with previouse power detect setting */
+ | PMC_LVDSC2_LVWACK_MASK);
+}
+
+#if (defined(FSL_FEATURE_PMC_HAS_HVDSC1) && FSL_FEATURE_PMC_HAS_HVDSC1)
+void PMC_ConfigureHighVoltDetect(PMC_Type *base, const pmc_high_volt_detect_config_t *config)
+{
+ base->HVDSC1 = (((uint32_t)config->voltSelect << PMC_HVDSC1_HVDV_SHIFT) |
+ ((uint32_t)config->enableInt << PMC_HVDSC1_HVDIE_SHIFT) |
+ ((uint32_t)config->enableReset << PMC_HVDSC1_HVDRE_SHIFT)
+ /* Clear the High Voltage Detect Flag with previouse power detect setting */
+ | PMC_HVDSC1_HVDACK_MASK);
+}
+#endif /* FSL_FEATURE_PMC_HAS_HVDSC1 */
+
+#if ((defined(FSL_FEATURE_PMC_HAS_BGBE) && FSL_FEATURE_PMC_HAS_BGBE) || \
+ (defined(FSL_FEATURE_PMC_HAS_BGEN) && FSL_FEATURE_PMC_HAS_BGEN) || \
+ (defined(FSL_FEATURE_PMC_HAS_BGBDS) && FSL_FEATURE_PMC_HAS_BGBDS))
+void PMC_ConfigureBandgapBuffer(PMC_Type *base, const pmc_bandgap_buffer_config_t *config)
+{
+ base->REGSC = (0U
+#if (defined(FSL_FEATURE_PMC_HAS_BGBE) && FSL_FEATURE_PMC_HAS_BGBE)
+ | ((uint32_t)config->enable << PMC_REGSC_BGBE_SHIFT)
+#endif /* FSL_FEATURE_PMC_HAS_BGBE */
+#if (defined(FSL_FEATURE_PMC_HAS_BGEN) && FSL_FEATURE_PMC_HAS_BGEN)
+ | (((uint32_t)config->enableInLowPowerMode << PMC_REGSC_BGEN_SHIFT))
+#endif /* FSL_FEATURE_PMC_HAS_BGEN */
+#if (defined(FSL_FEATURE_PMC_HAS_BGBDS) && FSL_FEATURE_PMC_HAS_BGBDS)
+ | ((uint32_t)config->drive << PMC_REGSC_BGBDS_SHIFT)
+#endif /* FSL_FEATURE_PMC_HAS_BGBDS */
+ );
+}
+#endif
diff --git a/drivers/fsl_pmc.h b/drivers/fsl_pmc.h
new file mode 100644
index 0000000..f39a22f
--- /dev/null
+++ b/drivers/fsl_pmc.h
@@ -0,0 +1,421 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_PMC_H_
+#define _FSL_PMC_H_
+
+#include "fsl_common.h"
+
+/*! @addtogroup pmc */
+/*! @{ */
+
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+/*! @name Driver version */
+/*@{*/
+/*! @brief PMC driver version */
+#define FSL_PMC_DRIVER_VERSION (MAKE_VERSION(2, 0, 0)) /*!< Version 2.0.0. */
+/*@}*/
+
+#if (defined(FSL_FEATURE_PMC_HAS_LVDV) && FSL_FEATURE_PMC_HAS_LVDV)
+/*!
+ * @brief Low-Voltage Detect Voltage Select
+ */
+typedef enum _pmc_low_volt_detect_volt_select
+{
+ kPMC_LowVoltDetectLowTrip = 0U, /*!< Low trip point selected (VLVD = VLVDL )*/
+ kPMC_LowVoltDetectHighTrip = 1U /*!< High trip point selected (VLVD = VLVDH )*/
+} pmc_low_volt_detect_volt_select_t;
+#endif
+
+#if (defined(FSL_FEATURE_PMC_HAS_LVWV) && FSL_FEATURE_PMC_HAS_LVWV)
+/*!
+ * @brief Low-Voltage Warning Voltage Select
+ */
+typedef enum _pmc_low_volt_warning_volt_select
+{
+ kPMC_LowVoltWarningLowTrip = 0U, /*!< Low trip point selected (VLVW = VLVW1)*/
+ kPMC_LowVoltWarningMid1Trip = 1U, /*!< Mid 1 trip point selected (VLVW = VLVW2)*/
+ kPMC_LowVoltWarningMid2Trip = 2U, /*!< Mid 2 trip point selected (VLVW = VLVW3)*/
+ kPMC_LowVoltWarningHighTrip = 3U /*!< High trip point selected (VLVW = VLVW4)*/
+} pmc_low_volt_warning_volt_select_t;
+#endif
+
+#if (defined(FSL_FEATURE_PMC_HAS_HVDSC1) && FSL_FEATURE_PMC_HAS_HVDSC1)
+/*!
+ * @brief High-Voltage Detect Voltage Select
+ */
+typedef enum _pmc_high_volt_detect_volt_select
+{
+ kPMC_HighVoltDetectLowTrip = 0U, /*!< Low trip point selected (VHVD = VHVDL )*/
+ kPMC_HighVoltDetectHighTrip = 1U /*!< High trip point selected (VHVD = VHVDH )*/
+} pmc_high_volt_detect_volt_select_t;
+#endif /* FSL_FEATURE_PMC_HAS_HVDSC1 */
+
+#if (defined(FSL_FEATURE_PMC_HAS_BGBDS) && FSL_FEATURE_PMC_HAS_BGBDS)
+/*!
+ * @brief Bandgap Buffer Drive Select.
+ */
+typedef enum _pmc_bandgap_buffer_drive_select
+{
+ kPMC_BandgapBufferDriveLow = 0U, /*!< Low drive. */
+ kPMC_BandgapBufferDriveHigh = 1U /*!< High drive. */
+} pmc_bandgap_buffer_drive_select_t;
+#endif /* FSL_FEATURE_PMC_HAS_BGBDS */
+
+#if (defined(FSL_FEATURE_PMC_HAS_VLPO) && FSL_FEATURE_PMC_HAS_VLPO)
+/*!
+ * @brief VLPx Option
+ */
+typedef enum _pmc_vlp_freq_option
+{
+ kPMC_FreqRestrict = 0U, /*!< Frequency is restricted in VLPx mode. */
+ kPMC_FreqUnrestrict = 1U /*!< Frequency is unrestricted in VLPx mode. */
+} pmc_vlp_freq_mode_t;
+#endif /* FSL_FEATURE_PMC_HAS_VLPO */
+
+#if (defined(FSL_FEATURE_PMC_HAS_VERID) && FSL_FEATURE_PMC_HAS_VERID)
+/*!
+ @brief IP version ID definition.
+ */
+typedef struct _pmc_version_id
+{
+ uint16_t feature; /*!< Feature Specification Number. */
+ uint8_t minor; /*!< Minor version number. */
+ uint8_t major; /*!< Major version number. */
+} pmc_version_id_t;
+#endif /* FSL_FEATURE_PMC_HAS_VERID */
+
+#if (defined(FSL_FEATURE_PMC_HAS_PARAM) && FSL_FEATURE_PMC_HAS_PARAM)
+/*! @brief IP parameter definition. */
+typedef struct _pmc_param
+{
+ bool vlpoEnable; /*!< VLPO enable. */
+ bool hvdEnable; /*!< HVD enable. */
+} pmc_param_t;
+#endif /* FSL_FEATURE_PMC_HAS_PARAM */
+
+/*!
+ * @brief Low-Voltage Detect Configuration Structure
+ */
+typedef struct _pmc_low_volt_detect_config
+{
+ bool enableInt; /*!< Enable interrupt when low-voltage detect*/
+ bool enableReset; /*!< Enable system reset when low-voltage detect*/
+#if (defined(FSL_FEATURE_PMC_HAS_LVDV) && FSL_FEATURE_PMC_HAS_LVDV)
+ pmc_low_volt_detect_volt_select_t voltSelect; /*!< Low-voltage detect trip point voltage selection*/
+#endif
+} pmc_low_volt_detect_config_t;
+
+/*!
+ * @brief Low-Voltage Warning Configuration Structure
+ */
+typedef struct _pmc_low_volt_warning_config
+{
+ bool enableInt; /*!< Enable interrupt when low-voltage warning*/
+#if (defined(FSL_FEATURE_PMC_HAS_LVWV) && FSL_FEATURE_PMC_HAS_LVWV)
+ pmc_low_volt_warning_volt_select_t voltSelect; /*!< Low-voltage warning trip point voltage selection*/
+#endif
+} pmc_low_volt_warning_config_t;
+
+#if (defined(FSL_FEATURE_PMC_HAS_HVDSC1) && FSL_FEATURE_PMC_HAS_HVDSC1)
+/*!
+ * @brief High-Voltage Detect Configuration Structure
+ */
+typedef struct _pmc_high_volt_detect_config
+{
+ bool enableInt; /*!< Enable interrupt when high-voltage detect*/
+ bool enableReset; /*!< Enable system reset when high-voltage detect*/
+ pmc_high_volt_detect_volt_select_t voltSelect; /*!< High-voltage detect trip point voltage selection*/
+} pmc_high_volt_detect_config_t;
+#endif /* FSL_FEATURE_PMC_HAS_HVDSC1 */
+
+#if ((defined(FSL_FEATURE_PMC_HAS_BGBE) && FSL_FEATURE_PMC_HAS_BGBE) || \
+ (defined(FSL_FEATURE_PMC_HAS_BGEN) && FSL_FEATURE_PMC_HAS_BGEN) || \
+ (defined(FSL_FEATURE_PMC_HAS_BGBDS) && FSL_FEATURE_PMC_HAS_BGBDS))
+/*!
+ * @brief Bandgap Buffer configuration.
+ */
+typedef struct _pmc_bandgap_buffer_config
+{
+#if (defined(FSL_FEATURE_PMC_HAS_BGBE) && FSL_FEATURE_PMC_HAS_BGBE)
+ bool enable; /*!< Enable bandgap buffer. */
+#endif
+#if (defined(FSL_FEATURE_PMC_HAS_BGEN) && FSL_FEATURE_PMC_HAS_BGEN)
+ bool enableInLowPowerMode; /*!< Enable bandgap buffer in low-power mode. */
+#endif /* FSL_FEATURE_PMC_HAS_BGEN */
+#if (defined(FSL_FEATURE_PMC_HAS_BGBDS) && FSL_FEATURE_PMC_HAS_BGBDS)
+ pmc_bandgap_buffer_drive_select_t drive; /*!< Bandgap buffer drive select. */
+#endif /* FSL_FEATURE_PMC_HAS_BGBDS */
+} pmc_bandgap_buffer_config_t;
+#endif
+
+/*******************************************************************************
+ * API
+ ******************************************************************************/
+
+#if defined(__cplusplus)
+extern "C" {
+#endif /* __cplusplus*/
+
+/*! @name Power Management Controller Control APIs*/
+/*@{*/
+
+#if (defined(FSL_FEATURE_PMC_HAS_VERID) && FSL_FEATURE_PMC_HAS_VERID)
+/*!
+ * @brief Gets the PMC version ID.
+ *
+ * This function gets the PMC version ID, including major version number,
+ * minor version number and feature specification number.
+ *
+ * @param base PMC peripheral base address.
+ * @param versionId Pointer to version ID structure.
+ */
+static inline void PMC_GetVersionId(PMC_Type *base, pmc_version_id_t *versionId)
+{
+ *((uint32_t *)versionId) = base->VERID;
+}
+#endif /* FSL_FEATURE_PMC_HAS_VERID */
+
+#if (defined(FSL_FEATURE_PMC_HAS_PARAM) && FSL_FEATURE_PMC_HAS_PARAM)
+/*!
+ * @brief Gets the PMC parameter.
+ *
+ * This function gets the PMC parameter, including VLPO enable and HVD enable.
+ *
+ * @param base PMC peripheral base address.
+ * @param param Pointer to PMC param structure.
+ */
+void PMC_GetParam(PMC_Type *base, pmc_param_t *param);
+#endif
+
+/*!
+ * @brief Configure the low-voltage detect setting.
+ *
+ * This function configures the low-voltage detect setting, including the trip
+ * point voltage setting, enable interrupt or not, enable system reset or not.
+ *
+ * @param base PMC peripheral base address.
+ * @param config Low-Voltage detect configuration structure.
+ */
+void PMC_ConfigureLowVoltDetect(PMC_Type *base, const pmc_low_volt_detect_config_t *config);
+
+/*!
+ * @brief Get Low-Voltage Detect Flag status
+ *
+ * This function reads the current LVDF status. If it returns 1, a low-voltage event is detected.
+ *
+ * @param base PMC peripheral base address.
+ * @return Current low-voltage detect flag
+ * - true: Low-voltage detected
+ * - false: Low-voltage not detected
+ */
+static inline bool PMC_GetLowVoltDetectFlag(PMC_Type *base)
+{
+ return (bool)(base->LVDSC1 & PMC_LVDSC1_LVDF_MASK);
+}
+
+/*!
+ * @brief Acknowledge to clear the Low-voltage Detect flag
+ *
+ * This function acknowledges the low-voltage detection errors (write 1 to
+ * clear LVDF).
+ *
+ * @param base PMC peripheral base address.
+ */
+static inline void PMC_ClearLowVoltDetectFlag(PMC_Type *base)
+{
+ base->LVDSC1 |= PMC_LVDSC1_LVDACK_MASK;
+}
+
+/*!
+ * @brief Configure the low-voltage warning setting.
+ *
+ * This function configures the low-voltage warning setting, including the trip
+ * point voltage setting and enable interrupt or not.
+ *
+ * @param base PMC peripheral base address.
+ * @param config Low-Voltage warning configuration structure.
+ */
+void PMC_ConfigureLowVoltWarning(PMC_Type *base, const pmc_low_volt_warning_config_t *config);
+
+/*!
+ * @brief Get Low-Voltage Warning Flag status
+ *
+ * This function polls the current LVWF status. When 1 is returned, it
+ * indicates a low-voltage warning event. LVWF is set when V Supply transitions
+ * below the trip point or after reset and V Supply is already below the V LVW.
+ *
+ * @param base PMC peripheral base address.
+ * @return Current LVWF status
+ * - true: Low-Voltage Warning Flag is set.
+ * - false: the Low-Voltage Warning does not happen.
+ */
+static inline bool PMC_GetLowVoltWarningFlag(PMC_Type *base)
+{
+ return (bool)(base->LVDSC2 & PMC_LVDSC2_LVWF_MASK);
+}
+
+/*!
+ * @brief Acknowledge to Low-Voltage Warning flag
+ *
+ * This function acknowledges the low voltage warning errors (write 1 to
+ * clear LVWF).
+ *
+ * @param base PMC peripheral base address.
+ */
+static inline void PMC_ClearLowVoltWarningFlag(PMC_Type *base)
+{
+ base->LVDSC2 |= PMC_LVDSC2_LVWACK_MASK;
+}
+
+#if (defined(FSL_FEATURE_PMC_HAS_HVDSC1) && FSL_FEATURE_PMC_HAS_HVDSC1)
+/*!
+ * @brief Configure the high-voltage detect setting.
+ *
+ * This function configures the high-voltage detect setting, including the trip
+ * point voltage setting, enable interrupt or not, enable system reset or not.
+ *
+ * @param base PMC peripheral base address.
+ * @param config High-voltage detect configuration structure.
+ */
+void PMC_ConfigureHighVoltDetect(PMC_Type *base, const pmc_high_volt_detect_config_t *config);
+
+/*!
+ * @brief Get High-Voltage Detect Flag status
+ *
+ * This function reads the current HVDF status. If it returns 1, a low
+ * voltage event is detected.
+ *
+ * @param base PMC peripheral base address.
+ * @return Current high-voltage detect flag
+ * - true: High-Voltage detected
+ * - false: High-Voltage not detected
+ */
+static inline bool PMC_GetHighVoltDetectFlag(PMC_Type *base)
+{
+ return (bool)(base->HVDSC1 & PMC_HVDSC1_HVDF_MASK);
+}
+
+/*!
+ * @brief Acknowledge to clear the High-Voltage Detect flag
+ *
+ * This function acknowledges the high-voltage detection errors (write 1 to
+ * clear HVDF).
+ *
+ * @param base PMC peripheral base address.
+ */
+static inline void PMC_ClearHighVoltDetectFlag(PMC_Type *base)
+{
+ base->HVDSC1 |= PMC_HVDSC1_HVDACK_MASK;
+}
+#endif /* FSL_FEATURE_PMC_HAS_HVDSC1 */
+
+#if ((defined(FSL_FEATURE_PMC_HAS_BGBE) && FSL_FEATURE_PMC_HAS_BGBE) || \
+ (defined(FSL_FEATURE_PMC_HAS_BGEN) && FSL_FEATURE_PMC_HAS_BGEN) || \
+ (defined(FSL_FEATURE_PMC_HAS_BGBDS) && FSL_FEATURE_PMC_HAS_BGBDS))
+/*!
+ * @brief Configure the PMC bandgap
+ *
+ * This function configures the PMC bandgap, including the drive select and
+ * behavior in low-power mode.
+ *
+ * @param base PMC peripheral base address.
+ * @param config Pointer to the configuration structure
+ */
+void PMC_ConfigureBandgapBuffer(PMC_Type *base, const pmc_bandgap_buffer_config_t *config);
+#endif
+
+#if (defined(FSL_FEATURE_PMC_HAS_ACKISO) && FSL_FEATURE_PMC_HAS_ACKISO)
+/*!
+ * @brief Gets the acknowledge Peripherals and I/O pads isolation flag.
+ *
+ * This function reads the Acknowledge Isolation setting that indicates
+ * whether certain peripherals and the I/O pads are in a latched state as
+ * a result of having been in the VLLS mode.
+ *
+ * @param base PMC peripheral base address.
+ * @param base Base address for current PMC instance.
+ * @return ACK isolation
+ * 0 - Peripherals and I/O pads are in a normal run state.
+ * 1 - Certain peripherals and I/O pads are in an isolated and
+ * latched state.
+ */
+static inline bool PMC_GetPeriphIOIsolationFlag(PMC_Type *base)
+{
+ return (bool)(base->REGSC & PMC_REGSC_ACKISO_MASK);
+}
+
+/*!
+ * @brief Acknowledge to Peripherals and I/O pads isolation flag.
+ *
+ * This function clears the ACK Isolation flag. Writing one to this setting
+ * when it is set releases the I/O pads and certain peripherals to their normal
+ * run mode state.
+ *
+ * @param base PMC peripheral base address.
+ */
+static inline void PMC_ClearPeriphIOIsolationFlag(PMC_Type *base)
+{
+ base->REGSC |= PMC_REGSC_ACKISO_MASK;
+}
+#endif /* FSL_FEATURE_PMC_HAS_ACKISO */
+
+#if (defined(FSL_FEATURE_PMC_HAS_REGONS) && FSL_FEATURE_PMC_HAS_REGONS)
+/*!
+ * @brief Gets the Regulator regulation status.
+ *
+ * This function returns the regulator to a run regulation status. It provides
+ * the current status of the internal voltage regulator.
+ *
+ * @param base PMC peripheral base address.
+ * @param base Base address for current PMC instance.
+ * @return Regulation status
+ * 0 - Regulator is in a stop regulation or in transition to/from the regulation.
+ * 1 - Regulator is in a run regulation.
+ *
+ */
+static inline bool PMC_IsRegulatorInRunRegulation(PMC_Type *base)
+{
+ return (bool)(base->REGSC & PMC_REGSC_REGONS_MASK);
+}
+#endif /* FSL_FEATURE_PMC_HAS_REGONS */
+
+/*@}*/
+
+#if defined(__cplusplus)
+}
+#endif /* __cplusplus*/
+
+/*! @}*/
+
+#endif /* _FSL_PMC_H_*/
diff --git a/drivers/fsl_port.h b/drivers/fsl_port.h
new file mode 100644
index 0000000..935b032
--- /dev/null
+++ b/drivers/fsl_port.h
@@ -0,0 +1,381 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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 SDRVL 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_PORT_H_
+#define _FSL_PORT_H_
+
+#include "fsl_common.h"
+
+/*!
+ * @addtogroup port
+ * @{
+ */
+
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+/*! @name Driver version */
+/*@{*/
+/*! Version 2.0.1. */
+#define FSL_PORT_DRIVER_VERSION (MAKE_VERSION(2, 0, 1))
+/*@}*/
+
+/*! @brief Internal resistor pull feature selection */
+enum _port_pull
+{
+ kPORT_PullDisable = 0U, /*!< Internal pull-up/down resistor is disabled. */
+ kPORT_PullDown = 2U, /*!< Internal pull-down resistor is enabled. */
+ kPORT_PullUp = 3U, /*!< Internal pull-up resistor is enabled. */
+};
+
+/*! @brief Slew rate selection */
+enum _port_slew_rate
+{
+ kPORT_FastSlewRate = 0U, /*!< Fast slew rate is configured. */
+ kPORT_SlowSlewRate = 1U, /*!< Slow slew rate is configured. */
+};
+
+#if defined(FSL_FEATURE_PORT_HAS_OPEN_DRAIN) && FSL_FEATURE_PORT_HAS_OPEN_DRAIN
+/*! @brief Internal resistor pull feature enable/disable */
+enum _port_open_drain_enable
+{
+ kPORT_OpenDrainDisable = 0U, /*!< Internal pull-down resistor is disabled. */
+ kPORT_OpenDrainEnable = 1U, /*!< Internal pull-up resistor is enabled. */
+};
+#endif /* FSL_FEATURE_PORT_HAS_OPEN_DRAIN */
+
+/*! @brief Passive filter feature enable/disable */
+enum _port_passive_filter_enable
+{
+ kPORT_PassiveFilterDisable = 0U, /*!< Fast slew rate is configured. */
+ kPORT_PassiveFilterEnable = 1U, /*!< Slow slew rate is configured. */
+};
+
+/*! @brief Configures the drive strength. */
+enum _port_drive_strength
+{
+ kPORT_LowDriveStrength = 0U, /*!< Low-drive strength is configured. */
+ kPORT_HighDriveStrength = 1U, /*!< High-drive strength is configured. */
+};
+
+#if defined(FSL_FEATURE_PORT_HAS_PIN_CONTROL_LOCK) && FSL_FEATURE_PORT_HAS_PIN_CONTROL_LOCK
+/*! @brief Unlock/lock the pin control register field[15:0] */
+enum _port_lock_register
+{
+ kPORT_UnlockRegister = 0U, /*!< Pin Control Register fields [15:0] are not locked. */
+ kPORT_LockRegister = 1U, /*!< Pin Control Register fields [15:0] are locked. */
+};
+#endif /* FSL_FEATURE_PORT_HAS_PIN_CONTROL_LOCK */
+
+/*! @brief Pin mux selection */
+typedef enum _port_mux
+{
+ kPORT_PinDisabledOrAnalog = 0U, /*!< Corresponding pin is disabled, but is used as an analog pin. */
+ kPORT_MuxAsGpio = 1U, /*!< Corresponding pin is configured as GPIO. */
+ kPORT_MuxAlt2 = 2U, /*!< Chip-specific */
+ kPORT_MuxAlt3 = 3U, /*!< Chip-specific */
+ kPORT_MuxAlt4 = 4U, /*!< Chip-specific */
+ kPORT_MuxAlt5 = 5U, /*!< Chip-specific */
+ kPORT_MuxAlt6 = 6U, /*!< Chip-specific */
+ kPORT_MuxAlt7 = 7U, /*!< Chip-specific */
+} port_mux_t;
+
+/*! @brief Configures the interrupt generation condition. */
+typedef enum _port_interrupt
+{
+ kPORT_InterruptOrDMADisabled = 0x0U, /*!< Interrupt/DMA request is disabled. */
+#if defined(FSL_FEATURE_PORT_HAS_DMA_REQUEST) && FSL_FEATURE_PORT_HAS_DMA_REQUEST
+ kPORT_DMARisingEdge = 0x1U, /*!< DMA request on rising edge. */
+ kPORT_DMAFallingEdge = 0x2U, /*!< DMA request on falling edge. */
+ kPORT_DMAEitherEdge = 0x3U, /*!< DMA request on either edge. */
+#endif
+#if defined(FSL_FEATURE_PORT_HAS_IRQC_FLAG) && FSL_FEATURE_PORT_HAS_IRQC_FLAG
+ kPORT_FlagRisingEdge = 0x05U, /*!< Flag sets on rising edge. */
+ kPORT_FlagFallingEdge = 0x06U, /*!< Flag sets on falling edge. */
+ kPORT_FlagEitherEdge = 0x07U, /*!< Flag sets on either edge. */
+#endif
+ kPORT_InterruptLogicZero = 0x8U, /*!< Interrupt when logic zero. */
+ kPORT_InterruptRisingEdge = 0x9U, /*!< Interrupt on rising edge. */
+ kPORT_InterruptFallingEdge = 0xAU, /*!< Interrupt on falling edge. */
+ kPORT_InterruptEitherEdge = 0xBU, /*!< Interrupt on either edge. */
+ kPORT_InterruptLogicOne = 0xCU, /*!< Interrupt when logic one. */
+#if defined(FSL_FEATURE_PORT_HAS_IRQC_TRIGGER) && FSL_FEATURE_PORT_HAS_IRQC_TRIGGER
+ kPORT_ActiveHighTriggerOutputEnable = 0xDU, /*!< Enable active high-trigger output. */
+ kPORT_ActiveLowTriggerOutputEnable = 0xEU, /*!< Enable active low-trigger output. */
+#endif
+} port_interrupt_t;
+
+#if defined(FSL_FEATURE_PORT_HAS_DIGITAL_FILTER) && FSL_FEATURE_PORT_HAS_DIGITAL_FILTER
+/*! @brief Digital filter clock source selection */
+typedef enum _port_digital_filter_clock_source
+{
+ kPORT_BusClock = 0U, /*!< Digital filters are clocked by the bus clock. */
+ kPORT_LpoClock = 1U, /*!< Digital filters are clocked by the 1 kHz LPO clock. */
+} port_digital_filter_clock_source_t;
+
+/*! @brief PORT digital filter feature configuration definition */
+typedef struct _port_digital_filter_config
+{
+ uint32_t digitalFilterWidth; /*!< Set digital filter width */
+ port_digital_filter_clock_source_t clockSource; /*!< Set digital filter clockSource */
+} port_digital_filter_config_t;
+#endif /* FSL_FEATURE_PORT_HAS_DIGITAL_FILTER */
+
+/*! @brief PORT pin configuration structure */
+typedef struct _port_pin_config
+{
+ uint16_t pullSelect : 2; /*!< No-pull/pull-down/pull-up select */
+ uint16_t slewRate : 1; /*!< Fast/slow slew rate Configure */
+ uint16_t : 1;
+ uint16_t passiveFilterEnable : 1; /*!< Passive filter enable/disable */
+#if defined(FSL_FEATURE_PORT_HAS_OPEN_DRAIN) && FSL_FEATURE_PORT_HAS_OPEN_DRAIN
+ uint16_t openDrainEnable : 1; /*!< Open drain enable/disable */
+#else
+ uint16_t : 1;
+#endif /* FSL_FEATURE_PORT_HAS_OPEN_DRAIN */
+ uint16_t driveStrength : 1; /*!< Fast/slow drive strength configure */
+ uint16_t : 1;
+ uint16_t mux : 3; /*!< Pin mux Configure */
+ uint16_t : 4;
+#if defined(FSL_FEATURE_PORT_HAS_PIN_CONTROL_LOCK) && FSL_FEATURE_PORT_HAS_PIN_CONTROL_LOCK
+ uint16_t lockRegister : 1; /*!< Lock/unlock the PCR field[15:0] */
+#else
+ uint16_t : 1;
+#endif /* FSL_FEATURE_PORT_HAS_PIN_CONTROL_LOCK */
+} port_pin_config_t;
+
+/*******************************************************************************
+ * API
+ ******************************************************************************/
+
+#if defined(__cplusplus)
+extern "C" {
+#endif
+
+/*! @name Configuration */
+/*@{*/
+
+/*!
+ * @brief Sets the port PCR register.
+ *
+ * This is an example to define an input pin or output pin PCR configuration:
+ * @code
+ * // Define a digital input pin PCR configuration
+ * port_pin_config_t config = {
+ * kPORT_PullUp,
+ * kPORT_FastSlewRate,
+ * kPORT_PassiveFilterDisable,
+ * kPORT_OpenDrainDisable,
+ * kPORT_LowDriveStrength,
+ * kPORT_MuxAsGpio,
+ * kPORT_UnLockRegister,
+ * };
+ * @endcode
+ *
+ * @param base PORT peripheral base pointer.
+ * @param pin PORT pin number.
+ * @param config PORT PCR register configuration structure.
+ */
+static inline void PORT_SetPinConfig(PORT_Type *base, uint32_t pin, const port_pin_config_t *config)
+{
+ assert(config);
+ uint32_t addr = (uint32_t)&base->PCR[pin];
+ *(volatile uint16_t *)(addr) = *((const uint16_t *)config);
+}
+
+/*!
+ * @brief Sets the port PCR register for multiple pins.
+ *
+ * This is an example to define input pins or output pins PCR configuration:
+ * @code
+ * // Define a digital input pin PCR configuration
+ * port_pin_config_t config = {
+ * kPORT_PullUp ,
+ * kPORT_PullEnable,
+ * kPORT_FastSlewRate,
+ * kPORT_PassiveFilterDisable,
+ * kPORT_OpenDrainDisable,
+ * kPORT_LowDriveStrength,
+ * kPORT_MuxAsGpio,
+ * kPORT_UnlockRegister,
+ * };
+ * @endcode
+ *
+ * @param base PORT peripheral base pointer.
+ * @param mask PORT pin number macro.
+ * @param config PORT PCR register configuration structure.
+ */
+static inline void PORT_SetMultiplePinsConfig(PORT_Type *base, uint32_t mask, const port_pin_config_t *config)
+{
+ assert(config);
+
+ uint16_t pcrl = *((const uint16_t *)config);
+
+ if (mask & 0xffffU)
+ {
+ base->GPCLR = ((mask & 0xffffU) << 16) | pcrl;
+ }
+ if (mask >> 16)
+ {
+ base->GPCHR = (mask & 0xffff0000U) | pcrl;
+ }
+}
+
+/*!
+ * @brief Configures the pin muxing.
+ *
+ * @param base PORT peripheral base pointer.
+ * @param pin PORT pin number.
+ * @param mux pin muxing slot selection.
+ * - #kPORT_PinDisabledOrAnalog: Pin disabled or work in analog function.
+ * - #kPORT_MuxAsGpio : Set as GPIO.
+ * - #kPORT_MuxAlt2 : chip-specific.
+ * - #kPORT_MuxAlt3 : chip-specific.
+ * - #kPORT_MuxAlt4 : chip-specific.
+ * - #kPORT_MuxAlt5 : chip-specific.
+ * - #kPORT_MuxAlt6 : chip-specific.
+ * - #kPORT_MuxAlt7 : chip-specific.
+ * @Note : This function is NOT recommended to use together with the PORT_SetPinsConfig, because
+ * the PORT_SetPinsConfig need to configure the pin mux anyway (Otherwise the pin mux is
+ * reset to zero : kPORT_PinDisabledOrAnalog).
+ * This function is recommended to use to reset the pin mux
+ *
+ */
+static inline void PORT_SetPinMux(PORT_Type *base, uint32_t pin, port_mux_t mux)
+{
+ base->PCR[pin] = (base->PCR[pin] & ~PORT_PCR_MUX_MASK) | PORT_PCR_MUX(mux);
+}
+
+#if defined(FSL_FEATURE_PORT_HAS_DIGITAL_FILTER) && FSL_FEATURE_PORT_HAS_DIGITAL_FILTER
+
+/*!
+ * @brief Enables the digital filter in one port, each bit of the 32-bit register represents one pin.
+ *
+ * @param base PORT peripheral base pointer.
+ * @param mask PORT pin number macro.
+ */
+static inline void PORT_EnablePinsDigitalFilter(PORT_Type *base, uint32_t mask, bool enable)
+{
+ if (enable == true)
+ {
+ base->DFER |= mask;
+ }
+ else
+ {
+ base->DFER &= ~mask;
+ }
+}
+
+/*!
+ * @brief Sets the digital filter in one port, each bit of the 32-bit register represents one pin.
+ *
+ * @param base PORT peripheral base pointer.
+ * @param config PORT digital filter configuration structure.
+ */
+static inline void PORT_SetDigitalFilterConfig(PORT_Type *base, const port_digital_filter_config_t *config)
+{
+ assert(config);
+
+ base->DFCR = PORT_DFCR_CS(config->clockSource);
+ base->DFWR = PORT_DFWR_FILT(config->digitalFilterWidth);
+}
+
+#endif /* FSL_FEATURE_PORT_HAS_DIGITAL_FILTER */
+
+/*@}*/
+
+/*! @name Interrupt */
+/*@{*/
+
+/*!
+ * @brief Configures the port pin interrupt/DMA request.
+ *
+ * @param base PORT peripheral base pointer.
+ * @param pin PORT pin number.
+ * @param config PORT pin interrupt configuration.
+ * - #kPORT_InterruptOrDMADisabled: Interrupt/DMA request disabled.
+ * - #kPORT_DMARisingEdge : DMA request on rising edge(if the DMA requests exit).
+ * - #kPORT_DMAFallingEdge: DMA request on falling edge(if the DMA requests exit).
+ * - #kPORT_DMAEitherEdge : DMA request on either edge(if the DMA requests exit).
+ * - #kPORT_FlagRisingEdge : Flag sets on rising edge(if the Flag states exit).
+ * - #kPORT_FlagFallingEdge : Flag sets on falling edge(if the Flag states exit).
+ * - #kPORT_FlagEitherEdge : Flag sets on either edge(if the Flag states exit).
+ * - #kPORT_InterruptLogicZero : Interrupt when logic zero.
+ * - #kPORT_InterruptRisingEdge : Interrupt on rising edge.
+ * - #kPORT_InterruptFallingEdge: Interrupt on falling edge.
+ * - #kPORT_InterruptEitherEdge : Interrupt on either edge.
+ * - #kPORT_InterruptLogicOne : Interrupt when logic one.
+ * - #kPORT_ActiveHighTriggerOutputEnable : Enable active high-trigger output (if the trigger states exit).
+ * - #kPORT_ActiveLowTriggerOutputEnable : Enable active low-trigger output (if the trigger states exit).
+ */
+static inline void PORT_SetPinInterruptConfig(PORT_Type *base, uint32_t pin, port_interrupt_t config)
+{
+ base->PCR[pin] = (base->PCR[pin] & ~PORT_PCR_IRQC_MASK) | PORT_PCR_IRQC(config);
+}
+
+/*!
+ * @brief Reads the whole port status flag.
+ *
+ * If a pin is configured to generate the DMA request, the corresponding flag
+ * is cleared automatically at the completion of the requested DMA transfer.
+ * Otherwise, the flag remains set until a logic one is written to that flag.
+ * If configured for a level sensitive interrupt that remains asserted, the flag
+ * is set again immediately.
+ *
+ * @param base PORT peripheral base pointer.
+ * @return Current port interrupt status flags, for example, 0x00010001 means the
+ * pin 0 and 17 have the interrupt.
+ */
+static inline uint32_t PORT_GetPinsInterruptFlags(PORT_Type *base)
+{
+ return base->ISFR;
+}
+
+/*!
+ * @brief Clears the multiple pin interrupt status flag.
+ *
+ * @param base PORT peripheral base pointer.
+ * @param mask PORT pin number macro.
+ */
+static inline void PORT_ClearPinsInterruptFlags(PORT_Type *base, uint32_t mask)
+{
+ base->ISFR = mask;
+}
+
+/*@}*/
+
+#if defined(__cplusplus)
+}
+#endif
+
+/*! @}*/
+
+#endif /* _FSL_PORT_H_ */
diff --git a/drivers/fsl_rcm.c b/drivers/fsl_rcm.c
new file mode 100644
index 0000000..9cf7479
--- /dev/null
+++ b/drivers/fsl_rcm.c
@@ -0,0 +1,65 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_rcm.h"
+
+void RCM_ConfigureResetPinFilter(RCM_Type *base, const rcm_reset_pin_filter_config_t *config)
+{
+ assert(config);
+
+#if (defined(FSL_FEATURE_RCM_REG_WIDTH) && (FSL_FEATURE_RCM_REG_WIDTH == 32))
+ uint32_t reg;
+
+ reg = (((uint32_t)config->enableFilterInStop << RCM_RPC_RSTFLTSS_SHIFT) | (uint32_t)config->filterInRunWait);
+ if (config->filterInRunWait == kRCM_FilterBusClock)
+ {
+ reg |= ((uint32_t)config->busClockFilterCount << RCM_RPC_RSTFLTSEL_SHIFT);
+ }
+ base->RPC = reg;
+#else
+ base->RPFC = ((uint8_t)(config->enableFilterInStop << RCM_RPFC_RSTFLTSS_SHIFT) | (uint8_t)config->filterInRunWait);
+ if (config->filterInRunWait == kRCM_FilterBusClock)
+ {
+ base->RPFW = config->busClockFilterCount;
+ }
+#endif /* FSL_FEATURE_RCM_REG_WIDTH */
+}
+
+#if (defined(FSL_FEATURE_RCM_HAS_BOOTROM) && FSL_FEATURE_RCM_HAS_BOOTROM)
+void RCM_SetForceBootRomSource(RCM_Type *base, rcm_boot_rom_config_t config)
+{
+ uint32_t reg;
+
+ reg = base->FM;
+ reg &= ~RCM_FM_FORCEROM_MASK;
+ reg |= ((uint32_t)config << RCM_FM_FORCEROM_SHIFT);
+ base->FM = reg;
+}
+#endif /* #if FSL_FEATURE_RCM_HAS_BOOTROM */
diff --git a/drivers/fsl_rcm.h b/drivers/fsl_rcm.h
new file mode 100644
index 0000000..fbc5169
--- /dev/null
+++ b/drivers/fsl_rcm.h
@@ -0,0 +1,431 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_RCM_H_
+#define _FSL_RCM_H_
+
+#include "fsl_common.h"
+
+/*! @addtogroup rcm */
+/*! @{*/
+
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+/*! @name Driver version */
+/*@{*/
+/*! @brief RCM driver version 2.0.1. */
+#define FSL_RCM_DRIVER_VERSION (MAKE_VERSION(2, 0, 1))
+/*@}*/
+
+/*!
+ * @brief System Reset Source Name definitions
+ */
+typedef enum _rcm_reset_source
+{
+#if (defined(FSL_FEATURE_RCM_REG_WIDTH) && (FSL_FEATURE_RCM_REG_WIDTH == 32))
+/* RCM register bit width is 32. */
+#if (defined(FSL_FEATURE_RCM_HAS_WAKEUP) && FSL_FEATURE_RCM_HAS_WAKEUP)
+ kRCM_SourceWakeup = RCM_SRS_WAKEUP_MASK, /*!< Low-leakage wakeup reset */
+#endif
+ kRCM_SourceLvd = RCM_SRS_LVD_MASK, /*!< Low-voltage detect reset */
+#if (defined(FSL_FEATURE_RCM_HAS_LOC) && FSL_FEATURE_RCM_HAS_LOC)
+ kRCM_SourceLoc = RCM_SRS_LOC_MASK, /*!< Loss of clock reset */
+#endif /* FSL_FEATURE_RCM_HAS_LOC */
+#if (defined(FSL_FEATURE_RCM_HAS_LOL) && FSL_FEATURE_RCM_HAS_LOL)
+ kRCM_SourceLol = RCM_SRS_LOL_MASK, /*!< Loss of lock reset */
+#endif /* FSL_FEATURE_RCM_HAS_LOL */
+ kRCM_SourceWdog = RCM_SRS_WDOG_MASK, /*!< Watchdog reset */
+ kRCM_SourcePin = RCM_SRS_PIN_MASK, /*!< External pin reset */
+ kRCM_SourcePor = RCM_SRS_POR_MASK, /*!< Power on reset */
+#if (defined(FSL_FEATURE_RCM_HAS_JTAG) && FSL_FEATURE_RCM_HAS_JTAG)
+ kRCM_SourceJtag = RCM_SRS_JTAG_MASK, /*!< JTAG generated reset */
+#endif /* FSL_FEATURE_RCM_HAS_JTAG */
+ kRCM_SourceLockup = RCM_SRS_LOCKUP_MASK, /*!< Core lock up reset */
+ kRCM_SourceSw = RCM_SRS_SW_MASK, /*!< Software reset */
+#if (defined(FSL_FEATURE_RCM_HAS_MDM_AP) && FSL_FEATURE_RCM_HAS_MDM_AP)
+ kRCM_SourceMdmap = RCM_SRS_MDM_AP_MASK, /*!< MDM-AP system reset */
+#endif /* FSL_FEATURE_RCM_HAS_MDM_AP */
+#if (defined(FSL_FEATURE_RCM_HAS_EZPORT) && FSL_FEATURE_RCM_HAS_EZPORT)
+ kRCM_SourceEzpt = RCM_SRS_EZPT_MASK, /*!< EzPort reset */
+#endif /* FSL_FEATURE_RCM_HAS_EZPORT */
+ kRCM_SourceSackerr = RCM_SRS_SACKERR_MASK, /*!< Parameter could get all reset flags */
+
+#else /* (FSL_FEATURE_RCM_REG_WIDTH == 32) */
+/* RCM register bit width is 8. */
+#if (defined(FSL_FEATURE_RCM_HAS_WAKEUP) && FSL_FEATURE_RCM_HAS_WAKEUP)
+ kRCM_SourceWakeup = RCM_SRS0_WAKEUP_MASK, /*!< Low-leakage wakeup reset */
+#endif
+ kRCM_SourceLvd = RCM_SRS0_LVD_MASK, /*!< Low-voltage detect reset */
+#if (defined(FSL_FEATURE_RCM_HAS_LOC) && FSL_FEATURE_RCM_HAS_LOC)
+ kRCM_SourceLoc = RCM_SRS0_LOC_MASK, /*!< Loss of clock reset */
+#endif /* FSL_FEATURE_RCM_HAS_LOC */
+#if (defined(FSL_FEATURE_RCM_HAS_LOL) && FSL_FEATURE_RCM_HAS_LOL)
+ kRCM_SourceLol = RCM_SRS0_LOL_MASK, /*!< Loss of lock reset */
+#endif /* FSL_FEATURE_RCM_HAS_LOL */
+ kRCM_SourceWdog = RCM_SRS0_WDOG_MASK, /*!< Watchdog reset */
+ kRCM_SourcePin = RCM_SRS0_PIN_MASK, /*!< External pin reset */
+ kRCM_SourcePor = RCM_SRS0_POR_MASK, /*!< Power on reset */
+#if (defined(FSL_FEATURE_RCM_HAS_JTAG) && FSL_FEATURE_RCM_HAS_JTAG)
+ kRCM_SourceJtag = RCM_SRS1_JTAG_MASK << 8U, /*!< JTAG generated reset */
+#endif /* FSL_FEATURE_RCM_HAS_JTAG */
+ kRCM_SourceLockup = RCM_SRS1_LOCKUP_MASK << 8U, /*!< Core lock up reset */
+ kRCM_SourceSw = RCM_SRS1_SW_MASK << 8U, /*!< Software reset */
+#if (defined(FSL_FEATURE_RCM_HAS_MDM_AP) && FSL_FEATURE_RCM_HAS_MDM_AP)
+ kRCM_SourceMdmap = RCM_SRS1_MDM_AP_MASK << 8U, /*!< MDM-AP system reset */
+#endif /* FSL_FEATURE_RCM_HAS_MDM_AP */
+#if (defined(FSL_FEATURE_RCM_HAS_EZPORT) && FSL_FEATURE_RCM_HAS_EZPORT)
+ kRCM_SourceEzpt = RCM_SRS1_EZPT_MASK << 8U, /*!< EzPort reset */
+#endif /* FSL_FEATURE_RCM_HAS_EZPORT */
+ kRCM_SourceSackerr = RCM_SRS1_SACKERR_MASK << 8U, /*!< Parameter could get all reset flags */
+#endif /* (FSL_FEATURE_RCM_REG_WIDTH == 32) */
+ kRCM_SourceAll = 0xffffffffU,
+} rcm_reset_source_t;
+
+/*!
+ * @brief Reset pin filter select in Run and Wait modes
+ */
+typedef enum _rcm_run_wait_filter_mode
+{
+ kRCM_FilterDisable = 0U, /*!< All filtering disabled */
+ kRCM_FilterBusClock = 1U, /*!< Bus clock filter enabled */
+ kRCM_FilterLpoClock = 2U /*!< LPO clock filter enabled */
+} rcm_run_wait_filter_mode_t;
+
+#if (defined(FSL_FEATURE_RCM_HAS_BOOTROM) && FSL_FEATURE_RCM_HAS_BOOTROM)
+/*!
+ * @brief Boot from ROM configuration.
+ */
+typedef enum _rcm_boot_rom_config
+{
+ kRCM_BootFlash = 0U, /*!< Boot from flash */
+ kRCM_BootRomCfg0 = 1U, /*!< Boot from boot ROM due to BOOTCFG0 */
+ kRCM_BootRomFopt = 2U, /*!< Boot from boot ROM due to FOPT[7] */
+ kRCM_BootRomBoth = 3U /*!< Boot from boot ROM due to both BOOTCFG0 and FOPT[7] */
+} rcm_boot_rom_config_t;
+#endif /* FSL_FEATURE_RCM_HAS_BOOTROM */
+
+#if (defined(FSL_FEATURE_RCM_HAS_SRIE) && FSL_FEATURE_RCM_HAS_SRIE)
+/*!
+ * @brief Max delay time from interrupt asserts to system reset.
+ */
+typedef enum _rcm_reset_delay
+{
+ kRCM_ResetDelay8Lpo = 0U, /*!< Delay 8 LPO cycles. */
+ kRCM_ResetDelay32Lpo = 1U, /*!< Delay 32 LPO cycles. */
+ kRCM_ResetDelay128Lpo = 2U, /*!< Delay 128 LPO cycles. */
+ kRCM_ResetDelay512Lpo = 3U /*!< Delay 512 LPO cycles. */
+} rcm_reset_delay_t;
+
+/*!
+ * @brief System reset interrupt enable bit definitions.
+ */
+typedef enum _rcm_interrupt_enable
+{
+ kRCM_IntNone = 0U, /*!< No interrupt enabled. */
+ kRCM_IntLossOfClk = RCM_SRIE_LOC_MASK, /*!< Loss of clock interrupt. */
+ kRCM_IntLossOfLock = RCM_SRIE_LOL_MASK, /*!< Loss of lock interrupt. */
+ kRCM_IntWatchDog = RCM_SRIE_WDOG_MASK, /*!< Watch dog interrupt. */
+ kRCM_IntExternalPin = RCM_SRIE_PIN_MASK, /*!< External pin interrupt. */
+ kRCM_IntGlobal = RCM_SRIE_GIE_MASK, /*!< Global interrupts. */
+ kRCM_IntCoreLockup = RCM_SRIE_LOCKUP_MASK, /*!< Core lock up interrupt */
+ kRCM_IntSoftware = RCM_SRIE_SW_MASK, /*!< software interrupt */
+ kRCM_IntStopModeAckErr = RCM_SRIE_SACKERR_MASK, /*!< Stop mode ACK error interrupt. */
+#if (defined(FSL_FEATURE_RCM_HAS_CORE1) && FSL_FEATURE_RCM_HAS_CORE1)
+ kRCM_IntCore1 = RCM_SRIE_CORE1_MASK, /*!< Core 1 interrupt. */
+#endif
+ kRCM_IntAll = RCM_SRIE_LOC_MASK /*!< Enable all interrupts. */
+ |
+ RCM_SRIE_LOL_MASK | RCM_SRIE_WDOG_MASK | RCM_SRIE_PIN_MASK | RCM_SRIE_GIE_MASK |
+ RCM_SRIE_LOCKUP_MASK | RCM_SRIE_SW_MASK | RCM_SRIE_SACKERR_MASK
+#if (defined(FSL_FEATURE_RCM_HAS_CORE1) && FSL_FEATURE_RCM_HAS_CORE1)
+ |
+ RCM_SRIE_CORE1_MASK
+#endif
+} rcm_interrupt_enable_t;
+#endif /* FSL_FEATURE_RCM_HAS_SRIE */
+
+#if (defined(FSL_FEATURE_RCM_HAS_VERID) && FSL_FEATURE_RCM_HAS_VERID)
+/*!
+ * @brief IP version ID definition.
+ */
+typedef struct _rcm_version_id
+{
+ uint16_t feature; /*!< Feature Specification Number. */
+ uint8_t minor; /*!< Minor version number. */
+ uint8_t major; /*!< Major version number. */
+} rcm_version_id_t;
+#endif
+
+/*!
+ * @brief Reset pin filter configuration
+ */
+typedef struct _rcm_reset_pin_filter_config
+{
+ bool enableFilterInStop; /*!< Reset pin filter select in stop mode. */
+ rcm_run_wait_filter_mode_t filterInRunWait; /*!< Reset pin filter in run/wait mode. */
+ uint8_t busClockFilterCount; /*!< Reset pin bus clock filter width. */
+} rcm_reset_pin_filter_config_t;
+
+/*******************************************************************************
+ * API
+ ******************************************************************************/
+#if defined(__cplusplus)
+extern "C" {
+#endif /* __cplusplus*/
+
+/*! @name Reset Control Module APIs*/
+/*@{*/
+
+#if (defined(FSL_FEATURE_RCM_HAS_VERID) && FSL_FEATURE_RCM_HAS_VERID)
+/*!
+ * @brief Gets the RCM version ID.
+ *
+ * This function gets the RCM version ID including the major version number,
+ * the minor version number, and the feature specification number.
+ *
+ * @param base RCM peripheral base address.
+ * @param versionId Pointer to version ID structure.
+ */
+static inline void RCM_GetVersionId(RCM_Type *base, rcm_version_id_t *versionId)
+{
+ *((uint32_t *)versionId) = base->VERID;
+}
+#endif
+
+#if (defined(FSL_FEATURE_RCM_HAS_PARAM) && FSL_FEATURE_RCM_HAS_PARAM)
+/*!
+ * @brief Gets the reset source implemented status.
+ *
+ * This function gets the RCM parameter that indicates whether the corresponding reset source is implemented.
+ * Use source masks defined in the rcm_reset_source_t to get the desired source status.
+ *
+ * Example:
+ @code
+ uint32_t status;
+
+ // To test whether the MCU is reset using Watchdog.
+ status = RCM_GetResetSourceImplementedStatus(RCM) & (kRCM_SourceWdog | kRCM_SourcePin);
+ @endcode
+ *
+ * @param base RCM peripheral base address.
+ * @return All reset source implemented status bit map.
+ */
+static inline uint32_t RCM_GetResetSourceImplementedStatus(RCM_Type *base)
+{
+ return base->PARAM;
+}
+#endif /* FSL_FEATURE_RCM_HAS_PARAM */
+
+/*!
+ * @brief Gets the reset source status which caused a previous reset.
+ *
+ * This function gets the current reset source status. Use source masks
+ * defined in the rcm_reset_source_t to get the desired source status.
+ *
+ * Example:
+ @code
+ uint32_t resetStatus;
+
+ // To get all reset source statuses.
+ resetStatus = RCM_GetPreviousResetSources(RCM) & kRCM_SourceAll;
+
+ // To test whether the MCU is reset using Watchdog.
+ resetStatus = RCM_GetPreviousResetSources(RCM) & kRCM_SourceWdog;
+
+ // To test multiple reset sources.
+ resetStatus = RCM_GetPreviousResetSources(RCM) & (kRCM_SourceWdog | kRCM_SourcePin);
+ @endcode
+ *
+ * @param base RCM peripheral base address.
+ * @return All reset source status bit map.
+ */
+static inline uint32_t RCM_GetPreviousResetSources(RCM_Type *base)
+{
+#if (defined(FSL_FEATURE_RCM_REG_WIDTH) && (FSL_FEATURE_RCM_REG_WIDTH == 32))
+ return base->SRS;
+#else
+ return (uint32_t)((uint32_t)base->SRS0 | ((uint32_t)base->SRS1 << 8U));
+#endif /* (FSL_FEATURE_RCM_REG_WIDTH == 32) */
+}
+
+#if (defined(FSL_FEATURE_RCM_HAS_SSRS) && FSL_FEATURE_RCM_HAS_SSRS)
+/*!
+ * @brief Gets the sticky reset source status.
+ *
+ * This function gets the current reset source status that has not been cleared
+ * by software for some specific source.
+ *
+ * Example:
+ @code
+ uint32_t resetStatus;
+
+ // To get all reset source statuses.
+ resetStatus = RCM_GetStickyResetSources(RCM) & kRCM_SourceAll;
+
+ // To test whether the MCU is reset using Watchdog.
+ resetStatus = RCM_GetStickyResetSources(RCM) & kRCM_SourceWdog;
+
+ // To test multiple reset sources.
+ resetStatus = RCM_GetStickyResetSources(RCM) & (kRCM_SourceWdog | kRCM_SourcePin);
+ @endcode
+ *
+ * @param base RCM peripheral base address.
+ * @return All reset source status bit map.
+ */
+static inline uint32_t RCM_GetStickyResetSources(RCM_Type *base)
+{
+#if (defined(FSL_FEATURE_RCM_REG_WIDTH) && (FSL_FEATURE_RCM_REG_WIDTH == 32))
+ return base->SSRS;
+#else
+ return (base->SSRS0 | ((uint32_t)base->SSRS1 << 8U));
+#endif /* (FSL_FEATURE_RCM_REG_WIDTH == 32) */
+}
+
+/*!
+ * @brief Clears the sticky reset source status.
+ *
+ * This function clears the sticky system reset flags indicated by source masks.
+ *
+ * Example:
+ @code
+ // Clears multiple reset sources.
+ RCM_ClearStickyResetSources(kRCM_SourceWdog | kRCM_SourcePin);
+ @endcode
+ *
+ * @param base RCM peripheral base address.
+ * @param sourceMasks reset source status bit map
+ */
+static inline void RCM_ClearStickyResetSources(RCM_Type *base, uint32_t sourceMasks)
+{
+#if (defined(FSL_FEATURE_RCM_REG_WIDTH) && (FSL_FEATURE_RCM_REG_WIDTH == 32))
+ base->SSRS = sourceMasks;
+#else
+ base->SSRS0 = (sourceMasks & 0xffU);
+ base->SSRS1 = ((sourceMasks >> 8U) & 0xffU);
+#endif /* (FSL_FEATURE_RCM_REG_WIDTH == 32) */
+}
+#endif /* FSL_FEATURE_RCM_HAS_SSRS */
+
+/*!
+ * @brief Configures the reset pin filter.
+ *
+ * This function sets the reset pin filter including the filter source, filter
+ * width, and so on.
+ *
+ * @param base RCM peripheral base address.
+ * @param config Pointer to the configuration structure.
+ */
+void RCM_ConfigureResetPinFilter(RCM_Type *base, const rcm_reset_pin_filter_config_t *config);
+
+#if (defined(FSL_FEATURE_RCM_HAS_EZPMS) && FSL_FEATURE_RCM_HAS_EZPMS)
+/*!
+ * @brief Gets the EZP_MS_B pin assert status.
+ *
+ * This function gets the easy port mode status (EZP_MS_B) pin assert status.
+ *
+ * @param base RCM peripheral base address.
+ * @return status true - asserted, false - reasserted
+ */
+static inline bool RCM_GetEasyPortModePinStatus(RCM_Type *base)
+{
+ return (bool)(base->MR & RCM_MR_EZP_MS_MASK);
+}
+#endif /* FSL_FEATURE_RCM_HAS_EZPMS */
+
+#if (defined(FSL_FEATURE_RCM_HAS_BOOTROM) && FSL_FEATURE_RCM_HAS_BOOTROM)
+/*!
+ * @brief Gets the ROM boot source.
+ *
+ * This function gets the ROM boot source during the last chip reset.
+ *
+ * @param base RCM peripheral base address.
+ * @return The ROM boot source.
+ */
+static inline rcm_boot_rom_config_t RCM_GetBootRomSource(RCM_Type *base)
+{
+ return (rcm_boot_rom_config_t)((base->MR & RCM_MR_BOOTROM_MASK) >> RCM_MR_BOOTROM_SHIFT);
+}
+
+/*!
+ * @brief Clears the ROM boot source flag.
+ *
+ * This function clears the ROM boot source flag.
+ *
+ * @param base Register base address of RCM
+ */
+static inline void RCM_ClearBootRomSource(RCM_Type *base)
+{
+ base->MR |= RCM_MR_BOOTROM_MASK;
+}
+
+/*!
+ * @brief Forces the boot from ROM.
+ *
+ * This function forces booting from ROM during all subsequent system resets.
+ *
+ * @param base RCM peripheral base address.
+ * @param config Boot configuration.
+ */
+void RCM_SetForceBootRomSource(RCM_Type *base, rcm_boot_rom_config_t config);
+#endif /* FSL_FEATURE_RCM_HAS_BOOTROM */
+
+#if (defined(FSL_FEATURE_RCM_HAS_SRIE) && FSL_FEATURE_RCM_HAS_SRIE)
+/*!
+ * @brief Sets the system reset interrupt configuration.
+ *
+ * For a graceful shut down, the RCM supports delaying the assertion of the system
+ * reset for a period of time when the reset interrupt is generated. This function
+ * can be used to enable the interrupt and the delay period. The interrupts
+ * are passed in as bit mask. See rcm_int_t for details. For example, to
+ * delay a reset for 512 LPO cycles after the WDOG timeout or loss-of-clock occurs,
+ * configure as follows:
+ * RCM_SetSystemResetInterruptConfig(kRCM_IntWatchDog | kRCM_IntLossOfClk, kRCM_ResetDelay512Lpo);
+ *
+ * @param base RCM peripheral base address.
+ * @param intMask Bit mask of the system reset interrupts to enable. See
+ * rcm_interrupt_enable_t for details.
+ * @param Delay Bit mask of the system reset interrupts to enable.
+ */
+static inline void RCM_SetSystemResetInterruptConfig(RCM_Type *base, uint32_t intMask, rcm_reset_delay_t delay)
+{
+ base->SRIE = (intMask | delay);
+}
+#endif /* FSL_FEATURE_RCM_HAS_SRIE */
+/*@}*/
+
+#if defined(__cplusplus)
+}
+#endif /* __cplusplus*/
+
+/*! @}*/
+
+#endif /* _FSL_RCM_H_ */
diff --git a/drivers/fsl_rtc.c b/drivers/fsl_rtc.c
new file mode 100644
index 0000000..db6a2fa
--- /dev/null
+++ b/drivers/fsl_rtc.c
@@ -0,0 +1,379 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_rtc.h"
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+#define SECONDS_IN_A_DAY (86400U)
+#define SECONDS_IN_A_HOUR (3600U)
+#define SECONDS_IN_A_MINUTE (60U)
+#define DAYS_IN_A_YEAR (365U)
+#define YEAR_RANGE_START (1970U)
+#define YEAR_RANGE_END (2099U)
+
+/*******************************************************************************
+ * Prototypes
+ ******************************************************************************/
+/*!
+ * @brief Checks whether the date and time passed in is valid
+ *
+ * @param datetime Pointer to structure where the date and time details are stored
+ *
+ * @return Returns false if the date & time details are out of range; true if in range
+ */
+static bool RTC_CheckDatetimeFormat(const rtc_datetime_t *datetime);
+
+/*!
+ * @brief Converts time data from datetime to seconds
+ *
+ * @param datetime Pointer to datetime structure where the date and time details are stored
+ *
+ * @return The result of the conversion in seconds
+ */
+static uint32_t RTC_ConvertDatetimeToSeconds(const rtc_datetime_t *datetime);
+
+/*!
+ * @brief Converts time data from seconds to a datetime structure
+ *
+ * @param seconds Seconds value that needs to be converted to datetime format
+ * @param datetime Pointer to the datetime structure where the result of the conversion is stored
+ */
+static void RTC_ConvertSecondsToDatetime(uint32_t seconds, rtc_datetime_t *datetime);
+
+/*******************************************************************************
+ * Code
+ ******************************************************************************/
+static bool RTC_CheckDatetimeFormat(const rtc_datetime_t *datetime)
+{
+ assert(datetime);
+
+ /* Table of days in a month for a non leap year. First entry in the table is not used,
+ * valid months start from 1
+ */
+ uint8_t daysPerMonth[] = {0U, 31U, 28U, 31U, 30U, 31U, 30U, 31U, 31U, 30U, 31U, 30U, 31U};
+
+ /* Check year, month, hour, minute, seconds */
+ if ((datetime->year < YEAR_RANGE_START) || (datetime->year > YEAR_RANGE_END) || (datetime->month > 12U) ||
+ (datetime->month < 1U) || (datetime->hour >= 24U) || (datetime->minute >= 60U) || (datetime->second >= 60U))
+ {
+ /* If not correct then error*/
+ return false;
+ }
+
+ /* Adjust the days in February for a leap year */
+ if ((((datetime->year & 3U) == 0) && (datetime->year % 100 != 0)) || (datetime->year % 400 == 0))
+ {
+ daysPerMonth[2] = 29U;
+ }
+
+ /* Check the validity of the day */
+ if ((datetime->day > daysPerMonth[datetime->month]) || (datetime->day < 1U))
+ {
+ return false;
+ }
+
+ return true;
+}
+
+static uint32_t RTC_ConvertDatetimeToSeconds(const rtc_datetime_t *datetime)
+{
+ assert(datetime);
+
+ /* Number of days from begin of the non Leap-year*/
+ /* Number of days from begin of the non Leap-year*/
+ uint16_t monthDays[] = {0U, 0U, 31U, 59U, 90U, 120U, 151U, 181U, 212U, 243U, 273U, 304U, 334U};
+ uint32_t seconds;
+
+ /* Compute number of days from 1970 till given year*/
+ seconds = (datetime->year - 1970U) * DAYS_IN_A_YEAR;
+ /* Add leap year days */
+ seconds += ((datetime->year / 4) - (1970U / 4));
+ /* Add number of days till given month*/
+ seconds += monthDays[datetime->month];
+ /* Add days in given month. We subtract the current day as it is
+ * represented in the hours, minutes and seconds field*/
+ seconds += (datetime->day - 1);
+ /* For leap year if month less than or equal to Febraury, decrement day counter*/
+ if ((!(datetime->year & 3U)) && (datetime->month <= 2U))
+ {
+ seconds--;
+ }
+
+ seconds = (seconds * SECONDS_IN_A_DAY) + (datetime->hour * SECONDS_IN_A_HOUR) +
+ (datetime->minute * SECONDS_IN_A_MINUTE) + datetime->second;
+
+ return seconds;
+}
+
+static void RTC_ConvertSecondsToDatetime(uint32_t seconds, rtc_datetime_t *datetime)
+{
+ assert(datetime);
+
+ uint32_t x;
+ uint32_t secondsRemaining, days;
+ uint16_t daysInYear;
+ /* Table of days in a month for a non leap year. First entry in the table is not used,
+ * valid months start from 1
+ */
+ uint8_t daysPerMonth[] = {0U, 31U, 28U, 31U, 30U, 31U, 30U, 31U, 31U, 30U, 31U, 30U, 31U};
+
+ /* Start with the seconds value that is passed in to be converted to date time format */
+ secondsRemaining = seconds;
+
+ /* Calcuate the number of days, we add 1 for the current day which is represented in the
+ * hours and seconds field
+ */
+ days = secondsRemaining / SECONDS_IN_A_DAY + 1;
+
+ /* Update seconds left*/
+ secondsRemaining = secondsRemaining % SECONDS_IN_A_DAY;
+
+ /* Calculate the datetime hour, minute and second fields */
+ datetime->hour = secondsRemaining / SECONDS_IN_A_HOUR;
+ secondsRemaining = secondsRemaining % SECONDS_IN_A_HOUR;
+ datetime->minute = secondsRemaining / 60U;
+ datetime->second = secondsRemaining % SECONDS_IN_A_MINUTE;
+
+ /* Calculate year */
+ daysInYear = DAYS_IN_A_YEAR;
+ datetime->year = YEAR_RANGE_START;
+ while (days > daysInYear)
+ {
+ /* Decrease day count by a year and increment year by 1 */
+ days -= daysInYear;
+ datetime->year++;
+
+ /* Adjust the number of days for a leap year */
+ if (datetime->year & 3U)
+ {
+ daysInYear = DAYS_IN_A_YEAR;
+ }
+ else
+ {
+ daysInYear = DAYS_IN_A_YEAR + 1;
+ }
+ }
+
+ /* Adjust the days in February for a leap year */
+ if (!(datetime->year & 3U))
+ {
+ daysPerMonth[2] = 29U;
+ }
+
+ for (x = 1U; x <= 12U; x++)
+ {
+ if (days <= daysPerMonth[x])
+ {
+ datetime->month = x;
+ break;
+ }
+ else
+ {
+ days -= daysPerMonth[x];
+ }
+ }
+
+ datetime->day = days;
+}
+
+void RTC_Init(RTC_Type *base, const rtc_config_t *config)
+{
+ assert(config);
+
+ uint32_t reg;
+
+ CLOCK_EnableClock(kCLOCK_Rtc0);
+
+ /* Issue a software reset if timer is invalid */
+ if (RTC_GetStatusFlags(RTC) & kRTC_TimeInvalidFlag)
+ {
+ RTC_Reset(RTC);
+ }
+
+ reg = base->CR;
+ /* Setup the update mode and supervisor access mode */
+ reg &= ~(RTC_CR_UM_MASK | RTC_CR_SUP_MASK);
+ reg |= RTC_CR_UM(config->updateMode) | RTC_CR_SUP(config->supervisorAccess);
+#if defined(FSL_FEATURE_RTC_HAS_WAKEUP_PIN_SELECTION) && FSL_FEATURE_RTC_HAS_WAKEUP_PIN_SELECTION
+ /* Setup the wakeup pin select */
+ reg &= ~(RTC_CR_WPS_MASK);
+ reg |= RTC_CR_WPS(config->wakeupSelect);
+#endif /* FSL_FEATURE_RTC_HAS_WAKEUP_PIN */
+ base->CR = reg;
+
+ /* Configure the RTC time compensation register */
+ base->TCR = (RTC_TCR_CIR(config->compensationInterval) | RTC_TCR_TCR(config->compensationTime));
+}
+
+void RTC_GetDefaultConfig(rtc_config_t *config)
+{
+ assert(config);
+
+ /* Wakeup pin will assert if the RTC interrupt asserts or if the wakeup pin is turned on */
+ config->wakeupSelect = false;
+ /* Registers cannot be written when locked */
+ config->updateMode = false;
+ /* Non-supervisor mode write accesses are not supported and will generate a bus error */
+ config->supervisorAccess = false;
+ /* Compensation interval used by the crystal compensation logic */
+ config->compensationInterval = 0;
+ /* Compensation time used by the crystal compensation logic */
+ config->compensationTime = 0;
+}
+
+status_t RTC_SetDatetime(RTC_Type *base, const rtc_datetime_t *datetime)
+{
+ assert(datetime);
+
+ /* Return error if the time provided is not valid */
+ if (!(RTC_CheckDatetimeFormat(datetime)))
+ {
+ return kStatus_InvalidArgument;
+ }
+
+ /* Set time in seconds */
+ base->TSR = RTC_ConvertDatetimeToSeconds(datetime);
+
+ return kStatus_Success;
+}
+
+void RTC_GetDatetime(RTC_Type *base, rtc_datetime_t *datetime)
+{
+ assert(datetime);
+
+ uint32_t seconds = 0;
+
+ seconds = base->TSR;
+ RTC_ConvertSecondsToDatetime(seconds, datetime);
+}
+
+status_t RTC_SetAlarm(RTC_Type *base, const rtc_datetime_t *alarmTime)
+{
+ assert(alarmTime);
+
+ uint32_t alarmSeconds = 0;
+ uint32_t currSeconds = 0;
+
+ /* Return error if the alarm time provided is not valid */
+ if (!(RTC_CheckDatetimeFormat(alarmTime)))
+ {
+ return kStatus_InvalidArgument;
+ }
+
+ alarmSeconds = RTC_ConvertDatetimeToSeconds(alarmTime);
+
+ /* Get the current time */
+ currSeconds = base->TSR;
+
+ /* Return error if the alarm time has passed */
+ if (alarmSeconds < currSeconds)
+ {
+ return kStatus_Fail;
+ }
+
+ /* Set alarm in seconds*/
+ base->TAR = alarmSeconds;
+
+ return kStatus_Success;
+}
+
+void RTC_GetAlarm(RTC_Type *base, rtc_datetime_t *datetime)
+{
+ assert(datetime);
+
+ uint32_t alarmSeconds = 0;
+
+ /* Get alarm in seconds */
+ alarmSeconds = base->TAR;
+
+ RTC_ConvertSecondsToDatetime(alarmSeconds, datetime);
+}
+
+void RTC_ClearStatusFlags(RTC_Type *base, uint32_t mask)
+{
+ /* The alarm flag is cleared by writing to the TAR register */
+ if (mask & kRTC_AlarmFlag)
+ {
+ base->TAR = 0U;
+ }
+
+ /* The timer overflow flag is cleared by initializing the TSR register.
+ * The time counter should be disabled for this write to be successful
+ */
+ if (mask & kRTC_TimeOverflowFlag)
+ {
+ base->TSR = 1U;
+ }
+
+ /* The timer overflow flag is cleared by initializing the TSR register.
+ * The time counter should be disabled for this write to be successful
+ */
+ if (mask & kRTC_TimeInvalidFlag)
+ {
+ base->TSR = 1U;
+ }
+}
+
+#if defined(FSL_FEATURE_RTC_HAS_MONOTONIC) && (FSL_FEATURE_RTC_HAS_MONOTONIC)
+
+void RTC_GetMonotonicCounter(RTC_Type *base, uint64_t *counter)
+{
+ assert(counter);
+
+ *counter = (((uint64_t)base->MCHR << 32) | ((uint64_t)base->MCLR));
+}
+
+void RTC_SetMonotonicCounter(RTC_Type *base, uint64_t counter)
+{
+ /* Prepare to initialize the register with the new value written */
+ base->MER &= ~RTC_MER_MCE_MASK;
+
+ base->MCHR = (uint32_t)((counter) >> 32);
+ base->MCLR = (uint32_t)(counter);
+}
+
+status_t RTC_IncrementMonotonicCounter(RTC_Type *base)
+{
+ if (base->SR & (RTC_SR_MOF_MASK | RTC_SR_TIF_MASK))
+ {
+ return kStatus_Fail;
+ }
+
+ /* Prepare to switch to increment mode */
+ base->MER |= RTC_MER_MCE_MASK;
+ /* Write anything so the counter increments*/
+ base->MCLR = 1U;
+
+ return kStatus_Success;
+}
+
+#endif /* FSL_FEATURE_RTC_HAS_MONOTONIC */
diff --git a/drivers/fsl_rtc.h b/drivers/fsl_rtc.h
new file mode 100644
index 0000000..4357c2e
--- /dev/null
+++ b/drivers/fsl_rtc.h
@@ -0,0 +1,412 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_RTC_H_
+#define _FSL_RTC_H_
+
+#include "fsl_common.h"
+
+/*!
+ * @addtogroup rtc
+ * @{
+ */
+
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+/*! @name Driver version */
+/*@{*/
+#define FSL_RTC_DRIVER_VERSION (MAKE_VERSION(2, 0, 0)) /*!< Version 2.0.0 */
+/*@}*/
+
+/*! @brief List of RTC interrupts */
+typedef enum _rtc_interrupt_enable
+{
+ kRTC_TimeInvalidInterruptEnable = RTC_IER_TIIE_MASK, /*!< Time invalid interrupt.*/
+ kRTC_TimeOverflowInterruptEnable = RTC_IER_TOIE_MASK, /*!< Time overflow interrupt.*/
+ kRTC_AlarmInterruptEnable = RTC_IER_TAIE_MASK, /*!< Alarm interrupt.*/
+ kRTC_SecondsInterruptEnable = RTC_IER_TSIE_MASK /*!< Seconds interrupt.*/
+} rtc_interrupt_enable_t;
+
+/*! @brief List of RTC flags */
+typedef enum _rtc_status_flags
+{
+ kRTC_TimeInvalidFlag = RTC_SR_TIF_MASK, /*!< Time invalid flag */
+ kRTC_TimeOverflowFlag = RTC_SR_TOF_MASK, /*!< Time overflow flag */
+ kRTC_AlarmFlag = RTC_SR_TAF_MASK /*!< Alarm flag*/
+} rtc_status_flags_t;
+
+#if (defined(FSL_FEATURE_RTC_HAS_OSC_SCXP) && FSL_FEATURE_RTC_HAS_OSC_SCXP)
+
+/*! @brief List of RTC Oscillator capacitor load settings */
+typedef enum _rtc_osc_cap_load
+{
+ kRTC_Capacitor_2p = RTC_CR_SC2P_MASK, /*!< 2pF capacitor load */
+ kRTC_Capacitor_4p = RTC_CR_SC4P_MASK, /*!< 4pF capacitor load */
+ kRTC_Capacitor_8p = RTC_CR_SC8P_MASK, /*!< 8pF capacitor load */
+ kRTC_Capacitor_16p = RTC_CR_SC16P_MASK /*!< 16pF capacitor load */
+} rtc_osc_cap_load_t;
+
+#endif /* FSL_FEATURE_SCG_HAS_OSC_SCXP */
+
+/*! @brief Structure is used to hold the date and time */
+typedef struct _rtc_datetime
+{
+ uint16_t year; /*!< Range from 1970 to 2099.*/
+ uint8_t month; /*!< Range from 1 to 12.*/
+ uint8_t day; /*!< Range from 1 to 31 (depending on month).*/
+ uint8_t hour; /*!< Range from 0 to 23.*/
+ uint8_t minute; /*!< Range from 0 to 59.*/
+ uint8_t second; /*!< Range from 0 to 59.*/
+} rtc_datetime_t;
+
+/*!
+ * @brief RTC config structure
+ *
+ * This structure holds the configuration settings for the RTC peripheral. To initialize this
+ * structure to reasonable defaults, call the RTC_GetDefaultConfig() function and pass a
+ * pointer to your config structure instance.
+ *
+ * The config struct can be made const so it resides in flash
+ */
+typedef struct _rtc_config
+{
+ bool wakeupSelect; /*!< true: Wakeup pin outputs the 32 KHz clock;
+ false:Wakeup pin used to wakeup the chip */
+ bool updateMode; /*!< true: Registers can be written even when locked under certain
+ conditions, false: No writes allowed when registers are locked */
+ bool supervisorAccess; /*!< true: Non-supervisor accesses are allowed;
+ false: Non-supervisor accesses are not supported */
+ uint32_t compensationInterval; /*!< Compensation interval that is written to the CIR field in RTC TCR Register */
+ uint32_t compensationTime; /*!< Compensation time that is written to the TCR field in RTC TCR Register */
+} rtc_config_t;
+
+/*******************************************************************************
+ * API
+ ******************************************************************************/
+
+#if defined(__cplusplus)
+extern "C" {
+#endif
+
+/*!
+ * @name Initialization and deinitialization
+ * @{
+ */
+
+/*!
+ * @brief Ungates the RTC clock and configures the peripheral for basic operation.
+ *
+ * This function will issue a software reset if the timer invalid flag is set.
+ *
+ * @note This API should be called at the beginning of the application using the RTC driver.
+ *
+ * @param base RTC peripheral base address
+ * @param config Pointer to user's RTC config structure.
+ */
+void RTC_Init(RTC_Type *base, const rtc_config_t *config);
+
+/*!
+ * @brief Stop the timer and gate the RTC clock
+ *
+ * @param base RTC peripheral base address
+ */
+static inline void RTC_Deinit(RTC_Type *base)
+{
+ /* Stop the RTC timer */
+ base->SR &= ~RTC_SR_TCE_MASK;
+
+ /* Gate the module clock */
+ CLOCK_DisableClock(kCLOCK_Rtc0);
+}
+
+/*!
+ * @brief Fill in the RTC config struct with the default settings
+ *
+ * The default values are:
+ * @code
+ * config->wakeupSelect = false;
+ * config->updateMode = false;
+ * config->supervisorAccess = false;
+ * config->compensationInterval = 0;
+ * config->compensationTime = 0;
+ * @endcode
+ * @param config Pointer to user's RTC config structure.
+ */
+void RTC_GetDefaultConfig(rtc_config_t *config);
+
+/*! @}*/
+
+/*!
+ * @name Current Time & Alarm
+ * @{
+ */
+
+/*!
+ * @brief Sets the RTC date and time according to the given time structure.
+ *
+ * The RTC counter must be stopped prior to calling this function as writes to the RTC
+ * seconds register will fail if the RTC counter is running.
+ *
+ * @param base RTC peripheral base address
+ * @param datetime Pointer to structure where the date and time details to set are stored
+ *
+ * @return kStatus_Success: Success in setting the time and starting the RTC
+ * kStatus_InvalidArgument: Error because the datetime format is incorrect
+ */
+status_t RTC_SetDatetime(RTC_Type *base, const rtc_datetime_t *datetime);
+
+/*!
+ * @brief Gets the RTC time and stores it in the given time structure.
+ *
+ * @param base RTC peripheral base address
+ * @param datetime Pointer to structure where the date and time details are stored.
+ */
+void RTC_GetDatetime(RTC_Type *base, rtc_datetime_t *datetime);
+
+/*!
+ * @brief Sets the RTC alarm time
+ *
+ * The function checks whether the specified alarm time is greater than the present
+ * time. If not, the function does not set the alarm and returns an error.
+ *
+ * @param base RTC peripheral base address
+ * @param alarmTime Pointer to structure where the alarm time is stored.
+ *
+ * @return kStatus_Success: success in setting the RTC alarm
+ * kStatus_InvalidArgument: Error because the alarm datetime format is incorrect
+ * kStatus_Fail: Error because the alarm time has already passed
+ */
+status_t RTC_SetAlarm(RTC_Type *base, const rtc_datetime_t *alarmTime);
+
+/*!
+ * @brief Returns the RTC alarm time.
+ *
+ * @param base RTC peripheral base address
+ * @param datetime Pointer to structure where the alarm date and time details are stored.
+ */
+void RTC_GetAlarm(RTC_Type *base, rtc_datetime_t *datetime);
+
+/*! @}*/
+
+/*!
+ * @name Interrupt Interface
+ * @{
+ */
+
+/*!
+ * @brief Enables the selected RTC interrupts.
+ *
+ * @param base RTC peripheral base address
+ * @param mask The interrupts to enable. This is a logical OR of members of the
+ * enumeration ::rtc_interrupt_enable_t
+ */
+static inline void RTC_EnableInterrupts(RTC_Type *base, uint32_t mask)
+{
+ base->IER |= mask;
+}
+
+/*!
+ * @brief Disables the selected RTC interrupts.
+ *
+ * @param base RTC peripheral base address
+ * @param mask The interrupts to enable. This is a logical OR of members of the
+ * enumeration ::rtc_interrupt_enable_t
+ */
+static inline void RTC_DisableInterrupts(RTC_Type *base, uint32_t mask)
+{
+ base->IER &= ~mask;
+}
+
+/*!
+ * @brief Gets the enabled RTC interrupts.
+ *
+ * @param base RTC peripheral base address
+ *
+ * @return The enabled interrupts. This is the logical OR of members of the
+ * enumeration ::rtc_interrupt_enable_t
+ */
+static inline uint32_t RTC_GetEnabledInterrupts(RTC_Type *base)
+{
+ return (base->IER & (RTC_IER_TIIE_MASK | RTC_IER_TOIE_MASK | RTC_IER_TAIE_MASK | RTC_IER_TSIE_MASK));
+}
+
+/*! @}*/
+
+/*!
+ * @name Status Interface
+ * @{
+ */
+
+/*!
+ * @brief Gets the RTC status flags
+ *
+ * @param base RTC peripheral base address
+ *
+ * @return The status flags. This is the logical OR of members of the
+ * enumeration ::rtc_status_flags_t
+ */
+static inline uint32_t RTC_GetStatusFlags(RTC_Type *base)
+{
+ return (base->SR & (RTC_SR_TIF_MASK | RTC_SR_TOF_MASK | RTC_SR_TAF_MASK));
+}
+
+/*!
+ * @brief Clears the RTC status flags.
+ *
+ * @param base RTC peripheral base address
+ * @param mask The status flags to clear. This is a logical OR of members of the
+ * enumeration ::rtc_status_flags_t
+ */
+void RTC_ClearStatusFlags(RTC_Type *base, uint32_t mask);
+
+/*! @}*/
+
+/*!
+ * @name Timer Start and Stop
+ * @{
+ */
+
+/*!
+ * @brief Starts the RTC time counter.
+ *
+ * After calling this function, the timer counter increments once a second provided SR[TOF] or
+ * SR[TIF] are not set.
+ *
+ * @param base RTC peripheral base address
+ */
+static inline void RTC_StartTimer(RTC_Type *base)
+{
+ base->SR |= RTC_SR_TCE_MASK;
+}
+
+/*!
+ * @brief Stops the RTC time counter.
+ *
+ * RTC's seconds register can be written to only when the timer is stopped.
+ *
+ * @param base RTC peripheral base address
+ */
+static inline void RTC_StopTimer(RTC_Type *base)
+{
+ base->SR &= ~RTC_SR_TCE_MASK;
+}
+
+/*! @}*/
+
+#if (defined(FSL_FEATURE_RTC_HAS_OSC_SCXP) && FSL_FEATURE_RTC_HAS_OSC_SCXP)
+
+/*!
+ * @brief This function sets the specified capacitor configuration for the RTC oscillator.
+ *
+ * @param base RTC peripheral base address
+ * @param capLoad Oscillator loads to enable. This is a logical OR of members of the
+ * enumeration ::rtc_osc_cap_load_t
+ */
+static inline void RTC_SetOscCapLoad(RTC_Type *base, uint32_t capLoad)
+{
+ uint32_t reg = base->CR;
+
+ reg &= ~(RTC_CR_SC2P_MASK | RTC_CR_SC4P_MASK | RTC_CR_SC8P_MASK | RTC_CR_SC16P_MASK);
+ reg |= capLoad;
+
+ base->CR = reg;
+}
+
+#endif /* FSL_FEATURE_SCG_HAS_OSC_SCXP */
+
+/*!
+ * @brief Performs a software reset on the RTC module.
+ *
+ * This resets all RTC registers except for the SWR bit and the RTC_WAR and RTC_RAR
+ * registers. The SWR bit is cleared by software explicitly clearing it.
+ *
+ * @param base RTC peripheral base address
+ */
+static inline void RTC_Reset(RTC_Type *base)
+{
+ base->CR |= RTC_CR_SWR_MASK;
+ base->CR &= ~RTC_CR_SWR_MASK;
+
+ /* Set TSR register to 0x1 to avoid the timer invalid (TIF) bit being set in the SR register */
+ base->TSR = 1U;
+}
+
+#if defined(FSL_FEATURE_RTC_HAS_MONOTONIC) && (FSL_FEATURE_RTC_HAS_MONOTONIC)
+
+/*!
+ * @name Monotonic counter functions
+ * @{
+ */
+
+/*!
+ * @brief Reads the values of the Monotonic Counter High and Monotonic Counter Low and returns
+ * them as a single value.
+ *
+ * @param base RTC peripheral base address
+ * @param counter Pointer to variable where the value is stored.
+ */
+void RTC_GetMonotonicCounter(RTC_Type *base, uint64_t *counter);
+
+/*!
+ * @brief Writes values Monotonic Counter High and Monotonic Counter Low by decomposing
+ * the given single value.
+ *
+ * @param base RTC peripheral base address
+ * @param counter Counter value
+ */
+void RTC_SetMonotonicCounter(RTC_Type *base, uint64_t counter);
+
+/*!
+ * @brief Increments the Monotonic Counter by one.
+ *
+ * Increments the Monotonic Counter (registers RTC_MCLR and RTC_MCHR accordingly) by setting
+ * the monotonic counter enable (MER[MCE]) and then writing to the RTC_MCLR register. A write to the
+ * monotonic counter low that causes it to overflow also increments the monotonic counter high.
+ *
+ * @param base RTC peripheral base address
+ *
+ * @return kStatus_Success: success
+ * kStatus_Fail: error occurred, either time invalid or monotonic overflow flag was found
+ */
+status_t RTC_IncrementMonotonicCounter(RTC_Type *base);
+
+/*! @}*/
+
+#endif /* FSL_FEATURE_RTC_HAS_MONOTONIC */
+
+#if defined(__cplusplus)
+}
+#endif
+
+/*! @}*/
+
+#endif /* _FSL_RTC_H_ */
diff --git a/drivers/fsl_sai.c b/drivers/fsl_sai.c
new file mode 100644
index 0000000..c38165e
--- /dev/null
+++ b/drivers/fsl_sai.c
@@ -0,0 +1,1066 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_sai.h"
+
+/*******************************************************************************
+ * Definitations
+ ******************************************************************************/
+enum _sai_transfer_state
+{
+ kSAI_Busy = 0x0U, /*!< SAI is busy */
+ kSAI_Idle, /*!< Transfer is done. */
+ kSAI_Error /*!< Transfer error occured. */
+};
+
+/*! @brief Typedef for sai tx interrupt handler. */
+typedef void (*sai_tx_isr_t)(I2S_Type *base, sai_handle_t *saiHandle);
+
+/*! @brief Typedef for sai rx interrupt handler. */
+typedef void (*sai_rx_isr_t)(I2S_Type *base, sai_handle_t *saiHandle);
+
+/*******************************************************************************
+ * Prototypes
+ ******************************************************************************/
+#if defined(FSL_FEATURE_SAI_HAS_MCLKDIV_REGISTER) && (FSL_FEATURE_SAI_HAS_MCLKDIV_REGISTER)
+
+/*!
+ * @brief Set the master clock divider.
+ *
+ * This API will compute the master clock divider according to master clock frequency and master
+ * clock source clock source frequency.
+ *
+ * @param base SAI base pointer.
+ * @param mclk_Hz Mater clock frequency in Hz.
+ * @param mclkSrcClock_Hz Master clock source frequency in Hz.
+ */
+static void SAI_SetMasterClockDivider(I2S_Type *base, uint32_t mclk_Hz, uint32_t mclkSrcClock_Hz);
+#endif /* FSL_FEATURE_SAI_HAS_MCLKDIV_REGISTER */
+
+/*!
+ * @brief Get the instance number for SAI.
+ *
+ * @param base SAI base pointer.
+ */
+uint32_t SAI_GetInstance(I2S_Type *base);
+
+/*!
+ * @brief sends a piece of data in non-blocking way.
+ *
+ * @param base SAI base pointer
+ * @param channel Data channel used.
+ * @param bitWidth How many bits in a audio word, usually 8/16/24/32 bits.
+ * @param buffer Pointer to the data to be written.
+ * @param size Bytes to be written.
+ */
+static void SAI_WriteNonBlocking(I2S_Type *base, uint32_t channel, uint32_t bitWidth, uint8_t *buffer, uint32_t size);
+
+/*!
+ * @brief Receive a piece of data in non-blocking way.
+ *
+ * @param base SAI base pointer
+ * @param channel Data channel used.
+ * @param bitWidth How many bits in a audio word, usually 8/16/24/32 bits.
+ * @param buffer Pointer to the data to be read.
+ * @param size Bytes to be read.
+ */
+static void SAI_ReadNonBlocking(I2S_Type *base, uint32_t channel, uint32_t bitWidth, uint8_t *buffer, uint32_t size);
+/*******************************************************************************
+ * Variables
+ ******************************************************************************/
+/*!@brief SAI handle pointer */
+sai_handle_t *s_saiHandle[FSL_FEATURE_SOC_I2S_COUNT][2];
+/* Base pointer array */
+static I2S_Type *const s_saiBases[] = I2S_BASE_PTRS;
+/* IRQ number array */
+static const IRQn_Type s_saiTxIRQ[] = I2S_TX_IRQS;
+static const IRQn_Type s_saiRxIRQ[] = I2S_RX_IRQS;
+/* Clock name array */
+static const clock_ip_name_t s_saiClock[] = SAI_CLOCKS;
+/*! @brief Pointer to tx IRQ handler for each instance. */
+static sai_tx_isr_t s_saiTxIsr;
+/*! @brief Pointer to tx IRQ handler for each instance. */
+static sai_rx_isr_t s_saiRxIsr;
+
+/*******************************************************************************
+ * Code
+ ******************************************************************************/
+#if defined(FSL_FEATURE_SAI_HAS_MCLKDIV_REGISTER) && (FSL_FEATURE_SAI_HAS_MCLKDIV_REGISTER)
+static void SAI_SetMasterClockDivider(I2S_Type *base, uint32_t mclk_Hz, uint32_t mclkSrcClock_Hz)
+{
+ uint32_t freq = mclkSrcClock_Hz;
+ uint16_t fract, divide;
+ uint32_t remaind = 0;
+ uint32_t current_remainder = 0xFFFFFFFFU;
+ uint16_t current_fract = 0;
+ uint16_t current_divide = 0;
+ uint32_t mul_freq = 0;
+ uint32_t max_fract = 256;
+
+ /*In order to prevent overflow */
+ freq /= 100;
+ mclk_Hz /= 100;
+
+ /* Compute the max fract number */
+ max_fract = mclk_Hz * 4096 / freq + 1;
+ if (max_fract > 256)
+ {
+ max_fract = 256;
+ }
+
+ /* Looking for the closet frequency */
+ for (fract = 1; fract < max_fract; fract++)
+ {
+ mul_freq = freq * fract;
+ remaind = mul_freq % mclk_Hz;
+ divide = mul_freq / mclk_Hz;
+
+ /* Find the exactly frequency */
+ if (remaind == 0)
+ {
+ current_fract = fract;
+ current_divide = mul_freq / mclk_Hz;
+ break;
+ }
+
+ /* Closer to next one, set the closest to next data */
+ if (remaind > mclk_Hz / 2)
+ {
+ remaind = mclk_Hz - remaind;
+ divide += 1;
+ }
+
+ /* Update the closest div and fract */
+ if (remaind < current_remainder)
+ {
+ current_fract = fract;
+ current_divide = divide;
+ current_remainder = remaind;
+ }
+ }
+
+ /* Fill the computed fract and divider to registers */
+ base->MDR = I2S_MDR_DIVIDE(current_divide - 1) | I2S_MDR_FRACT(current_fract - 1);
+
+ /* Waiting for the divider updated */
+ while (base->MCR & I2S_MCR_DUF_MASK)
+ {
+ }
+}
+#endif /* FSL_FEATURE_SAI_HAS_MCLKDIV_REGISTER */
+
+uint32_t SAI_GetInstance(I2S_Type *base)
+{
+ uint32_t instance;
+
+ /* Find the instance index from base address mappings. */
+ for (instance = 0; instance < FSL_FEATURE_SOC_I2S_COUNT; instance++)
+ {
+ if (s_saiBases[instance] == base)
+ {
+ break;
+ }
+ }
+
+ assert(instance < FSL_FEATURE_SOC_I2S_COUNT);
+
+ return instance;
+}
+
+static void SAI_WriteNonBlocking(I2S_Type *base, uint32_t channel, uint32_t bitWidth, uint8_t *buffer, uint32_t size)
+{
+ uint32_t i = 0;
+ uint8_t j = 0;
+ uint8_t bytesPerWord = bitWidth / 8U;
+ uint32_t data = 0;
+ uint32_t temp = 0;
+
+ for (i = 0; i < size / bytesPerWord; i++)
+ {
+ for (j = 0; j < bytesPerWord; j++)
+ {
+ temp = (uint32_t)(*buffer);
+ data |= (temp << (8U * j));
+ buffer++;
+ }
+ base->TDR[channel] = data;
+ data = 0;
+ }
+}
+
+static void SAI_ReadNonBlocking(I2S_Type *base, uint32_t channel, uint32_t bitWidth, uint8_t *buffer, uint32_t size)
+{
+ uint32_t i = 0;
+ uint8_t j = 0;
+ uint8_t bytesPerWord = bitWidth / 8U;
+ uint32_t data = 0;
+
+ for (i = 0; i < size / bytesPerWord; i++)
+ {
+ data = base->RDR[channel];
+ for (j = 0; j < bytesPerWord; j++)
+ {
+ *buffer = (data >> (8U * j)) & 0xFF;
+ buffer++;
+ }
+ }
+}
+
+void SAI_TxInit(I2S_Type *base, const sai_config_t *config)
+{
+ uint32_t val = 0;
+
+ /* Enable the SAI clock */
+ CLOCK_EnableClock(s_saiClock[SAI_GetInstance(base)]);
+
+#if defined(FSL_FEATURE_SAI_HAS_MCR) && (FSL_FEATURE_SAI_HAS_MCR)
+ /* Master clock source setting */
+ val = (base->MCR & ~I2S_MCR_MICS_MASK);
+ base->MCR = (val | I2S_MCR_MICS(config->mclkSource));
+
+ /* Configure Master clock output enable */
+ val = (base->MCR & ~I2S_MCR_MOE_MASK);
+ base->MCR = (val | I2S_MCR_MOE(config->mclkOutputEnable));
+#endif /* FSL_FEATURE_SAI_HAS_MCR */
+
+ /* Configure audio protocol */
+ switch (config->protocol)
+ {
+ case kSAI_BusLeftJustified:
+ base->TCR2 |= I2S_TCR2_BCP_MASK;
+ base->TCR3 &= ~I2S_TCR3_WDFL_MASK;
+ base->TCR4 = I2S_TCR4_MF(1U) | I2S_TCR4_SYWD(31U) | I2S_TCR4_FSE(0U) | I2S_TCR4_FSP(0U) | I2S_TCR4_FRSZ(1U);
+ break;
+
+ case kSAI_BusRightJustified:
+ base->TCR2 |= I2S_TCR2_BCP_MASK;
+ base->TCR3 &= ~I2S_TCR3_WDFL_MASK;
+ base->TCR4 = I2S_TCR4_MF(1U) | I2S_TCR4_SYWD(31U) | I2S_TCR4_FSE(0U) | I2S_TCR4_FSP(0U) | I2S_TCR4_FRSZ(1U);
+ break;
+
+ case kSAI_BusI2S:
+ base->TCR2 |= I2S_TCR2_BCP_MASK;
+ base->TCR3 &= ~I2S_TCR3_WDFL_MASK;
+ base->TCR4 = I2S_TCR4_MF(1U) | I2S_TCR4_SYWD(31U) | I2S_TCR4_FSE(1U) | I2S_TCR4_FSP(1U) | I2S_TCR4_FRSZ(1U);
+ break;
+
+ case kSAI_BusPCMA:
+ base->TCR2 &= ~I2S_TCR2_BCP_MASK;
+ base->TCR3 &= ~I2S_TCR3_WDFL_MASK;
+ base->TCR4 = I2S_TCR4_MF(1U) | I2S_TCR4_SYWD(0U) | I2S_TCR4_FSE(1U) | I2S_TCR4_FSP(0U) | I2S_TCR4_FRSZ(1U);
+ break;
+
+ case kSAI_BusPCMB:
+ base->TCR2 &= ~I2S_TCR2_BCP_MASK;
+ base->TCR3 &= ~I2S_TCR3_WDFL_MASK;
+ base->TCR4 = I2S_TCR4_MF(1U) | I2S_TCR4_SYWD(0U) | I2S_TCR4_FSE(0U) | I2S_TCR4_FSP(0U) | I2S_TCR4_FRSZ(1U);
+ break;
+
+ default:
+ break;
+ }
+
+ /* Set master or slave */
+ if (config->masterSlave == kSAI_Master)
+ {
+ base->TCR2 |= I2S_TCR2_BCD_MASK;
+ base->TCR4 |= I2S_TCR4_FSD_MASK;
+
+ /* Bit clock source setting */
+ val = base->TCR2 & (~I2S_TCR2_MSEL_MASK);
+ base->TCR2 = (val | I2S_TCR2_MSEL(config->bclkSource));
+ }
+ else
+ {
+ base->TCR2 &= ~I2S_TCR2_BCD_MASK;
+ base->TCR4 &= ~I2S_TCR4_FSD_MASK;
+ }
+
+ /* Set Sync mode */
+ switch (config->syncMode)
+ {
+ case kSAI_ModeAsync:
+ val = base->TCR2;
+ val &= ~I2S_TCR2_SYNC_MASK;
+ base->TCR2 = (val | I2S_TCR2_SYNC(0U));
+ break;
+ case kSAI_ModeSync:
+ val = base->TCR2;
+ val &= ~I2S_TCR2_SYNC_MASK;
+ base->TCR2 = (val | I2S_TCR2_SYNC(1U));
+ /* If sync with Rx, should set Rx to async mode */
+ val = base->RCR2;
+ val &= ~I2S_RCR2_SYNC_MASK;
+ base->RCR2 = (val | I2S_RCR2_SYNC(0U));
+ break;
+ case kSAI_ModeSyncWithOtherTx:
+ val = base->TCR2;
+ val &= ~I2S_TCR2_SYNC_MASK;
+ base->TCR2 = (val | I2S_TCR2_SYNC(2U));
+ break;
+ case kSAI_ModeSyncWithOtherRx:
+ val = base->TCR2;
+ val &= ~I2S_TCR2_SYNC_MASK;
+ base->TCR2 = (val | I2S_TCR2_SYNC(3U));
+ break;
+ default:
+ break;
+ }
+}
+
+void SAI_RxInit(I2S_Type *base, const sai_config_t *config)
+{
+ uint32_t val = 0;
+
+ /* Enable SAI clock first. */
+ CLOCK_EnableClock(s_saiClock[SAI_GetInstance(base)]);
+
+#if defined(FSL_FEATURE_SAI_HAS_MCR) && (FSL_FEATURE_SAI_HAS_MCR)
+ /* Master clock source setting */
+ val = (base->MCR & ~I2S_MCR_MICS_MASK);
+ base->MCR = (val | I2S_MCR_MICS(config->mclkSource));
+
+ /* Configure Master clock output enable */
+ val = (base->MCR & ~I2S_MCR_MOE_MASK);
+ base->MCR = (val | I2S_MCR_MOE(config->mclkOutputEnable));
+#endif /* FSL_FEATURE_SAI_HAS_MCR */
+
+ /* Configure audio protocol */
+ switch (config->protocol)
+ {
+ case kSAI_BusLeftJustified:
+ base->RCR2 |= I2S_RCR2_BCP_MASK;
+ base->RCR3 &= ~I2S_RCR3_WDFL_MASK;
+ base->RCR4 = I2S_RCR4_MF(1U) | I2S_RCR4_SYWD(31U) | I2S_RCR4_FSE(0U) | I2S_RCR4_FSP(0U) | I2S_RCR4_FRSZ(1U);
+ break;
+
+ case kSAI_BusRightJustified:
+ base->RCR2 |= I2S_RCR2_BCP_MASK;
+ base->RCR3 &= ~I2S_RCR3_WDFL_MASK;
+ base->RCR4 = I2S_RCR4_MF(1U) | I2S_RCR4_SYWD(31U) | I2S_RCR4_FSE(0U) | I2S_RCR4_FSP(0U) | I2S_RCR4_FRSZ(1U);
+ break;
+
+ case kSAI_BusI2S:
+ base->RCR2 |= I2S_RCR2_BCP_MASK;
+ base->RCR3 &= ~I2S_RCR3_WDFL_MASK;
+ base->RCR4 = I2S_RCR4_MF(1U) | I2S_RCR4_SYWD(31U) | I2S_RCR4_FSE(1U) | I2S_RCR4_FSP(1U) | I2S_RCR4_FRSZ(1U);
+ break;
+
+ case kSAI_BusPCMA:
+ base->RCR2 &= ~I2S_RCR2_BCP_MASK;
+ base->RCR3 &= ~I2S_RCR3_WDFL_MASK;
+ base->RCR4 = I2S_RCR4_MF(1U) | I2S_RCR4_SYWD(0U) | I2S_RCR4_FSE(1U) | I2S_RCR4_FSP(0U) | I2S_RCR4_FRSZ(1U);
+ break;
+
+ case kSAI_BusPCMB:
+ base->RCR2 &= ~I2S_RCR2_BCP_MASK;
+ base->RCR3 &= ~I2S_RCR3_WDFL_MASK;
+ base->RCR4 = I2S_RCR4_MF(1U) | I2S_RCR4_SYWD(0U) | I2S_RCR4_FSE(0U) | I2S_RCR4_FSP(0U) | I2S_RCR4_FRSZ(1U);
+ break;
+
+ default:
+ break;
+ }
+
+ /* Set master or slave */
+ if (config->masterSlave == kSAI_Master)
+ {
+ base->RCR2 |= I2S_RCR2_BCD_MASK;
+ base->RCR4 |= I2S_RCR4_FSD_MASK;
+
+ /* Bit clock source setting */
+ val = base->RCR2 & (~I2S_RCR2_MSEL_MASK);
+ base->RCR2 = (val | I2S_RCR2_MSEL(config->bclkSource));
+ }
+ else
+ {
+ base->RCR2 &= ~I2S_RCR2_BCD_MASK;
+ base->RCR4 &= ~I2S_RCR4_FSD_MASK;
+ }
+
+ /* Set Sync mode */
+ switch (config->syncMode)
+ {
+ case kSAI_ModeAsync:
+ val = base->RCR2;
+ val &= ~I2S_RCR2_SYNC_MASK;
+ base->RCR2 = (val | I2S_RCR2_SYNC(0U));
+ break;
+ case kSAI_ModeSync:
+ val = base->RCR2;
+ val &= ~I2S_RCR2_SYNC_MASK;
+ base->RCR2 = (val | I2S_RCR2_SYNC(1U));
+ /* If sync with Tx, should set Tx to async mode */
+ val = base->TCR2;
+ val &= ~I2S_TCR2_SYNC_MASK;
+ base->TCR2 = (val | I2S_TCR2_SYNC(0U));
+ break;
+ case kSAI_ModeSyncWithOtherTx:
+ val = base->RCR2;
+ val &= ~I2S_RCR2_SYNC_MASK;
+ base->RCR2 = (val | I2S_RCR2_SYNC(2U));
+ break;
+ case kSAI_ModeSyncWithOtherRx:
+ val = base->RCR2;
+ val &= ~I2S_RCR2_SYNC_MASK;
+ base->RCR2 = (val | I2S_RCR2_SYNC(3U));
+ break;
+ default:
+ break;
+ }
+}
+
+void SAI_Deinit(I2S_Type *base)
+{
+ SAI_TxEnable(base, false);
+ SAI_RxEnable(base, false);
+ CLOCK_DisableClock(s_saiClock[SAI_GetInstance(base)]);
+}
+
+void SAI_TxGetDefaultConfig(sai_config_t *config)
+{
+ config->bclkSource = kSAI_BclkSourceMclkDiv;
+ config->masterSlave = kSAI_Master;
+ config->mclkSource = kSAI_MclkSourceSysclk;
+ config->protocol = kSAI_BusLeftJustified;
+ config->syncMode = kSAI_ModeAsync;
+#if defined(FSL_FEATURE_SAI_HAS_MCR) && (FSL_FEATURE_SAI_HAS_MCR)
+ config->mclkOutputEnable = true;
+#endif /* FSL_FEATURE_SAI_HAS_MCR */
+}
+
+void SAI_RxGetDefaultConfig(sai_config_t *config)
+{
+ config->bclkSource = kSAI_BclkSourceMclkDiv;
+ config->masterSlave = kSAI_Master;
+ config->mclkSource = kSAI_MclkSourceSysclk;
+ config->protocol = kSAI_BusLeftJustified;
+ config->syncMode = kSAI_ModeSync;
+#if defined(FSL_FEATURE_SAI_HAS_MCR) && (FSL_FEATURE_SAI_HAS_MCR)
+ config->mclkOutputEnable = true;
+#endif /* FSL_FEATURE_SAI_HAS_MCR */
+}
+
+void SAI_TxReset(I2S_Type *base)
+{
+ /* Set the software reset and FIFO reset to clear internal state */
+ base->TCSR = I2S_TCSR_SR_MASK | I2S_TCSR_FR_MASK;
+
+ /* Clear software reset bit, this should be done by software */
+ base->TCSR &= ~I2S_TCSR_SR_MASK;
+
+ /* Reset all Tx register values */
+ base->TCR2 = 0;
+ base->TCR3 = 0;
+ base->TCR4 = 0;
+ base->TCR5 = 0;
+ base->TMR = 0;
+}
+
+void SAI_RxReset(I2S_Type *base)
+{
+ /* Set the software reset and FIFO reset to clear internal state */
+ base->RCSR = I2S_RCSR_SR_MASK | I2S_RCSR_FR_MASK;
+
+ /* Clear software reset bit, this should be done by software */
+ base->RCSR &= ~I2S_RCSR_SR_MASK;
+
+ /* Reset all Rx register values */
+ base->RCR2 = 0;
+ base->RCR3 = 0;
+ base->RCR4 = 0;
+ base->RCR5 = 0;
+ base->RMR = 0;
+}
+
+void SAI_TxEnable(I2S_Type *base, bool enable)
+{
+ if (enable)
+ {
+ /* If clock is sync with Rx, should enable RE bit. */
+ if (((base->TCR2 & I2S_TCR2_SYNC_MASK) >> I2S_TCR2_SYNC_SHIFT) == 0x1U)
+ {
+ base->RCSR = ((base->RCSR & 0xFFE3FFFFU) | I2S_RCSR_RE_MASK);
+ }
+ base->TCSR = ((base->TCSR & 0xFFE3FFFFU) | I2S_TCSR_TE_MASK);
+ }
+ else
+ {
+ /* Should not close RE even sync with Rx */
+ base->TCSR = ((base->TCSR & 0xFFE3FFFFU) & (~I2S_TCSR_TE_MASK));
+ }
+}
+
+void SAI_RxEnable(I2S_Type *base, bool enable)
+{
+ if (enable)
+ {
+ /* If clock is sync with Tx, should enable TE bit. */
+ if (((base->RCR2 & I2S_RCR2_SYNC_MASK) >> I2S_RCR2_SYNC_SHIFT) == 0x1U)
+ {
+ base->TCSR = ((base->TCSR & 0xFFE3FFFFU) | I2S_TCSR_TE_MASK);
+ }
+ base->RCSR = ((base->RCSR & 0xFFE3FFFFU) | I2S_RCSR_RE_MASK);
+ }
+ else
+ {
+ base->RCSR = ((base->RCSR & 0xFFE3FFFFU) & (~I2S_RCSR_RE_MASK));
+ }
+}
+
+void SAI_TxSetFormat(I2S_Type *base,
+ sai_transfer_format_t *format,
+ uint32_t mclkSourceClockHz,
+ uint32_t bclkSourceClockHz)
+{
+ uint32_t bclk = format->sampleRate_Hz * 32U * 2U;
+
+/* Compute the mclk */
+#if defined(FSL_FEATURE_SAI_HAS_MCLKDIV_REGISTER) && (FSL_FEATURE_SAI_HAS_MCLKDIV_REGISTER)
+ /* Check if master clock divider enabled, then set master clock divider */
+ if (base->MCR & I2S_MCR_MOE_MASK)
+ {
+ SAI_SetMasterClockDivider(base, format->masterClockHz, mclkSourceClockHz);
+ }
+#endif /* FSL_FEATURE_SAI_HAS_MCLKDIV_REGISTER */
+
+ /* Set bclk if needed */
+ if (base->TCR2 & I2S_TCR2_BCD_MASK)
+ {
+ base->TCR2 &= ~I2S_TCR2_DIV_MASK;
+ base->TCR2 |= I2S_TCR2_DIV((bclkSourceClockHz / bclk) / 2U - 1U);
+ }
+
+ /* Set bitWidth */
+ if (format->protocol == kSAI_BusRightJustified)
+ {
+ base->TCR5 = I2S_TCR5_WNW(31U) | I2S_TCR5_W0W(31U) | I2S_TCR5_FBT(31U);
+ }
+ else
+ {
+ base->TCR5 = I2S_TCR5_WNW(31U) | I2S_TCR5_W0W(31U) | I2S_TCR5_FBT(format->bitWidth - 1);
+ }
+
+ /* Set mono or stereo */
+ base->TMR = (uint32_t)format->stereo;
+
+ /* Set data channel */
+ base->TCR3 &= ~I2S_TCR3_TCE_MASK;
+ base->TCR3 |= I2S_TCR3_TCE(1U << format->channel);
+
+#if defined(FSL_FEATURE_SAI_FIFO_COUNT) && (FSL_FEATURE_SAI_FIFO_COUNT > 1)
+ /* Set watermark */
+ base->TCR1 = format->watermark;
+#endif /* FSL_FEATURE_SAI_FIFO_COUNT */
+}
+
+void SAI_RxSetFormat(I2S_Type *base,
+ sai_transfer_format_t *format,
+ uint32_t mclkSourceClockHz,
+ uint32_t bclkSourceClockHz)
+{
+ uint32_t bclk = format->sampleRate_Hz * 32U * 2U;
+
+/* Compute the mclk */
+#if defined(FSL_FEATURE_SAI_HAS_MCLKDIV_REGISTER) && (FSL_FEATURE_SAI_HAS_MCLKDIV_REGISTER)
+ /* Check if master clock divider enabled */
+ if (base->MCR & I2S_MCR_MOE_MASK)
+ {
+ SAI_SetMasterClockDivider(base, format->masterClockHz, mclkSourceClockHz);
+ }
+#endif /* FSL_FEATURE_SAI_HAS_MCLKDIV_REGISTER */
+
+ /* Set bclk if needed */
+ if (base->RCR2 & I2S_RCR2_BCD_MASK)
+ {
+ base->RCR2 &= ~I2S_RCR2_DIV_MASK;
+ base->RCR2 |= I2S_RCR2_DIV((bclkSourceClockHz / bclk) / 2U - 1U);
+ }
+
+ /* Set bitWidth */
+ if (format->protocol == kSAI_BusRightJustified)
+ {
+ base->RCR5 = I2S_RCR5_WNW(31U) | I2S_RCR5_W0W(31U) | I2S_RCR5_FBT(31U);
+ }
+ else
+ {
+ base->RCR5 = I2S_RCR5_WNW(31U) | I2S_RCR5_W0W(31U) | I2S_RCR5_FBT(format->bitWidth - 1);
+ }
+
+ /* Set mono or stereo */
+ base->RMR = (uint32_t)format->stereo;
+
+ /* Set data channel */
+ base->RCR3 &= ~I2S_RCR3_RCE_MASK;
+ base->RCR3 |= I2S_RCR3_RCE(1U << format->channel);
+
+#if defined(FSL_FEATURE_SAI_FIFO_COUNT) && (FSL_FEATURE_SAI_FIFO_COUNT > 1)
+ /* Set watermark */
+ base->RCR1 = format->watermark;
+#endif /* FSL_FEATURE_SAI_FIFO_COUNT */
+}
+
+void SAI_WriteBlocking(I2S_Type *base, uint32_t channel, uint32_t bitWidth, uint8_t *buffer, uint32_t size)
+{
+ uint32_t i = 0;
+ uint8_t bytesPerWord = bitWidth / 8U;
+
+ for (i = 0; i < size; i++)
+ {
+ /* Wait until it can write data */
+ while (!(base->TCSR & I2S_TCSR_FWF_MASK))
+ {
+ }
+
+ SAI_WriteNonBlocking(base, channel, bitWidth, buffer, bytesPerWord);
+ buffer += bytesPerWord;
+ }
+
+ /* Wait until the last data is sent */
+ while (!(base->TCSR & I2S_TCSR_FWF_MASK))
+ {
+ }
+}
+
+void SAI_ReadBlocking(I2S_Type *base, uint32_t channel, uint32_t bitWidth, uint8_t *buffer, uint32_t size)
+{
+ uint32_t i = 0;
+ uint8_t bytesPerWord = bitWidth / 8U;
+
+ for (i = 0; i < size; i++)
+ {
+ /* Wait until data is received */
+ while (!(base->RCSR & I2S_RCSR_FWF_MASK))
+ {
+ }
+
+ SAI_ReadNonBlocking(base, channel, bitWidth, buffer, bytesPerWord);
+ buffer += bytesPerWord;
+ }
+}
+
+void SAI_TransferTxCreateHandle(I2S_Type *base, sai_handle_t *handle, sai_transfer_callback_t callback, void *userData)
+{
+ assert(handle);
+
+ s_saiHandle[SAI_GetInstance(base)][0] = handle;
+
+ handle->callback = callback;
+ handle->userData = userData;
+
+ /* Set the isr pointer */
+ s_saiTxIsr = SAI_TransferTxHandleIRQ;
+
+ /* Enable Tx irq */
+ EnableIRQ(s_saiTxIRQ[SAI_GetInstance(base)]);
+}
+
+void SAI_TransferRxCreateHandle(I2S_Type *base, sai_handle_t *handle, sai_transfer_callback_t callback, void *userData)
+{
+ assert(handle);
+
+ s_saiHandle[SAI_GetInstance(base)][1] = handle;
+
+ handle->callback = callback;
+ handle->userData = userData;
+
+ /* Set the isr pointer */
+ s_saiRxIsr = SAI_TransferRxHandleIRQ;
+
+ /* Enable Rx irq */
+ EnableIRQ(s_saiRxIRQ[SAI_GetInstance(base)]);
+}
+
+status_t SAI_TransferTxSetFormat(I2S_Type *base,
+ sai_handle_t *handle,
+ sai_transfer_format_t *format,
+ uint32_t mclkSourceClockHz,
+ uint32_t bclkSourceClockHz)
+{
+ assert(handle);
+
+ if ((mclkSourceClockHz < format->sampleRate_Hz) || (bclkSourceClockHz < format->sampleRate_Hz))
+ {
+ return kStatus_InvalidArgument;
+ }
+
+ /* Copy format to handle */
+ handle->bitWidth = format->bitWidth;
+#if defined(FSL_FEATURE_SAI_FIFO_COUNT) && (FSL_FEATURE_SAI_FIFO_COUNT > 1)
+ handle->watermark = format->watermark;
+#endif
+ handle->channel = format->channel;
+
+ SAI_TxSetFormat(base, format, mclkSourceClockHz, bclkSourceClockHz);
+
+ return kStatus_Success;
+}
+
+status_t SAI_TransferRxSetFormat(I2S_Type *base,
+ sai_handle_t *handle,
+ sai_transfer_format_t *format,
+ uint32_t mclkSourceClockHz,
+ uint32_t bclkSourceClockHz)
+{
+ assert(handle);
+
+ if ((mclkSourceClockHz < format->sampleRate_Hz) || (bclkSourceClockHz < format->sampleRate_Hz))
+ {
+ return kStatus_InvalidArgument;
+ }
+
+ /* Copy format to handle */
+ handle->bitWidth = format->bitWidth;
+#if defined(FSL_FEATURE_SAI_FIFO_COUNT) && (FSL_FEATURE_SAI_FIFO_COUNT > 1)
+ handle->watermark = format->watermark;
+#endif
+ handle->channel = format->channel;
+
+ SAI_RxSetFormat(base, format, mclkSourceClockHz, bclkSourceClockHz);
+
+ return kStatus_Success;
+}
+
+status_t SAI_TransferSendNonBlocking(I2S_Type *base, sai_handle_t *handle, sai_transfer_t *xfer)
+{
+ assert(handle);
+
+ /* Check if the queue is full */
+ if (handle->saiQueue[handle->queueUser].data)
+ {
+ return kStatus_SAI_QueueFull;
+ }
+
+ /* Add into queue */
+ handle->transferSize[handle->queueUser] = xfer->dataSize;
+ handle->saiQueue[handle->queueUser].data = xfer->data;
+ handle->saiQueue[handle->queueUser].dataSize = xfer->dataSize;
+ handle->queueUser = (handle->queueUser + 1) % SAI_XFER_QUEUE_SIZE;
+
+ /* Set the state to busy */
+ handle->state = kSAI_Busy;
+
+/* Enable interrupt */
+#if defined(FSL_FEATURE_SAI_FIFO_COUNT) && (FSL_FEATURE_SAI_FIFO_COUNT > 1)
+ /* Use FIFO request interrupt and fifo error*/
+ SAI_TxEnableInterrupts(base, kSAI_FIFOErrorInterruptEnable | kSAI_FIFORequestInterruptEnable);
+#else
+ SAI_TxEnableInterrupts(base, kSAI_FIFOErrorInterruptEnable | kSAI_FIFOWarningInterruptEnable);
+#endif /* FSL_FEATURE_SAI_FIFO_COUNT */
+
+ /* Enable Tx transfer */
+ SAI_TxEnable(base, true);
+
+ return kStatus_Success;
+}
+
+status_t SAI_TransferReceiveNonBlocking(I2S_Type *base, sai_handle_t *handle, sai_transfer_t *xfer)
+{
+ assert(handle);
+
+ /* Check if the queue is full */
+ if (handle->saiQueue[handle->queueUser].data)
+ {
+ return kStatus_SAI_QueueFull;
+ }
+
+ /* Add into queue */
+ handle->transferSize[handle->queueUser] = xfer->dataSize;
+ handle->saiQueue[handle->queueUser].data = xfer->data;
+ handle->saiQueue[handle->queueUser].dataSize = xfer->dataSize;
+ handle->queueUser = (handle->queueUser + 1) % SAI_XFER_QUEUE_SIZE;
+
+ /* Set state to busy */
+ handle->state = kSAI_Busy;
+
+/* Enable interrupt */
+#if defined(FSL_FEATURE_SAI_FIFO_COUNT) && (FSL_FEATURE_SAI_FIFO_COUNT > 1)
+ /* Use FIFO request interrupt and fifo error*/
+ SAI_RxEnableInterrupts(base, kSAI_FIFOErrorInterruptEnable | kSAI_FIFORequestInterruptEnable);
+#else
+ SAI_RxEnableInterrupts(base, kSAI_FIFOErrorInterruptEnable | kSAI_FIFOWarningInterruptEnable);
+#endif /* FSL_FEATURE_SAI_FIFO_COUNT */
+
+ /* Enable Rx transfer */
+ SAI_RxEnable(base, true);
+
+ return kStatus_Success;
+}
+
+status_t SAI_TransferGetSendCount(I2S_Type *base, sai_handle_t *handle, size_t *count)
+{
+ assert(handle);
+
+ status_t status = kStatus_Success;
+
+ if (handle->state != kSAI_Busy)
+ {
+ status = kStatus_NoTransferInProgress;
+ }
+ else
+ {
+ *count = (handle->transferSize[handle->queueDriver] - handle->saiQueue[handle->queueDriver].dataSize);
+ }
+
+ return status;
+}
+
+status_t SAI_TransferGetReceiveCount(I2S_Type *base, sai_handle_t *handle, size_t *count)
+{
+ assert(handle);
+
+ status_t status = kStatus_Success;
+
+ if (handle->state != kSAI_Busy)
+ {
+ status = kStatus_NoTransferInProgress;
+ }
+ else
+ {
+ *count = (handle->transferSize[handle->queueDriver] - handle->saiQueue[handle->queueDriver].dataSize);
+ }
+
+ return status;
+}
+
+void SAI_TransferAbortSend(I2S_Type *base, sai_handle_t *handle)
+{
+ assert(handle);
+
+ /* Stop Tx transfer and disable interrupt */
+ SAI_TxEnable(base, false);
+#if defined(FSL_FEATURE_SAI_FIFO_COUNT) && (FSL_FEATURE_SAI_FIFO_COUNT > 1)
+ /* Use FIFO request interrupt and fifo error */
+ SAI_TxDisableInterrupts(base, kSAI_FIFOErrorInterruptEnable | kSAI_FIFORequestInterruptEnable);
+#else
+ SAI_TxDisableInterrupts(base, kSAI_FIFOErrorInterruptEnable | kSAI_FIFOWarningInterruptEnable);
+#endif /* FSL_FEATURE_SAI_FIFO_COUNT */
+
+ handle->state = kSAI_Idle;
+
+ /* Clear the queue */
+ memset(handle->saiQueue, 0, sizeof(sai_transfer_t) * SAI_XFER_QUEUE_SIZE);
+ handle->queueDriver = 0;
+ handle->queueUser = 0;
+}
+
+void SAI_TransferAbortReceive(I2S_Type *base, sai_handle_t *handle)
+{
+ assert(handle);
+
+ /* Stop Tx transfer and disable interrupt */
+ SAI_RxEnable(base, false);
+#if defined(FSL_FEATURE_SAI_FIFO_COUNT) && (FSL_FEATURE_SAI_FIFO_COUNT > 1)
+ /* Use FIFO request interrupt and fifo error */
+ SAI_RxDisableInterrupts(base, kSAI_FIFOErrorInterruptEnable | kSAI_FIFORequestInterruptEnable);
+#else
+ SAI_RxDisableInterrupts(base, kSAI_FIFOErrorInterruptEnable | kSAI_FIFOWarningInterruptEnable);
+#endif /* FSL_FEATURE_SAI_FIFO_COUNT */
+
+ handle->state = kSAI_Idle;
+
+ /* Clear the queue */
+ memset(handle->saiQueue, 0, sizeof(sai_transfer_t) * SAI_XFER_QUEUE_SIZE);
+ handle->queueDriver = 0;
+ handle->queueUser = 0;
+}
+
+void SAI_TransferTxHandleIRQ(I2S_Type *base, sai_handle_t *handle)
+{
+ assert(handle);
+
+ uint8_t *buffer = handle->saiQueue[handle->queueDriver].data;
+ uint8_t dataSize = handle->bitWidth / 8U;
+
+ /* Handle Error */
+ if (base->TCSR & I2S_TCSR_FEF_MASK)
+ {
+ /* Clear FIFO error flag to continue transfer */
+ SAI_TxClearStatusFlags(base, kSAI_FIFOErrorFlag);
+
+ /* Call the callback */
+ if (handle->callback)
+ {
+ (handle->callback)(base, handle, kStatus_SAI_TxError, handle->userData);
+ }
+ }
+
+/* Handle transfer */
+#if defined(FSL_FEATURE_SAI_FIFO_COUNT) && (FSL_FEATURE_SAI_FIFO_COUNT > 1)
+ if (base->TCSR & I2S_TCSR_FRF_MASK)
+ {
+ /* Judge if the data need to transmit is less than space */
+ uint8_t size = MIN((handle->saiQueue[handle->queueDriver].dataSize),
+ (size_t)((FSL_FEATURE_SAI_FIFO_COUNT - handle->watermark) * dataSize));
+
+ /* Copy the data from sai buffer to FIFO */
+ SAI_WriteNonBlocking(base, handle->channel, handle->bitWidth, buffer, size);
+
+ /* Update the internal counter */
+ handle->saiQueue[handle->queueDriver].dataSize -= size;
+ handle->saiQueue[handle->queueDriver].data += size;
+ }
+#else
+ if (base->TCSR & I2S_TCSR_FWF_MASK)
+ {
+ uint8_t size = MIN((handle->saiQueue[handle->queueDriver].dataSize), dataSize);
+
+ SAI_WriteNonBlocking(base, handle->channel, handle->bitWidth, buffer, size);
+
+ /* Update internal counter */
+ handle->saiQueue[handle->queueDriver].dataSize -= size;
+ handle->saiQueue[handle->queueDriver].data += size;
+ }
+#endif /* FSL_FEATURE_SAI_FIFO_COUNT */
+
+ /* If finished a blcok, call the callback function */
+ if (handle->saiQueue[handle->queueDriver].dataSize == 0U)
+ {
+ memset(&handle->saiQueue[handle->queueDriver], 0, sizeof(sai_transfer_t));
+ handle->queueDriver = (handle->queueDriver + 1) % SAI_XFER_QUEUE_SIZE;
+ if (handle->callback)
+ {
+ (handle->callback)(base, handle, kStatus_SAI_TxIdle, handle->userData);
+ }
+ }
+
+ /* If all data finished, just stop the transfer */
+ if (handle->saiQueue[handle->queueDriver].data == NULL)
+ {
+ SAI_TransferAbortSend(base, handle);
+ }
+}
+
+void SAI_TransferRxHandleIRQ(I2S_Type *base, sai_handle_t *handle)
+{
+ assert(handle);
+
+ uint8_t *buffer = handle->saiQueue[handle->queueDriver].data;
+ uint8_t dataSize = handle->bitWidth / 8U;
+
+ /* Handle Error */
+ if (base->RCSR & I2S_RCSR_FEF_MASK)
+ {
+ /* Clear FIFO error flag to continue transfer */
+ SAI_RxClearStatusFlags(base, kSAI_FIFOErrorFlag);
+
+ /* Call the callback */
+ if (handle->callback)
+ {
+ (handle->callback)(base, handle, kStatus_SAI_RxError, handle->userData);
+ }
+ }
+
+/* Handle transfer */
+#if defined(FSL_FEATURE_SAI_FIFO_COUNT) && (FSL_FEATURE_SAI_FIFO_COUNT > 1)
+ if (base->RCSR & I2S_RCSR_FRF_MASK)
+ {
+ /* Judge if the data need to transmit is less than space */
+ uint8_t size = MIN((handle->saiQueue[handle->queueDriver].dataSize), (handle->watermark * dataSize));
+
+ /* Copy the data from sai buffer to FIFO */
+ SAI_ReadNonBlocking(base, handle->channel, handle->bitWidth, buffer, size);
+
+ /* Update the internal counter */
+ handle->saiQueue[handle->queueDriver].dataSize -= size;
+ handle->saiQueue[handle->queueDriver].data += size;
+ }
+#else
+ if (base->RCSR & I2S_RCSR_FWF_MASK)
+ {
+ uint8_t size = MIN((handle->saiQueue[handle->queueDriver].dataSize), dataSize);
+
+ SAI_ReadNonBlocking(base, handle->channel, handle->bitWidth, buffer, size);
+
+ /* Update internal state */
+ handle->saiQueue[handle->queueDriver].dataSize -= size;
+ handle->saiQueue[handle->queueDriver].data += size;
+ }
+#endif /* FSL_FEATURE_SAI_FIFO_COUNT */
+
+ /* If finished a blcok, call the callback function */
+ if (handle->saiQueue[handle->queueDriver].dataSize == 0U)
+ {
+ memset(&handle->saiQueue[handle->queueDriver], 0, sizeof(sai_transfer_t));
+ handle->queueDriver = (handle->queueDriver + 1) % SAI_XFER_QUEUE_SIZE;
+ if (handle->callback)
+ {
+ (handle->callback)(base, handle, kStatus_SAI_RxIdle, handle->userData);
+ }
+ }
+
+ /* If all data finished, just stop the transfer */
+ if (handle->saiQueue[handle->queueDriver].data == NULL)
+ {
+ SAI_TransferAbortReceive(base, handle);
+ }
+}
+
+#if defined(I2S0)
+#if defined(FSL_FEATURE_SAI_INT_SOURCE_NUM) && (FSL_FEATURE_SAI_INT_SOURCE_NUM == 1)
+void I2S0_DriverIRQHandler(void)
+{
+ if ((s_saiHandle[0][1]) && ((I2S0->RCSR & kSAI_FIFOWarningFlag) || (I2S0->RCSR & kSAI_FIFOErrorFlag)))
+ {
+ s_saiRxIsr(I2S0, s_saiHandle[0][1]);
+ }
+ if ((s_saiHandle[0][0]) && ((I2S0->TCSR & kSAI_FIFOWarningFlag) || (I2S0->TCSR & kSAI_FIFOErrorFlag)))
+ {
+ s_saiTxIsr(I2S0, s_saiHandle[0][0]);
+ }
+}
+#else
+void I2S0_Tx_DriverIRQHandler(void)
+{
+ assert(s_saiHandle[0][0]);
+ s_saiTxIsr(I2S0, s_saiHandle[0][0]);
+}
+
+void I2S0_Rx_DriverIRQHandler(void)
+{
+ assert(s_saiHandle[0][1]);
+ s_saiRxIsr(I2S0, s_saiHandle[0][1]);
+}
+#endif /* FSL_FEATURE_SAI_INT_SOURCE_NUM */
+#endif /* I2S0*/
+
+#if defined(I2S1)
+void I2S1_Tx_DriverIRQHandler(void)
+{
+ assert(s_saiHandle[1][0]);
+ s_saiTxIsr(I2S1, s_saiHandle[1][0]);
+}
+
+void I2S1_Rx_DriverIRQHandler(void)
+{
+ assert(s_saiHandle[1][1]);
+ s_saiRxIsr(I2S1, s_saiHandle[1][1]);
+}
+#endif
diff --git a/drivers/fsl_sai.h b/drivers/fsl_sai.h
new file mode 100644
index 0000000..d40c575
--- /dev/null
+++ b/drivers/fsl_sai.h
@@ -0,0 +1,849 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_SAI_H_
+#define _FSL_SAI_H_
+
+#include "fsl_common.h"
+
+/*!
+ * @addtogroup sai
+ * @{
+ */
+
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+/*! @name Driver version */
+/*@{*/
+#define FSL_SAI_DRIVER_VERSION (MAKE_VERSION(2, 1, 1)) /*!< Version 2.1.1 */
+/*@}*/
+
+/*! @brief SAI return status*/
+enum _sai_status_t
+{
+ kStatus_SAI_TxBusy = MAKE_STATUS(kStatusGroup_SAI, 0), /*!< SAI Tx is busy. */
+ kStatus_SAI_RxBusy = MAKE_STATUS(kStatusGroup_SAI, 1), /*!< SAI Rx is busy. */
+ kStatus_SAI_TxError = MAKE_STATUS(kStatusGroup_SAI, 2), /*!< SAI Tx FIFO error. */
+ kStatus_SAI_RxError = MAKE_STATUS(kStatusGroup_SAI, 3), /*!< SAI Rx FIFO error. */
+ kStatus_SAI_QueueFull = MAKE_STATUS(kStatusGroup_SAI, 4), /*!< SAI transfer queue is full. */
+ kStatus_SAI_TxIdle = MAKE_STATUS(kStatusGroup_SAI, 5), /*!< SAI Tx is idle */
+ kStatus_SAI_RxIdle = MAKE_STATUS(kStatusGroup_SAI, 6) /*!< SAI Rx is idle */
+};
+
+/*! @brief Define the SAI bus type */
+typedef enum _sai_protocol
+{
+ kSAI_BusLeftJustified = 0x0U, /*!< Uses left justified format.*/
+ kSAI_BusRightJustified, /*!< Uses right justified format. */
+ kSAI_BusI2S, /*!< Uses I2S format. */
+ kSAI_BusPCMA, /*!< Uses I2S PCM A format.*/
+ kSAI_BusPCMB /*!< Uses I2S PCM B format. */
+} sai_protocol_t;
+
+/*! @brief Master or slave mode */
+typedef enum _sai_master_slave
+{
+ kSAI_Master = 0x0U, /*!< Master mode */
+ kSAI_Slave = 0x1U /*!< Slave mode */
+} sai_master_slave_t;
+
+/*! @brief Mono or stereo audio format */
+typedef enum _sai_mono_stereo
+{
+ kSAI_Stereo = 0x0U, /*!< Stereo sound. */
+ kSAI_MonoLeft, /*!< Only left channel have sound. */
+ kSAI_MonoRight /*!< Only Right channel have sound. */
+} sai_mono_stereo_t;
+
+/*! @brief Synchronous or asynchronous mode */
+typedef enum _sai_sync_mode
+{
+ kSAI_ModeAsync = 0x0U, /*!< Asynchronous mode */
+ kSAI_ModeSync, /*!< Synchronous mode (with receiver or transmit) */
+ kSAI_ModeSyncWithOtherTx, /*!< Synchronous with another SAI transmit */
+ kSAI_ModeSyncWithOtherRx /*!< Synchronous with another SAI receiver */
+} sai_sync_mode_t;
+
+/*! @brief Mater clock source */
+typedef enum _sai_mclk_source
+{
+ kSAI_MclkSourceSysclk = 0x0U, /*!< Master clock from the system clock */
+ kSAI_MclkSourceSelect1, /*!< Master clock from source 1 */
+ kSAI_MclkSourceSelect2, /*!< Master clock from source 2 */
+ kSAI_MclkSourceSelect3 /*!< Master clock from source 3 */
+} sai_mclk_source_t;
+
+/*! @brief Bit clock source */
+typedef enum _sai_bclk_source
+{
+ kSAI_BclkSourceBusclk = 0x0U, /*!< Bit clock using bus clock */
+ kSAI_BclkSourceMclkDiv, /*!< Bit clock using master clock divider */
+ kSAI_BclkSourceOtherSai0, /*!< Bit clock from other SAI device */
+ kSAI_BclkSourceOtherSai1 /*!< Bit clock from other SAI device */
+} sai_bclk_source_t;
+
+/*! @brief The SAI interrupt enable flag */
+enum _sai_interrupt_enable_t
+{
+ kSAI_WordStartInterruptEnable =
+ I2S_TCSR_WSIE_MASK, /*!< Word start flag, means the first word in a frame detected */
+ kSAI_SyncErrorInterruptEnable = I2S_TCSR_SEIE_MASK, /*!< Sync error flag, means the sync error is detected */
+ kSAI_FIFOWarningInterruptEnable = I2S_TCSR_FWIE_MASK, /*!< FIFO warning flag, means the FIFO is empty */
+ kSAI_FIFOErrorInterruptEnable = I2S_TCSR_FEIE_MASK, /*!< FIFO error flag */
+#if defined(FSL_FEATURE_SAI_FIFO_COUNT) && (FSL_FEATURE_SAI_FIFO_COUNT > 1)
+ kSAI_FIFORequestInterruptEnable = I2S_TCSR_FRIE_MASK, /*!< FIFO request, means reached watermark */
+#endif /* FSL_FEATURE_SAI_FIFO_COUNT */
+};
+
+/*! @brief The DMA request sources */
+enum _sai_dma_enable_t
+{
+ kSAI_FIFOWarningDMAEnable = I2S_TCSR_FWDE_MASK, /*!< FIFO warning caused by the DMA request */
+#if defined(FSL_FEATURE_SAI_FIFO_COUNT) && (FSL_FEATURE_SAI_FIFO_COUNT > 1)
+ kSAI_FIFORequestDMAEnable = I2S_TCSR_FRDE_MASK, /*!< FIFO request caused by the DMA request */
+#endif /* FSL_FEATURE_SAI_FIFO_COUNT */
+};
+
+/*! @brief The SAI status flag */
+enum _sai_flags
+{
+ kSAI_WordStartFlag = I2S_TCSR_WSF_MASK, /*!< Word start flag, means the first word in a frame detected */
+ kSAI_SyncErrorFlag = I2S_TCSR_SEF_MASK, /*!< Sync error flag, means the sync error is detected */
+ kSAI_FIFOErrorFlag = I2S_TCSR_FEF_MASK, /*!< FIFO error flag */
+#if defined(FSL_FEATURE_SAI_FIFO_COUNT) && (FSL_FEATURE_SAI_FIFO_COUNT > 1)
+ kSAI_FIFORequestFlag = I2S_TCSR_FRF_MASK, /*!< FIFO request flag. */
+#endif /* FSL_FEATURE_SAI_FIFO_COUNT */
+ kSAI_FIFOWarningFlag = I2S_TCSR_FWF_MASK, /*!< FIFO warning flag */
+};
+
+/*! @brief The reset type */
+typedef enum _sai_reset_type
+{
+ kSAI_ResetTypeSoftware = I2S_TCSR_SR_MASK, /*!< Software reset, reset the logic state */
+ kSAI_ResetTypeFIFO = I2S_TCSR_FR_MASK, /*!< FIFO reset, reset the FIFO read and write pointer */
+ kSAI_ResetAll = I2S_TCSR_SR_MASK | I2S_TCSR_FR_MASK /*!< All reset. */
+} sai_reset_type_t;
+
+#if defined(FSL_FEATURE_SAI_HAS_FIFO_PACKING) && FSL_FEATURE_SAI_HAS_FIFO_PACKING
+/*!
+ * @brief The SAI packing mode
+ * The mode includes 8 bit and 16 bit packing.
+ */
+typedef enum _sai_fifo_packing
+{
+ kSAI_FifoPackingDisabled = 0x0U, /*!< Packing disabled */
+ kSAI_FifoPacking8bit = 0x2U, /*!< 8 bit packing enabled */
+ kSAI_FifoPacking16bit = 0x3U /*!< 16bit packing enabled */
+} sai_fifo_packing_t;
+#endif /* FSL_FEATURE_SAI_HAS_FIFO_PACKING */
+
+/*! @brief SAI user configuration structure */
+typedef struct _sai_config
+{
+ sai_protocol_t protocol; /*!< Audio bus protocol in SAI */
+ sai_sync_mode_t syncMode; /*!< SAI sync mode, control Tx/Rx clock sync */
+#if defined(FSL_FEATURE_SAI_HAS_MCR) && (FSL_FEATURE_SAI_HAS_MCR)
+ bool mclkOutputEnable; /*!< Master clock output enable, true means master clock divider enabled */
+#endif /* FSL_FEATURE_SAI_HAS_MCR */
+ sai_mclk_source_t mclkSource; /*!< Master Clock source */
+ sai_bclk_source_t bclkSource; /*!< Bit Clock source */
+ sai_master_slave_t masterSlave; /*!< Master or slave */
+} sai_config_t;
+
+/*!@brief SAI transfer queue size, user can refine it according to use case. */
+#define SAI_XFER_QUEUE_SIZE (4)
+
+/*! @brief Audio sample rate */
+typedef enum _sai_sample_rate
+{
+ kSAI_SampleRate8KHz = 8000U, /*!< Sample rate 8000 Hz */
+ kSAI_SampleRate11025Hz = 11025U, /*!< Sample rate 11025 Hz */
+ kSAI_SampleRate12KHz = 12000U, /*!< Sample rate 12000 Hz */
+ kSAI_SampleRate16KHz = 16000U, /*!< Sample rate 16000 Hz */
+ kSAI_SampleRate22050Hz = 22050U, /*!< Sample rate 22050 Hz */
+ kSAI_SampleRate24KHz = 24000U, /*!< Sample rate 24000 Hz */
+ kSAI_SampleRate32KHz = 32000U, /*!< Sample rate 32000 Hz */
+ kSAI_SampleRate44100Hz = 44100U, /*!< Sample rate 44100 Hz */
+ kSAI_SampleRate48KHz = 48000U, /*!< Sample rate 48000 Hz */
+ kSAI_SampleRate96KHz = 96000U /*!< Sample rate 96000 Hz */
+} sai_sample_rate_t;
+
+/*! @brief Audio word width */
+typedef enum _sai_word_width
+{
+ kSAI_WordWidth8bits = 8U, /*!< Audio data width 8 bits */
+ kSAI_WordWidth16bits = 16U, /*!< Audio data width 16 bits */
+ kSAI_WordWidth24bits = 24U, /*!< Audio data width 24 bits */
+ kSAI_WordWidth32bits = 32U /*!< Audio data width 32 bits */
+} sai_word_width_t;
+
+/*! @brief sai transfer format */
+typedef struct _sai_transfer_format
+{
+ uint32_t sampleRate_Hz; /*!< Sample rate of audio data */
+ uint32_t bitWidth; /*!< Data length of audio data, usually 8/16/24/32 bits */
+ sai_mono_stereo_t stereo; /*!< Mono or stereo */
+ uint32_t masterClockHz; /*!< Master clock frequency in Hz */
+#if defined(FSL_FEATURE_SAI_FIFO_COUNT) && (FSL_FEATURE_SAI_FIFO_COUNT > 1)
+ uint8_t watermark; /*!< Watermark value */
+#endif /* FSL_FEATURE_SAI_FIFO_COUNT */
+ uint8_t channel; /*!< Data channel used in transfer.*/
+ sai_protocol_t protocol; /*!< Which audio protocol used */
+} sai_transfer_format_t;
+
+/*! @brief SAI transfer structure */
+typedef struct _sai_transfer
+{
+ uint8_t *data; /*!< Data start address to transfer. */
+ size_t dataSize; /*!< Transfer size. */
+} sai_transfer_t;
+
+typedef struct _sai_handle sai_handle_t;
+
+/*! @brief SAI transfer callback prototype */
+typedef void (*sai_transfer_callback_t)(I2S_Type *base, sai_handle_t *handle, status_t status, void *userData);
+
+/*! @brief SAI handle structure */
+struct _sai_handle
+{
+ uint32_t state; /*!< Transfer status */
+ sai_transfer_callback_t callback; /*!< Callback function called at transfer event*/
+ void *userData; /*!< Callback parameter passed to callback function*/
+ uint8_t bitWidth; /*!< Bit width for transfer, 8/16/24/32 bits */
+ uint8_t channel; /*!< Transfer channel */
+ sai_transfer_t saiQueue[SAI_XFER_QUEUE_SIZE]; /*!< Transfer queue storing queued transfer */
+ size_t transferSize[SAI_XFER_QUEUE_SIZE]; /*!< Data bytes need to transfer */
+ volatile uint8_t queueUser; /*!< Index for user to queue transfer */
+ volatile uint8_t queueDriver; /*!< Index for driver to get the transfer data and size */
+#if defined(FSL_FEATURE_SAI_FIFO_COUNT) && (FSL_FEATURE_SAI_FIFO_COUNT > 1)
+ uint8_t watermark; /*!< Watermark value */
+#endif
+};
+
+/*******************************************************************************
+ * API
+ ******************************************************************************/
+
+#if defined(__cplusplus)
+extern "C" {
+#endif /*_cplusplus*/
+
+/*!
+ * @name Initialization and deinitialization
+ * @{
+ */
+
+/*!
+ * @brief Initializes the SAI Tx peripheral.
+ *
+ * Ungates the SAI clock, resets the module, and configures SAI Tx with a configuration structure.
+ * The configuration structure can be custom filled or set with default values by
+ * SAI_TxGetDefaultConfig().
+ *
+ * @note This API should be called at the beginning of the application to use
+ * the SAI driver. Otherwise, accessing the SAIM module can cause a hard fault
+ * because the clock is not enabled.
+ *
+ * @param base SAI base pointer
+ * @param config SAI configuration structure.
+*/
+void SAI_TxInit(I2S_Type *base, const sai_config_t *config);
+
+/*!
+ * @brief Initializes the the SAI Rx peripheral.
+ *
+ * Ungates the SAI clock, resets the module, and configures the SAI Rx with a configuration structure.
+ * The configuration structure can be custom filled or set with default values by
+ * SAI_RxGetDefaultConfig().
+ *
+ * @note This API should be called at the beginning of the application to use
+ * the SAI driver. Otherwise, accessing the SAI module can cause a hard fault
+ * because the clock is not enabled.
+ *
+ * @param base SAI base pointer
+ * @param config SAI configuration structure.
+ */
+void SAI_RxInit(I2S_Type *base, const sai_config_t *config);
+
+/*!
+ * @brief Sets the SAI Tx configuration structure to default values.
+ *
+ * This API initializes the configuration structure for use in SAI_TxConfig().
+ * The initialized structure can remain unchanged in SAI_TxConfig(), or it can be modified
+ * before calling SAI_TxConfig().
+ * Example:
+ @code
+ sai_config_t config;
+ SAI_TxGetDefaultConfig(&config);
+ @endcode
+ *
+ * @param config pointer to master configuration structure
+ */
+void SAI_TxGetDefaultConfig(sai_config_t *config);
+
+/*!
+ * @brief Sets the SAI Rx configuration structure to default values.
+ *
+ * This API initializes the configuration structure for use in SAI_RxConfig().
+ * The initialized structure can remain unchanged in SAI_RxConfig() or it can be modified
+ * before calling SAI_RxConfig().
+ * Example:
+ @code
+ sai_config_t config;
+ SAI_RxGetDefaultConfig(&config);
+ @endcode
+ *
+ * @param config pointer to master configuration structure
+ */
+void SAI_RxGetDefaultConfig(sai_config_t *config);
+
+/*!
+ * @brief De-initializes the SAI peripheral.
+ *
+ * This API gates the SAI clock. The SAI module can't operate unless SAI_TxInit
+ * or SAI_RxInit is called to enable the clock.
+ *
+ * @param base SAI base pointer
+*/
+void SAI_Deinit(I2S_Type *base);
+
+/*!
+ * @brief Resets the SAI Tx.
+ *
+ * This function enables the software reset and FIFO reset of SAI Tx. After reset, clear the reset bit.
+ *
+ * @param base SAI base pointer
+ */
+void SAI_TxReset(I2S_Type *base);
+
+/*!
+ * @brief Resets the SAI Rx.
+ *
+ * This function enables the software reset and FIFO reset of SAI Rx. After reset, clear the reset bit.
+ *
+ * @param base SAI base pointer
+ */
+void SAI_RxReset(I2S_Type *base);
+
+/*!
+ * @brief Enables/disables SAI Tx.
+ *
+ * @param base SAI base pointer
+ * @param enable True means enable SAI Tx, false means disable.
+ */
+void SAI_TxEnable(I2S_Type *base, bool enable);
+
+/*!
+ * @brief Enables/disables SAI Rx.
+ *
+ * @param base SAI base pointer
+ * @param enable True means enable SAI Rx, false means disable.
+ */
+void SAI_RxEnable(I2S_Type *base, bool enable);
+
+/*! @} */
+
+/*!
+ * @name Status
+ * @{
+ */
+
+/*!
+ * @brief Gets the SAI Tx status flag state.
+ *
+ * @param base SAI base pointer
+ * @return SAI Tx status flag value. Use the Status Mask to get the status value needed.
+ */
+static inline uint32_t SAI_TxGetStatusFlag(I2S_Type *base)
+{
+ return base->TCSR;
+}
+
+/*!
+ * @brief Clears the SAI Tx status flag state.
+ *
+ * @param base SAI base pointer
+ * @param mask State mask. It can be a combination of the following source if defined:
+ * @arg kSAI_WordStartFlag
+ * @arg kSAI_SyncErrorFlag
+ * @arg kSAI_FIFOErrorFlag
+ */
+static inline void SAI_TxClearStatusFlags(I2S_Type *base, uint32_t mask)
+{
+ base->TCSR = ((base->TCSR & 0xFFE3FFFFU) | mask);
+}
+
+/*!
+ * @brief Gets the SAI Tx status flag state.
+ *
+ * @param base SAI base pointer
+ * @return SAI Rx status flag value. Use the Status Mask to get the status value needed.
+ */
+static inline uint32_t SAI_RxGetStatusFlag(I2S_Type *base)
+{
+ return base->RCSR;
+}
+
+/*!
+ * @brief Clears the SAI Rx status flag state.
+ *
+ * @param base SAI base pointer
+ * @param mask State mask. It can be a combination of the following source if defined:
+ * @arg kSAI_WordStartFlag
+ * @arg kSAI_SyncErrorFlag
+ * @arg kSAI_FIFOErrorFlag
+ */
+static inline void SAI_RxClearStatusFlags(I2S_Type *base, uint32_t mask)
+{
+ base->RCSR = ((base->RCSR & 0xFFE3FFFFU) | mask);
+}
+
+/*! @} */
+
+/*!
+ * @name Interrupts
+ * @{
+ */
+
+/*!
+ * @brief Enables SAI Tx interrupt requests.
+ *
+ * @param base SAI base pointer
+ * @param mask interrupt source
+ * The parameter can be a combination of the following source if defined:
+ * @arg kSAI_WordStartInterruptEnable
+ * @arg kSAI_SyncErrorInterruptEnable
+ * @arg kSAI_FIFOWarningInterruptEnable
+ * @arg kSAI_FIFORequestInterruptEnable
+ * @arg kSAI_FIFOErrorInterruptEnable
+ */
+static inline void SAI_TxEnableInterrupts(I2S_Type *base, uint32_t mask)
+{
+ base->TCSR = ((base->TCSR & 0xFFE3FFFFU) | mask);
+}
+
+/*!
+ * @brief Enables SAI Rx interrupt requests.
+ *
+ * @param base SAI base pointer
+ * @param mask interrupt source
+ * The parameter can be a combination of the following source if defined:
+ * @arg kSAI_WordStartInterruptEnable
+ * @arg kSAI_SyncErrorInterruptEnable
+ * @arg kSAI_FIFOWarningInterruptEnable
+ * @arg kSAI_FIFORequestInterruptEnable
+ * @arg kSAI_FIFOErrorInterruptEnable
+ */
+static inline void SAI_RxEnableInterrupts(I2S_Type *base, uint32_t mask)
+{
+ base->RCSR = ((base->RCSR & 0xFFE3FFFFU) | mask);
+}
+
+/*!
+ * @brief Disables SAI Tx interrupt requests.
+ *
+ * @param base SAI base pointer
+ * @param mask interrupt source
+ * The parameter can be a combination of the following source if defined:
+ * @arg kSAI_WordStartInterruptEnable
+ * @arg kSAI_SyncErrorInterruptEnable
+ * @arg kSAI_FIFOWarningInterruptEnable
+ * @arg kSAI_FIFORequestInterruptEnable
+ * @arg kSAI_FIFOErrorInterruptEnable
+ */
+static inline void SAI_TxDisableInterrupts(I2S_Type *base, uint32_t mask)
+{
+ base->TCSR = ((base->TCSR & 0xFFE3FFFFU) & (~mask));
+}
+
+/*!
+ * @brief Disables SAI Rx interrupt requests.
+ *
+ * @param base SAI base pointer
+ * @param mask interrupt source
+ * The parameter can be a combination of the following source if defined:
+ * @arg kSAI_WordStartInterruptEnable
+ * @arg kSAI_SyncErrorInterruptEnable
+ * @arg kSAI_FIFOWarningInterruptEnable
+ * @arg kSAI_FIFORequestInterruptEnable
+ * @arg kSAI_FIFOErrorInterruptEnable
+ */
+static inline void SAI_RxDisableInterrupts(I2S_Type *base, uint32_t mask)
+{
+ base->RCSR = ((base->RCSR & 0xFFE3FFFFU) & (~mask));
+}
+
+/*! @} */
+
+/*!
+ * @name DMA Control
+ * @{
+ */
+
+/*!
+ * @brief Enables/disables SAI Tx DMA requests.
+ * @param base SAI base pointer
+ * @param mask DMA source
+ * The parameter can be combination of the following source if defined:
+ * @arg kSAI_FIFOWarningDMAEnable
+ * @arg kSAI_FIFORequestDMAEnable
+ * @param enable True means enable DMA, false means disable DMA.
+ */
+static inline void SAI_TxEnableDMA(I2S_Type *base, uint32_t mask, bool enable)
+{
+ if (enable)
+ {
+ base->TCSR = ((base->TCSR & 0xFFE3FFFFU) | mask);
+ }
+ else
+ {
+ base->TCSR = ((base->TCSR & 0xFFE3FFFFU) & (~mask));
+ }
+}
+
+/*!
+ * @brief Enables/disables SAI Rx DMA requests.
+ * @param base SAI base pointer
+ * @param mask DMA source
+ * The parameter can be a combination of the following source if defined:
+ * @arg kSAI_FIFOWarningDMAEnable
+ * @arg kSAI_FIFORequestDMAEnable
+ * @param enable True means enable DMA, false means disable DMA.
+ */
+static inline void SAI_RxEnableDMA(I2S_Type *base, uint32_t mask, bool enable)
+{
+ if (enable)
+ {
+ base->RCSR = ((base->RCSR & 0xFFE3FFFFU) | mask);
+ }
+ else
+ {
+ base->RCSR = ((base->RCSR & 0xFFE3FFFFU) & (~mask));
+ }
+}
+
+/*!
+ * @brief Gets the SAI Tx data register address.
+ *
+ * This API is used to provide a transfer address for SAI DMA transfer configuration.
+ *
+ * @param base SAI base pointer.
+ * @param channel Which data channel used.
+ * @return data register address.
+ */
+static inline uint32_t SAI_TxGetDataRegisterAddress(I2S_Type *base, uint32_t channel)
+{
+ return (uint32_t)(&(base->TDR)[channel]);
+}
+
+/*!
+ * @brief Gets the SAI Rx data register address.
+ *
+ * This API is used to provide a transfer address for SAI DMA transfer configuration.
+ *
+ * @param base SAI base pointer.
+ * @param channel Which data channel used.
+ * @return data register address.
+ */
+static inline uint32_t SAI_RxGetDataRegisterAddress(I2S_Type *base, uint32_t channel)
+{
+ return (uint32_t)(&(base->RDR)[channel]);
+}
+
+/*! @} */
+
+/*!
+ * @name Bus Operations
+ * @{
+ */
+
+/*!
+ * @brief Configures the SAI Tx audio format.
+ *
+ * The audio format can be changed at run-time. This function configures the sample rate and audio data
+ * format to be transferred.
+ *
+ * @param base SAI base pointer.
+ * @param format Pointer to SAI audio data format structure.
+ * @param mclkSourceClockHz SAI master clock source frequency in Hz.
+ * @param bclkSourceClockHz SAI bit clock source frequency in Hz. If bit clock source is master
+ * clock, this value should equals to masterClockHz in format.
+*/
+void SAI_TxSetFormat(I2S_Type *base,
+ sai_transfer_format_t *format,
+ uint32_t mclkSourceClockHz,
+ uint32_t bclkSourceClockHz);
+
+/*!
+ * @brief Configures the SAI Rx audio format.
+ *
+ * The audio format can be changed at run-time. This function configures the sample rate and audio data
+ * format to be transferred.
+ *
+ * @param base SAI base pointer.
+ * @param format Pointer to SAI audio data format structure.
+ * @param mclkSourceClockHz SAI master clock source frequency in Hz.
+ * @param bclkSourceClockHz SAI bit clock source frequency in Hz. If bit clock source is master
+ * clock, this value should equals to masterClockHz in format.
+*/
+void SAI_RxSetFormat(I2S_Type *base,
+ sai_transfer_format_t *format,
+ uint32_t mclkSourceClockHz,
+ uint32_t bclkSourceClockHz);
+
+/*!
+ * @brief Sends data using a blocking method.
+ *
+ * @note This function blocks by polling until data is ready to be sent.
+ *
+ * @param base SAI base pointer.
+ * @param channel Data channel used.
+ * @param bitWidth How many bits in a audio word, usually 8/16/24/32 bits.
+ * @param buffer Pointer to the data to be written.
+ * @param size Bytes to be written.
+ */
+void SAI_WriteBlocking(I2S_Type *base, uint32_t channel, uint32_t bitWidth, uint8_t *buffer, uint32_t size);
+
+/*!
+ * @brief Writes data into SAI FIFO.
+ *
+ * @param base SAI base pointer.
+ * @param channel Data channel used.
+ * @param data Data needs to be written.
+ */
+static inline void SAI_WriteData(I2S_Type *base, uint32_t channel, uint32_t data)
+{
+ base->TDR[channel] = data;
+}
+
+/*!
+ * @brief Receives data using a blocking method.
+ *
+ * @note This function blocks by polling until data is ready to be sent.
+ *
+ * @param base SAI base pointer.
+ * @param channel Data channel used.
+ * @param bitWidth How many bits in a audio word, usually 8/16/24/32 bits.
+ * @param buffer Pointer to the data to be read.
+ * @param size Bytes to be read.
+ */
+void SAI_ReadBlocking(I2S_Type *base, uint32_t channel, uint32_t bitWidth, uint8_t *buffer, uint32_t size);
+
+/*!
+ * @brief Reads data from SAI FIFO.
+ *
+ * @param base SAI base pointer.
+ * @param channel Data channel used.
+ * @return Data in SAI FIFO.
+ */
+static inline uint32_t SAI_ReadData(I2S_Type *base, uint32_t channel)
+{
+ return base->RDR[channel];
+}
+
+/*! @} */
+
+/*!
+ * @name Transactional
+ * @{
+ */
+
+/*!
+ * @brief Initializes the SAI Tx handle.
+ *
+ * This function initializes the Tx handle for SAI Tx transactional APIs. Call
+ * this function one time to get the handle initialized.
+ *
+ * @param base SAI base pointer
+ * @param handle SAI handle pointer.
+ * @param callback pointer to user callback function
+ * @param userData user parameter passed to the callback function
+ */
+void SAI_TransferTxCreateHandle(I2S_Type *base, sai_handle_t *handle, sai_transfer_callback_t callback, void *userData);
+
+/*!
+ * @brief Initializes the SAI Rx handle.
+ *
+ * This function initializes the Rx handle for SAI Rx transactional APIs. Call
+ * this function one time to get the handle initialized.
+ *
+ * @param base SAI base pointer.
+ * @param handle SAI handle pointer.
+ * @param callback pointer to user callback function
+ * @param userData user parameter passed to the callback function
+ */
+void SAI_TransferRxCreateHandle(I2S_Type *base, sai_handle_t *handle, sai_transfer_callback_t callback, void *userData);
+
+/*!
+ * @brief Configures the SAI Tx audio format.
+ *
+ * The audio format can be changed at run-time. This function configures the sample rate and audio data
+ * format to be transferred.
+ *
+ * @param base SAI base pointer.
+ * @param handle SAI handle pointer.
+ * @param format Pointer to SAI audio data format structure.
+ * @param mclkSourceClockHz SAI master clock source frequency in Hz.
+ * @param bclkSourceClockHz SAI bit clock source frequency in Hz. If a bit clock source is a master
+ * clock, this value should equal to masterClockHz in format.
+ * @return Status of this function. Return value is one of status_t.
+*/
+status_t SAI_TransferTxSetFormat(I2S_Type *base,
+ sai_handle_t *handle,
+ sai_transfer_format_t *format,
+ uint32_t mclkSourceClockHz,
+ uint32_t bclkSourceClockHz);
+
+/*!
+ * @brief Configures the SAI Rx audio format.
+ *
+ * The audio format can be changed at run-time. This function configures the sample rate and audio data
+ * format to be transferred.
+ *
+ * @param base SAI base pointer.
+ * @param handle SAI handle pointer.
+ * @param format Pointer to SAI audio data format structure.
+ * @param mclkSourceClockHz SAI master clock source frequency in Hz.
+ * @param bclkSourceClockHz SAI bit clock source frequency in Hz. If bit clock source is master
+ * clock, this value should equals to masterClockHz in format.
+ * @return Status of this function. Return value is one of status_t.
+*/
+status_t SAI_TransferRxSetFormat(I2S_Type *base,
+ sai_handle_t *handle,
+ sai_transfer_format_t *format,
+ uint32_t mclkSourceClockHz,
+ uint32_t bclkSourceClockHz);
+
+/*!
+ * @brief Performs an interrupt non-blocking send transfer on SAI.
+ *
+ * @note This API returns immediately after the transfer initiates.
+ * Call the SAI_TxGetTransferStatusIRQ to poll the transfer status and check whether
+ * the transfer is finished. If the return status is not kStatus_SAI_Busy, the transfer
+ * is finished.
+ *
+ * @param base SAI base pointer
+ * @param handle pointer to sai_handle_t structure which stores the transfer state
+ * @param xfer pointer to sai_transfer_t structure
+ * @retval kStatus_Success Successfully started the data receive.
+ * @retval kStatus_SAI_TxBusy Previous receive still not finished.
+ * @retval kStatus_InvalidArgument The input parameter is invalid.
+ */
+status_t SAI_TransferSendNonBlocking(I2S_Type *base, sai_handle_t *handle, sai_transfer_t *xfer);
+
+/*!
+ * @brief Performs an interrupt non-blocking receive transfer on SAI.
+ *
+ * @note This API returns immediately after the transfer initiates.
+ * Call the SAI_RxGetTransferStatusIRQ to poll the transfer status and check whether
+ * the transfer is finished. If the return status is not kStatus_SAI_Busy, the transfer
+ * is finished.
+ *
+ * @param base SAI base pointer
+ * @param handle pointer to sai_handle_t structure which stores the transfer state
+ * @param xfer pointer to sai_transfer_t structure
+ * @retval kStatus_Success Successfully started the data receive.
+ * @retval kStatus_SAI_RxBusy Previous receive still not finished.
+ * @retval kStatus_InvalidArgument The input parameter is invalid.
+ */
+status_t SAI_TransferReceiveNonBlocking(I2S_Type *base, sai_handle_t *handle, sai_transfer_t *xfer);
+
+/*!
+ * @brief Gets a set byte count.
+ *
+ * @param base SAI base pointer.
+ * @param handle pointer to sai_handle_t structure which stores the transfer state.
+ * @param count Bytes count sent.
+ * @retval kStatus_Success Succeed get the transfer count.
+ * @retval kStatus_NoTransferInProgress There is not a non-blocking transaction currently in progress.
+ */
+status_t SAI_TransferGetSendCount(I2S_Type *base, sai_handle_t *handle, size_t *count);
+
+/*!
+ * @brief Gets a received byte count.
+ *
+ * @param base SAI base pointer.
+ * @param handle pointer to sai_handle_t structure which stores the transfer state.
+ * @param count Bytes count received.
+ * @retval kStatus_Success Succeed get the transfer count.
+ * @retval kStatus_NoTransferInProgress There is not a non-blocking transaction currently in progress.
+ */
+status_t SAI_TransferGetReceiveCount(I2S_Type *base, sai_handle_t *handle, size_t *count);
+
+/*!
+ * @brief Aborts the current send.
+ *
+ * @note This API can be called any time when an interrupt non-blocking transfer initiates
+ * to abort the transfer early.
+ *
+ * @param base SAI base pointer.
+ * @param handle pointer to sai_handle_t structure which stores the transfer state.
+ */
+void SAI_TransferAbortSend(I2S_Type *base, sai_handle_t *handle);
+
+/*!
+ * @brief Aborts the the current IRQ receive.
+ *
+ * @note This API can be called any time when an interrupt non-blocking transfer initiates
+ * to abort the transfer early.
+ *
+ * @param base SAI base pointer
+ * @param handle pointer to sai_handle_t structure which stores the transfer state.
+ */
+void SAI_TransferAbortReceive(I2S_Type *base, sai_handle_t *handle);
+
+/*!
+ * @brief Tx interrupt handler.
+ *
+ * @param base SAI base pointer.
+ * @param handle pointer to sai_handle_t structure.
+ */
+void SAI_TransferTxHandleIRQ(I2S_Type *base, sai_handle_t *handle);
+
+/*!
+ * @brief Tx interrupt handler.
+ *
+ * @param base SAI base pointer.
+ * @param handle pointer to sai_handle_t structure.
+ */
+void SAI_TransferRxHandleIRQ(I2S_Type *base, sai_handle_t *handle);
+
+/*! @} */
+
+#if defined(__cplusplus)
+}
+#endif /*_cplusplus*/
+
+/*! @} */
+
+#endif /* _FSL_SAI_H_ */
diff --git a/drivers/fsl_sai_edma.c b/drivers/fsl_sai_edma.c
new file mode 100644
index 0000000..9b1b2f6
--- /dev/null
+++ b/drivers/fsl_sai_edma.c
@@ -0,0 +1,379 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_sai_edma.h"
+
+/*******************************************************************************
+ * Definitations
+ ******************************************************************************/
+/* Used for 32byte aligned */
+#define STCD_ADDR(address) (edma_tcd_t *)(((uint32_t)address + 32) & ~0x1FU)
+
+/*<! Structure definition for uart_edma_private_handle_t. The structure is private. */
+typedef struct _sai_edma_private_handle
+{
+ I2S_Type *base;
+ sai_edma_handle_t *handle;
+} sai_edma_private_handle_t;
+
+enum _sai_edma_transfer_state
+{
+ kSAI_Busy = 0x0U, /*!< SAI is busy */
+ kSAI_Idle, /*!< Transfer is done. */
+};
+
+/*<! Private handle only used for internally. */
+static sai_edma_private_handle_t s_edmaPrivateHandle[FSL_FEATURE_SOC_I2S_COUNT][2];
+
+/*******************************************************************************
+ * Prototypes
+ ******************************************************************************/
+/*!
+ * @brief Get the instance number for SAI.
+ *
+ * @param base SAI base pointer.
+ */
+extern uint32_t SAI_GetInstance(I2S_Type *base);
+
+/*!
+ * @brief SAI EDMA callback for send.
+ *
+ * @param handle pointer to sai_edma_handle_t structure which stores the transfer state.
+ * @param userData Parameter for user callback.
+ * @param done If the DMA transfer finished.
+ * @param tcds The TCD index.
+ */
+static void SAI_TxEDMACallback(edma_handle_t *handle, void *userData, bool done, uint32_t tcds);
+
+/*!
+ * @brief SAI EDMA callback for receive.
+ *
+ * @param handle pointer to sai_edma_handle_t structure which stores the transfer state.
+ * @param userData Parameter for user callback.
+ * @param done If the DMA transfer finished.
+ * @param tcds The TCD index.
+ */
+static void SAI_RxEDMACallback(edma_handle_t *handle, void *userData, bool done, uint32_t tcds);
+
+/*******************************************************************************
+* Code
+******************************************************************************/
+static void SAI_TxEDMACallback(edma_handle_t *handle, void *userData, bool done, uint32_t tcds)
+{
+ sai_edma_private_handle_t *privHandle = (sai_edma_private_handle_t *)userData;
+ sai_edma_handle_t *saiHandle = privHandle->handle;
+
+ /* If finished a blcok, call the callback function */
+ memset(&saiHandle->saiQueue[saiHandle->queueDriver], 0, sizeof(sai_transfer_t));
+ saiHandle->queueDriver = (saiHandle->queueDriver + 1) % SAI_XFER_QUEUE_SIZE;
+ if (saiHandle->callback)
+ {
+ (saiHandle->callback)(privHandle->base, saiHandle, kStatus_SAI_TxIdle, saiHandle->userData);
+ }
+
+ /* If all data finished, just stop the transfer */
+ if (saiHandle->saiQueue[saiHandle->queueDriver].data == NULL)
+ {
+ SAI_TransferAbortSendEDMA(privHandle->base, saiHandle);
+ }
+}
+
+static void SAI_RxEDMACallback(edma_handle_t *handle, void *userData, bool done, uint32_t tcds)
+{
+ sai_edma_private_handle_t *privHandle = (sai_edma_private_handle_t *)userData;
+ sai_edma_handle_t *saiHandle = privHandle->handle;
+
+ /* If finished a blcok, call the callback function */
+ memset(&saiHandle->saiQueue[saiHandle->queueDriver], 0, sizeof(sai_transfer_t));
+ saiHandle->queueDriver = (saiHandle->queueDriver + 1) % SAI_XFER_QUEUE_SIZE;
+ if (saiHandle->callback)
+ {
+ (saiHandle->callback)(privHandle->base, saiHandle, kStatus_SAI_RxIdle, saiHandle->userData);
+ }
+
+ /* If all data finished, just stop the transfer */
+ if (saiHandle->saiQueue[saiHandle->queueDriver].data == NULL)
+ {
+ SAI_TransferAbortReceiveEDMA(privHandle->base, saiHandle);
+ }
+}
+
+void SAI_TransferTxCreateHandleEDMA(
+ I2S_Type *base, sai_edma_handle_t *handle, sai_edma_callback_t callback, void *userData, edma_handle_t *dmaHandle)
+{
+ assert(handle && dmaHandle);
+
+ uint32_t instance = SAI_GetInstance(base);
+
+ /* Set sai base to handle */
+ handle->dmaHandle = dmaHandle;
+ handle->callback = callback;
+ handle->userData = userData;
+
+ /* Set SAI state to idle */
+ handle->state = kSAI_Idle;
+
+ s_edmaPrivateHandle[instance][0].base = base;
+ s_edmaPrivateHandle[instance][0].handle = handle;
+
+ /* Need to use scatter gather */
+ EDMA_InstallTCDMemory(dmaHandle, STCD_ADDR(handle->tcd), SAI_XFER_QUEUE_SIZE);
+
+ /* Install callback for Tx dma channel */
+ EDMA_SetCallback(dmaHandle, SAI_TxEDMACallback, &s_edmaPrivateHandle[instance][0]);
+}
+
+void SAI_TransferRxCreateHandleEDMA(
+ I2S_Type *base, sai_edma_handle_t *handle, sai_edma_callback_t callback, void *userData, edma_handle_t *dmaHandle)
+{
+ assert(handle && dmaHandle);
+
+ uint32_t instance = SAI_GetInstance(base);
+
+ /* Set sai base to handle */
+ handle->dmaHandle = dmaHandle;
+ handle->callback = callback;
+ handle->userData = userData;
+
+ /* Set SAI state to idle */
+ handle->state = kSAI_Idle;
+
+ s_edmaPrivateHandle[instance][1].base = base;
+ s_edmaPrivateHandle[instance][1].handle = handle;
+
+ /* Need to use scatter gather */
+ EDMA_InstallTCDMemory(dmaHandle, STCD_ADDR(handle->tcd), SAI_XFER_QUEUE_SIZE);
+
+ /* Install callback for Tx dma channel */
+ EDMA_SetCallback(dmaHandle, SAI_RxEDMACallback, &s_edmaPrivateHandle[instance][1]);
+}
+
+void SAI_TransferTxSetFormatEDMA(I2S_Type *base,
+ sai_edma_handle_t *handle,
+ sai_transfer_format_t *format,
+ uint32_t mclkSourceClockHz,
+ uint32_t bclkSourceClockHz)
+{
+ assert(handle && format);
+
+ /* Configure the audio format to SAI registers */
+ SAI_TxSetFormat(base, format, mclkSourceClockHz, bclkSourceClockHz);
+
+ /* Get the tranfer size from format, this should be used in EDMA configuration */
+ handle->bytesPerFrame = format->bitWidth / 8U;
+
+ /* Update the data channel SAI used */
+ handle->channel = format->channel;
+#if defined(FSL_FEATURE_SAI_FIFO_COUNT) && (FSL_FEATURE_SAI_FIFO_COUNT > 1)
+ handle->count = FSL_FEATURE_SAI_FIFO_COUNT - format->watermark;
+#else
+ handle->count = 1U;
+#endif /* FSL_FEATURE_SAI_FIFO_COUNT */
+}
+
+void SAI_TransferRxSetFormatEDMA(I2S_Type *base,
+ sai_edma_handle_t *handle,
+ sai_transfer_format_t *format,
+ uint32_t mclkSourceClockHz,
+ uint32_t bclkSourceClockHz)
+{
+ assert(handle && format);
+
+ /* Configure the audio format to SAI registers */
+ SAI_RxSetFormat(base, format, mclkSourceClockHz, bclkSourceClockHz);
+
+ /* Get the tranfer size from format, this should be used in EDMA configuration */
+ handle->bytesPerFrame = format->bitWidth / 8U;
+
+ /* Update the data channel SAI used */
+ handle->channel = format->channel;
+
+#if defined(FSL_FEATURE_SAI_FIFO_COUNT) && (FSL_FEATURE_SAI_FIFO_COUNT > 1)
+ handle->count = format->watermark;
+#else
+ handle->count = 1U;
+#endif /* FSL_FEATURE_SAI_FIFO_COUNT */
+}
+
+status_t SAI_TransferSendEDMA(I2S_Type *base, sai_edma_handle_t *handle, sai_transfer_t *xfer)
+{
+ assert(handle && xfer);
+
+ edma_transfer_config_t config = {0};
+ uint32_t destAddr = SAI_TxGetDataRegisterAddress(base, handle->channel);
+
+ /* Check if input parameter invalid */
+ if ((xfer->data == NULL) || (xfer->dataSize == 0U))
+ {
+ return kStatus_InvalidArgument;
+ }
+
+ if (handle->saiQueue[handle->queueUser].data)
+ {
+ return kStatus_SAI_QueueFull;
+ }
+
+ /* Change the state of handle */
+ handle->state = kSAI_Busy;
+
+ /* Update the queue state */
+ handle->transferSize[handle->queueUser] = xfer->dataSize;
+ handle->saiQueue[handle->queueUser].data = xfer->data;
+ handle->saiQueue[handle->queueUser].dataSize = xfer->dataSize;
+ handle->queueUser = (handle->queueUser + 1) % SAI_XFER_QUEUE_SIZE;
+
+ /* Prepare edma configure */
+ EDMA_PrepareTransfer(&config, xfer->data, handle->bytesPerFrame, (void *)destAddr, handle->bytesPerFrame,
+ handle->count * handle->bytesPerFrame, xfer->dataSize, kEDMA_MemoryToPeripheral);
+
+ EDMA_SubmitTransfer(handle->dmaHandle, &config);
+
+ /* Start DMA transfer */
+ EDMA_StartTransfer(handle->dmaHandle);
+
+ /* Enable DMA enable bit */
+ SAI_TxEnableDMA(base, kSAI_FIFORequestDMAEnable, true);
+
+ /* Enable SAI Tx clock */
+ SAI_TxEnable(base, true);
+
+ return kStatus_Success;
+}
+
+status_t SAI_TransferReceiveEDMA(I2S_Type *base, sai_edma_handle_t *handle, sai_transfer_t *xfer)
+{
+ assert(handle && xfer);
+
+ edma_transfer_config_t config = {0};
+ uint32_t srcAddr = SAI_RxGetDataRegisterAddress(base, handle->channel);
+
+ /* Check if input parameter invalid */
+ if ((xfer->data == NULL) || (xfer->dataSize == 0U))
+ {
+ return kStatus_InvalidArgument;
+ }
+
+ if (handle->saiQueue[handle->queueUser].data)
+ {
+ return kStatus_SAI_QueueFull;
+ }
+
+ /* Change the state of handle */
+ handle->state = kSAI_Busy;
+
+ /* Update queue state */
+ handle->transferSize[handle->queueUser] = xfer->dataSize;
+ handle->saiQueue[handle->queueUser].data = xfer->data;
+ handle->saiQueue[handle->queueUser].dataSize = xfer->dataSize;
+ handle->queueUser = (handle->queueUser + 1) % SAI_XFER_QUEUE_SIZE;
+
+ /* Prepare edma configure */
+ EDMA_PrepareTransfer(&config, (void *)srcAddr, handle->bytesPerFrame, xfer->data, handle->bytesPerFrame,
+ handle->count * handle->bytesPerFrame, xfer->dataSize, kEDMA_PeripheralToMemory);
+
+ EDMA_SubmitTransfer(handle->dmaHandle, &config);
+
+ /* Start DMA transfer */
+ EDMA_StartTransfer(handle->dmaHandle);
+
+ /* Enable DMA enable bit */
+ SAI_RxEnableDMA(base, kSAI_FIFORequestDMAEnable, true);
+
+ /* Enable SAI Rx clock */
+ SAI_RxEnable(base, true);
+
+ return kStatus_Success;
+}
+
+void SAI_TransferAbortSendEDMA(I2S_Type *base, sai_edma_handle_t *handle)
+{
+ assert(handle);
+
+ /* Disable dma */
+ EDMA_AbortTransfer(handle->dmaHandle);
+
+ /* Disable DMA enable bit */
+ SAI_TxEnableDMA(base, kSAI_FIFORequestDMAEnable, false);
+
+ /* Set the handle state */
+ handle->state = kSAI_Idle;
+}
+
+void SAI_TransferAbortReceiveEDMA(I2S_Type *base, sai_edma_handle_t *handle)
+{
+ assert(handle);
+
+ /* Disable dma */
+ EDMA_AbortTransfer(handle->dmaHandle);
+
+ /* Disable DMA enable bit */
+ SAI_RxEnableDMA(base, kSAI_FIFORequestDMAEnable, false);
+
+ /* Set the handle state */
+ handle->state = kSAI_Idle;
+}
+
+status_t SAI_TransferGetSendCountEDMA(I2S_Type *base, sai_edma_handle_t *handle, size_t *count)
+{
+ assert(handle);
+
+ status_t status = kStatus_Success;
+
+ if (handle->state != kSAI_Busy)
+ {
+ status = kStatus_NoTransferInProgress;
+ }
+ else
+ {
+ *count = (handle->transferSize[handle->queueDriver] -
+ EDMA_GetRemainingBytes(handle->dmaHandle->base, handle->dmaHandle->channel));
+ }
+
+ return status;
+}
+
+status_t SAI_TransferGetReceiveCountEDMA(I2S_Type *base, sai_edma_handle_t *handle, size_t *count)
+{
+ assert(handle);
+
+ status_t status = kStatus_Success;
+
+ if (handle->state != kSAI_Busy)
+ {
+ status = kStatus_NoTransferInProgress;
+ }
+ else
+ {
+ *count = (handle->transferSize[handle->queueDriver] -
+ EDMA_GetRemainingBytes(handle->dmaHandle->base, handle->dmaHandle->channel));
+ }
+
+ return status;
+}
diff --git a/drivers/fsl_sai_edma.h b/drivers/fsl_sai_edma.h
new file mode 100644
index 0000000..03c2e51
--- /dev/null
+++ b/drivers/fsl_sai_edma.h
@@ -0,0 +1,231 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_SAI_EDMA_H_
+#define _FSL_SAI_EDMA_H_
+
+#include "fsl_sai.h"
+#include "fsl_edma.h"
+
+/*!
+ * @addtogroup sai_edma
+ * @{
+ */
+
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+typedef struct _sai_edma_handle sai_edma_handle_t;
+
+/*! @brief SAI eDMA transfer callback function for finish and error */
+typedef void (*sai_edma_callback_t)(I2S_Type *base, sai_edma_handle_t *handle, status_t status, void *userData);
+
+/*! @brief SAI DMA transfer handle, users should not touch the content of the handle.*/
+struct _sai_edma_handle
+{
+ edma_handle_t *dmaHandle; /*!< DMA handler for SAI send */
+ uint8_t bytesPerFrame; /*!< Bytes in a frame */
+ uint8_t channel; /*!< Which data channel */
+ uint8_t count; /*!< The transfer data count in a DMA request */
+ uint32_t state; /*!< Internal state for SAI eDMA transfer */
+ sai_edma_callback_t callback; /*!< Callback for users while transfer finish or error occurs */
+ void *userData; /*!< User callback parameter */
+ edma_tcd_t tcd[SAI_XFER_QUEUE_SIZE + 1U]; /*!< TCD pool for eDMA transfer. */
+ sai_transfer_t saiQueue[SAI_XFER_QUEUE_SIZE]; /*!< Transfer queue storing queued transfer. */
+ size_t transferSize[SAI_XFER_QUEUE_SIZE]; /*!< Data bytes need to transfer */
+ volatile uint8_t queueUser; /*!< Index for user to queue transfer. */
+ volatile uint8_t queueDriver; /*!< Index for driver to get the transfer data and size */
+};
+
+/*******************************************************************************
+ * APIs
+ ******************************************************************************/
+#if defined(__cplusplus)
+extern "C" {
+#endif
+
+/*!
+ * @name eDMA Transactional
+ * @{
+ */
+
+/*!
+ * @brief Initializes the SAI eDMA handle.
+ *
+ * This function initializes the SAI master DMA handle, which can be used for other SAI master transactional APIs.
+ * Usually, for a specified SAI instance, call this API once to get the initialized handle.
+ *
+ * @param base SAI base pointer.
+ * @param handle SAI eDMA handle pointer.
+ * @param base SAI peripheral base address.
+ * @param callback Pointer to user callback function.
+ * @param userData User parameter passed to the callback function.
+ * @param dmaHandle eDMA handle pointer, this handle shall be static allocated by users.
+ */
+void SAI_TransferTxCreateHandleEDMA(
+ I2S_Type *base, sai_edma_handle_t *handle, sai_edma_callback_t callback, void *userData, edma_handle_t *dmaHandle);
+
+/*!
+ * @brief Initializes the SAI Rx eDMA handle.
+ *
+ * This function initializes the SAI slave DMA handle, which can be used for other SAI master transactional APIs.
+ * Usually, for a specified SAI instance, call this API once to get the initialized handle.
+ *
+ * @param base SAI base pointer.
+ * @param handle SAI eDMA handle pointer.
+ * @param base SAI peripheral base address.
+ * @param callback Pointer to user callback function.
+ * @param userData User parameter passed to the callback function.
+ * @param dmaHandle eDMA handle pointer, this handle shall be static allocated by users.
+ */
+void SAI_TransferRxCreateHandleEDMA(
+ I2S_Type *base, sai_edma_handle_t *handle, sai_edma_callback_t callback, void *userData, edma_handle_t *dmaHandle);
+
+/*!
+ * @brief Configures the SAI Tx audio format.
+ *
+ * The audio format can be changed at run-time. This function configures the sample rate and audio data
+ * format to be transferred. This function also sets the eDMA parameter according to formatting requirements.
+ *
+ * @param base SAI base pointer.
+ * @param handle SAI eDMA handle pointer.
+ * @param format Pointer to SAI audio data format structure.
+ * @param mclkSourceClockHz SAI master clock source frequency in Hz.
+ * @param bclkSourceClockHz SAI bit clock source frequency in Hz. If bit clock source is master
+ * clock, this value should equals to masterClockHz in format.
+ * @retval kStatus_Success Audio format set successfully.
+ * @retval kStatus_InvalidArgument The input argument is invalid.
+*/
+void SAI_TransferTxSetFormatEDMA(I2S_Type *base,
+ sai_edma_handle_t *handle,
+ sai_transfer_format_t *format,
+ uint32_t mclkSourceClockHz,
+ uint32_t bclkSourceClockHz);
+
+/*!
+ * @brief Configures the SAI Rx audio format.
+ *
+ * The audio format can be changed at run-time. This function configures the sample rate and audio data
+ * format to be transferred. This function also sets the eDMA parameter according to formatting requirements.
+ *
+ * @param base SAI base pointer.
+ * @param handle SAI eDMA handle pointer.
+ * @param format Pointer to SAI audio data format structure.
+ * @param mclkSourceClockHz SAI master clock source frequency in Hz.
+ * @param bclkSourceClockHz SAI bit clock source frequency in Hz. If a bit clock source is the master
+ * clock, this value should equal to masterClockHz in format.
+ * @retval kStatus_Success Audio format set successfully.
+ * @retval kStatus_InvalidArgument The input argument is invalid.
+*/
+void SAI_TransferRxSetFormatEDMA(I2S_Type *base,
+ sai_edma_handle_t *handle,
+ sai_transfer_format_t *format,
+ uint32_t mclkSourceClockHz,
+ uint32_t bclkSourceClockHz);
+
+/*!
+ * @brief Performs a non-blocking SAI transfer using DMA.
+ *
+ * @note This interface returns immediately after the transfer initiates. Call
+ * SAI_GetTransferStatus to poll the transfer status and check whether the SAI transfer is finished.
+ *
+ * @param base SAI base pointer.
+ * @param handle SAI eDMA handle pointer.
+ * @param xfer Pointer to the DMA transfer structure.
+ * @retval kStatus_Success Start a SAI eDMA send successfully.
+ * @retval kStatus_InvalidArgument The input argument is invalid.
+ * @retval kStatus_TxBusy SAI is busy sending data.
+ */
+status_t SAI_TransferSendEDMA(I2S_Type *base, sai_edma_handle_t *handle, sai_transfer_t *xfer);
+
+/*!
+ * @brief Performs a non-blocking SAI receive using eDMA.
+ *
+ * @note This interface returns immediately after the transfer initiates. Call
+ * the SAI_GetReceiveRemainingBytes to poll the transfer status and check whether the SAI transfer is finished.
+ *
+ * @param base SAI base pointer
+ * @param handle SAI eDMA handle pointer.
+ * @param xfer Pointer to DMA transfer structure.
+ * @retval kStatus_Success Start a SAI eDMA receive successfully.
+ * @retval kStatus_InvalidArgument The input argument is invalid.
+ * @retval kStatus_RxBusy SAI is busy receiving data.
+ */
+status_t SAI_TransferReceiveEDMA(I2S_Type *base, sai_edma_handle_t *handle, sai_transfer_t *xfer);
+
+/*!
+ * @brief Aborts a SAI transfer using eDMA.
+ *
+ * @param base SAI base pointer.
+ * @param handle SAI eDMA handle pointer.
+ */
+void SAI_TransferAbortSendEDMA(I2S_Type *base, sai_edma_handle_t *handle);
+
+/*!
+ * @brief Aborts a SAI receive using eDMA.
+ *
+ * @param base SAI base pointer
+ * @param handle SAI eDMA handle pointer.
+ */
+void SAI_TransferAbortReceiveEDMA(I2S_Type *base, sai_edma_handle_t *handle);
+
+/*!
+ * @brief Gets byte count sent by SAI.
+ *
+ * @param base SAI base pointer.
+ * @param handle SAI eDMA handle pointer.
+ * @param count Bytes count sent by SAI.
+ * @retval kStatus_Success Succeed get the transfer count.
+ * @retval kStatus_NoTransferInProgress There is no non-blocking transaction in progress.
+ */
+status_t SAI_TransferGetSendCountEDMA(I2S_Type *base, sai_edma_handle_t *handle, size_t *count);
+
+/*!
+ * @brief Gets byte count received by SAI.
+ *
+ * @param base SAI base pointer
+ * @param handle SAI eDMA handle pointer.
+ * @param count Bytes count received by SAI.
+ * @retval kStatus_Success Succeed get the transfer count.
+ * @retval kStatus_NoTransferInProgress There is no non-blocking transaction in progress.
+ */
+status_t SAI_TransferGetReceiveCountEDMA(I2S_Type *base, sai_edma_handle_t *handle, size_t *count);
+
+/*! @} */
+
+#if defined(__cplusplus)
+}
+#endif
+
+/*!
+ * @}
+ */
+#endif
diff --git a/drivers/fsl_sdhc.c b/drivers/fsl_sdhc.c
new file mode 100644
index 0000000..7697cdc
--- /dev/null
+++ b/drivers/fsl_sdhc.c
@@ -0,0 +1,1297 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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 SL 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_sdhc.h"
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+/*! @brief Clock setting */
+/* Max SD clock divisor from base clock */
+#define SDHC_MAX_DVS ((SDHC_SYSCTL_DVS_MASK >> SDHC_SYSCTL_DVS_SHIFT) + 1U)
+#define SDHC_INITIAL_DVS (1U) /* Initial value of SD clock divisor */
+#define SDHC_INITIAL_CLKFS (2U) /* Initial value of SD clock frequency selector */
+#define SDHC_NEXT_DVS(x) ((x) += 1U)
+#define SDHC_PREV_DVS(x) ((x) -= 1U)
+#define SDHC_MAX_CLKFS ((SDHC_SYSCTL_SDCLKFS_MASK >> SDHC_SYSCTL_SDCLKFS_SHIFT) + 1U)
+#define SDHC_NEXT_CLKFS(x) ((x) <<= 1U)
+#define SDHC_PREV_CLKFS(x) ((x) >>= 1U)
+
+/*! @brief ADMA table configuration */
+typedef struct _sdhc_adma_table_config
+{
+ uint32_t *admaTable; /*!< ADMA table address, can't be null if transfer way is ADMA1/ADMA2 */
+ uint32_t admaTableWords; /*!< ADMA table length united as words, can't be 0 if transfer way is ADMA1/ADMA2 */
+} sdhc_adma_table_config_t;
+
+/*******************************************************************************
+ * Prototypes
+ ******************************************************************************/
+/*!
+ * @brief Get the instance.
+ *
+ * @param base SDHC peripheral base address.
+ * @return Instance number.
+ */
+static uint32_t SDHC_GetInstance(SDHC_Type *base);
+
+/*!
+ * @brief Set transfer interrupt.
+ *
+ * @param base SDHC peripheral base address.
+ * @param usingInterruptSignal True to use IRQ signal.
+ */
+static void SDHC_SetTransferInterrupt(SDHC_Type *base, bool usingInterruptSignal);
+
+/*!
+ * @brief Start transfer according to current transfer state
+ *
+ * @param base SDHC peripheral base address.
+ * @param command Command to be sent.
+ * @param data Data to be transferred.
+ */
+static void SDHC_StartTransfer(SDHC_Type *base, sdhc_command_t *command, sdhc_data_t *data);
+
+/*!
+ * @brief Receive command response
+ *
+ * @param base SDHC peripheral base address.
+ * @param command Command to be sent.
+ */
+static void SDHC_ReceiveCommandResponse(SDHC_Type *base, sdhc_command_t *command);
+
+/*!
+ * @brief Read DATAPORT when buffer enable bit is set.
+ *
+ * @param base SDHC peripheral base address.
+ * @param data Data to be read.
+ * @param transferredWords The number of data words have been transferred last time transaction.
+ * @return The number of total data words have been transferred after this time transaction.
+ */
+static uint32_t SDHC_ReadDataPort(SDHC_Type *base, sdhc_data_t *data, uint32_t transferredWords);
+
+/*!
+ * @brief Read data by using DATAPORT polling way.
+ *
+ * @param base SDHC peripheral base address.
+ * @param data Data to be read.
+ * @retval kStatus_Fail Read DATAPORT failed.
+ * @retval kStatus_Success Operate successfully.
+ */
+static status_t SDHC_ReadByDataPortBlocking(SDHC_Type *base, sdhc_data_t *data);
+
+/*!
+ * @brief Write DATAPORT when buffer enable bit is set.
+ *
+ * @param base SDHC peripheral base address.
+ * @param data Data to be read.
+ * @param transferredWords The number of data words have been transferred last time.
+ * @return The number of total data words have been transferred after this time transaction.
+ */
+static uint32_t SDHC_WriteDataPort(SDHC_Type *base, sdhc_data_t *data, uint32_t transferredWords);
+
+/*!
+ * @brief Write data by using DATAPORT polling way.
+ *
+ * @param base SDHC peripheral base address.
+ * @param data Data to be transferred.
+ * @retval kStatus_Fail Write DATAPORT failed.
+ * @retval kStatus_Success Operate successfully.
+ */
+static status_t SDHC_WriteByDataPortBlocking(SDHC_Type *base, sdhc_data_t *data);
+
+/*!
+ * @brief Send command by using polling way.
+ *
+ * @param base SDHC peripheral base address.
+ * @param command Command to be sent.
+ * @retval kStatus_Fail Send command failed.
+ * @retval kStatus_Success Operate successfully.
+ */
+static status_t SDHC_SendCommandBlocking(SDHC_Type *base, sdhc_command_t *command);
+
+/*!
+ * @brief Transfer data by DATAPORT and polling way.
+ *
+ * @param base SDHC peripheral base address.
+ * @param data Data to be transferred.
+ * @retval kStatus_Fail Transfer data failed.
+ * @retval kStatus_Success Operate successfully.
+ */
+static status_t SDHC_TransferByDataPortBlocking(SDHC_Type *base, sdhc_data_t *data);
+
+/*!
+ * @brief Transfer data by ADMA2 and polling way.
+ *
+ * @param base SDHC peripheral base address.
+ * @param data Data to be transferred.
+ * @retval kStatus_Fail Transfer data failed.
+ * @retval kStatus_Success Operate successfully.
+ */
+static status_t SDHC_TransferByAdma2Blocking(SDHC_Type *base, sdhc_data_t *data);
+
+/*!
+ * @brief Transfer data by polling way.
+ *
+ * @param dmaMode DMA mode.
+ * @param base SDHC peripheral base address.
+ * @param data Data to be transferred.
+ * @retval kStatus_Fail Transfer data failed.
+ * @retval kStatus_InvalidArgument Argument is invalid.
+ * @retval kStatus_Success Operate successfully.
+ */
+static status_t SDHC_TransferDataBlocking(sdhc_dma_mode_t dmaMode, SDHC_Type *base, sdhc_data_t *data);
+
+/*!
+ * @brief Handle card detect interrupt.
+ *
+ * @param handle SDHC handle.
+ * @param interruptFlags Card detect related interrupt flags.
+ */
+static void SDHC_TransferHandleCardDetect(sdhc_handle_t *handle, uint32_t interruptFlags);
+
+/*!
+ * @brief Handle command interrupt.
+ *
+ * @param base SDHC peripheral base address.
+ * @param handle SDHC handle.
+ * @param interruptFlags Command related interrupt flags.
+ */
+static void SDHC_TransferHandleCommand(SDHC_Type *base, sdhc_handle_t *handle, uint32_t interruptFlags);
+
+/*!
+ * @brief Handle data interrupt.
+ *
+ * @param base SDHC peripheral base address.
+ * @param handle SDHC handle.
+ * @param interruptFlags Data related interrupt flags.
+ */
+static void SDHC_TransferHandleData(SDHC_Type *base, sdhc_handle_t *handle, uint32_t interruptFlags);
+
+/*!
+ * @brief Handle SDIO card interrupt signal.
+ *
+ * @param handle SDHC handle.
+ */
+static void SDHC_TransferHandleSdioInterrupt(sdhc_handle_t *handle);
+
+/*!
+ * @brief Handle SDIO block gap event.
+ *
+ * @param handle SDHC handle.
+ */
+static void SDHC_TransferHandleSdioBlockGap(sdhc_handle_t *handle);
+
+/*******************************************************************************
+ * Variables
+ ******************************************************************************/
+/*! @brief SDHC internal handle pointer array */
+static sdhc_handle_t *s_sdhcHandle[FSL_FEATURE_SOC_SDHC_COUNT];
+
+/*! @brief SDHC base pointer array */
+static SDHC_Type *const s_sdhcBase[] = SDHC_BASE_PTRS;
+
+/*! @brief SDHC IRQ name array */
+static const IRQn_Type s_sdhcIRQ[] = SDHC_IRQS;
+
+/*! @brief SDHC clock array name */
+static const clock_ip_name_t s_sdhcClock[] = SDHC_CLOCKS;
+
+/*******************************************************************************
+ * Code
+ ******************************************************************************/
+static uint32_t SDHC_GetInstance(SDHC_Type *base)
+{
+ uint8_t instance = 0;
+
+ while ((instance < FSL_FEATURE_SOC_SDHC_COUNT) && (s_sdhcBase[instance] != base))
+ {
+ instance++;
+ }
+
+ assert(instance < FSL_FEATURE_SOC_SDHC_COUNT);
+
+ return instance;
+}
+
+static void SDHC_SetTransferInterrupt(SDHC_Type *base, bool usingInterruptSignal)
+{
+ uint32_t interruptEnabled; /* The Interrupt status flags to be enabled */
+ sdhc_dma_mode_t dmaMode = (sdhc_dma_mode_t)((base->PROCTL & SDHC_PROCTL_DMAS_MASK) >> SDHC_PROCTL_DMAS_SHIFT);
+ bool cardDetectDat3 = (bool)(base->PROCTL & SDHC_PROCTL_D3CD_MASK);
+
+ /* Disable all interrupts */
+ SDHC_DisableInterruptStatus(base, (uint32_t)kSDHC_AllInterruptFlags);
+ SDHC_DisableInterruptSignal(base, (uint32_t)kSDHC_AllInterruptFlags);
+ DisableIRQ(s_sdhcIRQ[SDHC_GetInstance(base)]);
+
+ interruptEnabled =
+ (kSDHC_CommandIndexErrorFlag | kSDHC_CommandCrcErrorFlag | kSDHC_CommandEndBitErrorFlag |
+ kSDHC_CommandTimeoutFlag | kSDHC_CommandCompleteFlag | kSDHC_DataTimeoutFlag | kSDHC_DataCrcErrorFlag |
+ kSDHC_DataEndBitErrorFlag | kSDHC_DataCompleteFlag | kSDHC_AutoCommand12ErrorFlag);
+ if (cardDetectDat3)
+ {
+ interruptEnabled |= (kSDHC_CardInsertionFlag | kSDHC_CardRemovalFlag);
+ }
+ switch (dmaMode)
+ {
+ case kSDHC_DmaModeAdma1:
+ case kSDHC_DmaModeAdma2:
+ interruptEnabled |= (kSDHC_DmaErrorFlag | kSDHC_DmaCompleteFlag);
+ break;
+ case kSDHC_DmaModeNo:
+ interruptEnabled |= (kSDHC_BufferReadReadyFlag | kSDHC_BufferWriteReadyFlag);
+ break;
+ default:
+ break;
+ }
+
+ SDHC_EnableInterruptStatus(base, interruptEnabled);
+ if (usingInterruptSignal)
+ {
+ SDHC_EnableInterruptSignal(base, interruptEnabled);
+ }
+}
+
+static void SDHC_StartTransfer(SDHC_Type *base, sdhc_command_t *command, sdhc_data_t *data)
+{
+ assert(command);
+
+ uint32_t flags = 0U;
+ sdhc_transfer_config_t sdhcTransferConfig;
+ sdhc_dma_mode_t dmaMode;
+
+ /* Define the flag corresponding to each response type. */
+ switch (command->responseType)
+ {
+ case kSDHC_ResponseTypeNone:
+ break;
+ case kSDHC_ResponseTypeR1: /* Response 1 */
+ flags |= (kSDHC_ResponseLength48Flag | kSDHC_EnableCrcCheckFlag | kSDHC_EnableIndexCheckFlag);
+ break;
+ case kSDHC_ResponseTypeR1b: /* Response 1 with busy */
+ flags |= (kSDHC_ResponseLength48BusyFlag | kSDHC_EnableCrcCheckFlag | kSDHC_EnableIndexCheckFlag);
+ break;
+ case kSDHC_ResponseTypeR2: /* Response 2 */
+ flags |= (kSDHC_ResponseLength136Flag | kSDHC_EnableCrcCheckFlag);
+ break;
+ case kSDHC_ResponseTypeR3: /* Response 3 */
+ flags |= (kSDHC_ResponseLength48Flag);
+ break;
+ case kSDHC_ResponseTypeR4: /* Response 4 */
+ flags |= (kSDHC_ResponseLength48Flag);
+ break;
+ case kSDHC_ResponseTypeR5: /* Response 5 */
+ flags |= (kSDHC_ResponseLength48Flag | kSDHC_EnableCrcCheckFlag);
+ break;
+ case kSDHC_ResponseTypeR5b: /* Response 5 with busy */
+ flags |= (kSDHC_ResponseLength48BusyFlag | kSDHC_EnableCrcCheckFlag | kSDHC_EnableIndexCheckFlag);
+ break;
+ case kSDHC_ResponseTypeR6: /* Response 6 */
+ flags |= (kSDHC_ResponseLength48Flag | kSDHC_EnableCrcCheckFlag | kSDHC_EnableIndexCheckFlag);
+ break;
+ case kSDHC_ResponseTypeR7: /* Response 7 */
+ flags |= (kSDHC_ResponseLength48Flag | kSDHC_EnableCrcCheckFlag | kSDHC_EnableIndexCheckFlag);
+ break;
+ default:
+ break;
+ }
+ if (command->type == kSDHC_CommandTypeAbort)
+ {
+ flags |= kSDHC_CommandTypeAbortFlag;
+ }
+
+ if (data)
+ {
+ flags |= kSDHC_DataPresentFlag;
+ dmaMode = (sdhc_dma_mode_t)((base->PROCTL & SDHC_PROCTL_DMAS_MASK) >> SDHC_PROCTL_DMAS_SHIFT);
+ if (dmaMode != kSDHC_DmaModeNo)
+ {
+ flags |= kSDHC_EnableDmaFlag;
+ }
+ if (data->rxData)
+ {
+ flags |= kSDHC_DataReadFlag;
+ }
+ if (data->blockCount > 1U)
+ {
+ flags |= (kSDHC_MultipleBlockFlag | kSDHC_EnableBlockCountFlag);
+ if (data->enableAutoCommand12)
+ {
+ /* Enable Auto command 12. */
+ flags |= kSDHC_EnableAutoCommand12Flag;
+ }
+ }
+ if (data->blockCount > SDHC_MAX_BLOCK_COUNT)
+ {
+ sdhcTransferConfig.dataBlockSize = data->blockSize;
+ sdhcTransferConfig.dataBlockCount = SDHC_MAX_BLOCK_COUNT;
+
+ flags &= ~(uint32_t)kSDHC_EnableBlockCountFlag;
+ }
+ else
+ {
+ sdhcTransferConfig.dataBlockSize = data->blockSize;
+ sdhcTransferConfig.dataBlockCount = data->blockCount;
+ }
+ }
+ else
+ {
+ sdhcTransferConfig.dataBlockSize = 0U;
+ sdhcTransferConfig.dataBlockCount = 0U;
+ }
+
+ sdhcTransferConfig.commandArgument = command->argument;
+ sdhcTransferConfig.commandIndex = command->index;
+ sdhcTransferConfig.flags = flags;
+ SDHC_SetTransferConfig(base, &sdhcTransferConfig);
+}
+
+static void SDHC_ReceiveCommandResponse(SDHC_Type *base, sdhc_command_t *command)
+{
+ assert(command);
+
+ uint32_t i;
+
+ if (command->responseType != kSDHC_ResponseTypeNone)
+ {
+ command->response[0U] = SDHC_GetCommandResponse(base, 0U);
+ if (command->responseType == kSDHC_ResponseTypeR2)
+ {
+ command->response[1U] = SDHC_GetCommandResponse(base, 1U);
+ command->response[2U] = SDHC_GetCommandResponse(base, 2U);
+ command->response[3U] = SDHC_GetCommandResponse(base, 3U);
+
+ i = 4U;
+ /* R3-R2-R1-R0(lowest 8 bit is invalid bit) has the same format as R2 format in SD specification document
+ after removed internal CRC7 and end bit. */
+ do
+ {
+ command->response[i - 1U] <<= 8U;
+ if (i > 1U)
+ {
+ command->response[i - 1U] |= ((command->response[i - 2U] & 0xFF000000U) >> 24U);
+ }
+ } while (i--);
+ }
+ }
+}
+
+static uint32_t SDHC_ReadDataPort(SDHC_Type *base, sdhc_data_t *data, uint32_t transferredWords)
+{
+ assert(data);
+
+ uint32_t i;
+ uint32_t totalWords;
+ uint32_t wordsCanBeRead; /* The words can be read at this time. */
+ uint32_t readWatermark = ((base->WML & SDHC_WML_RDWML_MASK) >> SDHC_WML_RDWML_SHIFT);
+
+ totalWords = ((data->blockCount * data->blockSize) / sizeof(uint32_t));
+
+ /* If watermark level is equal or bigger than totalWords, transfers totalWords data. */
+ if (readWatermark >= totalWords)
+ {
+ wordsCanBeRead = totalWords;
+ }
+ /* If watermark level is less than totalWords and left words to be sent is equal or bigger than readWatermark,
+ transfers watermark level words. */
+ else if ((readWatermark < totalWords) && ((totalWords - transferredWords) >= readWatermark))
+ {
+ wordsCanBeRead = readWatermark;
+ }
+ /* If watermark level is less than totalWords and left words to be sent is less than readWatermark, transfers left
+ words. */
+ else
+ {
+ wordsCanBeRead = (totalWords - transferredWords);
+ }
+
+ i = 0U;
+ while (i < wordsCanBeRead)
+ {
+ data->rxData[transferredWords++] = SDHC_ReadData(base);
+ i++;
+ }
+
+ return transferredWords;
+}
+
+static status_t SDHC_ReadByDataPortBlocking(SDHC_Type *base, sdhc_data_t *data)
+{
+ assert(data);
+
+ uint32_t totalWords;
+ uint32_t transferredWords = 0U;
+ status_t error = kStatus_Success;
+
+ totalWords = ((data->blockCount * data->blockSize) / sizeof(uint32_t));
+
+ while ((error == kStatus_Success) && (transferredWords < totalWords))
+ {
+ while (!(SDHC_GetInterruptStatusFlags(base) & (kSDHC_BufferReadReadyFlag | kSDHC_DataErrorFlag)))
+ {
+ }
+
+ if (SDHC_GetInterruptStatusFlags(base) & kSDHC_DataErrorFlag)
+ {
+ if (!(data->enableIgnoreError))
+ {
+ error = kStatus_Fail;
+ }
+ }
+ if (error == kStatus_Success)
+ {
+ transferredWords = SDHC_ReadDataPort(base, data, transferredWords);
+ }
+
+ /* Clear buffer enable flag to trigger transfer. Clear data error flag when SDHC encounter error */
+ SDHC_ClearInterruptStatusFlags(base, (kSDHC_BufferReadReadyFlag | kSDHC_DataErrorFlag));
+ }
+
+ /* Clear data complete flag after the last read operation. */
+ SDHC_ClearInterruptStatusFlags(base, kSDHC_DataCompleteFlag);
+
+ return error;
+}
+
+static uint32_t SDHC_WriteDataPort(SDHC_Type *base, sdhc_data_t *data, uint32_t transferredWords)
+{
+ assert(data);
+
+ uint32_t i;
+ uint32_t totalWords;
+ uint32_t wordsCanBeWrote; /* Words can be wrote at this time. */
+ uint32_t writeWatermark = ((base->WML & SDHC_WML_WRWML_MASK) >> SDHC_WML_WRWML_SHIFT);
+
+ totalWords = ((data->blockCount * data->blockSize) / sizeof(uint32_t));
+
+ /* If watermark level is equal or bigger than totalWords, transfers totalWords data.*/
+ if (writeWatermark >= totalWords)
+ {
+ wordsCanBeWrote = totalWords;
+ }
+ /* If watermark level is less than totalWords and left words to be sent is equal or bigger than watermark,
+ transfers watermark level words. */
+ else if ((writeWatermark < totalWords) && ((totalWords - transferredWords) >= writeWatermark))
+ {
+ wordsCanBeWrote = writeWatermark;
+ }
+ /* If watermark level is less than totalWords and left words to be sent is less than watermark, transfers left
+ words. */
+ else
+ {
+ wordsCanBeWrote = (totalWords - transferredWords);
+ }
+
+ i = 0U;
+ while (i < wordsCanBeWrote)
+ {
+ SDHC_WriteData(base, data->txData[transferredWords++]);
+ i++;
+ }
+
+ return transferredWords;
+}
+
+static status_t SDHC_WriteByDataPortBlocking(SDHC_Type *base, sdhc_data_t *data)
+{
+ assert(data);
+
+ uint32_t totalWords;
+ uint32_t transferredWords = 0U;
+ status_t error = kStatus_Success;
+
+ totalWords = (data->blockCount * data->blockSize) / sizeof(uint32_t);
+
+ while ((error == kStatus_Success) && (transferredWords < totalWords))
+ {
+ while (!(SDHC_GetInterruptStatusFlags(base) & (kSDHC_BufferWriteReadyFlag | kSDHC_DataErrorFlag)))
+ {
+ }
+
+ if (SDHC_GetInterruptStatusFlags(base) & kSDHC_DataErrorFlag)
+ {
+ if (!(data->enableIgnoreError))
+ {
+ error = kStatus_Fail;
+ }
+ }
+ if (error == kStatus_Success)
+ {
+ transferredWords = SDHC_WriteDataPort(base, data, transferredWords);
+ }
+
+ /* Clear buffer enable flag to trigger transfer. Clear error flag when SDHC encounter error. */
+ SDHC_ClearInterruptStatusFlags(base, (kSDHC_BufferWriteReadyFlag | kSDHC_DataErrorFlag));
+ }
+
+ /* Wait write data complete or data transfer error after the last writing operation. */
+ while (!(SDHC_GetInterruptStatusFlags(base) & (kSDHC_DataCompleteFlag | kSDHC_DataErrorFlag)))
+ {
+ }
+ if (SDHC_GetInterruptStatusFlags(base) & kSDHC_DataErrorFlag)
+ {
+ if (!(data->enableIgnoreError))
+ {
+ error = kStatus_Fail;
+ }
+ }
+ SDHC_ClearInterruptStatusFlags(base, (kSDHC_DataCompleteFlag | kSDHC_DataErrorFlag));
+
+ return error;
+}
+
+static status_t SDHC_SendCommandBlocking(SDHC_Type *base, sdhc_command_t *command)
+{
+ assert(command);
+
+ status_t error = kStatus_Success;
+
+ /* Wait command complete or SDHC encounters error. */
+ while (!(SDHC_GetInterruptStatusFlags(base) & (kSDHC_CommandCompleteFlag | kSDHC_CommandErrorFlag)))
+ {
+ }
+
+ if (SDHC_GetInterruptStatusFlags(base) & kSDHC_CommandErrorFlag)
+ {
+ error = kStatus_Fail;
+ }
+ /* Receive response when command completes successfully. */
+ if (error == kStatus_Success)
+ {
+ SDHC_ReceiveCommandResponse(base, command);
+ }
+
+ SDHC_ClearInterruptStatusFlags(base, (kSDHC_CommandCompleteFlag | kSDHC_CommandErrorFlag));
+
+ return error;
+}
+
+static status_t SDHC_TransferByDataPortBlocking(SDHC_Type *base, sdhc_data_t *data)
+{
+ assert(data);
+
+ status_t error = kStatus_Success;
+
+ if (data->rxData)
+ {
+ error = SDHC_ReadByDataPortBlocking(base, data);
+ }
+ else
+ {
+ error = SDHC_WriteByDataPortBlocking(base, data);
+ }
+
+ return error;
+}
+
+static status_t SDHC_TransferByAdma2Blocking(SDHC_Type *base, sdhc_data_t *data)
+{
+ status_t error = kStatus_Success;
+
+ /* Wait data complete or SDHC encounters error. */
+ while (!(SDHC_GetInterruptStatusFlags(base) & (kSDHC_DataCompleteFlag | kSDHC_DataErrorFlag | kSDHC_DmaErrorFlag)))
+ {
+ }
+ if (SDHC_GetInterruptStatusFlags(base) & (kSDHC_DataErrorFlag | kSDHC_DmaErrorFlag))
+ {
+ if (!(data->enableIgnoreError))
+ {
+ error = kStatus_Fail;
+ }
+ }
+ SDHC_ClearInterruptStatusFlags(
+ base, (kSDHC_DataCompleteFlag | kSDHC_DmaCompleteFlag | kSDHC_DataErrorFlag | kSDHC_DmaErrorFlag));
+ return error;
+}
+
+#if defined FSL_SDHC_ENABLE_ADMA1
+#define SDHC_TransferByAdma1Blocking(base, data) SDHC_TransferByAdma2Blocking(base, data)
+#endif /* FSL_SDHC_ENABLE_ADMA1 */
+
+static status_t SDHC_TransferDataBlocking(sdhc_dma_mode_t dmaMode, SDHC_Type *base, sdhc_data_t *data)
+{
+ status_t error = kStatus_Success;
+
+ switch (dmaMode)
+ {
+ case kSDHC_DmaModeNo:
+ error = SDHC_TransferByDataPortBlocking(base, data);
+ break;
+#if defined FSL_SDHC_ENABLE_ADMA1
+ case kSDHC_DmaModeAdma1:
+ error = SDHC_TransferByAdma1Blocking(base, data);
+ break;
+#endif /* FSL_SDHC_ENABLE_ADMA1 */
+ case kSDHC_DmaModeAdma2:
+ error = SDHC_TransferByAdma2Blocking(base, data);
+ break;
+ default:
+ error = kStatus_InvalidArgument;
+ break;
+ }
+
+ return error;
+}
+
+static void SDHC_TransferHandleCardDetect(sdhc_handle_t *handle, uint32_t interruptFlags)
+{
+ assert(interruptFlags & kSDHC_CardDetectFlag);
+
+ if (interruptFlags & kSDHC_CardInsertionFlag)
+ {
+ if (handle->callback.CardInserted)
+ {
+ handle->callback.CardInserted();
+ }
+ }
+ else
+ {
+ if (handle->callback.CardRemoved)
+ {
+ handle->callback.CardRemoved();
+ }
+ }
+}
+
+static void SDHC_TransferHandleCommand(SDHC_Type *base, sdhc_handle_t *handle, uint32_t interruptFlags)
+{
+ assert(interruptFlags & kSDHC_CommandFlag);
+
+ if ((interruptFlags & kSDHC_CommandErrorFlag) && (!(handle->data)) && (handle->callback.TransferComplete))
+ {
+ handle->callback.TransferComplete(base, handle, kStatus_SDHC_SendCommandFailed, handle->userData);
+ }
+ else
+ {
+ /* Receive response */
+ SDHC_ReceiveCommandResponse(base, handle->command);
+ if ((!(handle->data)) && (handle->callback.TransferComplete))
+ {
+ handle->callback.TransferComplete(base, handle, kStatus_Success, handle->userData);
+ }
+ }
+}
+
+static void SDHC_TransferHandleData(SDHC_Type *base, sdhc_handle_t *handle, uint32_t interruptFlags)
+{
+ assert(handle->data);
+ assert(interruptFlags & kSDHC_DataFlag);
+
+ if ((!(handle->data->enableIgnoreError)) && (interruptFlags & (kSDHC_DataErrorFlag | kSDHC_DmaErrorFlag)) &&
+ (handle->callback.TransferComplete))
+ {
+ handle->callback.TransferComplete(base, handle, kStatus_SDHC_TransferDataFailed, handle->userData);
+ }
+ else
+ {
+ if (interruptFlags & kSDHC_BufferReadReadyFlag)
+ {
+ handle->transferredWords = SDHC_ReadDataPort(base, handle->data, handle->transferredWords);
+ }
+ else if (interruptFlags & kSDHC_BufferWriteReadyFlag)
+ {
+ handle->transferredWords = SDHC_WriteDataPort(base, handle->data, handle->transferredWords);
+ }
+ else if ((interruptFlags & kSDHC_DataCompleteFlag) && (handle->callback.TransferComplete))
+ {
+ handle->callback.TransferComplete(base, handle, kStatus_Success, handle->userData);
+ }
+ else
+ {
+ /* Do nothing when DMA complete flag is set. Wait until data complete flag is set. */
+ }
+ }
+}
+
+static void SDHC_TransferHandleSdioInterrupt(sdhc_handle_t *handle)
+{
+ if (handle->callback.SdioInterrupt)
+ {
+ handle->callback.SdioInterrupt();
+ }
+}
+
+static void SDHC_TransferHandleSdioBlockGap(sdhc_handle_t *handle)
+{
+ if (handle->callback.SdioBlockGap)
+ {
+ handle->callback.SdioBlockGap();
+ }
+}
+
+void SDHC_Init(SDHC_Type *base, const sdhc_config_t *config)
+{
+ assert(config);
+#if !defined FSL_SDHC_ENABLE_ADMA1
+ assert(config->dmaMode != kSDHC_DmaModeAdma1);
+#endif /* FSL_SDHC_ENABLE_ADMA1 */
+
+ uint32_t proctl;
+ uint32_t wml;
+
+ /* Enable SDHC clock. */
+ CLOCK_EnableClock(s_sdhcClock[SDHC_GetInstance(base)]);
+
+ /* Reset SDHC. */
+ SDHC_Reset(base, kSDHC_ResetAll, 100);
+
+ proctl = base->PROCTL;
+ wml = base->WML;
+
+ proctl &= ~(SDHC_PROCTL_D3CD_MASK | SDHC_PROCTL_EMODE_MASK | SDHC_PROCTL_DMAS_MASK);
+ /* Set DAT3 as card detection pin */
+ if (config->cardDetectDat3)
+ {
+ proctl |= SDHC_PROCTL_D3CD_MASK;
+ }
+ /* Endian mode and DMA mode */
+ proctl |= (SDHC_PROCTL_EMODE(config->endianMode) | SDHC_PROCTL_DMAS(config->dmaMode));
+
+ /* Watermark level */
+ wml &= ~(SDHC_WML_RDWML_MASK | SDHC_WML_WRWML_MASK);
+ wml |= (SDHC_WML_RDWML(config->readWatermarkLevel) | SDHC_WML_WRWML(config->writeWatermarkLevel));
+
+ base->WML = wml;
+ base->PROCTL = proctl;
+
+ /* Disable all clock auto gated off feature because of DAT0 line logic(card buffer full status) can't be updated
+ correctly when clock auto gated off is enabled. */
+ base->SYSCTL |= (SDHC_SYSCTL_PEREN_MASK | SDHC_SYSCTL_HCKEN_MASK | SDHC_SYSCTL_IPGEN_MASK);
+
+ /* Enable interrupt status but doesn't enable interrupt signal. */
+ SDHC_SetTransferInterrupt(base, false);
+}
+
+void SDHC_Deinit(SDHC_Type *base)
+{
+ /* Disable clock. */
+ CLOCK_DisableClock(s_sdhcClock[SDHC_GetInstance(base)]);
+}
+
+bool SDHC_Reset(SDHC_Type *base, uint32_t mask, uint32_t timeout)
+{
+ base->SYSCTL |= (mask & (SDHC_SYSCTL_RSTA_MASK | SDHC_SYSCTL_RSTC_MASK | SDHC_SYSCTL_RSTD_MASK));
+ /* Delay some time to wait reset success. */
+ while ((base->SYSCTL & mask))
+ {
+ if (!timeout)
+ {
+ break;
+ }
+ timeout--;
+ }
+
+ return ((!timeout) ? false : true);
+}
+
+void SDHC_GetCapability(SDHC_Type *base, sdhc_capability_t *capability)
+{
+ assert(capability);
+
+ uint32_t htCapability;
+ uint32_t hostVer;
+ uint32_t maxBlockLength;
+
+ hostVer = base->HOSTVER;
+ htCapability = base->HTCAPBLT;
+
+ /* Get the capability of SDHC. */
+ capability->specVersion = ((hostVer & SDHC_HOSTVER_SVN_MASK) >> SDHC_HOSTVER_SVN_SHIFT);
+ capability->vendorVersion = ((hostVer & SDHC_HOSTVER_VVN_MASK) >> SDHC_HOSTVER_VVN_SHIFT);
+ maxBlockLength = ((htCapability & SDHC_HTCAPBLT_MBL_MASK) >> SDHC_HTCAPBLT_MBL_SHIFT);
+ capability->maxBlockLength = (512U << maxBlockLength);
+ /* Other attributes not in HTCAPBLT register. */
+ capability->maxBlockCount = SDHC_MAX_BLOCK_COUNT;
+ capability->flags = (htCapability & (kSDHC_SupportAdmaFlag | kSDHC_SupportHighSpeedFlag | kSDHC_SupportDmaFlag |
+ kSDHC_SupportSuspendResumeFlag | kSDHC_SupportV330Flag));
+#if defined FSL_FEATURE_SDHC_HAS_V300_SUPPORT && FSL_FEATURE_SDHC_HAS_V300_SUPPORT
+ capability->flags |= (htCapability & kSDHC_SupportV300Flag);
+#endif
+#if defined FSL_FEATURE_SDHC_HAS_V180_SUPPORT && FSL_FEATURE_SDHC_HAS_V180_SUPPORT
+ capability->flags |= (htCapability & kSDHC_SupportV180Flag);
+#endif
+ /* eSDHC on all kinetis boards will support 4/8 bit data bus width. */
+ capability->flags |= (kSDHC_Support4BitFlag | kSDHC_Support8BitFlag);
+}
+
+uint32_t SDHC_SetSdClock(SDHC_Type *base, uint32_t srcClock_Hz, uint32_t busClock_Hz)
+{
+ assert(busClock_Hz && (busClock_Hz < srcClock_Hz));
+
+ uint32_t divisor;
+ uint32_t prescaler;
+ uint32_t sysctl;
+ uint32_t nearestFrequency = 0;
+
+ divisor = SDHC_INITIAL_DVS;
+ prescaler = SDHC_INITIAL_CLKFS;
+
+ /* Disable SD clock. It should be disabled before changing the SD clock frequency.*/
+ base->SYSCTL &= ~SDHC_SYSCTL_SDCLKEN_MASK;
+
+ if (busClock_Hz > 0U)
+ {
+ while ((srcClock_Hz / prescaler / SDHC_MAX_DVS > busClock_Hz) && (prescaler < SDHC_MAX_CLKFS))
+ {
+ SDHC_NEXT_CLKFS(prescaler);
+ }
+ while ((srcClock_Hz / prescaler / divisor > busClock_Hz) && (divisor < SDHC_MAX_DVS))
+ {
+ SDHC_NEXT_DVS(divisor);
+ }
+ nearestFrequency = srcClock_Hz / prescaler / divisor;
+ SDHC_PREV_CLKFS(prescaler);
+ SDHC_PREV_DVS(divisor);
+
+ /* Set the SD clock frequency divisor, SD clock frequency select, data timeout counter value. */
+ sysctl = base->SYSCTL;
+ sysctl &= ~(SDHC_SYSCTL_DVS_MASK | SDHC_SYSCTL_SDCLKFS_MASK | SDHC_SYSCTL_DTOCV_MASK);
+ sysctl |= (SDHC_SYSCTL_DVS(divisor) | SDHC_SYSCTL_SDCLKFS(prescaler) | SDHC_SYSCTL_DTOCV(0xEU));
+ base->SYSCTL = sysctl;
+
+ /* Wait until the SD clock is stable. */
+ while (!(base->PRSSTAT & SDHC_PRSSTAT_SDSTB_MASK))
+ {
+ }
+ /* Enable the SD clock. */
+ base->SYSCTL |= SDHC_SYSCTL_SDCLKEN_MASK;
+ }
+
+ return nearestFrequency;
+}
+
+bool SDHC_SetCardActive(SDHC_Type *base, uint32_t timeout)
+{
+ base->SYSCTL |= SDHC_SYSCTL_INITA_MASK;
+ /* Delay some time to wait card become active state. */
+ while (!(base->SYSCTL & SDHC_SYSCTL_INITA_MASK))
+ {
+ if (!timeout)
+ {
+ break;
+ }
+ timeout--;
+ }
+
+ return ((!timeout) ? false : true);
+}
+
+void SDHC_SetTransferConfig(SDHC_Type *base, const sdhc_transfer_config_t *config)
+{
+ assert(config);
+
+ base->BLKATTR = ((base->BLKATTR & ~(SDHC_BLKATTR_BLKSIZE_MASK | SDHC_BLKATTR_BLKCNT_MASK)) |
+ (SDHC_BLKATTR_BLKSIZE(config->dataBlockSize) | SDHC_BLKATTR_BLKCNT(config->dataBlockCount)));
+ base->CMDARG = config->commandArgument;
+ base->XFERTYP = (((config->commandIndex << SDHC_XFERTYP_CMDINX_SHIFT) & SDHC_XFERTYP_CMDINX_MASK) |
+ (config->flags & (SDHC_XFERTYP_DMAEN_MASK | SDHC_XFERTYP_MSBSEL_MASK | SDHC_XFERTYP_DPSEL_MASK |
+ SDHC_XFERTYP_CMDTYP_MASK | SDHC_XFERTYP_BCEN_MASK | SDHC_XFERTYP_CICEN_MASK |
+ SDHC_XFERTYP_CCCEN_MASK | SDHC_XFERTYP_RSPTYP_MASK | SDHC_XFERTYP_DTDSEL_MASK |
+ SDHC_XFERTYP_AC12EN_MASK)));
+}
+
+void SDHC_EnableSdioControl(SDHC_Type *base, uint32_t mask, bool enable)
+{
+ uint32_t proctl = base->PROCTL;
+ uint32_t vendor = base->VENDOR;
+
+ if (enable)
+ {
+ if (mask & kSDHC_StopAtBlockGapFlag)
+ {
+ proctl |= SDHC_PROCTL_SABGREQ_MASK;
+ }
+ if (mask & kSDHC_ReadWaitControlFlag)
+ {
+ proctl |= SDHC_PROCTL_RWCTL_MASK;
+ }
+ if (mask & kSDHC_InterruptAtBlockGapFlag)
+ {
+ proctl |= SDHC_PROCTL_IABG_MASK;
+ }
+ if (mask & kSDHC_ExactBlockNumberReadFlag)
+ {
+ vendor |= SDHC_VENDOR_EXBLKNU_MASK;
+ }
+ }
+ else
+ {
+ if (mask & kSDHC_StopAtBlockGapFlag)
+ {
+ proctl &= ~SDHC_PROCTL_SABGREQ_MASK;
+ }
+ if (mask & kSDHC_ReadWaitControlFlag)
+ {
+ proctl &= ~SDHC_PROCTL_RWCTL_MASK;
+ }
+ if (mask & kSDHC_InterruptAtBlockGapFlag)
+ {
+ proctl &= ~SDHC_PROCTL_IABG_MASK;
+ }
+ if (mask & kSDHC_ExactBlockNumberReadFlag)
+ {
+ vendor &= ~SDHC_VENDOR_EXBLKNU_MASK;
+ }
+ }
+
+ base->PROCTL = proctl;
+ base->VENDOR = vendor;
+}
+
+void SDHC_SetMmcBootConfig(SDHC_Type *base, const sdhc_boot_config_t *config)
+{
+ assert(config);
+
+ uint32_t mmcboot;
+
+ mmcboot = base->MMCBOOT;
+ mmcboot |= (SDHC_MMCBOOT_DTOCVACK(config->ackTimeoutCount) | SDHC_MMCBOOT_BOOTMODE(config->bootMode) |
+ SDHC_MMCBOOT_BOOTBLKCNT(config->blockCount));
+ if (config->enableBootAck)
+ {
+ mmcboot |= SDHC_MMCBOOT_BOOTACK_MASK;
+ }
+ if (config->enableBoot)
+ {
+ mmcboot |= SDHC_MMCBOOT_BOOTEN_MASK;
+ }
+ if (config->enableAutoStopAtBlockGap)
+ {
+ mmcboot |= SDHC_MMCBOOT_AUTOSABGEN_MASK;
+ }
+ base->MMCBOOT = mmcboot;
+}
+
+status_t SDHC_SetAdmaTableConfig(SDHC_Type *base,
+ sdhc_dma_mode_t dmaMode,
+ uint32_t *table,
+ uint32_t tableWords,
+ const uint32_t *data,
+ uint32_t dataBytes)
+{
+ status_t error = kStatus_Success;
+ const uint32_t *startAddress;
+ uint32_t entries;
+ uint32_t i;
+#if defined FSL_SDHC_ENABLE_ADMA1
+ sdhc_adma1_descriptor_t *adma1EntryAddress;
+#endif
+ sdhc_adma2_descriptor_t *adma2EntryAddress;
+
+ if ((((!table) || (!tableWords)) && ((dmaMode == kSDHC_DmaModeAdma1) || (dmaMode == kSDHC_DmaModeAdma2))) ||
+ (!data) || (!dataBytes)
+#if !defined FSL_SDHC_ENABLE_ADMA1
+ || (dmaMode == kSDHC_DmaModeAdma1)
+#else
+ /* Buffer address configured in ADMA1 descriptor must be 4KB aligned. */
+ || ((dmaMode == kSDHC_DmaModeAdma1) && (((uint32_t)data % SDHC_ADMA1_LENGTH_ALIGN) != 0U))
+#endif /* FSL_SDHC_ENABLE_ADMA1 */
+ )
+ {
+ error = kStatus_InvalidArgument;
+ }
+ else
+ {
+ switch (dmaMode)
+ {
+ case kSDHC_DmaModeNo:
+ break;
+#if defined FSL_SDHC_ENABLE_ADMA1
+ case kSDHC_DmaModeAdma1:
+ startAddress = data;
+ /* Check if ADMA descriptor's number is enough. */
+ entries = ((dataBytes / SDHC_ADMA1_DESCRIPTOR_MAX_LENGTH_PER_ENTRY) + 1U);
+ /* ADMA1 needs two descriptors to finish a transfer */
+ entries <<= 1U;
+ if (entries > ((tableWords * sizeof(uint32_t)) / sizeof(sdhc_adma1_descriptor_t)))
+ {
+ error = kStatus_OutOfRange;
+ }
+ else
+ {
+ adma1EntryAddress = (sdhc_adma1_descriptor_t *)(table);
+ for (i = 0U; i < entries; i += 2U)
+ {
+ /* Each descriptor for ADMA1 is 32-bit in length */
+ if ((dataBytes - sizeof(uint32_t) * (startAddress - data)) <=
+ SDHC_ADMA1_DESCRIPTOR_MAX_LENGTH_PER_ENTRY)
+ {
+ /* The last piece of data, setting end flag in descriptor */
+ adma1EntryAddress[i] = ((uint32_t)(dataBytes - sizeof(uint32_t) * (startAddress - data))
+ << SDHC_ADMA1_DESCRIPTOR_LENGTH_SHIFT);
+ adma1EntryAddress[i] |= kSDHC_Adma1DescriptorTypeSetLength;
+ adma1EntryAddress[i + 1U] =
+ ((uint32_t)(startAddress) << SDHC_ADMA1_DESCRIPTOR_ADDRESS_SHIFT);
+ adma1EntryAddress[i + 1U] |=
+ (kSDHC_Adma1DescriptorTypeTransfer | kSDHC_Adma1DescriptorEndFlag);
+ }
+ else
+ {
+ adma1EntryAddress[i] = ((uint32_t)SDHC_ADMA1_DESCRIPTOR_MAX_LENGTH_PER_ENTRY
+ << SDHC_ADMA1_DESCRIPTOR_LENGTH_SHIFT);
+ adma1EntryAddress[i] |= kSDHC_Adma1DescriptorTypeSetLength;
+ adma1EntryAddress[i + 1U] =
+ ((uint32_t)(startAddress) << SDHC_ADMA1_DESCRIPTOR_ADDRESS_SHIFT);
+ adma1EntryAddress[i + 1U] |= kSDHC_Adma1DescriptorTypeTransfer;
+ startAddress += SDHC_ADMA1_DESCRIPTOR_MAX_LENGTH_PER_ENTRY / sizeof(uint32_t);
+ }
+ }
+
+ /* When use ADMA, disable simple DMA */
+ base->DSADDR = 0U;
+ base->ADSADDR = (uint32_t)table;
+ }
+ break;
+#endif /* FSL_SDHC_ENABLE_ADMA1 */
+ case kSDHC_DmaModeAdma2:
+ startAddress = data;
+ /* Check if ADMA descriptor's number is enough. */
+ entries = ((dataBytes / SDHC_ADMA2_DESCRIPTOR_MAX_LENGTH_PER_ENTRY) + 1U);
+ if (entries > ((tableWords * sizeof(uint32_t)) / sizeof(sdhc_adma2_descriptor_t)))
+ {
+ error = kStatus_OutOfRange;
+ }
+ else
+ {
+ adma2EntryAddress = (sdhc_adma2_descriptor_t *)(table);
+ for (i = 0U; i < entries; i++)
+ {
+ /* Each descriptor for ADMA2 is 64-bit in length */
+ if ((dataBytes - sizeof(uint32_t) * (startAddress - data)) <=
+ SDHC_ADMA2_DESCRIPTOR_MAX_LENGTH_PER_ENTRY)
+ {
+ /* The last piece of data, setting end flag in descriptor */
+ adma2EntryAddress[i].address = startAddress;
+ adma2EntryAddress[i].attribute = ((dataBytes - sizeof(uint32_t) * (startAddress - data))
+ << SDHC_ADMA2_DESCRIPTOR_LENGTH_SHIFT);
+ adma2EntryAddress[i].attribute |=
+ (kSDHC_Adma2DescriptorTypeTransfer | kSDHC_Adma2DescriptorEndFlag);
+ }
+ else
+ {
+ adma2EntryAddress[i].address = startAddress;
+ adma2EntryAddress[i].attribute =
+ (((SDHC_ADMA2_DESCRIPTOR_MAX_LENGTH_PER_ENTRY / sizeof(uint32_t)) * sizeof(uint32_t))
+ << SDHC_ADMA2_DESCRIPTOR_LENGTH_SHIFT);
+ adma2EntryAddress[i].attribute |= kSDHC_Adma2DescriptorTypeTransfer;
+ startAddress += (SDHC_ADMA2_DESCRIPTOR_MAX_LENGTH_PER_ENTRY / sizeof(uint32_t));
+ }
+ }
+
+ /* When use ADMA, disable simple DMA */
+ base->DSADDR = 0U;
+ base->ADSADDR = (uint32_t)table;
+ }
+ break;
+ default:
+ break;
+ }
+ }
+
+ return error;
+}
+
+status_t SDHC_TransferBlocking(SDHC_Type *base, uint32_t *admaTable, uint32_t admaTableWords, sdhc_transfer_t *transfer)
+{
+ assert(transfer);
+ assert(transfer->command); /* Command must not be NULL, data can be NULL. */
+
+ status_t error = kStatus_Success;
+ sdhc_dma_mode_t dmaMode = (sdhc_dma_mode_t)((base->PROCTL & SDHC_PROCTL_DMAS_MASK) >> SDHC_PROCTL_DMAS_SHIFT);
+ sdhc_command_t *command = transfer->command;
+ sdhc_data_t *data = transfer->data;
+
+ /* DATA-PORT is 32-bit align, ADMA2 4 bytes align, ADMA1 is 4096 bytes align */
+ if ((!command) || (data && (data->blockSize % 4U)))
+ {
+ error = kStatus_InvalidArgument;
+ }
+ else
+ {
+ /* Wait until command/data bus out of busy status. */
+ while (SDHC_GetPresentStatusFlags(base) & kSDHC_CommandInhibitFlag)
+ {
+ }
+ while (data && (SDHC_GetPresentStatusFlags(base) & kSDHC_DataInhibitFlag))
+ {
+ }
+
+ /* Update ADMA descriptor table if data isn't NULL. */
+ if (data && (kStatus_Success != SDHC_SetAdmaTableConfig(base, dmaMode, admaTable, admaTableWords,
+ (data->rxData ? data->rxData : data->txData),
+ (data->blockCount * data->blockSize))))
+ {
+ error = kStatus_SDHC_PrepareAdmaDescriptorFailed;
+ }
+ else
+ {
+ SDHC_StartTransfer(base, command, data);
+
+ /* Send command and receive data. */
+ if (kStatus_Success != SDHC_SendCommandBlocking(base, command))
+ {
+ error = kStatus_SDHC_SendCommandFailed;
+ }
+ else if (data && (kStatus_Success != SDHC_TransferDataBlocking(dmaMode, base, data)))
+ {
+ error = kStatus_SDHC_TransferDataFailed;
+ }
+ else
+ {
+ }
+ }
+ }
+
+ return error;
+}
+
+void SDHC_TransferCreateHandle(SDHC_Type *base,
+ sdhc_handle_t *handle,
+ const sdhc_transfer_callback_t *callback,
+ void *userData)
+{
+ assert(handle);
+ assert(callback);
+
+ /* Zero the handle. */
+ memset(handle, 0, sizeof(*handle));
+
+ /* Set the callback. */
+ handle->callback.CardInserted = callback->CardInserted;
+ handle->callback.CardRemoved = callback->CardRemoved;
+ handle->callback.SdioInterrupt = callback->SdioInterrupt;
+ handle->callback.SdioBlockGap = callback->SdioBlockGap;
+ handle->callback.TransferComplete = callback->TransferComplete;
+ handle->userData = userData;
+
+ /* Save the handle in global variables to support the double weak mechanism. */
+ s_sdhcHandle[SDHC_GetInstance(base)] = handle;
+
+ /* Enable interrupt in NVIC. */
+ SDHC_SetTransferInterrupt(base, true);
+ EnableIRQ(s_sdhcIRQ[SDHC_GetInstance(base)]);
+}
+
+status_t SDHC_TransferNonBlocking(
+ SDHC_Type *base, sdhc_handle_t *handle, uint32_t *admaTable, uint32_t admaTableWords, sdhc_transfer_t *transfer)
+{
+ assert(transfer);
+
+ sdhc_dma_mode_t dmaMode = (sdhc_dma_mode_t)((base->PROCTL & SDHC_PROCTL_DMAS_MASK) >> SDHC_PROCTL_DMAS_SHIFT);
+ status_t error = kStatus_Success;
+ sdhc_command_t *command = transfer->command;
+ sdhc_data_t *data = transfer->data;
+
+ /* DATA-PORT is 32-bit align, ADMA2 4 bytes align, ADMA1 is 4096 bytes align */
+ if ((!(transfer->command)) || ((transfer->data) && (transfer->data->blockSize % 4U)))
+ {
+ error = kStatus_InvalidArgument;
+ }
+ else
+ {
+ /* Wait until command/data bus out of busy status. */
+ if ((SDHC_GetPresentStatusFlags(base) & kSDHC_CommandInhibitFlag) ||
+ (data && (SDHC_GetPresentStatusFlags(base) & kSDHC_DataInhibitFlag)))
+ {
+ error = kStatus_SDHC_BusyTransferring;
+ }
+ else
+ {
+ /* Update ADMA descriptor table and reset transferred words if data isn't NULL. */
+ if (data && (kStatus_Success != SDHC_SetAdmaTableConfig(base, dmaMode, admaTable, admaTableWords,
+ (data->rxData ? data->rxData : data->txData),
+ (data->blockCount * data->blockSize))))
+ {
+ error = kStatus_SDHC_PrepareAdmaDescriptorFailed;
+ }
+ else
+ {
+ /* Save command and data into handle before transferring. */
+ handle->command = command;
+ handle->data = data;
+ handle->interruptFlags = 0U;
+ /* transferredWords will only be updated in ISR when transfer way is DATAPORT. */
+ handle->transferredWords = 0U;
+ SDHC_StartTransfer(base, command, data);
+ }
+ }
+ }
+
+ return error;
+}
+
+void SDHC_TransferHandleIRQ(SDHC_Type *base, sdhc_handle_t *handle)
+{
+ assert(handle);
+
+ uint32_t interruptFlags;
+
+ interruptFlags = SDHC_GetInterruptStatusFlags(base);
+ handle->interruptFlags = interruptFlags;
+
+ if (interruptFlags & kSDHC_CardDetectFlag)
+ {
+ SDHC_TransferHandleCardDetect(handle, (interruptFlags & kSDHC_CardDetectFlag));
+ }
+ if (interruptFlags & kSDHC_CommandFlag)
+ {
+ SDHC_TransferHandleCommand(base, handle, (interruptFlags & kSDHC_CommandFlag));
+ }
+ if (interruptFlags & kSDHC_DataFlag)
+ {
+ SDHC_TransferHandleData(base, handle, (interruptFlags & kSDHC_DataFlag));
+ }
+ if (interruptFlags & kSDHC_CardInterruptFlag)
+ {
+ SDHC_TransferHandleSdioInterrupt(handle);
+ }
+ if (interruptFlags & kSDHC_BlockGapEventFlag)
+ {
+ SDHC_TransferHandleSdioBlockGap(handle);
+ }
+
+ SDHC_ClearInterruptStatusFlags(base, interruptFlags);
+}
+
+#if defined(SDHC)
+void SDHC_DriverIRQHandler(void)
+{
+ assert(s_sdhcHandle[0]);
+
+ SDHC_TransferHandleIRQ(SDHC, s_sdhcHandle[0]);
+}
+#endif
diff --git a/drivers/fsl_sdhc.h b/drivers/fsl_sdhc.h
new file mode 100644
index 0000000..2c5c61d
--- /dev/null
+++ b/drivers/fsl_sdhc.h
@@ -0,0 +1,1081 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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 SL 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_SDHC_H_
+#define _FSL_SDHC_H_
+
+#include "fsl_common.h"
+
+/*!
+ * @addtogroup sdhc
+ * @{
+ */
+
+
+/******************************************************************************
+ * Definitions.
+ *****************************************************************************/
+
+/*! @name Driver version */
+/*@{*/
+/*! @brief Driver version 2.1.1. */
+#define FSL_SDHC_DRIVER_VERSION (MAKE_VERSION(2U, 1U, 1U))
+/*@}*/
+
+/*! @brief Maximum block count can be set one time */
+#define SDHC_MAX_BLOCK_COUNT (SDHC_BLKATTR_BLKCNT_MASK >> SDHC_BLKATTR_BLKCNT_SHIFT)
+
+/*! @brief SDHC status */
+enum _sdhc_status
+{
+ kStatus_SDHC_BusyTransferring = MAKE_STATUS(kStatusGroup_SDHC, 0U), /*!< Transfer is on-going */
+ kStatus_SDHC_PrepareAdmaDescriptorFailed = MAKE_STATUS(kStatusGroup_SDHC, 1U), /*!< Set DMA descriptor failed */
+ kStatus_SDHC_SendCommandFailed = MAKE_STATUS(kStatusGroup_SDHC, 2U), /*!< Send command failed */
+ kStatus_SDHC_TransferDataFailed = MAKE_STATUS(kStatusGroup_SDHC, 3U), /*!< Transfer data failed */
+};
+
+/*! @brief Host controller capabilities flag mask */
+enum _sdhc_capability_flag
+{
+ kSDHC_SupportAdmaFlag = SDHC_HTCAPBLT_ADMAS_MASK, /*!< Support ADMA */
+ kSDHC_SupportHighSpeedFlag = SDHC_HTCAPBLT_HSS_MASK, /*!< Support high-speed */
+ kSDHC_SupportDmaFlag = SDHC_HTCAPBLT_DMAS_MASK, /*!< Support DMA */
+ kSDHC_SupportSuspendResumeFlag = SDHC_HTCAPBLT_SRS_MASK, /*!< Support suspend/resume */
+ kSDHC_SupportV330Flag = SDHC_HTCAPBLT_VS33_MASK, /*!< Support voltage 3.3V */
+#if defined FSL_FEATURE_SDHC_HAS_V300_SUPPORT && FSL_FEATURE_SDHC_HAS_V300_SUPPORT
+ kSDHC_SupportV300Flag = SDHC_HTCAPBLT_VS30_MASK, /*!< Support voltage 3.0V */
+#endif
+#if defined FSL_FEATURE_SDHC_HAS_V180_SUPPORT && FSL_FEATURE_SDHC_HAS_V180_SUPPORT
+ kSDHC_SupportV180Flag = SDHC_HTCAPBLT_VS18_MASK, /*!< Support voltage 1.8V */
+#endif
+ /* Put additional two flags in HTCAPBLT_MBL's position. */
+ kSDHC_Support4BitFlag = (SDHC_HTCAPBLT_MBL_SHIFT << 0U), /*!< Support 4 bit mode */
+ kSDHC_Support8BitFlag = (SDHC_HTCAPBLT_MBL_SHIFT << 1U), /*!< Support 8 bit mode */
+};
+
+/*! @brief Wakeup event mask */
+enum _sdhc_wakeup_event
+{
+ kSDHC_WakeupEventOnCardInt = SDHC_PROCTL_WECINT_MASK, /*!< Wakeup on card interrupt */
+ kSDHC_WakeupEventOnCardInsert = SDHC_PROCTL_WECINS_MASK, /*!< Wakeup on card insertion */
+ kSDHC_WakeupEventOnCardRemove = SDHC_PROCTL_WECRM_MASK, /*!< Wakeup on card removal */
+
+ kSDHC_WakeupEventsAll = (kSDHC_WakeupEventOnCardInt | kSDHC_WakeupEventOnCardInsert |
+ kSDHC_WakeupEventOnCardRemove), /*!< All wakeup events */
+};
+
+/*! @brief Reset type mask */
+enum _sdhc_reset
+{
+ kSDHC_ResetAll = SDHC_SYSCTL_RSTA_MASK, /*!< Reset all except card detection */
+ kSDHC_ResetCommand = SDHC_SYSCTL_RSTC_MASK, /*!< Reset command line */
+ kSDHC_ResetData = SDHC_SYSCTL_RSTD_MASK, /*!< Reset data line */
+
+ kSDHC_ResetsAll = (kSDHC_ResetAll | kSDHC_ResetCommand | kSDHC_ResetData), /*!< All reset types */
+};
+
+/*! @brief Transfer flag mask */
+enum _sdhc_transfer_flag
+{
+ kSDHC_EnableDmaFlag = SDHC_XFERTYP_DMAEN_MASK, /*!< Enable DMA */
+
+ kSDHC_CommandTypeSuspendFlag = (SDHC_XFERTYP_CMDTYP(1U)), /*!< Suspend command */
+ kSDHC_CommandTypeResumeFlag = (SDHC_XFERTYP_CMDTYP(2U)), /*!< Resume command */
+ kSDHC_CommandTypeAbortFlag = (SDHC_XFERTYP_CMDTYP(3U)), /*!< Abort command */
+
+ kSDHC_EnableBlockCountFlag = SDHC_XFERTYP_BCEN_MASK, /*!< Enable block count */
+ kSDHC_EnableAutoCommand12Flag = SDHC_XFERTYP_AC12EN_MASK, /*!< Enable auto CMD12 */
+ kSDHC_DataReadFlag = SDHC_XFERTYP_DTDSEL_MASK, /*!< Enable data read */
+ kSDHC_MultipleBlockFlag = SDHC_XFERTYP_MSBSEL_MASK, /*!< Multiple block data read/write */
+
+ kSDHC_ResponseLength136Flag = SDHC_XFERTYP_RSPTYP(1U), /*!< 136 bit response length */
+ kSDHC_ResponseLength48Flag = SDHC_XFERTYP_RSPTYP(2U), /*!< 48 bit response length */
+ kSDHC_ResponseLength48BusyFlag = SDHC_XFERTYP_RSPTYP(3U), /*!< 48 bit response length with busy status */
+
+ kSDHC_EnableCrcCheckFlag = SDHC_XFERTYP_CCCEN_MASK, /*!< Enable CRC check */
+ kSDHC_EnableIndexCheckFlag = SDHC_XFERTYP_CICEN_MASK, /*!< Enable index check */
+ kSDHC_DataPresentFlag = SDHC_XFERTYP_DPSEL_MASK, /*!< Data present flag */
+};
+
+/*! @brief Present status flag mask */
+enum _sdhc_present_status_flag
+{
+ kSDHC_CommandInhibitFlag = SDHC_PRSSTAT_CIHB_MASK, /*!< Command inhibit */
+ kSDHC_DataInhibitFlag = SDHC_PRSSTAT_CDIHB_MASK, /*!< Data inhibit */
+ kSDHC_DataLineActiveFlag = SDHC_PRSSTAT_DLA_MASK, /*!< Data line active */
+ kSDHC_SdClockStableFlag = SDHC_PRSSTAT_SDSTB_MASK, /*!< SD bus clock stable */
+ kSDHC_WriteTransferActiveFlag = SDHC_PRSSTAT_WTA_MASK, /*!< Write transfer active */
+ kSDHC_ReadTransferActiveFlag = SDHC_PRSSTAT_RTA_MASK, /*!< Read transfer active */
+ kSDHC_BufferWriteEnableFlag = SDHC_PRSSTAT_BWEN_MASK, /*!< Buffer write enable */
+ kSDHC_BufferReadEnableFlag = SDHC_PRSSTAT_BREN_MASK, /*!< Buffer read enable */
+ kSDHC_CardInsertedFlag = SDHC_PRSSTAT_CINS_MASK, /*!< Card inserted */
+ kSDHC_CommandLineLevelFlag = SDHC_PRSSTAT_CLSL_MASK, /*!< Command line signal level */
+ kSDHC_Data0LineLevelFlag = (1U << 24U), /*!< Data0 line signal level */
+ kSDHC_Data1LineLevelFlag = (1U << 25U), /*!< Data1 line signal level */
+ kSDHC_Data2LineLevelFlag = (1U << 26U), /*!< Data2 line signal level */
+ kSDHC_Data3LineLevelFlag = (1U << 27U), /*!< Data3 line signal level */
+ kSDHC_Data4LineLevelFlag = (1U << 28U), /*!< Data4 line signal level */
+ kSDHC_Data5LineLevelFlag = (1U << 29U), /*!< Data5 line signal level */
+ kSDHC_Data6LineLevelFlag = (1U << 30U), /*!< Data6 line signal level */
+ kSDHC_Data7LineLevelFlag = (1U << 31U), /*!< Data7 line signal level */
+};
+
+/*! @brief Interrupt status flag mask */
+enum _sdhc_interrupt_status_flag
+{
+ kSDHC_CommandCompleteFlag = SDHC_IRQSTAT_CC_MASK, /*!< Command complete */
+ kSDHC_DataCompleteFlag = SDHC_IRQSTAT_TC_MASK, /*!< Data complete */
+ kSDHC_BlockGapEventFlag = SDHC_IRQSTAT_BGE_MASK, /*!< Block gap event */
+ kSDHC_DmaCompleteFlag = SDHC_IRQSTAT_DINT_MASK, /*!< DMA interrupt */
+ kSDHC_BufferWriteReadyFlag = SDHC_IRQSTAT_BWR_MASK, /*!< Buffer write ready */
+ kSDHC_BufferReadReadyFlag = SDHC_IRQSTAT_BRR_MASK, /*!< Buffer read ready */
+ kSDHC_CardInsertionFlag = SDHC_IRQSTAT_CINS_MASK, /*!< Card inserted */
+ kSDHC_CardRemovalFlag = SDHC_IRQSTAT_CRM_MASK, /*!< Card removed */
+ kSDHC_CardInterruptFlag = SDHC_IRQSTAT_CINT_MASK, /*!< Card interrupt */
+ kSDHC_CommandTimeoutFlag = SDHC_IRQSTAT_CTOE_MASK, /*!< Command timeout error */
+ kSDHC_CommandCrcErrorFlag = SDHC_IRQSTAT_CCE_MASK, /*!< Command CRC error */
+ kSDHC_CommandEndBitErrorFlag = SDHC_IRQSTAT_CEBE_MASK, /*!< Command end bit error */
+ kSDHC_CommandIndexErrorFlag = SDHC_IRQSTAT_CIE_MASK, /*!< Command index error */
+ kSDHC_DataTimeoutFlag = SDHC_IRQSTAT_DTOE_MASK, /*!< Data timeout error */
+ kSDHC_DataCrcErrorFlag = SDHC_IRQSTAT_DCE_MASK, /*!< Data CRC error */
+ kSDHC_DataEndBitErrorFlag = SDHC_IRQSTAT_DEBE_MASK, /*!< Data end bit error */
+ kSDHC_AutoCommand12ErrorFlag = SDHC_IRQSTAT_AC12E_MASK, /*!< Auto CMD12 error */
+ kSDHC_DmaErrorFlag = SDHC_IRQSTAT_DMAE_MASK, /*!< DMA error */
+
+ kSDHC_CommandErrorFlag = (kSDHC_CommandTimeoutFlag | kSDHC_CommandCrcErrorFlag | kSDHC_CommandEndBitErrorFlag |
+ kSDHC_CommandIndexErrorFlag), /*!< Command error */
+ kSDHC_DataErrorFlag = (kSDHC_DataTimeoutFlag | kSDHC_DataCrcErrorFlag | kSDHC_DataEndBitErrorFlag |
+ kSDHC_AutoCommand12ErrorFlag), /*!< Data error */
+ kSDHC_ErrorFlag = (kSDHC_CommandErrorFlag | kSDHC_DataErrorFlag | kSDHC_DmaErrorFlag), /*!< All error */
+ kSDHC_DataFlag = (kSDHC_DataCompleteFlag | kSDHC_DmaCompleteFlag | kSDHC_BufferWriteReadyFlag |
+ kSDHC_BufferReadReadyFlag | kSDHC_DataErrorFlag | kSDHC_DmaErrorFlag), /*!< Data interrupts */
+ kSDHC_CommandFlag = (kSDHC_CommandErrorFlag | kSDHC_CommandCompleteFlag), /*!< Command interrupts */
+ kSDHC_CardDetectFlag = (kSDHC_CardInsertionFlag | kSDHC_CardRemovalFlag), /*!< Card detection interrupts */
+
+ kSDHC_AllInterruptFlags = (kSDHC_BlockGapEventFlag | kSDHC_CardInterruptFlag | kSDHC_CommandFlag | kSDHC_DataFlag |
+ kSDHC_ErrorFlag), /*!< All flags mask */
+};
+
+/*! @brief Auto CMD12 error status flag mask */
+enum _sdhc_auto_command12_error_status_flag
+{
+ kSDHC_AutoCommand12NotExecutedFlag = SDHC_AC12ERR_AC12NE_MASK, /*!< Not executed error */
+ kSDHC_AutoCommand12TimeoutFlag = SDHC_AC12ERR_AC12TOE_MASK, /*!< Timeout error */
+ kSDHC_AutoCommand12EndBitErrorFlag = SDHC_AC12ERR_AC12EBE_MASK, /*!< End bit error */
+ kSDHC_AutoCommand12CrcErrorFlag = SDHC_AC12ERR_AC12CE_MASK, /*!< CRC error */
+ kSDHC_AutoCommand12IndexErrorFlag = SDHC_AC12ERR_AC12IE_MASK, /*!< Index error */
+ kSDHC_AutoCommand12NotIssuedFlag = SDHC_AC12ERR_CNIBAC12E_MASK, /*!< Not issued error */
+};
+
+/*! @brief ADMA error status flag mask */
+enum _sdhc_adma_error_status_flag
+{
+ kSDHC_AdmaLenghMismatchFlag = SDHC_ADMAES_ADMALME_MASK, /*!< Length mismatch error */
+ kSDHC_AdmaDescriptorErrorFlag = SDHC_ADMAES_ADMADCE_MASK, /*!< Descriptor error */
+};
+
+/*!
+ * @brief ADMA error state
+ *
+ * This state is the detail state when ADMA error has occurred.
+ */
+typedef enum _sdhc_adma_error_state
+{
+ kSDHC_AdmaErrorStateStopDma = 0x00U, /*!< Stop DMA */
+ kSDHC_AdmaErrorStateFetchDescriptor = 0x01U, /*!< Fetch descriptor */
+ kSDHC_AdmaErrorStateChangeAddress = 0x02U, /*!< Change address */
+ kSDHC_AdmaErrorStateTransferData = 0x03U, /*!< Transfer data */
+} sdhc_adma_error_state_t;
+
+/*! @brief Force event mask */
+enum _sdhc_force_event
+{
+ kSDHC_ForceEventAutoCommand12NotExecuted = SDHC_FEVT_AC12NE_MASK, /*!< Auto CMD12 not executed error */
+ kSDHC_ForceEventAutoCommand12Timeout = SDHC_FEVT_AC12TOE_MASK, /*!< Auto CMD12 timeout error */
+ kSDHC_ForceEventAutoCommand12CrcError = SDHC_FEVT_AC12CE_MASK, /*!< Auto CMD12 CRC error */
+ kSDHC_ForceEventEndBitError = SDHC_FEVT_AC12EBE_MASK, /*!< Auto CMD12 end bit error */
+ kSDHC_ForceEventAutoCommand12IndexError = SDHC_FEVT_AC12IE_MASK, /*!< Auto CMD12 index error */
+ kSDHC_ForceEventAutoCommand12NotIssued = SDHC_FEVT_CNIBAC12E_MASK, /*!< Auto CMD12 not issued error */
+ kSDHC_ForceEventCommandTimeout = SDHC_FEVT_CTOE_MASK, /*!< Command timeout error */
+ kSDHC_ForceEventCommandCrcError = SDHC_FEVT_CCE_MASK, /*!< Command CRC error */
+ kSDHC_ForceEventCommandEndBitError = SDHC_FEVT_CEBE_MASK, /*!< Command end bit error */
+ kSDHC_ForceEventCommandIndexError = SDHC_FEVT_CIE_MASK, /*!< Command index error */
+ kSDHC_ForceEventDataTimeout = SDHC_FEVT_DTOE_MASK, /*!< Data timeout error */
+ kSDHC_ForceEventDataCrcError = SDHC_FEVT_DCE_MASK, /*!< Data CRC error */
+ kSDHC_ForceEventDataEndBitError = SDHC_FEVT_DEBE_MASK, /*!< Data end bit error */
+ kSDHC_ForceEventAutoCommand12Error = SDHC_FEVT_AC12E_MASK, /*!< Auto CMD12 error */
+ kSDHC_ForceEventCardInt = SDHC_FEVT_CINT_MASK, /*!< Card interrupt */
+ kSDHC_ForceEventDmaError = SDHC_FEVT_DMAE_MASK, /*!< Dma error */
+
+ kSDHC_ForceEventsAll =
+ (kSDHC_ForceEventAutoCommand12NotExecuted | kSDHC_ForceEventAutoCommand12Timeout |
+ kSDHC_ForceEventAutoCommand12CrcError | kSDHC_ForceEventEndBitError | kSDHC_ForceEventAutoCommand12IndexError |
+ kSDHC_ForceEventAutoCommand12NotIssued | kSDHC_ForceEventCommandTimeout | kSDHC_ForceEventCommandCrcError |
+ kSDHC_ForceEventCommandEndBitError | kSDHC_ForceEventCommandIndexError | kSDHC_ForceEventDataTimeout |
+ kSDHC_ForceEventDataCrcError | kSDHC_ForceEventDataEndBitError | kSDHC_ForceEventAutoCommand12Error |
+ kSDHC_ForceEventCardInt | kSDHC_ForceEventDmaError), /*!< All force event flags mask */
+};
+
+/*! @brief Data transfer width */
+typedef enum _sdhc_data_bus_width
+{
+ kSDHC_DataBusWidth1Bit = 0U, /*!< 1-bit mode */
+ kSDHC_DataBusWidth4Bit = 1U, /*!< 4-bit mode */
+ kSDHC_DataBusWidth8Bit = 2U, /*!< 8-bit mode */
+} sdhc_data_bus_width_t;
+
+/*! @brief Endian mode */
+typedef enum _sdhc_endian_mode
+{
+ kSDHC_EndianModeBig = 0U, /*!< Big endian mode */
+ kSDHC_EndianModeHalfWordBig = 1U, /*!< Half word big endian mode */
+ kSDHC_EndianModeLittle = 2U, /*!< Little endian mode */
+} sdhc_endian_mode_t;
+
+/*! @brief DMA mode */
+typedef enum _sdhc_dma_mode
+{
+ kSDHC_DmaModeNo = 0U, /*!< No DMA */
+ kSDHC_DmaModeAdma1 = 1U, /*!< ADMA1 is selected */
+ kSDHC_DmaModeAdma2 = 2U, /*!< ADMA2 is selected */
+} sdhc_dma_mode_t;
+
+/*! @brief SDIO control flag mask */
+enum _sdhc_sdio_control_flag
+{
+ kSDHC_StopAtBlockGapFlag = 0x01, /*!< Stop at block gap */
+ kSDHC_ReadWaitControlFlag = 0x02, /*!< Read wait control */
+ kSDHC_InterruptAtBlockGapFlag = 0x04, /*!< Interrupt at block gap */
+ kSDHC_ExactBlockNumberReadFlag = 0x08, /*!< Exact block number read */
+};
+
+/*! @brief MMC card boot mode */
+typedef enum _sdhc_boot_mode
+{
+ kSDHC_BootModeNormal = 0U, /*!< Normal boot */
+ kSDHC_BootModeAlternative = 1U, /*!< Alternative boot */
+} sdhc_boot_mode_t;
+
+/*! @brief The command type */
+typedef enum _sdhc_command_type
+{
+ kSDHC_CommandTypeNormal = 0U, /*!< Normal command */
+ kSDHC_CommandTypeSuspend = 1U, /*!< Suspend command */
+ kSDHC_CommandTypeResume = 2U, /*!< Resume command */
+ kSDHC_CommandTypeAbort = 3U, /*!< Abort command */
+} sdhc_command_type_t;
+
+/*!
+ * @brief The command response type.
+ *
+ * Define the command response type from card to host controller.
+ */
+typedef enum _sdhc_response_type
+{
+ kSDHC_ResponseTypeNone = 0U, /*!< Response type: none */
+ kSDHC_ResponseTypeR1 = 1U, /*!< Response type: R1 */
+ kSDHC_ResponseTypeR1b = 2U, /*!< Response type: R1b */
+ kSDHC_ResponseTypeR2 = 3U, /*!< Response type: R2 */
+ kSDHC_ResponseTypeR3 = 4U, /*!< Response type: R3 */
+ kSDHC_ResponseTypeR4 = 5U, /*!< Response type: R4 */
+ kSDHC_ResponseTypeR5 = 6U, /*!< Response type: R5 */
+ kSDHC_ResponseTypeR5b = 7U, /*!< Response type: R5b */
+ kSDHC_ResponseTypeR6 = 8U, /*!< Response type: R6 */
+ kSDHC_ResponseTypeR7 = 9U, /*!< Response type: R7 */
+} sdhc_response_type_t;
+
+/*! @brief The alignment size for ADDRESS filed in ADMA1's descriptor */
+#define SDHC_ADMA1_ADDRESS_ALIGN (4096U)
+/*! @brief The alignment size for LENGTH field in ADMA1's descriptor */
+#define SDHC_ADMA1_LENGTH_ALIGN (4096U)
+/*! @brief The alignment size for ADDRESS field in ADMA2's descriptor */
+#define SDHC_ADMA2_ADDRESS_ALIGN (4U)
+/*! @brief The alignment size for LENGTH filed in ADMA2's descriptor */
+#define SDHC_ADMA2_LENGTH_ALIGN (4U)
+
+/* ADMA1 descriptor table
+ * |------------------------|---------|--------------------------|
+ * | Address/page field |Reserved | Attribute |
+ * |------------------------|---------|--------------------------|
+ * |31 12|11 6|05 |04 |03|02 |01 |00 |
+ * |------------------------|---------|----|----|--|---|---|-----|
+ * | address or data length | 000000 |Act2|Act1| 0|Int|End|Valid|
+ * |------------------------|---------|----|----|--|---|---|-----|
+ *
+ *
+ * |------|------|-----------------|-------|-------------|
+ * | Act2 | Act1 | Comment | 31-28 | 27 - 12 |
+ * |------|------|-----------------|---------------------|
+ * | 0 | 0 | No op | Don't care |
+ * |------|------|-----------------|-------|-------------|
+ * | 0 | 1 | Set data length | 0000 | Data Length |
+ * |------|------|-----------------|-------|-------------|
+ * | 1 | 0 | Transfer data | Data address |
+ * |------|------|-----------------|---------------------|
+ * | 1 | 1 | Link descriptor | Descriptor address |
+ * |------|------|-----------------|---------------------|
+ */
+/*! @brief The bit shift for ADDRESS filed in ADMA1's descriptor */
+#define SDHC_ADMA1_DESCRIPTOR_ADDRESS_SHIFT (12U)
+/*! @brief The bit mask for ADDRESS field in ADMA1's descriptor */
+#define SDHC_ADMA1_DESCRIPTOR_ADDRESS_MASK (0xFFFFFU)
+/*! @brief The bit shift for LENGTH filed in ADMA1's descriptor */
+#define SDHC_ADMA1_DESCRIPTOR_LENGTH_SHIFT (12U)
+/*! @brief The mask for LENGTH field in ADMA1's descriptor */
+#define SDHC_ADMA1_DESCRIPTOR_LENGTH_MASK (0xFFFFU)
+/*! @brief The maximum value of LENGTH filed in ADMA1's descriptor */
+#define SDHC_ADMA1_DESCRIPTOR_MAX_LENGTH_PER_ENTRY (SDHC_ADMA1_DESCRIPTOR_LENGTH_MASK + 1U)
+
+/*! @brief The mask for the control/status field in ADMA1 descriptor */
+enum _sdhc_adma1_descriptor_flag
+{
+ kSDHC_Adma1DescriptorValidFlag = (1U << 0U), /*!< Valid flag */
+ kSDHC_Adma1DescriptorEndFlag = (1U << 1U), /*!< End flag */
+ kSDHC_Adma1DescriptorInterrupFlag = (1U << 2U), /*!< Interrupt flag */
+ kSDHC_Adma1DescriptorActivity1Flag = (1U << 4U), /*!< Activity 1 flag */
+ kSDHC_Adma1DescriptorActivity2Flag = (1U << 5U), /*!< Activity 2 flag */
+ kSDHC_Adma1DescriptorTypeNop = (kSDHC_Adma1DescriptorValidFlag), /*!< No operation */
+ kSDHC_Adma1DescriptorTypeTransfer =
+ (kSDHC_Adma1DescriptorActivity2Flag | kSDHC_Adma1DescriptorValidFlag), /*!< Transfer data */
+ kSDHC_Adma1DescriptorTypeLink = (kSDHC_Adma1DescriptorActivity1Flag | kSDHC_Adma1DescriptorActivity2Flag |
+ kSDHC_Adma1DescriptorValidFlag), /*!< Link descriptor */
+ kSDHC_Adma1DescriptorTypeSetLength =
+ (kSDHC_Adma1DescriptorActivity1Flag | kSDHC_Adma1DescriptorValidFlag), /*!< Set data length */
+};
+
+/* ADMA2 descriptor table
+ * |----------------|---------------|-------------|--------------------------|
+ * | Address field | Length | Reserved | Attribute |
+ * |----------------|---------------|-------------|--------------------------|
+ * |63 32|31 16|15 06|05 |04 |03|02 |01 |00 |
+ * |----------------|---------------|-------------|----|----|--|---|---|-----|
+ * | 32-bit address | 16-bit length | 0000000000 |Act2|Act1| 0|Int|End|Valid|
+ * |----------------|---------------|-------------|----|----|--|---|---|-----|
+ *
+ *
+ * | Act2 | Act1 | Comment | Operation |
+ * |------|------|-----------------|-------------------------------------------------------------------|
+ * | 0 | 0 | No op | Don't care |
+ * |------|------|-----------------|-------------------------------------------------------------------|
+ * | 0 | 1 | Reserved | Read this line and go to next one |
+ * |------|------|-----------------|-------------------------------------------------------------------|
+ * | 1 | 0 | Transfer data | Transfer data with address and length set in this descriptor line |
+ * |------|------|-----------------|-------------------------------------------------------------------|
+ * | 1 | 1 | Link descriptor | Link to another descriptor |
+ * |------|------|-----------------|-------------------------------------------------------------------|
+ */
+/*! @brief The bit shift for LENGTH field in ADMA2's descriptor */
+#define SDHC_ADMA2_DESCRIPTOR_LENGTH_SHIFT (16U)
+/*! @brief The bit mask for LENGTH field in ADMA2's descriptor */
+#define SDHC_ADMA2_DESCRIPTOR_LENGTH_MASK (0xFFFFU)
+/*! @brief The maximum value of LENGTH field in ADMA2's descriptor */
+#define SDHC_ADMA2_DESCRIPTOR_MAX_LENGTH_PER_ENTRY (SDHC_ADMA2_DESCRIPTOR_LENGTH_MASK)
+
+/*! @brief ADMA1 descriptor control and status mask */
+enum _sdhc_adma2_descriptor_flag
+{
+ kSDHC_Adma2DescriptorValidFlag = (1U << 0U), /*!< Valid flag */
+ kSDHC_Adma2DescriptorEndFlag = (1U << 1U), /*!< End flag */
+ kSDHC_Adma2DescriptorInterruptFlag = (1U << 2U), /*!< Interrupt flag */
+ kSDHC_Adma2DescriptorActivity1Flag = (1U << 4U), /*!< Activity 1 mask */
+ kSDHC_Adma2DescriptorActivity2Flag = (1U << 5U), /*!< Activity 2 mask */
+
+ kSDHC_Adma2DescriptorTypeNop = (kSDHC_Adma2DescriptorValidFlag), /*!< No operation */
+ kSDHC_Adma2DescriptorTypeReserved =
+ (kSDHC_Adma2DescriptorActivity1Flag | kSDHC_Adma2DescriptorValidFlag), /*!< Reserved */
+ kSDHC_Adma2DescriptorTypeTransfer =
+ (kSDHC_Adma2DescriptorActivity2Flag | kSDHC_Adma2DescriptorValidFlag), /*!< Transfer type */
+ kSDHC_Adma2DescriptorTypeLink = (kSDHC_Adma2DescriptorActivity1Flag | kSDHC_Adma2DescriptorActivity2Flag |
+ kSDHC_Adma2DescriptorValidFlag), /*!< Link type */
+};
+
+/*! @brief Defines the adma1 descriptor structure. */
+typedef uint32_t sdhc_adma1_descriptor_t;
+
+/*! @brief Defines the ADMA2 descriptor structure. */
+typedef struct _sdhc_adma2_descriptor
+{
+ uint32_t attribute; /*!< The control and status field */
+ const uint32_t *address; /*!< The address field */
+} sdhc_adma2_descriptor_t;
+
+/*!
+ * @brief SDHC capability information.
+ *
+ * Defines a structure to save the capability information of SDHC.
+ */
+typedef struct _sdhc_capability
+{
+ uint32_t specVersion; /*!< Specification version */
+ uint32_t vendorVersion; /*!< Vendor version */
+ uint32_t maxBlockLength; /*!< Maximum block length united as byte */
+ uint32_t maxBlockCount; /*!< Maximum block count can be set one time */
+ uint32_t flags; /*!< Capability flags to indicate the support information(_sdhc_capability_flag) */
+} sdhc_capability_t;
+
+/*! @brief Card transfer configuration.
+ *
+ * Define structure to configure the transfer-related command index/argument/flags and data block
+ * size/data block numbers. This structure needs to be filled each time a command is sent to the card.
+ */
+typedef struct _sdhc_transfer_config
+{
+ size_t dataBlockSize; /*!< Data block size */
+ uint32_t dataBlockCount; /*!< Data block count */
+ uint32_t commandArgument; /*!< Command argument */
+ uint32_t commandIndex; /*!< Command index */
+ uint32_t flags; /*!< Transfer flags(_sdhc_transfer_flag) */
+} sdhc_transfer_config_t;
+
+/*! @brief Data structure to configure the MMC boot feature */
+typedef struct _sdhc_boot_config
+{
+ uint32_t ackTimeoutCount; /*!< Timeout value for the boot ACK */
+ sdhc_boot_mode_t bootMode; /*!< Boot mode selection. */
+ uint32_t blockCount; /*!< Stop at block gap value of automatic mode */
+ bool enableBootAck; /*!< Enable or disable boot ACK */
+ bool enableBoot; /*!< Enable or disable fast boot */
+ bool enableAutoStopAtBlockGap; /*!< Enable or disable auto stop at block gap function in boot period */
+} sdhc_boot_config_t;
+
+/*! @brief Data structure to initialize the SDHC */
+typedef struct _sdhc_config
+{
+ bool cardDetectDat3; /*!< Enable DAT3 as card detection pin */
+ sdhc_endian_mode_t endianMode; /*!< Endian mode */
+ sdhc_dma_mode_t dmaMode; /*!< DMA mode */
+ uint32_t readWatermarkLevel; /*!< Watermark level for DMA read operation */
+ uint32_t writeWatermarkLevel; /*!< Watermark level for DMA write operation */
+} sdhc_config_t;
+
+/*!
+ * @brief Card data descriptor
+ *
+ * Defines a structure to contain data-related attribute. 'enableIgnoreError' is used for the case that upper card driver
+ * want to ignore the error event to read/write all the data not to stop read/write immediately when error event
+ * happen for example bus testing procedure for MMC card.
+ */
+typedef struct _sdhc_data
+{
+ bool enableAutoCommand12; /*!< Enable auto CMD12 */
+ bool enableIgnoreError; /*!< Enable to ignore error event to read/write all the data */
+ size_t blockSize; /*!< Block size */
+ uint32_t blockCount; /*!< Block count */
+ uint32_t *rxData; /*!< Buffer to save data read */
+ const uint32_t *txData; /*!< Data buffer to write */
+} sdhc_data_t;
+
+/*!
+ * @brief Card command descriptor
+ *
+ * Define card command-related attribute.
+ */
+typedef struct _sdhc_command
+{
+ uint32_t index; /*!< Command index */
+ uint32_t argument; /*!< Command argument */
+ sdhc_command_type_t type; /*!< Command type */
+ sdhc_response_type_t responseType; /*!< Command response type */
+ uint32_t response[4U]; /*!< Response for this command */
+} sdhc_command_t;
+
+/*! @brief Transfer state */
+typedef struct _sdhc_transfer
+{
+ sdhc_data_t *data; /*!< Data to transfer */
+ sdhc_command_t *command; /*!< Command to send */
+} sdhc_transfer_t;
+
+/*! @brief SDHC handle typedef */
+typedef struct _sdhc_handle sdhc_handle_t;
+
+/*! @brief SDHC callback functions. */
+typedef struct _sdhc_transfer_callback
+{
+ void (*CardInserted)(void); /*!< Card inserted occurs when DAT3/CD pin is for card detect */
+ void (*CardRemoved)(void); /*!< Card removed occurs */
+ void (*SdioInterrupt)(void); /*!< SDIO card interrupt occurs */
+ void (*SdioBlockGap)(void); /*!< SDIO card stopped at block gap occurs */
+ void (*TransferComplete)(SDHC_Type *base,
+ sdhc_handle_t *handle,
+ status_t status,
+ void *userData); /*!< Transfer complete callback */
+} sdhc_transfer_callback_t;
+
+/*!
+ * @brief SDHC handle
+ *
+ * Defines the structure to save the SDHC state information and callback function. The detail interrupt status when
+ * send command or transfer data can be obtained from interruptFlags field by using mask defined in sdhc_interrupt_flag_t;
+ *
+ * @note All the fields except interruptFlags and transferredWords must be allocated by the user.
+ */
+struct _sdhc_handle
+{
+ /* Transfer parameter */
+ sdhc_data_t *volatile data; /*!< Data to transfer */
+ sdhc_command_t *volatile command; /*!< Command to send */
+
+ /* Transfer status */
+ volatile uint32_t interruptFlags; /*!< Interrupt flags of last transaction */
+ volatile uint32_t transferredWords; /*!< Words transferred by DATAPORT way */
+
+ /* Callback functions */
+ sdhc_transfer_callback_t callback; /*!< Callback function */
+ void *userData; /*!< Parameter for transfer complete callback */
+};
+
+/*! @brief SDHC transfer function. */
+typedef status_t (*sdhc_transfer_function_t)(SDHC_Type *base, sdhc_transfer_t *content);
+
+/*! @brief SDHC host descriptor */
+typedef struct _sdhc_host
+{
+ SDHC_Type *base; /*!< SDHC peripheral base address */
+ uint32_t sourceClock_Hz; /*!< SDHC source clock frequency united in Hz */
+ sdhc_config_t config; /*!< SDHC configuration */
+ sdhc_capability_t capability; /*!< SDHC capability information */
+ sdhc_transfer_function_t transfer; /*!< SDHC transfer function */
+} sdhc_host_t;
+
+/*************************************************************************************************
+ * API
+ ************************************************************************************************/
+#if defined(__cplusplus)
+extern "C" {
+#endif
+
+/*!
+ * @name Initialization and deinitialization
+ * @{
+ */
+
+/*!
+ * @brief SDHC module initialization function.
+ *
+ * Configures the SDHC according to the user configuration.
+ *
+ * Example:
+ @code
+ sdhc_config_t config;
+ config.enableDat3AsCDPin = false;
+ config.endianMode = kSDHC_EndianModeLittle;
+ config.dmaMode = kSDHC_DmaModeAdma2;
+ config.readWatermarkLevel = 512U;
+ config.writeWatermarkLevel = 512U;
+ SDHC_Init(SDHC, &config);
+ @endcode
+ *
+ * @param base SDHC peripheral base address.
+ * @param config SDHC configuration information.
+ * @retval kStatus_Success Operate successfully.
+ */
+void SDHC_Init(SDHC_Type *base, const sdhc_config_t *config);
+
+/*!
+ * @brief Deinitializes the SDHC.
+ *
+ * @param base SDHC peripheral base address.
+ */
+void SDHC_Deinit(SDHC_Type *base);
+
+/*!
+ * @brief Resets the SDHC.
+ *
+ * @param base SDHC peripheral base address.
+ * @param mask The reset type mask(_sdhc_reset).
+ * @param timeout Timeout for reset.
+ * @retval true Reset successfully.
+ * @retval false Reset failed.
+ */
+bool SDHC_Reset(SDHC_Type *base, uint32_t mask, uint32_t timeout);
+
+/* @} */
+
+/*!
+ * @name DMA Control
+ * @{
+ */
+
+/*!
+ * @brief Sets the ADMA descriptor table configuration.
+ *
+ * @param base SDHC peripheral base address.
+ * @param dmaMode DMA mode.
+ * @param table ADMA table address.
+ * @param tableWords ADMA table buffer length united as Words.
+ * @param data Data buffer address.
+ * @param dataBytes Data length united as bytes.
+ * @retval kStatus_OutOfRange ADMA descriptor table length isn't enough to describe data.
+ * @retval kStatus_Success Operate successfully.
+ */
+status_t SDHC_SetAdmaTableConfig(SDHC_Type *base,
+ sdhc_dma_mode_t dmaMode,
+ uint32_t *table,
+ uint32_t tableWords,
+ const uint32_t *data,
+ uint32_t dataBytes);
+
+/* @} */
+
+/*!
+ * @name Interrupts
+ * @{
+ */
+
+/*!
+ * @brief Enables the interrupt status.
+ *
+ * @param base SDHC peripheral base address.
+ * @param mask Interrupt status flags mask(_sdhc_interrupt_status_flag).
+ */
+static inline void SDHC_EnableInterruptStatus(SDHC_Type *base, uint32_t mask)
+{
+ base->IRQSTATEN |= mask;
+}
+
+/*!
+ * @brief Disables the interrupt status.
+ *
+ * @param base SDHC peripheral base address.
+ * @param mask The interrupt status flags mask(_sdhc_interrupt_status_flag).
+ */
+static inline void SDHC_DisableInterruptStatus(SDHC_Type *base, uint32_t mask)
+{
+ base->IRQSTATEN &= ~mask;
+}
+
+/*!
+ * @brief Enables interrupts signal corresponding to the interrupt status flag.
+ *
+ * @param base SDHC peripheral base address.
+ * @param mask The interrupt status flags mask(_sdhc_interrupt_status_flag).
+ */
+static inline void SDHC_EnableInterruptSignal(SDHC_Type *base, uint32_t mask)
+{
+ base->IRQSIGEN |= mask;
+}
+
+/*!
+ * @brief Disables interrupts signal corresponding to the interrupt status flag.
+ *
+ * @param base SDHC peripheral base address.
+ * @param mask The interrupt status flags mask(_sdhc_interrupt_status_flag).
+ */
+static inline void SDHC_DisableInterruptSignal(SDHC_Type *base, uint32_t mask)
+{
+ base->IRQSIGEN &= ~mask;
+}
+
+/* @} */
+
+/*!
+ * @name Status
+ * @{
+ */
+
+/*!
+ * @brief Gets the current interrupt status.
+ *
+ * @param base SDHC peripheral base address.
+ * @return Current interrupt status flags mask(_sdhc_interrupt_status_flag).
+ */
+static inline uint32_t SDHC_GetInterruptStatusFlags(SDHC_Type *base)
+{
+ return base->IRQSTAT;
+}
+
+/*!
+ * @brief Clears a specified interrupt status.
+ *
+ * @param base SDHC peripheral base address.
+ * @param mask The interrupt status flags mask(_sdhc_interrupt_status_flag).
+ */
+static inline void SDHC_ClearInterruptStatusFlags(SDHC_Type *base, uint32_t mask)
+{
+ base->IRQSTAT = mask;
+}
+
+/*!
+ * @brief Gets the status of auto command 12 error.
+ *
+ * @param base SDHC peripheral base address.
+ * @return Auto command 12 error status flags mask(_sdhc_auto_command12_error_status_flag).
+ */
+static inline uint32_t SDHC_GetAutoCommand12ErrorStatusFlags(SDHC_Type *base)
+{
+ return base->AC12ERR;
+}
+
+/*!
+ * @brief Gets the status of the ADMA error.
+ *
+ * @param base SDHC peripheral base address.
+ * @return ADMA error status flags mask(_sdhc_adma_error_status_flag).
+ */
+static inline uint32_t SDHC_GetAdmaErrorStatusFlags(SDHC_Type *base)
+{
+ return base->ADMAES;
+}
+
+/*!
+ * @brief Gets a present status.
+ *
+ * This function gets the present SDHC's status except for interrupt status and error status.
+ *
+ * @param base SDHC peripheral base address.
+ * @return Present SDHC's status flags mask(_sdhc_present_status_flag).
+ */
+static inline uint32_t SDHC_GetPresentStatusFlags(SDHC_Type *base)
+{
+ return base->PRSSTAT;
+}
+
+/* @} */
+
+/*!
+ * @name Bus Operations
+ * @{
+ */
+
+/*!
+ * @brief Gets the capability information
+ *
+ * @param base SDHC peripheral base address.
+ * @param capability Structure to save capability information.
+ */
+void SDHC_GetCapability(SDHC_Type *base, sdhc_capability_t *capability);
+
+/*!
+ * @brief Enables or disables the SD bus clock.
+ *
+ * @param base SDHC peripheral base address.
+ * @param enable True to enable, false to disable.
+ */
+static inline void SDHC_EnableSdClock(SDHC_Type *base, bool enable)
+{
+ if (enable)
+ {
+ base->SYSCTL |= SDHC_SYSCTL_SDCLKEN_MASK;
+ }
+ else
+ {
+ base->SYSCTL &= ~SDHC_SYSCTL_SDCLKEN_MASK;
+ }
+}
+
+/*!
+ * @brief Sets the SD bus clock frequency.
+ *
+ * @param base SDHC peripheral base address.
+ * @param srcClock_Hz SDHC source clock frequency united in Hz.
+ * @param busClock_Hz SD bus clock frequency united in Hz.
+ *
+ * @return The nearest frequency of busClock_Hz configured to SD bus.
+ */
+uint32_t SDHC_SetSdClock(SDHC_Type *base, uint32_t srcClock_Hz, uint32_t busClock_Hz);
+
+/*!
+ * @brief Sends 80 clocks to the card to set it to be active state.
+ *
+ * This function must be called after each time the card is inserted to make card can receive command correctly.
+ *
+ * @param base SDHC peripheral base address.
+ * @param timeout Timeout to initialize card.
+ * @retval true Set card active successfully.
+ * @retval false Set card active failed.
+ */
+bool SDHC_SetCardActive(SDHC_Type *base, uint32_t timeout);
+
+/*!
+ * @brief Sets the data transfer width.
+ *
+ * @param base SDHC peripheral base address.
+ * @param width Data transfer width.
+ */
+static inline void SDHC_SetDataBusWidth(SDHC_Type *base, sdhc_data_bus_width_t width)
+{
+ base->PROCTL = ((base->PROCTL & ~SDHC_PROCTL_DTW_MASK) | SDHC_PROCTL_DTW(width));
+}
+
+/*!
+ * @brief Sets the card transfer-related configuration.
+ *
+ * This function fills card transfer-related command argument/transfer flag/data size. Command and data are sent by
+ * SDHC after calling this function.
+ *
+ * Example:
+ @code
+ sdhc_transfer_config_t transferConfig;
+ transferConfig.dataBlockSize = 512U;
+ transferConfig.dataBlockCount = 2U;
+ transferConfig.commandArgument = 0x01AAU;
+ transferConfig.commandIndex = 8U;
+ transferConfig.flags |= (kSDHC_EnableDmaFlag | kSDHC_EnableAutoCommand12Flag | kSDHC_MultipleBlockFlag);
+ SDHC_SetTransferConfig(SDHC, &transferConfig);
+ @endcode
+ *
+ * @param base SDHC peripheral base address.
+ * @param config Command configuration structure.
+ */
+void SDHC_SetTransferConfig(SDHC_Type *base, const sdhc_transfer_config_t *config);
+
+/*!
+ * @brief Gets the command response.
+ *
+ * @param base SDHC peripheral base address.
+ * @param index The index of response register, range from 0 to 3.
+ * @return Response register transfer.
+ */
+static inline uint32_t SDHC_GetCommandResponse(SDHC_Type *base, uint32_t index)
+{
+ assert(index < 4U);
+
+ return base->CMDRSP[index];
+}
+
+/*!
+ * @brief Fills the the data port.
+ *
+ * This function is mainly used to implement the data transfer by Data Port instead of DMA.
+ *
+ * @param base SDHC peripheral base address.
+ * @param data The data about to be sent.
+ */
+static inline void SDHC_WriteData(SDHC_Type *base, uint32_t data)
+{
+ base->DATPORT = data;
+}
+
+/*!
+ * @brief Retrieves the data from the data port.
+ *
+ * This function is mainly used to implement the data transfer by Data Port instead of DMA.
+ *
+ * @param base SDHC peripheral base address.
+ * @return The data has been read.
+ */
+static inline uint32_t SDHC_ReadData(SDHC_Type *base)
+{
+ return base->DATPORT;
+}
+
+/*!
+ * @brief Enables or disables a wakeup event in low-power mode.
+ *
+ * @param base SDHC peripheral base address.
+ * @param mask Wakeup events mask(_sdhc_wakeup_event).
+ * @param enable True to enable, false to disable.
+ */
+static inline void SDHC_EnableWakeupEvent(SDHC_Type *base, uint32_t mask, bool enable)
+{
+ if (enable)
+ {
+ base->PROCTL |= mask;
+ }
+ else
+ {
+ base->PROCTL &= ~mask;
+ }
+}
+
+/*!
+ * @brief Enables or disables the card detection level for test.
+ *
+ * @param base SDHC peripheral base address.
+ * @param enable True to enable, false to disable.
+ */
+static inline void SDHC_EnableCardDetectTest(SDHC_Type *base, bool enable)
+{
+ if (enable)
+ {
+ base->PROCTL |= SDHC_PROCTL_CDSS_MASK;
+ }
+ else
+ {
+ base->PROCTL &= ~SDHC_PROCTL_CDSS_MASK;
+ }
+}
+
+/*!
+ * @brief Sets the card detection test level.
+ *
+ * This function set the card detection test level to indicate whether the card is inserted into SDHC when DAT[3]/
+ * CD pin is selected as card detection pin. This function can also assert the pin logic when DAT[3]/CD pin is select
+ * as the card detection pin.
+ *
+ * @param base SDHC peripheral base address.
+ * @param high True to set the card detect level to high.
+ */
+static inline void SDHC_SetCardDetectTestLevel(SDHC_Type *base, bool high)
+{
+ if (high)
+ {
+ base->PROCTL |= SDHC_PROCTL_CDTL_MASK;
+ }
+ else
+ {
+ base->PROCTL &= ~SDHC_PROCTL_CDTL_MASK;
+ }
+}
+
+/*!
+ * @brief Enables or disables the SDIO card control.
+ *
+ * @param base SDHC peripheral base address.
+ * @param mask SDIO card control flags mask(_sdhc_sdio_control_flag).
+ * @param enable True to enable, false to disable.
+ */
+void SDHC_EnableSdioControl(SDHC_Type *base, uint32_t mask, bool enable);
+
+/*!
+ * @brief Restarts a transaction which has stopped at the block gap for SDIO card.
+ *
+ * @param base SDHC peripheral base address.
+ */
+static inline void SDHC_SetContinueRequest(SDHC_Type *base)
+{
+ base->PROCTL |= SDHC_PROCTL_CREQ_MASK;
+}
+
+/*!
+ * @brief Configures the MMC boot feature.
+ *
+ * Example:
+ @code
+ sdhc_boot_config_t bootConfig;
+ bootConfig.ackTimeoutCount = 4;
+ bootConfig.bootMode = kSDHC_BootModeNormal;
+ bootConfig.blockCount = 5;
+ bootConfig.enableBootAck = true;
+ bootConfig.enableBoot = true;
+ enableBoot.enableAutoStopAtBlockGap = true;
+ SDHC_SetMmcBootConfig(SDHC, &bootConfig);
+ @endcode
+ *
+ * @param base SDHC peripheral base address.
+ * @param config The MMC boot configuration information.
+ */
+void SDHC_SetMmcBootConfig(SDHC_Type *base, const sdhc_boot_config_t *config);
+
+/*!
+ * @brief Forces to generate events according to the given mask.
+ *
+ * @param base SDHC peripheral base address.
+ * @param mask The force events mask(_sdhc_force_event).
+ */
+static inline void SDHC_SetForceEvent(SDHC_Type *base, uint32_t mask)
+{
+ base->FEVT = mask;
+}
+
+/* @} */
+
+/*!
+ * @name Transactional
+ * @{
+ */
+
+/*!
+ * @brief Transfers the command/data using blocking way.
+ *
+ * This function waits until the command response/data is got or SDHC encounters error by polling the status flag.
+ * Application must not call this API in multiple threads at the same time because of that this API doesn't support
+ * re-entry mechanism.
+ *
+ * @note There is no need to call the API 'SDHC_TransferCreateHandle' when calling this API.
+ *
+ * @param base SDHC peripheral base address.
+ * @param admaTable ADMA table address, can't be null if transfer way is ADMA1/ADMA2.
+ * @param admaTableWords ADMA table length united as words, can't be 0 if transfer way is ADMA1/ADMA2.
+ * @param transfer Transfer content.
+ * @retval kStatus_InvalidArgument Argument is invalid.
+ * @retval kStatus_SDHC_PrepareAdmaDescriptorFailed Prepare ADMA descriptor failed.
+ * @retval kStatus_SDHC_SendCommandFailed Send command failed.
+ * @retval kStatus_SDHC_TransferDataFailed Transfer data failed.
+ * @retval kStatus_Success Operate successfully.
+ */
+status_t SDHC_TransferBlocking(SDHC_Type *base,
+ uint32_t *admaTable,
+ uint32_t admaTableWords,
+ sdhc_transfer_t *transfer);
+
+/*!
+ * @brief Creates the SDHC handle.
+ *
+ * @param base SDHC peripheral base address.
+ * @param handle SDHC handle pointer.
+ * @param callback Structure pointer to contain all callback functions.
+ * @param userData Callback function parameter.
+ */
+void SDHC_TransferCreateHandle(SDHC_Type *base,
+ sdhc_handle_t *handle,
+ const sdhc_transfer_callback_t *callback,
+ void *userData);
+
+/*!
+ * @brief Transfers the command/data using interrupt and asynchronous way.
+ *
+ * This function send command and data and return immediately. It doesn't wait the transfer complete or encounter error.
+ * Application must not call this API in multiple threads at the same time because of that this API doesn't support
+ * re-entry mechanism.
+ *
+ * @note Must call the API 'SDHC_TransferCreateHandle' when calling this API.
+ *
+ * @param base SDHC peripheral base address.
+ * @param handle SDHC handle.
+ * @param admaTable ADMA table address, can't be null if transfer way is ADMA1/ADMA2.
+ * @param admaTableWords ADMA table length united as words, can't be 0 if transfer way is ADMA1/ADMA2.
+ * @param transfer Transfer content.
+ * @retval kStatus_InvalidArgument Argument is invalid.
+ * @retval kStatus_SDHC_BusyTransferring Busy transferring.
+ * @retval kStatus_SDHC_PrepareAdmaDescriptorFailed Prepare ADMA descriptor failed.
+ * @retval kStatus_Success Operate successfully.
+ */
+status_t SDHC_TransferNonBlocking(
+ SDHC_Type *base, sdhc_handle_t *handle, uint32_t *admaTable, uint32_t admaTableWords, sdhc_transfer_t *transfer);
+
+/*!
+ * @brief IRQ handler for SDHC
+ *
+ * This function deals with IRQs on the given host controller.
+ *
+ * @param base SDHC peripheral base address.
+ * @param handle SDHC handle.
+ */
+void SDHC_TransferHandleIRQ(SDHC_Type *base, sdhc_handle_t *handle);
+
+/* @} */
+
+#if defined(__cplusplus)
+}
+#endif
+/*! @} */
+
+#endif /* _FSL_SDHC_H_*/
diff --git a/drivers/fsl_sim.c b/drivers/fsl_sim.c
new file mode 100644
index 0000000..3a4b801
--- /dev/null
+++ b/drivers/fsl_sim.c
@@ -0,0 +1,53 @@
+/*
+* Copyright (c) 2015, Freescale Semiconductor, Inc.
+* All rights reserved.
+*
+* 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 Freescale Semiconductor, Inc. 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_sim.h"
+
+/*******************************************************************************
+ * Codes
+ ******************************************************************************/
+#if (defined(FSL_FEATURE_SIM_OPT_HAS_USB_VOLTAGE_REGULATOR) && FSL_FEATURE_SIM_OPT_HAS_USB_VOLTAGE_REGULATOR)
+void SIM_SetUsbVoltRegulatorEnableMode(uint32_t mask)
+{
+ SIM->SOPT1CFG |= (SIM_SOPT1CFG_URWE_MASK | SIM_SOPT1CFG_UVSWE_MASK | SIM_SOPT1CFG_USSWE_MASK);
+
+ SIM->SOPT1 = (SIM->SOPT1 & ~kSIM_UsbVoltRegEnableInAllModes) | mask;
+}
+#endif /* FSL_FEATURE_SIM_OPT_HAS_USB_VOLTAGE_REGULATOR */
+
+void SIM_GetUniqueId(sim_uid_t *uid)
+{
+#if defined(SIM_UIDH)
+ uid->H = SIM->UIDH;
+#endif
+ uid->MH = SIM->UIDMH;
+ uid->ML = SIM->UIDML;
+ uid->L = SIM->UIDL;
+}
diff --git a/drivers/fsl_sim.h b/drivers/fsl_sim.h
new file mode 100644
index 0000000..77958f8
--- /dev/null
+++ b/drivers/fsl_sim.h
@@ -0,0 +1,127 @@
+/*
+* Copyright (c) 2015, Freescale Semiconductor, Inc.
+* All rights reserved.
+*
+* 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 Freescale Semiconductor, Inc. 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_SIM_H_
+#define _FSL_SIM_H_
+
+#include "fsl_common.h"
+
+/*! @addtogroup sim */
+/*! @{*/
+
+
+/*******************************************************************************
+ * Definitions
+ *******************************************************************************/
+
+/*! @name Driver version */
+/*@{*/
+#define FSL_SIM_DRIVER_VERSION (MAKE_VERSION(2, 0, 0)) /*!< Driver version 2.0.0 */
+/*@}*/
+
+#if (defined(FSL_FEATURE_SIM_OPT_HAS_USB_VOLTAGE_REGULATOR) && FSL_FEATURE_SIM_OPT_HAS_USB_VOLTAGE_REGULATOR)
+/*!@brief USB voltage regulator enable setting. */
+enum _sim_usb_volt_reg_enable_mode
+{
+ kSIM_UsbVoltRegEnable = SIM_SOPT1_USBREGEN_MASK, /*!< Enable voltage regulator. */
+ kSIM_UsbVoltRegEnableInLowPower = SIM_SOPT1_USBVSTBY_MASK, /*!< Enable voltage regulator in VLPR/VLPW modes. */
+ kSIM_UsbVoltRegEnableInStop = SIM_SOPT1_USBSSTBY_MASK, /*!< Enable voltage regulator in STOP/VLPS/LLS/VLLS modes. */
+ kSIM_UsbVoltRegEnableInAllModes = SIM_SOPT1_USBREGEN_MASK | SIM_SOPT1_USBSSTBY_MASK |
+ SIM_SOPT1_USBVSTBY_MASK /*!< Enable voltage regulator in all power modes. */
+};
+#endif /* (defined(FSL_FEATURE_SIM_OPT_HAS_USB_VOLTAGE_REGULATOR) && FSL_FEATURE_SIM_OPT_HAS_USB_VOLTAGE_REGULATOR) */
+
+/*!@brief Unique ID. */
+typedef struct _sim_uid
+{
+#if defined(SIM_UIDH)
+ uint32_t H; /*!< UIDH. */
+#endif
+ uint32_t MH; /*!< UIDMH. */
+ uint32_t ML; /*!< UIDML. */
+ uint32_t L; /*!< UIDL. */
+} sim_uid_t;
+
+/*!@brief Flash enable mode. */
+enum _sim_flash_mode
+{
+ kSIM_FlashDisableInWait = SIM_FCFG1_FLASHDOZE_MASK, /*!< Disable flash in wait mode. */
+ kSIM_FlashDisable = SIM_FCFG1_FLASHDIS_MASK /*!< Disable flash in normal mode. */
+};
+
+/*******************************************************************************
+ * API
+ ******************************************************************************/
+
+#if defined(__cplusplus)
+extern "C" {
+#endif /* __cplusplus*/
+
+#if (defined(FSL_FEATURE_SIM_OPT_HAS_USB_VOLTAGE_REGULATOR) && FSL_FEATURE_SIM_OPT_HAS_USB_VOLTAGE_REGULATOR)
+/*!
+ * @brief Sets the USB voltage regulator setting.
+ *
+ * This function configures whether the USB voltage regulator is enabled in
+ * normal RUN mode, STOP/VLPS/LLS/VLLS modes and VLPR/VLPW modes. The configurations
+ * are passed in as mask value of \ref _sim_usb_volt_reg_enable_mode. For example, enable
+ * USB voltage regulator in RUN/VLPR/VLPW modes and disable in STOP/VLPS/LLS/VLLS mode,
+ * please use:
+ *
+ * SIM_SetUsbVoltRegulatorEnableMode(kSIM_UsbVoltRegEnable | kSIM_UsbVoltRegEnableInLowPower);
+ *
+ * @param mask USB voltage regulator enable setting.
+ */
+void SIM_SetUsbVoltRegulatorEnableMode(uint32_t mask);
+#endif /* FSL_FEATURE_SIM_OPT_HAS_USB_VOLTAGE_REGULATOR */
+
+/*!
+ * @brief Get the unique identification register value.
+ *
+ * @param uid Pointer to the structure to save the UID value.
+ */
+void SIM_GetUniqueId(sim_uid_t *uid);
+
+/*!
+ * @brief Set the flash enable mode.
+ *
+ * @param mode The mode to set, see \ref _sim_flash_mode for mode details.
+ */
+static inline void SIM_SetFlashMode(uint8_t mode)
+{
+ SIM->FCFG1 = mode;
+}
+
+#if defined(__cplusplus)
+}
+#endif /* __cplusplus*/
+
+/*! @}*/
+
+#endif /* _FSL_SIM_H_ */
diff --git a/drivers/fsl_smc.c b/drivers/fsl_smc.c
new file mode 100644
index 0000000..45382fd
--- /dev/null
+++ b/drivers/fsl_smc.c
@@ -0,0 +1,366 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_smc.h"
+
+#if (defined(FSL_FEATURE_SMC_HAS_PARAM) && FSL_FEATURE_SMC_HAS_PARAM)
+void SMC_GetParam(SMC_Type *base, smc_param_t *param)
+{
+ uint32_t reg = base->PARAM;
+ param->hsrunEnable = (bool)(reg & SMC_PARAM_EHSRUN_MASK);
+ param->llsEnable = (bool)(reg & SMC_PARAM_ELLS_MASK);
+ param->lls2Enable = (bool)(reg & SMC_PARAM_ELLS2_MASK);
+ param->vlls0Enable = (bool)(reg & SMC_PARAM_EVLLS0_MASK);
+}
+#endif /* FSL_FEATURE_SMC_HAS_PARAM */
+
+status_t SMC_SetPowerModeRun(SMC_Type *base)
+{
+ uint8_t reg;
+
+ reg = base->PMCTRL;
+ /* configure Normal RUN mode */
+ reg &= ~SMC_PMCTRL_RUNM_MASK;
+ reg |= (kSMC_RunNormal << SMC_PMCTRL_RUNM_SHIFT);
+ base->PMCTRL = reg;
+
+ return kStatus_Success;
+}
+
+#if (defined(FSL_FEATURE_SMC_HAS_HIGH_SPEED_RUN_MODE) && FSL_FEATURE_SMC_HAS_HIGH_SPEED_RUN_MODE)
+status_t SMC_SetPowerModeHsrun(SMC_Type *base)
+{
+ uint8_t reg;
+
+ reg = base->PMCTRL;
+ /* configure High Speed RUN mode */
+ reg &= ~SMC_PMCTRL_RUNM_MASK;
+ reg |= (kSMC_Hsrun << SMC_PMCTRL_RUNM_SHIFT);
+ base->PMCTRL = reg;
+
+ return kStatus_Success;
+}
+#endif /* FSL_FEATURE_SMC_HAS_HIGH_SPEED_RUN_MODE */
+
+status_t SMC_SetPowerModeWait(SMC_Type *base)
+{
+ /* configure Normal Wait mode */
+ SCB->SCR &= ~SCB_SCR_SLEEPDEEP_Msk;
+ __DSB();
+ __WFI();
+ __ISB();
+
+ return kStatus_Success;
+}
+
+status_t SMC_SetPowerModeStop(SMC_Type *base, smc_partial_stop_option_t option)
+{
+ uint8_t reg;
+
+#if (defined(FSL_FEATURE_SMC_HAS_PSTOPO) && FSL_FEATURE_SMC_HAS_PSTOPO)
+ /* configure the Partial Stop mode in Noraml Stop mode */
+ reg = base->STOPCTRL;
+ reg &= ~SMC_STOPCTRL_PSTOPO_MASK;
+ reg |= ((uint32_t)option << SMC_STOPCTRL_PSTOPO_SHIFT);
+ base->STOPCTRL = reg;
+#endif
+
+ /* configure Normal Stop mode */
+ reg = base->PMCTRL;
+ reg &= ~SMC_PMCTRL_STOPM_MASK;
+ reg |= (kSMC_StopNormal << SMC_PMCTRL_STOPM_SHIFT);
+ base->PMCTRL = reg;
+
+ /* Set the SLEEPDEEP bit to enable deep sleep mode (stop mode) */
+ SCB->SCR |= SCB_SCR_SLEEPDEEP_Msk;
+
+ /* read back to make sure the configuration valid before enter stop mode */
+ (void)base->PMCTRL;
+ __DSB();
+ __WFI();
+ __ISB();
+
+ /* check whether the power mode enter Stop mode succeed */
+ if (base->PMCTRL & SMC_PMCTRL_STOPA_MASK)
+ {
+ return kStatus_SMC_StopAbort;
+ }
+ else
+ {
+ return kStatus_Success;
+ }
+}
+
+status_t SMC_SetPowerModeVlpr(SMC_Type *base
+#if (defined(FSL_FEATURE_SMC_HAS_LPWUI) && FSL_FEATURE_SMC_HAS_LPWUI)
+ ,
+ bool wakeupMode
+#endif
+ )
+{
+ uint8_t reg;
+
+ reg = base->PMCTRL;
+#if (defined(FSL_FEATURE_SMC_HAS_LPWUI) && FSL_FEATURE_SMC_HAS_LPWUI)
+ /* configure whether the system remains in VLP mode on an interrupt */
+ if (wakeupMode)
+ {
+ /* exits to RUN mode on an interrupt */
+ reg |= SMC_PMCTRL_LPWUI_MASK;
+ }
+ else
+ {
+ /* remains in VLP mode on an interrupt */
+ reg &= ~SMC_PMCTRL_LPWUI_MASK;
+ }
+#endif /* FSL_FEATURE_SMC_HAS_LPWUI */
+
+ /* configure VLPR mode */
+ reg &= ~SMC_PMCTRL_RUNM_MASK;
+ reg |= (kSMC_RunVlpr << SMC_PMCTRL_RUNM_SHIFT);
+ base->PMCTRL = reg;
+
+ return kStatus_Success;
+}
+
+status_t SMC_SetPowerModeVlpw(SMC_Type *base)
+{
+ /* configure VLPW mode */
+ /* Set the SLEEPDEEP bit to enable deep sleep mode */
+ SCB->SCR &= ~SCB_SCR_SLEEPDEEP_Msk;
+ __DSB();
+ __WFI();
+ __ISB();
+
+ return kStatus_Success;
+}
+
+status_t SMC_SetPowerModeVlps(SMC_Type *base)
+{
+ uint8_t reg;
+
+ /* configure VLPS mode */
+ reg = base->PMCTRL;
+ reg &= ~SMC_PMCTRL_STOPM_MASK;
+ reg |= (kSMC_StopVlps << SMC_PMCTRL_STOPM_SHIFT);
+ base->PMCTRL = reg;
+
+ /* Set the SLEEPDEEP bit to enable deep sleep mode */
+ SCB->SCR |= SCB_SCR_SLEEPDEEP_Msk;
+
+ /* read back to make sure the configuration valid before enter stop mode */
+ (void)base->PMCTRL;
+ __DSB();
+ __WFI();
+ __ISB();
+
+ /* check whether the power mode enter VLPS mode succeed */
+ if (base->PMCTRL & SMC_PMCTRL_STOPA_MASK)
+ {
+ return kStatus_SMC_StopAbort;
+ }
+ else
+ {
+ return kStatus_Success;
+ }
+}
+
+#if (defined(FSL_FEATURE_SMC_HAS_LOW_LEAKAGE_STOP_MODE) && FSL_FEATURE_SMC_HAS_LOW_LEAKAGE_STOP_MODE)
+status_t SMC_SetPowerModeLls(SMC_Type *base
+#if ((defined(FSL_FEATURE_SMC_HAS_LLS_SUBMODE) && FSL_FEATURE_SMC_HAS_LLS_SUBMODE) || \
+ (defined(FSL_FEATURE_SMC_HAS_LPOPO) && FSL_FEATURE_SMC_HAS_LPOPO))
+ ,
+ const smc_power_mode_lls_config_t *config
+#endif
+ )
+{
+ uint8_t reg;
+
+ /* configure to LLS mode */
+ reg = base->PMCTRL;
+ reg &= ~SMC_PMCTRL_STOPM_MASK;
+ reg |= (kSMC_StopLls << SMC_PMCTRL_STOPM_SHIFT);
+ base->PMCTRL = reg;
+
+/* configure LLS sub-mode*/
+#if (defined(FSL_FEATURE_SMC_HAS_LLS_SUBMODE) && FSL_FEATURE_SMC_HAS_LLS_SUBMODE)
+ reg = base->STOPCTRL;
+ reg &= ~SMC_STOPCTRL_LLSM_MASK;
+ reg |= ((uint32_t)config->subMode << SMC_STOPCTRL_LLSM_SHIFT);
+ base->STOPCTRL = reg;
+#endif /* FSL_FEATURE_SMC_HAS_LLS_SUBMODE */
+
+#if (defined(FSL_FEATURE_SMC_HAS_LPOPO) && FSL_FEATURE_SMC_HAS_LPOPO)
+ if (config->enableLpoClock)
+ {
+ base->STOPCTRL &= ~SMC_STOPCTRL_LPOPO_MASK;
+ }
+ else
+ {
+ base->STOPCTRL |= SMC_STOPCTRL_LPOPO_MASK;
+ }
+#endif /* FSL_FEATURE_SMC_HAS_LPOPO */
+
+ /* Set the SLEEPDEEP bit to enable deep sleep mode */
+ SCB->SCR |= SCB_SCR_SLEEPDEEP_Msk;
+
+ /* read back to make sure the configuration valid before enter stop mode */
+ (void)base->PMCTRL;
+ __DSB();
+ __WFI();
+ __ISB();
+
+ /* check whether the power mode enter LLS mode succeed */
+ if (base->PMCTRL & SMC_PMCTRL_STOPA_MASK)
+ {
+ return kStatus_SMC_StopAbort;
+ }
+ else
+ {
+ return kStatus_Success;
+ }
+}
+#endif /* FSL_FEATURE_SMC_HAS_LOW_LEAKAGE_STOP_MODE */
+
+#if (defined(FSL_FEATURE_SMC_HAS_VERY_LOW_LEAKAGE_STOP_MODE) && FSL_FEATURE_SMC_HAS_VERY_LOW_LEAKAGE_STOP_MODE)
+status_t SMC_SetPowerModeVlls(SMC_Type *base, const smc_power_mode_vlls_config_t *config)
+{
+ uint8_t reg;
+
+#if (defined(FSL_FEATURE_SMC_HAS_PORPO) && FSL_FEATURE_SMC_HAS_PORPO)
+#if (defined(FSL_FEATURE_SMC_USE_VLLSCTRL_REG) && FSL_FEATURE_SMC_USE_VLLSCTRL_REG) || \
+ (defined(FSL_FEATURE_SMC_USE_STOPCTRL_VLLSM) && FSL_FEATURE_SMC_USE_STOPCTRL_VLLSM) || \
+ (defined(FSL_FEATURE_SMC_HAS_LLS_SUBMODE) && FSL_FEATURE_SMC_HAS_LLS_SUBMODE)
+ if (config->subMode == kSMC_StopSub0)
+#endif
+ {
+ /* configure whether the Por Detect work in Vlls0 mode */
+ if (config->enablePorDetectInVlls0)
+ {
+#if (defined(FSL_FEATURE_SMC_USE_VLLSCTRL_REG) && FSL_FEATURE_SMC_USE_VLLSCTRL_REG)
+ base->VLLSCTRL &= ~SMC_VLLSCTRL_PORPO_MASK;
+#else
+ base->STOPCTRL &= ~SMC_STOPCTRL_PORPO_MASK;
+#endif
+ }
+ else
+ {
+#if (defined(FSL_FEATURE_SMC_USE_VLLSCTRL_REG) && FSL_FEATURE_SMC_USE_VLLSCTRL_REG)
+ base->VLLSCTRL |= SMC_VLLSCTRL_PORPO_MASK;
+#else
+ base->STOPCTRL |= SMC_STOPCTRL_PORPO_MASK;
+#endif
+ }
+ }
+#endif /* FSL_FEATURE_SMC_HAS_PORPO */
+
+#if (defined(FSL_FEATURE_SMC_HAS_RAM2_POWER_OPTION) && FSL_FEATURE_SMC_HAS_RAM2_POWER_OPTION)
+ else if (config->subMode == kSMC_StopSub2)
+ {
+ /* configure whether the Por Detect work in Vlls0 mode */
+ if (config->enableRam2InVlls2)
+ {
+#if (defined(FSL_FEATURE_SMC_USE_VLLSCTRL_REG) && FSL_FEATURE_SMC_USE_VLLSCTRL_REG)
+ base->VLLSCTRL |= SMC_VLLSCTRL_RAM2PO_MASK;
+#else
+ base->STOPCTRL |= SMC_STOPCTRL_RAM2PO_MASK;
+#endif
+ }
+ else
+ {
+#if (defined(FSL_FEATURE_SMC_USE_VLLSCTRL_REG) && FSL_FEATURE_SMC_USE_VLLSCTRL_REG)
+ base->VLLSCTRL &= ~SMC_VLLSCTRL_RAM2PO_MASK;
+#else
+ base->STOPCTRL &= ~SMC_STOPCTRL_RAM2PO_MASK;
+#endif
+ }
+ }
+ else
+ {
+ }
+#endif /* FSL_FEATURE_SMC_HAS_RAM2_POWER_OPTION */
+
+ /* configure to VLLS mode */
+ reg = base->PMCTRL;
+ reg &= ~SMC_PMCTRL_STOPM_MASK;
+ reg |= (kSMC_StopVlls << SMC_PMCTRL_STOPM_SHIFT);
+ base->PMCTRL = reg;
+
+/* configure the VLLS sub-mode */
+#if (defined(FSL_FEATURE_SMC_USE_VLLSCTRL_REG) && FSL_FEATURE_SMC_USE_VLLSCTRL_REG)
+ reg = base->VLLSCTRL;
+ reg &= ~SMC_VLLSCTRL_VLLSM_MASK;
+ reg |= ((uint32_t)config->subMode << SMC_VLLSCTRL_VLLSM_SHIFT);
+ base->VLLSCTRL = reg;
+#else
+#if (defined(FSL_FEATURE_SMC_HAS_LLS_SUBMODE) && FSL_FEATURE_SMC_HAS_LLS_SUBMODE)
+ reg = base->STOPCTRL;
+ reg &= ~SMC_STOPCTRL_LLSM_MASK;
+ reg |= ((uint32_t)config->subMode << SMC_STOPCTRL_LLSM_SHIFT);
+ base->STOPCTRL = reg;
+#else
+ reg = base->STOPCTRL;
+ reg &= ~SMC_STOPCTRL_VLLSM_MASK;
+ reg |= ((uint32_t)config->subMode << SMC_STOPCTRL_VLLSM_SHIFT);
+ base->STOPCTRL = reg;
+#endif /* FSL_FEATURE_SMC_HAS_LLS_SUBMODE */
+#endif
+
+#if (defined(FSL_FEATURE_SMC_HAS_LPOPO) && FSL_FEATURE_SMC_HAS_LPOPO)
+ if (config->enableLpoClock)
+ {
+ base->STOPCTRL &= ~SMC_STOPCTRL_LPOPO_MASK;
+ }
+ else
+ {
+ base->STOPCTRL |= SMC_STOPCTRL_LPOPO_MASK;
+ }
+#endif /* FSL_FEATURE_SMC_HAS_LPOPO */
+
+ /* Set the SLEEPDEEP bit to enable deep sleep mode */
+ SCB->SCR |= SCB_SCR_SLEEPDEEP_Msk;
+
+ /* read back to make sure the configuration valid before enter stop mode */
+ (void)base->PMCTRL;
+ __DSB();
+ __WFI();
+ __ISB();
+
+ /* check whether the power mode enter LLS mode succeed */
+ if (base->PMCTRL & SMC_PMCTRL_STOPA_MASK)
+ {
+ return kStatus_SMC_StopAbort;
+ }
+ else
+ {
+ return kStatus_Success;
+ }
+}
+#endif /* FSL_FEATURE_SMC_HAS_VERY_LOW_LEAKAGE_STOP_MODE */
diff --git a/drivers/fsl_smc.h b/drivers/fsl_smc.h
new file mode 100644
index 0000000..4148734
--- /dev/null
+++ b/drivers/fsl_smc.h
@@ -0,0 +1,418 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_SMC_H_
+#define _FSL_SMC_H_
+
+#include "fsl_common.h"
+
+/*! @addtogroup smc */
+/*! @{ */
+
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+/*! @name Driver version */
+/*@{*/
+/*! @brief SMC driver version 2.0.2. */
+#define FSL_SMC_DRIVER_VERSION (MAKE_VERSION(2, 0, 2))
+/*@}*/
+
+/*!
+ * @brief Power Modes Protection
+ */
+typedef enum _smc_power_mode_protection
+{
+#if (defined(FSL_FEATURE_SMC_HAS_VERY_LOW_LEAKAGE_STOP_MODE) && FSL_FEATURE_SMC_HAS_VERY_LOW_LEAKAGE_STOP_MODE)
+ kSMC_AllowPowerModeVlls = SMC_PMPROT_AVLLS_MASK, /*!< Allow Very-Low-Leakage Stop Mode. */
+#endif
+#if (defined(FSL_FEATURE_SMC_HAS_LOW_LEAKAGE_STOP_MODE) && FSL_FEATURE_SMC_HAS_LOW_LEAKAGE_STOP_MODE)
+ kSMC_AllowPowerModeLls = SMC_PMPROT_ALLS_MASK, /*!< Allow Low-Leakage Stop Mode. */
+#endif /* FSL_FEATURE_SMC_HAS_LOW_LEAKAGE_STOP_MODE */
+ kSMC_AllowPowerModeVlp = SMC_PMPROT_AVLP_MASK, /*!< Allow Very-Low-Power Mode. */
+#if (defined(FSL_FEATURE_SMC_HAS_HIGH_SPEED_RUN_MODE) && FSL_FEATURE_SMC_HAS_HIGH_SPEED_RUN_MODE)
+ kSMC_AllowPowerModeHsrun = SMC_PMPROT_AHSRUN_MASK, /*!< Allow High Speed Run mode. */
+#endif /* FSL_FEATURE_SMC_HAS_HIGH_SPEED_RUN_MODE */
+ kSMC_AllowPowerModeAll = (0U
+#if (defined(FSL_FEATURE_SMC_HAS_VERY_LOW_LEAKAGE_STOP_MODE) && FSL_FEATURE_SMC_HAS_VERY_LOW_LEAKAGE_STOP_MODE)
+ |
+ SMC_PMPROT_AVLLS_MASK
+#endif
+#if (defined(FSL_FEATURE_SMC_HAS_LOW_LEAKAGE_STOP_MODE) && FSL_FEATURE_SMC_HAS_LOW_LEAKAGE_STOP_MODE)
+ |
+ SMC_PMPROT_ALLS_MASK
+#endif /* FSL_FEATURE_SMC_HAS_LOW_LEAKAGE_STOP_MODE */
+ |
+ SMC_PMPROT_AVLP_MASK
+#if (defined(FSL_FEATURE_SMC_HAS_HIGH_SPEED_RUN_MODE) && FSL_FEATURE_SMC_HAS_HIGH_SPEED_RUN_MODE)
+ |
+ kSMC_AllowPowerModeHsrun
+#endif /* FSL_FEATURE_SMC_HAS_HIGH_SPEED_RUN_MODE */
+ ) /*!< Allow all power mode. */
+} smc_power_mode_protection_t;
+
+/*!
+ * @brief Power Modes in PMSTAT
+ */
+typedef enum _smc_power_state
+{
+ kSMC_PowerStateRun = 0x01U << 0U, /*!< 0000_0001 - Current power mode is RUN */
+ kSMC_PowerStateStop = 0x01U << 1U, /*!< 0000_0010 - Current power mode is STOP */
+ kSMC_PowerStateVlpr = 0x01U << 2U, /*!< 0000_0100 - Current power mode is VLPR */
+ kSMC_PowerStateVlpw = 0x01U << 3U, /*!< 0000_1000 - Current power mode is VLPW */
+ kSMC_PowerStateVlps = 0x01U << 4U, /*!< 0001_0000 - Current power mode is VLPS */
+#if (defined(FSL_FEATURE_SMC_HAS_LOW_LEAKAGE_STOP_MODE) && FSL_FEATURE_SMC_HAS_LOW_LEAKAGE_STOP_MODE)
+ kSMC_PowerStateLls = 0x01U << 5U, /*!< 0010_0000 - Current power mode is LLS */
+#endif /* FSL_FEATURE_SMC_HAS_LOW_LEAKAGE_STOP_MODE */
+#if (defined(FSL_FEATURE_SMC_HAS_VERY_LOW_LEAKAGE_STOP_MODE) && FSL_FEATURE_SMC_HAS_VERY_LOW_LEAKAGE_STOP_MODE)
+ kSMC_PowerStateVlls = 0x01U << 6U, /*!< 0100_0000 - Current power mode is VLLS */
+#endif
+#if (defined(FSL_FEATURE_SMC_HAS_HIGH_SPEED_RUN_MODE) && FSL_FEATURE_SMC_HAS_HIGH_SPEED_RUN_MODE)
+ kSMC_PowerStateHsrun = 0x01U << 7U /*!< 1000_0000 - Current power mode is HSRUN */
+#endif /* FSL_FEATURE_SMC_HAS_HIGH_SPEED_RUN_MODE */
+} smc_power_state_t;
+
+/*!
+ * @brief Run mode definition
+ */
+typedef enum _smc_run_mode
+{
+ kSMC_RunNormal = 0U, /*!< normal RUN mode. */
+ kSMC_RunVlpr = 2U, /*!< Very-Low-Power RUN mode. */
+#if (defined(FSL_FEATURE_SMC_HAS_HIGH_SPEED_RUN_MODE) && FSL_FEATURE_SMC_HAS_HIGH_SPEED_RUN_MODE)
+ kSMC_Hsrun = 3U /*!< High Speed Run mode (HSRUN). */
+#endif /* FSL_FEATURE_SMC_HAS_HIGH_SPEED_RUN_MODE */
+} smc_run_mode_t;
+
+/*!
+ * @brief Stop mode definition
+ */
+typedef enum _smc_stop_mode
+{
+ kSMC_StopNormal = 0U, /*!< Normal STOP mode. */
+ kSMC_StopVlps = 2U, /*!< Very-Low-Power STOP mode. */
+#if (defined(FSL_FEATURE_SMC_HAS_LOW_LEAKAGE_STOP_MODE) && FSL_FEATURE_SMC_HAS_LOW_LEAKAGE_STOP_MODE)
+ kSMC_StopLls = 3U, /*!< Low-Leakage Stop mode. */
+#endif /* FSL_FEATURE_SMC_HAS_LOW_LEAKAGE_STOP_MODE */
+#if (defined(FSL_FEATURE_SMC_HAS_VERY_LOW_LEAKAGE_STOP_MODE) && FSL_FEATURE_SMC_HAS_VERY_LOW_LEAKAGE_STOP_MODE)
+ kSMC_StopVlls = 4U /*!< Very-Low-Leakage Stop mode. */
+#endif
+} smc_stop_mode_t;
+
+#if (defined(FSL_FEATURE_SMC_USE_VLLSCTRL_REG) && FSL_FEATURE_SMC_USE_VLLSCTRL_REG) || \
+ (defined(FSL_FEATURE_SMC_USE_STOPCTRL_VLLSM) && FSL_FEATURE_SMC_USE_STOPCTRL_VLLSM) || \
+ (defined(FSL_FEATURE_SMC_HAS_LLS_SUBMODE) && FSL_FEATURE_SMC_HAS_LLS_SUBMODE)
+/*!
+ * @brief VLLS/LLS stop sub mode definition
+ */
+typedef enum _smc_stop_submode
+{
+ kSMC_StopSub0 = 0U, /*!< Stop submode 0, for VLLS0/LLS0. */
+ kSMC_StopSub1 = 1U, /*!< Stop submode 1, for VLLS1/LLS1. */
+ kSMC_StopSub2 = 2U, /*!< Stop submode 2, for VLLS2/LLS2. */
+ kSMC_StopSub3 = 3U /*!< Stop submode 3, for VLLS3/LLS3. */
+} smc_stop_submode_t;
+#endif
+
+/*!
+ * @brief Partial STOP option
+ */
+typedef enum _smc_partial_stop_mode
+{
+ kSMC_PartialStop = 0U, /*!< STOP - Normal Stop mode*/
+ kSMC_PartialStop1 = 1U, /*!< Partial Stop with both system and bus clocks disabled*/
+ kSMC_PartialStop2 = 2U, /*!< Partial Stop with system clock disabled and bus clock enabled*/
+} smc_partial_stop_option_t;
+
+/*!
+ * @brief SMC configuration status
+ */
+enum _smc_status
+{
+ kStatus_SMC_StopAbort = MAKE_STATUS(kStatusGroup_POWER, 0) /*!< Entering Stop mode is abort*/
+};
+
+#if (defined(FSL_FEATURE_SMC_HAS_VERID) && FSL_FEATURE_SMC_HAS_VERID)
+/*!
+ * @brief IP version ID definition.
+ */
+typedef struct _smc_version_id
+{
+ uint16_t feature; /*!< Feature Specification Number. */
+ uint8_t minor; /*!< Minor version number. */
+ uint8_t major; /*!< Major version number. */
+} smc_version_id_t;
+#endif /* FSL_FEATURE_SMC_HAS_VERID */
+
+#if (defined(FSL_FEATURE_SMC_HAS_PARAM) && FSL_FEATURE_SMC_HAS_PARAM)
+/*!
+ * @brief IP parameter definition.
+ */
+typedef struct _smc_param
+{
+ bool hsrunEnable; /*!< HSRUN mode enable. */
+ bool llsEnable; /*!< LLS mode enable. */
+ bool lls2Enable; /*!< LLS2 mode enable. */
+ bool vlls0Enable; /*!< VLLS0 mode enable. */
+} smc_param_t;
+#endif /* FSL_FEATURE_SMC_HAS_PARAM */
+
+#if (defined(FSL_FEATURE_SMC_HAS_LLS_SUBMODE) && FSL_FEATURE_SMC_HAS_LLS_SUBMODE) || \
+ (defined(FSL_FEATURE_SMC_HAS_LPOPO) && FSL_FEATURE_SMC_HAS_LPOPO)
+/*!
+ * @brief SMC Low-Leakage Stop power mode config
+ */
+typedef struct _smc_power_mode_lls_config
+{
+#if (defined(FSL_FEATURE_SMC_HAS_LLS_SUBMODE) && FSL_FEATURE_SMC_HAS_LLS_SUBMODE)
+ smc_stop_submode_t subMode; /*!< Low-leakage Stop sub-mode */
+#endif
+#if (defined(FSL_FEATURE_SMC_HAS_LPOPO) && FSL_FEATURE_SMC_HAS_LPOPO)
+ bool enableLpoClock; /*!< Enable LPO clock in LLS mode */
+#endif
+} smc_power_mode_lls_config_t;
+#endif /* (FSL_FEATURE_SMC_HAS_LLS_SUBMODE || FSL_FEATURE_SMC_HAS_LPOPO) */
+
+#if (defined(FSL_FEATURE_SMC_HAS_VERY_LOW_LEAKAGE_STOP_MODE) && FSL_FEATURE_SMC_HAS_VERY_LOW_LEAKAGE_STOP_MODE)
+/*!
+ * @brief SMC Very Low-Leakage Stop power mode config
+ */
+typedef struct _smc_power_mode_vlls_config
+{
+#if (defined(FSL_FEATURE_SMC_USE_VLLSCTRL_REG) && FSL_FEATURE_SMC_USE_VLLSCTRL_REG) || \
+ (defined(FSL_FEATURE_SMC_USE_STOPCTRL_VLLSM) && FSL_FEATURE_SMC_USE_STOPCTRL_VLLSM) || \
+ (defined(FSL_FEATURE_SMC_HAS_LLS_SUBMODE) && FSL_FEATURE_SMC_HAS_LLS_SUBMODE)
+ smc_stop_submode_t subMode; /*!< Very Low-leakage Stop sub-mode */
+#endif
+#if (defined(FSL_FEATURE_SMC_HAS_PORPO) && FSL_FEATURE_SMC_HAS_PORPO)
+ bool enablePorDetectInVlls0; /*!< Enable Power on reset detect in VLLS mode */
+#endif
+#if (defined(FSL_FEATURE_SMC_HAS_RAM2_POWER_OPTION) && FSL_FEATURE_SMC_HAS_RAM2_POWER_OPTION)
+ bool enableRam2InVlls2; /*!< Enable RAM2 power in VLLS2 */
+#endif
+#if (defined(FSL_FEATURE_SMC_HAS_LPOPO) && FSL_FEATURE_SMC_HAS_LPOPO)
+ bool enableLpoClock; /*!< Enable LPO clock in VLLS mode */
+#endif
+} smc_power_mode_vlls_config_t;
+#endif
+
+/*******************************************************************************
+ * API
+ ******************************************************************************/
+
+#if defined(__cplusplus)
+extern "C" {
+#endif /* __cplusplus */
+
+/*! @name System mode controller APIs*/
+/*@{*/
+
+#if (defined(FSL_FEATURE_SMC_HAS_VERID) && FSL_FEATURE_SMC_HAS_VERID)
+/*!
+ * @brief Gets the SMC version ID.
+ *
+ * This function gets the SMC version ID, including major version number,
+ * minor version number and feature specification number.
+ *
+ * @param base SMC peripheral base address.
+ * @param versionId Pointer to version ID structure.
+ */
+static inline void SMC_GetVersionId(SMC_Type *base, smc_version_id_t *versionId)
+{
+ *((uint32_t *)versionId) = base->VERID;
+}
+#endif /* FSL_FEATURE_SMC_HAS_VERID */
+
+#if (defined(FSL_FEATURE_SMC_HAS_PARAM) && FSL_FEATURE_SMC_HAS_PARAM)
+/*!
+ * @brief Gets the SMC parameter.
+ *
+ * This function gets the SMC parameter, including the enabled power mdoes.
+ *
+ * @param base SMC peripheral base address.
+ * @param param Pointer to SMC param structure.
+ */
+void SMC_GetParam(SMC_Type *base, smc_param_t *param);
+#endif
+
+/*!
+ * @brief Configures all power mode protection settings.
+ *
+ * This function configures the power mode protection settings for
+ * supported power modes in the specified chip family. The available power modes
+ * are defined in the smc_power_mode_protection_t. This should be done at an early
+ * system level initialization stage. See the reference manual for details.
+ * This register can only write once after the power reset.
+ *
+ * The allowed modes are passed as bit map, for example, to allow LLS and VLLS,
+ * use SMC_SetPowerModeProtection(kSMC_AllowPowerModeVlls | kSMC_AllowPowerModeVlps).
+ * To allow all modes, use SMC_SetPowerModeProtection(kSMC_AllowPowerModeAll).
+ *
+ * @param base SMC peripheral base address.
+ * @param allowedModes Bitmap of the allowed power modes.
+ */
+static inline void SMC_SetPowerModeProtection(SMC_Type *base, uint8_t allowedModes)
+{
+ base->PMPROT = allowedModes;
+}
+
+/*!
+ * @brief Gets the current power mode status.
+ *
+ * This function returns the current power mode stat. Once application
+ * switches the power mode, it should always check the stat to check whether it
+ * runs into the specified mode or not. An application should check
+ * this mode before switching to a different mode. The system requires that
+ * only certain modes can switch to other specific modes. See the
+ * reference manual for details and the smc_power_state_t for information about
+ * the power stat.
+ *
+ * @param base SMC peripheral base address.
+ * @return Current power mode status.
+ */
+static inline smc_power_state_t SMC_GetPowerModeState(SMC_Type *base)
+{
+ return (smc_power_state_t)base->PMSTAT;
+}
+
+/*!
+ * @brief Configure the system to RUN power mode.
+ *
+ * @param base SMC peripheral base address.
+ * @return SMC configuration error code.
+ */
+status_t SMC_SetPowerModeRun(SMC_Type *base);
+
+#if (defined(FSL_FEATURE_SMC_HAS_HIGH_SPEED_RUN_MODE) && FSL_FEATURE_SMC_HAS_HIGH_SPEED_RUN_MODE)
+/*!
+ * @brief Configure the system to HSRUN power mode.
+ *
+ * @param base SMC peripheral base address.
+ * @return SMC configuration error code.
+ */
+status_t SMC_SetPowerModeHsrun(SMC_Type *base);
+#endif /* FSL_FEATURE_SMC_HAS_HIGH_SPEED_RUN_MODE */
+
+/*!
+ * @brief Configure the system to WAIT power mode.
+ *
+ * @param base SMC peripheral base address.
+ * @return SMC configuration error code.
+ */
+status_t SMC_SetPowerModeWait(SMC_Type *base);
+
+/*!
+ * @brief Configure the system to Stop power mode.
+ *
+ * @param base SMC peripheral base address.
+ * @param option Partial Stop mode option.
+ * @return SMC configuration error code.
+ */
+status_t SMC_SetPowerModeStop(SMC_Type *base, smc_partial_stop_option_t option);
+
+#if (defined(FSL_FEATURE_SMC_HAS_LPWUI) && FSL_FEATURE_SMC_HAS_LPWUI)
+/*!
+ * @brief Configure the system to VLPR power mode.
+ *
+ * @param base SMC peripheral base address.
+ * @param wakeupMode Enter Normal Run mode if true, else stay in VLPR mode.
+ * @return SMC configuration error code.
+ */
+status_t SMC_SetPowerModeVlpr(SMC_Type *base, bool wakeupMode);
+#else
+/*!
+ * @brief Configure the system to VLPR power mode.
+ *
+ * @param base SMC peripheral base address.
+ * @return SMC configuration error code.
+ */
+status_t SMC_SetPowerModeVlpr(SMC_Type *base);
+#endif /* FSL_FEATURE_SMC_HAS_LPWUI */
+
+/*!
+ * @brief Configure the system to VLPW power mode.
+ *
+ * @param base SMC peripheral base address.
+ * @return SMC configuration error code.
+ */
+status_t SMC_SetPowerModeVlpw(SMC_Type *base);
+
+/*!
+ * @brief Configure the system to VLPS power mode.
+ *
+ * @param base SMC peripheral base address.
+ * @return SMC configuration error code.
+ */
+status_t SMC_SetPowerModeVlps(SMC_Type *base);
+
+#if (defined(FSL_FEATURE_SMC_HAS_LOW_LEAKAGE_STOP_MODE) && FSL_FEATURE_SMC_HAS_LOW_LEAKAGE_STOP_MODE)
+#if ((defined(FSL_FEATURE_SMC_HAS_LLS_SUBMODE) && FSL_FEATURE_SMC_HAS_LLS_SUBMODE) || \
+ (defined(FSL_FEATURE_SMC_HAS_LPOPO) && FSL_FEATURE_SMC_HAS_LPOPO))
+/*!
+ * @brief Configure the system to LLS power mode.
+ *
+ * @param base SMC peripheral base address.
+ * @param config The LLS power mode configuration structure
+ * @return SMC configuration error code.
+ */
+status_t SMC_SetPowerModeLls(SMC_Type *base, const smc_power_mode_lls_config_t *config);
+#else
+/*!
+ * @brief Configure the system to LLS power mode.
+ *
+ * @param base SMC peripheral base address.
+ * @return SMC configuration error code.
+ */
+status_t SMC_SetPowerModeLls(SMC_Type *base);
+#endif
+#endif /* FSL_FEATURE_SMC_HAS_LOW_LEAKAGE_STOP_MODE */
+
+#if (defined(FSL_FEATURE_SMC_HAS_VERY_LOW_LEAKAGE_STOP_MODE) && FSL_FEATURE_SMC_HAS_VERY_LOW_LEAKAGE_STOP_MODE)
+/*!
+ * @brief Configure the system to VLLS power mode.
+ *
+ * @param base SMC peripheral base address.
+ * @param config The VLLS power mode configuration structure.
+ * @return SMC configuration error code.
+ */
+status_t SMC_SetPowerModeVlls(SMC_Type *base, const smc_power_mode_vlls_config_t *config);
+#endif /* FSL_FEATURE_SMC_HAS_VERY_LOW_LEAKAGE_STOP_MODE */
+
+/*@}*/
+
+#if defined(__cplusplus)
+}
+#endif /* __cplusplus */
+
+/*! @}*/
+
+#endif /* _FSL_SMC_H_ */
diff --git a/drivers/fsl_tsi_v2.c b/drivers/fsl_tsi_v2.c
new file mode 100644
index 0000000..0464eb2
--- /dev/null
+++ b/drivers/fsl_tsi_v2.c
@@ -0,0 +1,211 @@
+/*
+ * Copyright (c) 2014 - 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_tsi_v2.h"
+
+void TSI_Init(TSI_Type *base, const tsi_config_t *config)
+{
+ assert(config != NULL);
+
+ bool is_module_enabled = false;
+ bool is_int_enabled = false;
+
+ CLOCK_EnableClock(kCLOCK_Tsi0);
+ if (base->GENCS & TSI_GENCS_TSIEN_MASK)
+ {
+ is_module_enabled = true;
+ TSI_EnableModule(base, false); /* Disable module */
+ }
+ if (base->GENCS & TSI_GENCS_TSIIE_MASK)
+ {
+ is_int_enabled = true;
+ TSI_DisableInterrupts(base, kTSI_GlobalInterruptEnable);
+ }
+
+ TSI_SetHighThreshold(base, config->thresh);
+ TSI_SetLowThreshold(base, config->thresl);
+ TSI_SetLowPowerClock(base, config->lpclks);
+ TSI_SetLowPowerScanInterval(base, config->lpscnitv);
+ TSI_SetActiveModeSource(base, config->amclks);
+ TSI_SetActiveModePrescaler(base, config->ampsc);
+ TSI_SetElectrodeOSCPrescaler(base, config->ps);
+ TSI_SetElectrodeChargeCurrent(base, config->extchrg);
+ TSI_SetReferenceChargeCurrent(base, config->refchrg);
+ TSI_SetNumberOfScans(base, config->nscn);
+
+ if (is_module_enabled)
+ {
+ TSI_EnableModule(base, true);
+ }
+ if (is_int_enabled)
+ {
+ TSI_EnableInterrupts(base, kTSI_GlobalInterruptEnable);
+ }
+}
+
+void TSI_Deinit(TSI_Type *base)
+{
+ base->GENCS = 0U;
+ base->SCANC = 0U;
+ base->PEN = 0U;
+ base->THRESHOLD = 0U;
+ CLOCK_DisableClock(kCLOCK_Tsi0);
+}
+
+void TSI_GetNormalModeDefaultConfig(tsi_config_t *userConfig)
+{
+ userConfig->thresh = 0U;
+ userConfig->thresl = 0U;
+ userConfig->lpclks = kTSI_LowPowerClockSource_LPOCLK;
+ userConfig->lpscnitv = kTSI_LowPowerInterval_100ms;
+ userConfig->amclks = kTSI_ActiveClkSource_LPOSCCLK;
+ userConfig->ampsc = kTSI_ActiveModePrescaler_8div;
+ userConfig->ps = kTSI_ElecOscPrescaler_2div;
+ userConfig->extchrg = kTSI_ExtOscChargeCurrent_10uA;
+ userConfig->refchrg = kTSI_RefOscChargeCurrent_10uA;
+ userConfig->nscn = kTSI_ConsecutiveScansNumber_8time;
+}
+
+void TSI_GetLowPowerModeDefaultConfig(tsi_config_t *userConfig)
+{
+ userConfig->thresh = 15000U;
+ userConfig->thresl = 1000U;
+ userConfig->lpclks = kTSI_LowPowerClockSource_LPOCLK;
+ userConfig->lpscnitv = kTSI_LowPowerInterval_100ms;
+ userConfig->amclks = kTSI_ActiveClkSource_LPOSCCLK;
+ userConfig->ampsc = kTSI_ActiveModePrescaler_64div;
+ userConfig->ps = kTSI_ElecOscPrescaler_1div;
+ userConfig->extchrg = kTSI_ExtOscChargeCurrent_2uA;
+ userConfig->refchrg = kTSI_RefOscChargeCurrent_32uA;
+ userConfig->nscn = kTSI_ConsecutiveScansNumber_26time;
+}
+
+void TSI_Calibrate(TSI_Type *base, tsi_calibration_data_t *calBuff)
+{
+ assert(calBuff != NULL);
+
+ uint8_t i = 0U;
+ bool is_int_enabled = false;
+
+ if (base->GENCS & TSI_GENCS_TSIIE_MASK)
+ {
+ is_int_enabled = true;
+ TSI_DisableInterrupts(base, kTSI_GlobalInterruptEnable);
+ }
+
+ TSI_EnableChannels(base, 0xFFFFU, true);
+ TSI_StartSoftwareTrigger(base);
+ while (!(TSI_GetStatusFlags(base) & kTSI_EndOfScanFlag))
+ {
+ }
+
+ for (i = 0U; i < FSL_FEATURE_TSI_CHANNEL_COUNT; i++)
+ {
+ calBuff->calibratedData[i] = TSI_GetNormalModeCounter(base, i);
+ }
+ TSI_ClearStatusFlags(base, kTSI_EndOfScanFlag);
+ TSI_EnableChannels(base, 0xFFFFU, false);
+
+ if (is_int_enabled)
+ {
+ TSI_EnableInterrupts(base, kTSI_GlobalInterruptEnable);
+ }
+}
+
+void TSI_EnableInterrupts(TSI_Type *base, uint32_t mask)
+{
+ uint32_t regValue = base->GENCS & (~ALL_FLAGS_MASK);
+
+ if (mask & kTSI_GlobalInterruptEnable)
+ {
+ regValue |= TSI_GENCS_TSIIE_MASK;
+ }
+ if (mask & kTSI_OutOfRangeInterruptEnable)
+ {
+ regValue &= (~TSI_GENCS_ESOR_MASK);
+ }
+ if (mask & kTSI_EndOfScanInterruptEnable)
+ {
+ regValue |= TSI_GENCS_ESOR_MASK;
+ }
+ if (mask & kTSI_ErrorInterrruptEnable)
+ {
+ regValue |= TSI_GENCS_ERIE_MASK;
+ }
+
+ base->GENCS = regValue; /* write value to register */
+}
+
+void TSI_DisableInterrupts(TSI_Type *base, uint32_t mask)
+{
+ uint32_t regValue = base->GENCS & (~ALL_FLAGS_MASK);
+
+ if (mask & kTSI_GlobalInterruptEnable)
+ {
+ regValue &= (~TSI_GENCS_TSIIE_MASK);
+ }
+ if (mask & kTSI_OutOfRangeInterruptEnable)
+ {
+ regValue |= TSI_GENCS_ESOR_MASK;
+ }
+ if (mask & kTSI_EndOfScanInterruptEnable)
+ {
+ regValue &= (~TSI_GENCS_ESOR_MASK);
+ }
+ if (mask & kTSI_ErrorInterrruptEnable)
+ {
+ regValue &= (~TSI_GENCS_ERIE_MASK);
+ }
+
+ base->GENCS = regValue; /* write value to register */
+}
+
+void TSI_ClearStatusFlags(TSI_Type *base, uint32_t mask)
+{
+ uint32_t regValue = base->GENCS & (~ALL_FLAGS_MASK);
+
+ if (mask & kTSI_EndOfScanFlag)
+ {
+ regValue |= TSI_GENCS_EOSF_MASK;
+ }
+ if (mask & kTSI_OutOfRangeFlag)
+ {
+ regValue |= TSI_GENCS_OUTRGF_MASK;
+ }
+ if (mask & kTSI_ExternalElectrodeErrorFlag)
+ {
+ regValue |= TSI_GENCS_EXTERF_MASK;
+ }
+ if (mask & kTSI_OverrunErrorFlag)
+ {
+ regValue |= TSI_GENCS_OVRF_MASK;
+ }
+
+ base->GENCS = regValue; /* write value to register */
+}
diff --git a/drivers/fsl_tsi_v2.h b/drivers/fsl_tsi_v2.h
new file mode 100644
index 0000000..ee0d590
--- /dev/null
+++ b/drivers/fsl_tsi_v2.h
@@ -0,0 +1,777 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_TSI_V2_H_
+#define _FSL_TSI_V2_H_
+
+#include "fsl_common.h"
+
+/*!
+ * @addtogroup tsi_v2_driver
+ * @{
+ */
+
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+/*! @name Driver version */
+/*@{*/
+/*! @brief TSI driver version */
+#define FSL_TSI_DRIVER_VERSION (MAKE_VERSION(2, 1, 2))
+/*@}*/
+
+/*! @brief TSI status flags macro collection */
+#define ALL_FLAGS_MASK (TSI_GENCS_EOSF_MASK |\
+ TSI_GENCS_OUTRGF_MASK |\
+ TSI_GENCS_EXTERF_MASK |\
+ TSI_GENCS_OVRF_MASK)
+
+
+/*!
+ * @brief TSI number of scan intervals for each electrode.
+ *
+ * These constants define the TSI number of consecutive scans in a TSI instance for each electrode.
+ */
+typedef enum _tsi_n_consecutive_scans
+{
+ kTSI_ConsecutiveScansNumber_1time = 0U, /*!< Once per electrode */
+ kTSI_ConsecutiveScansNumber_2time = 1U, /*!< Twice per electrode */
+ kTSI_ConsecutiveScansNumber_3time = 2U, /*!< 3 times consecutive scan */
+ kTSI_ConsecutiveScansNumber_4time = 3U, /*!< 4 times consecutive scan */
+ kTSI_ConsecutiveScansNumber_5time = 4U, /*!< 5 times consecutive scan */
+ kTSI_ConsecutiveScansNumber_6time = 5U, /*!< 6 times consecutive scan */
+ kTSI_ConsecutiveScansNumber_7time = 6U, /*!< 7 times consecutive scan */
+ kTSI_ConsecutiveScansNumber_8time = 7U, /*!< 8 times consecutive scan */
+ kTSI_ConsecutiveScansNumber_9time = 8U, /*!< 9 times consecutive scan */
+ kTSI_ConsecutiveScansNumber_10time = 9U, /*!< 10 times consecutive scan */
+ kTSI_ConsecutiveScansNumber_11time = 10U, /*!< 11 times consecutive scan */
+ kTSI_ConsecutiveScansNumber_12time = 11U, /*!< 12 times consecutive scan */
+ kTSI_ConsecutiveScansNumber_13time = 12U, /*!< 13 times consecutive scan */
+ kTSI_ConsecutiveScansNumber_14time = 13U, /*!< 14 times consecutive scan */
+ kTSI_ConsecutiveScansNumber_15time = 14U, /*!< 15 times consecutive scan */
+ kTSI_ConsecutiveScansNumber_16time = 15U, /*!< 16 times consecutive scan */
+ kTSI_ConsecutiveScansNumber_17time = 16U, /*!< 17 times consecutive scan */
+ kTSI_ConsecutiveScansNumber_18time = 17U, /*!< 18 times consecutive scan */
+ kTSI_ConsecutiveScansNumber_19time = 18U, /*!< 19 times consecutive scan */
+ kTSI_ConsecutiveScansNumber_20time = 19U, /*!< 20 times consecutive scan */
+ kTSI_ConsecutiveScansNumber_21time = 20U, /*!< 21 times consecutive scan */
+ kTSI_ConsecutiveScansNumber_22time = 21U, /*!< 22 times consecutive scan */
+ kTSI_ConsecutiveScansNumber_23time = 22U, /*!< 23 times consecutive scan */
+ kTSI_ConsecutiveScansNumber_24time = 23U, /*!< 24 times consecutive scan */
+ kTSI_ConsecutiveScansNumber_25time = 24U, /*!< 25 times consecutive scan */
+ kTSI_ConsecutiveScansNumber_26time = 25U, /*!< 26 times consecutive scan */
+ kTSI_ConsecutiveScansNumber_27time = 26U, /*!< 27 times consecutive scan */
+ kTSI_ConsecutiveScansNumber_28time = 27U, /*!< 28 times consecutive scan */
+ kTSI_ConsecutiveScansNumber_29time = 28U, /*!< 29 times consecutive scan */
+ kTSI_ConsecutiveScansNumber_30time = 29U, /*!< 30 times consecutive scan */
+ kTSI_ConsecutiveScansNumber_31time = 30U, /*!< 31 times consecutive scan */
+ kTSI_ConsecutiveScansNumber_32time = 31U /*!< 32 times consecutive scan */
+} tsi_n_consecutive_scans_t;
+
+/*!
+ * @brief TSI electrode oscillator prescaler.
+ *
+ * These constants define the TSI electrode oscillator prescaler in a TSI instance.
+ */
+typedef enum _tsi_electrode_osc_prescaler
+{
+ kTSI_ElecOscPrescaler_1div = 0U, /*!< Electrode oscillator frequency divided by 1 */
+ kTSI_ElecOscPrescaler_2div = 1U, /*!< Electrode oscillator frequency divided by 2 */
+ kTSI_ElecOscPrescaler_4div = 2U, /*!< Electrode oscillator frequency divided by 4 */
+ kTSI_ElecOscPrescaler_8div = 3U, /*!< Electrode oscillator frequency divided by 8 */
+ kTSI_ElecOscPrescaler_16div = 4U, /*!< Electrode oscillator frequency divided by 16 */
+ kTSI_ElecOscPrescaler_32div = 5U, /*!< Electrode oscillator frequency divided by 32 */
+ kTSI_ElecOscPrescaler_64div = 6U, /*!< Electrode oscillator frequency divided by 64 */
+ kTSI_ElecOscPrescaler_128div = 7U /*!< Electrode oscillator frequency divided by 128 */
+} tsi_electrode_osc_prescaler_t;
+
+/*!
+ * @brief TSI low power mode clock source.
+ */
+typedef enum _tsi_low_power_clock_source
+{
+ kTSI_LowPowerClockSource_LPOCLK = 0U, /*!< LPOCLK is selected */
+ kTSI_LowPowerClockSource_VLPOSCCLK = 1U /*!< VLPOSCCLK is selected */
+} tsi_low_power_clock_source_t;
+
+/*!
+ * @brief TSI low power scan intervals.
+ *
+ * These constants define the TSI low power scan intervals in a TSI instance.
+ */
+typedef enum _tsi_low_power_scan_interval
+{
+ kTSI_LowPowerInterval_1ms = 0U, /*!< 1 ms scan interval */
+ kTSI_LowPowerInterval_5ms = 1U, /*!< 5 ms scan interval */
+ kTSI_LowPowerInterval_10ms = 2U, /*!< 10 ms scan interval */
+ kTSI_LowPowerInterval_15ms = 3U, /*!< 15 ms scan interval */
+ kTSI_LowPowerInterval_20ms = 4U, /*!< 20 ms scan interval */
+ kTSI_LowPowerInterval_30ms = 5U, /*!< 30 ms scan interval */
+ kTSI_LowPowerInterval_40ms = 6U, /*!< 40 ms scan interval */
+ kTSI_LowPowerInterval_50ms = 7U, /*!< 50 ms scan interval */
+ kTSI_LowPowerInterval_75ms = 8U, /*!< 75 ms scan interval */
+ kTSI_LowPowerInterval_100ms = 9U, /*!< 100 ms scan interval */
+ kTSI_LowPowerInterval_125ms = 10U, /*!< 125 ms scan interval */
+ kTSI_LowPowerInterval_150ms = 11U, /*!< 150 ms scan interval */
+ kTSI_LowPowerInterval_200ms = 12U, /*!< 200 ms scan interval */
+ kTSI_LowPowerInterval_300ms = 13U, /*!< 300 ms scan interval */
+ kTSI_LowPowerInterval_400ms = 14U, /*!< 400 ms scan interval */
+ kTSI_LowPowerInterval_500ms = 15U /*!< 500 ms scan interval */
+} tsi_low_power_scan_interval_t;
+
+/*!
+ * @brief TSI Reference oscillator charge current select.
+ *
+ * These constants define the TSI Reference oscillator charge current select in a TSI instance.
+ */
+typedef enum _tsi_reference_osc_charge_current
+{
+ kTSI_RefOscChargeCurrent_2uA = 0U, /*!< Reference oscillator charge current is 2 µA */
+ kTSI_RefOscChargeCurrent_4uA = 1U, /*!< Reference oscillator charge current is 4 µA */
+ kTSI_RefOscChargeCurrent_6uA = 2U, /*!< Reference oscillator charge current is 6 µA */
+ kTSI_RefOscChargeCurrent_8uA = 3U, /*!< Reference oscillator charge current is 8 µA */
+ kTSI_RefOscChargeCurrent_10uA = 4U, /*!< Reference oscillator charge current is 10 µA */
+ kTSI_RefOscChargeCurrent_12uA = 5U, /*!< Reference oscillator charge current is 12 µA */
+ kTSI_RefOscChargeCurrent_14uA = 6U, /*!< Reference oscillator charge current is 14 µA */
+ kTSI_RefOscChargeCurrent_16uA = 7U, /*!< Reference oscillator charge current is 16 µA */
+ kTSI_RefOscChargeCurrent_18uA = 8U, /*!< Reference oscillator charge current is 18 µA */
+ kTSI_RefOscChargeCurrent_20uA = 9U, /*!< Reference oscillator charge current is 20 µA */
+ kTSI_RefOscChargeCurrent_22uA = 10U, /*!< Reference oscillator charge current is 22 µA */
+ kTSI_RefOscChargeCurrent_24uA = 11U, /*!< Reference oscillator charge current is 24 µA */
+ kTSI_RefOscChargeCurrent_26uA = 12U, /*!< Reference oscillator charge current is 26 µA */
+ kTSI_RefOscChargeCurrent_28uA = 13U, /*!< Reference oscillator charge current is 28 µA */
+ kTSI_RefOscChargeCurrent_30uA = 14U, /*!< Reference oscillator charge current is 30 µA */
+ kTSI_RefOscChargeCurrent_32uA = 15U /*!< Reference oscillator charge current is 32 µA */
+} tsi_reference_osc_charge_current_t;
+
+/*!
+ * @brief TSI External oscillator charge current select.
+ *
+ * These constants define the TSI External oscillator charge current select in a TSI instance.
+ */
+typedef enum _tsi_external_osc_charge_current
+{
+ kTSI_ExtOscChargeCurrent_2uA = 0U, /*!< External oscillator charge current is 2 µA */
+ kTSI_ExtOscChargeCurrent_4uA = 1U, /*!< External oscillator charge current is 4 µA */
+ kTSI_ExtOscChargeCurrent_6uA = 2U, /*!< External oscillator charge current is 6 µA */
+ kTSI_ExtOscChargeCurrent_8uA = 3U, /*!< External oscillator charge current is 8 µA */
+ kTSI_ExtOscChargeCurrent_10uA = 4U, /*!< External oscillator charge current is 10 µA */
+ kTSI_ExtOscChargeCurrent_12uA = 5U, /*!< External oscillator charge current is 12 µA */
+ kTSI_ExtOscChargeCurrent_14uA = 6U, /*!< External oscillator charge current is 14 µA */
+ kTSI_ExtOscChargeCurrent_16uA = 7U, /*!< External oscillator charge current is 16 µA */
+ kTSI_ExtOscChargeCurrent_18uA = 8U, /*!< External oscillator charge current is 18 µA */
+ kTSI_ExtOscChargeCurrent_20uA = 9U, /*!< External oscillator charge current is 20 µA */
+ kTSI_ExtOscChargeCurrent_22uA = 10U, /*!< External oscillator charge current is 22 µA */
+ kTSI_ExtOscChargeCurrent_24uA = 11U, /*!< External oscillator charge current is 24 µA */
+ kTSI_ExtOscChargeCurrent_26uA = 12U, /*!< External oscillator charge current is 26 µA */
+ kTSI_ExtOscChargeCurrent_28uA = 13U, /*!< External oscillator charge current is 28 µA */
+ kTSI_ExtOscChargeCurrent_30uA = 14U, /*!< External oscillator charge current is 30 µA */
+ kTSI_ExtOscChargeCurrent_32uA = 15U /*!< External oscillator charge current is 32 µA */
+} tsi_external_osc_charge_current_t;
+
+/*!
+ * @brief TSI Active mode clock source.
+ *
+ * These constants define the active mode clock source in a TSI instance.
+ */
+typedef enum _tsi_active_mode_clock_source
+{
+ kTSI_ActiveClkSource_LPOSCCLK = 0U, /*!< Active mode clock source is set to LPOOSC Clock */
+ kTSI_ActiveClkSource_MCGIRCLK = 1U, /*!< Active mode clock source is set to MCG Internal reference clock */
+ kTSI_ActiveClkSource_OSCERCLK = 2U /*!< Active mode clock source is set to System oscillator output */
+} tsi_active_mode_clock_source_t;
+
+/*!
+ * @brief TSI active mode prescaler.
+ *
+ * These constants define the TSI active mode prescaler in a TSI instance.
+ */
+typedef enum _tsi_active_mode_prescaler
+{
+ kTSI_ActiveModePrescaler_1div = 0U, /*!< Input clock source divided by 1 */
+ kTSI_ActiveModePrescaler_2div = 1U, /*!< Input clock source divided by 2 */
+ kTSI_ActiveModePrescaler_4div = 2U, /*!< Input clock source divided by 4 */
+ kTSI_ActiveModePrescaler_8div = 3U, /*!< Input clock source divided by 8 */
+ kTSI_ActiveModePrescaler_16div = 4U, /*!< Input clock source divided by 16 */
+ kTSI_ActiveModePrescaler_32div = 5U, /*!< Input clock source divided by 32 */
+ kTSI_ActiveModePrescaler_64div = 6U, /*!< Input clock source divided by 64 */
+ kTSI_ActiveModePrescaler_128div = 7U /*!< Input clock source divided by 128 */
+} tsi_active_mode_prescaler_t;
+
+/*! @brief TSI status flags. */
+typedef enum _tsi_status_flags
+{
+ kTSI_EndOfScanFlag = TSI_GENCS_EOSF_MASK, /*!< End-Of-Scan flag */
+ kTSI_OutOfRangeFlag = TSI_GENCS_OUTRGF_MASK, /*!< Out-Of-Range flag */
+ kTSI_ExternalElectrodeErrorFlag = TSI_GENCS_EXTERF_MASK, /*!< External electrode error flag */
+ kTSI_OverrunErrorFlag = TSI_GENCS_OVRF_MASK /*!< Overrun error flag */
+} tsi_status_flags_t;
+
+/*! @brief TSI feature interrupt source.*/
+typedef enum _tsi_interrupt_enable
+{
+ kTSI_GlobalInterruptEnable = 1U, /*!< TSI module global interrupt */
+ kTSI_OutOfRangeInterruptEnable = 2U, /*!< Out-Of-Range interrupt */
+ kTSI_EndOfScanInterruptEnable = 4U, /*!< End-Of-Scan interrupt */
+ kTSI_ErrorInterrruptEnable = 8U /*!< Error interrupt */
+} tsi_interrupt_enable_t;
+
+/*! @brief TSI calibration data storage. */
+typedef struct _tsi_calibration_data
+{
+ uint16_t calibratedData[FSL_FEATURE_TSI_CHANNEL_COUNT]; /*!< TSI calibration data storage buffer */
+} tsi_calibration_data_t;
+
+/*!
+ * @brief TSI configuration structure.
+ *
+ * This structure contains the settings for the most common TSI configurations including
+ * the TSI module charge currents, number of scans, thresholds, and so on.
+ */
+typedef struct _tsi_config
+{
+ uint16_t thresh; /*!< High threshold. */
+ uint16_t thresl; /*!< Low threshold. */
+ tsi_low_power_clock_source_t lpclks; /*!< Low power clock. */
+ tsi_low_power_scan_interval_t lpscnitv; /*!< Low power scan interval. */
+ tsi_active_mode_clock_source_t amclks; /*!< Active mode clock source. */
+ tsi_active_mode_prescaler_t ampsc; /*!< Active mode prescaler. */
+ tsi_electrode_osc_prescaler_t ps; /*!< Electrode Oscillator Prescaler */
+ tsi_external_osc_charge_current_t extchrg; /*!< External Oscillator charge current */
+ tsi_reference_osc_charge_current_t refchrg; /*!< Reference Oscillator charge current */
+ tsi_n_consecutive_scans_t nscn; /*!< Number of scans. */
+} tsi_config_t;
+
+/*******************************************************************************
+ * API
+ ******************************************************************************/
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/*!
+ * @brief Initializes hardware.
+ *
+ * @details Initializes the peripheral to the targeted state specified by the parameter configuration,
+ * such as initialize and set prescalers, number of scans, clocks, delta voltage
+ * capacitance trimmer, reference, and electrode charge current and threshold.
+ *
+ * @param base TSI peripheral base address.
+ * @param config Pointer to the TSI peripheral configuration structure.
+ * @return none
+ */
+void TSI_Init(TSI_Type *base, const tsi_config_t *config);
+
+/*!
+ * @brief De-initializes hardware.
+ *
+ * @details De-initializes the peripheral to default state.
+ *
+ * @param base TSI peripheral base address.
+ * @return none
+ */
+void TSI_Deinit(TSI_Type *base);
+
+/*!
+ * @brief Gets TSI normal mode user configuration structure.
+ * This interface sets the userConfig structure to a default value. The configuration structure only
+ * includes the settings for the whole TSI.
+ * The user configure is set to these values:
+ * @code
+ userConfig.lpclks = kTSI_LowPowerClockSource_LPOCLK;
+ userConfig.lpscnitv = kTSI_LowPowerInterval_100ms;
+ userConfig.amclks = kTSI_ActiveClkSource_LPOSCCLK;
+ userConfig.ampsc = kTSI_ActiveModePrescaler_8div;
+ userConfig.ps = kTSI_ElecOscPrescaler_2div;
+ userConfig.extchrg = kTSI_ExtOscChargeCurrent_10uA;
+ userConfig.refchrg = kTSI_RefOscChargeCurrent_10uA;
+ userConfig.nscn = kTSI_ConsecutiveScansNumber_8time;
+ userConfig.thresh = 0U;
+ userConfig.thresl = 0U;
+ @endcode
+ *
+ * @param userConfig Pointer to the TSI user configuration structure.
+ */
+void TSI_GetNormalModeDefaultConfig(tsi_config_t *userConfig);
+
+/*!
+ * @brief Gets the TSI low power mode default user configuration structure.
+ * This interface sets userConfig structure to a default value. The configuration structure only
+ * includes the settings for the whole TSI.
+ * The user configure is set to these values:
+ * @code
+ userConfig.lpclks = kTSI_LowPowerClockSource_LPOCLK;
+ userConfig.lpscnitv = kTSI_LowPowerInterval_100ms;
+ userConfig.amclks = kTSI_ActiveClkSource_LPOSCCLK;
+ userConfig.ampsc = kTSI_ActiveModePrescaler_64div;
+ userConfig.ps = kTSI_ElecOscPrescaler_1div;
+ userConfig.extchrg = kTSI_ExtOscChargeCurrent_2uA;
+ userConfig.refchrg = kTSI_RefOscChargeCurrent_32uA;
+ userConfig.nscn = kTSI_ConsecutiveScansNumber_26time;
+ userConfig.thresh = 15000U;
+ userConfig.thresl = 1000U;
+ @endcode
+ *
+ * @param userConfig Pointer to the TSI user configuration structure.
+ */
+void TSI_GetLowPowerModeDefaultConfig(tsi_config_t *userConfig);
+
+/*!
+ * @brief Hardware calibration.
+ *
+ * @details Calibrates the peripheral to fetch the initial counter value of the enabled electrodes.
+ * This API is mostly used at the initial application setup. Call this function after the \ref TSI_Init API
+ * and use the calibrated counter values to set up applications
+ * (such as to determine under which counter value a touch event occurs).
+ *
+ * @note This API is called in normal power modes.
+ * @note For K60 series, the calibrated baseline counter value CANNOT be used in low power modes. To obtain
+ * the calibrated counter values in low power modes, see K60 Mask Set Errata for Mask 5N22D.
+ * @param base TSI peripheral base address.
+ * @param calBuff Data buffer that store the calibrated counter value.
+ * @return none
+ *
+ */
+void TSI_Calibrate(TSI_Type *base, tsi_calibration_data_t *calBuff);
+
+/*!
+ * @brief Enables the TSI interrupt requests.
+ * @param base TSI peripheral base address.
+ * @param mask interrupt source
+ * The parameter can be a combination of the following source if defined:
+ * @arg kTSI_GlobalInterruptEnable
+ * @arg kTSI_EndOfScanInterruptEnable
+ * @arg kTSI_OutOfRangeInterruptEnable
+ * @arg kTSI_ErrorInterrruptEnable
+ */
+void TSI_EnableInterrupts(TSI_Type *base, uint32_t mask);
+
+/*!
+ * @brief Disables the TSI interrupt requests.
+ * @param base TSI peripheral base address.
+ * @param mask interrupt source
+ * The parameter can be a combination of the following source if defined:
+ * @arg kTSI_GlobalInterruptEnable
+ * @arg kTSI_EndOfScanInterruptEnable
+ * @arg kTSI_OutOfRangeInterruptEnable
+ * @arg kTSI_ErrorInterrruptEnable
+ */
+void TSI_DisableInterrupts(TSI_Type *base, uint32_t mask);
+
+/*!
+* @brief Gets the interrupt flags.
+* This function get TSI interrupt flags.
+*
+* @param base TSI peripheral base address.
+* @return The mask of these status flag bits.
+*/
+static inline uint32_t TSI_GetStatusFlags(TSI_Type *base)
+{
+ return (base->GENCS &
+ (kTSI_EndOfScanFlag | kTSI_OutOfRangeFlag | kTSI_ExternalElectrodeErrorFlag | kTSI_OverrunErrorFlag));
+}
+
+/*!
+ * @brief Clears the interrupt flags.
+ *
+ * This function clears the TSI interrupt flags.
+ * @note The automatically cleared flags can't be cleared by this function.
+ *
+ * @param base TSI peripheral base address.
+ * @param mask the status flags to clear.
+ */
+void TSI_ClearStatusFlags(TSI_Type *base, uint32_t mask);
+
+/*!
+* @brief Gets the TSI scan trigger mode.
+*
+* @param base TSI peripheral base address.
+* @return Scan trigger mode.
+*/
+static inline uint32_t TSI_GetScanTriggerMode(TSI_Type *base)
+{
+ return (base->GENCS & TSI_GENCS_STM_MASK);
+}
+
+/*!
+* @brief Gets the scan in progress flag.
+*
+* @param base TSI peripheral base address.
+* @return True - if scan is in progress.
+* False - if scan is not in progress.
+*/
+static inline bool TSI_IsScanInProgress(TSI_Type *base)
+{
+ return (base->GENCS & TSI_GENCS_SCNIP_MASK);
+}
+
+/*!
+* @brief Sets the electrode oscillator prescaler.
+*
+* @param base TSI peripheral base address.
+* @param prescaler Prescaler value.
+* @return none.
+*/
+static inline void TSI_SetElectrodeOSCPrescaler(TSI_Type *base, tsi_electrode_osc_prescaler_t prescaler)
+{
+ base->GENCS = (base->GENCS & ~(TSI_GENCS_PS_MASK | ALL_FLAGS_MASK)) | (TSI_GENCS_PS(prescaler));
+}
+
+/*!
+* @brief Sets the number of scans (NSCN).
+*
+* @param base TSI peripheral base address.
+* @param number Number of scans.
+* @return none.
+*/
+static inline void TSI_SetNumberOfScans(TSI_Type *base, tsi_n_consecutive_scans_t number)
+{
+ base->GENCS = (base->GENCS & ~(TSI_GENCS_NSCN_MASK | ALL_FLAGS_MASK)) | (TSI_GENCS_NSCN(number));
+}
+
+/*!
+* @brief Enables/disables the TSI module.
+*
+* @param base TSI peripheral base address.
+* @param enable Choose whether to enable TSI module.
+* - true Enable module;
+* - false Disable module;
+* @return none.
+*/
+static inline void TSI_EnableModule(TSI_Type *base, bool enable)
+{
+ if (enable)
+ {
+ base->GENCS = (base->GENCS & ~ALL_FLAGS_MASK) | TSI_GENCS_TSIEN_MASK; /* Enable module */
+ }
+ else
+ {
+ base->GENCS = (base->GENCS & ~ALL_FLAGS_MASK) & (~TSI_GENCS_TSIEN_MASK); /* Disable module */
+ }
+}
+
+/*!
+* @brief Enables/disables the TSI module in low power stop mode.
+*
+* @param base TSI peripheral base address.
+* @param enable Choose whether to enable TSI module in low power modes.
+* - true Enable module in low power modes;
+* - false Disable module in low power modes;
+* @return none.
+*/
+static inline void TSI_EnableLowPower(TSI_Type *base, bool enable)
+{
+ if (enable)
+ {
+ base->GENCS = (base->GENCS & ~ALL_FLAGS_MASK) | TSI_GENCS_STPE_MASK; /* Enable module in low power stop mode */
+ }
+ else
+ {
+ base->GENCS = (base->GENCS & ~ALL_FLAGS_MASK) & (~TSI_GENCS_STPE_MASK); /* Disable module in low power stop mode */
+ }
+}
+
+/*!
+* @brief Enables/disables the periodical (hardware) trigger scan.
+*
+* @param base TSI peripheral base address.
+* @param enable Choose whether to enable periodical trigger scan.
+* - true Enable periodical trigger scan;
+* - false Enable software trigger scan;
+* @return none.
+*/
+static inline void TSI_EnablePeriodicalScan(TSI_Type *base, bool enable)
+{
+ if (enable)
+ {
+ base->GENCS = (base->GENCS & ~ALL_FLAGS_MASK) | TSI_GENCS_STM_MASK; /* Enable period trigger scan */
+ }
+ else
+ {
+ base->GENCS = (base->GENCS & ~ALL_FLAGS_MASK) & (~TSI_GENCS_STM_MASK); /* Enable software trigger scan */
+ }
+}
+
+/*!
+* @brief Starts a measurement (trigger a new measurement).
+*
+* @param base TSI peripheral base address.
+* @return none.
+*/
+static inline void TSI_StartSoftwareTrigger(TSI_Type *base)
+{
+ base->GENCS = (base->GENCS & ~ALL_FLAGS_MASK) | TSI_GENCS_SWTS_MASK;
+}
+
+/*!
+* @brief Sets a low power scan interval.
+*
+* @param base TSI peripheral base address.
+* @param interval Interval for low power scan.
+* @return none.
+*/
+static inline void TSI_SetLowPowerScanInterval(TSI_Type *base, tsi_low_power_scan_interval_t interval)
+{
+ base->GENCS = (base->GENCS & ~(TSI_GENCS_LPSCNITV_MASK | ALL_FLAGS_MASK)) | (TSI_GENCS_LPSCNITV(interval));
+}
+
+/*!
+* @brief Sets a low power clock.
+*
+* @param base TSI peripheral base address.
+* @param clock Low power clock selection.
+*/
+static inline void TSI_SetLowPowerClock(TSI_Type *base, uint32_t clock)
+{
+ base->GENCS = (base->GENCS & ~(TSI_GENCS_LPCLKS_MASK | ALL_FLAGS_MASK)) | (TSI_GENCS_LPCLKS(clock));
+}
+
+/*!
+* @brief Sets the reference oscillator charge current.
+*
+* @param base TSI peripheral base address.
+* @param current The reference oscillator charge current.
+* @return none.
+*/
+static inline void TSI_SetReferenceChargeCurrent(TSI_Type *base, tsi_reference_osc_charge_current_t current)
+{
+ base->SCANC = ((base->SCANC) & ~TSI_SCANC_REFCHRG_MASK) | (TSI_SCANC_REFCHRG(current));
+}
+
+/*!
+* @brief Sets the electrode charge current.
+*
+* @param base TSI peripheral base address.
+* @param current The external electrode charge current.
+* @return none.
+*/
+static inline void TSI_SetElectrodeChargeCurrent(TSI_Type *base, tsi_external_osc_charge_current_t current)
+{
+ base->SCANC = ((base->SCANC) & ~TSI_SCANC_EXTCHRG_MASK) | (TSI_SCANC_EXTCHRG(current));
+}
+
+/*!
+* @brief Sets the scan modulo value.
+*
+* @param base TSI peripheral base address.
+* @param modulo Scan modulo value.
+* @return none.
+*/
+static inline void TSI_SetScanModulo(TSI_Type *base, uint32_t modulo)
+{
+ base->SCANC = ((base->SCANC) & ~TSI_SCANC_SMOD_MASK) | (TSI_SCANC_SMOD(modulo));
+}
+
+/*!
+* @brief Sets the active mode source.
+*
+* @param base TSI peripheral base address.
+* @param source Active mode clock source (LPOSCCLK, MCGIRCLK, OSCERCLK).
+* @return none.
+*/
+static inline void TSI_SetActiveModeSource(TSI_Type *base, uint32_t source)
+{
+ base->SCANC = ((base->SCANC) & ~TSI_SCANC_AMCLKS_MASK) | (TSI_SCANC_AMCLKS(source));
+}
+
+/*!
+* @brief Sets the active mode prescaler.
+*
+* @param base TSI peripheral base address.
+* @param prescaler Prescaler value.
+* @return none.
+*/
+static inline void TSI_SetActiveModePrescaler(TSI_Type *base, tsi_active_mode_prescaler_t prescaler)
+{
+ base->SCANC = ((base->SCANC) & ~TSI_SCANC_AMPSC_MASK) | (TSI_SCANC_AMPSC(prescaler));
+}
+
+/*!
+* @brief Sets the low power channel.
+* Only one channel can be enabled in low power mode.
+*
+* @param base TSI peripheral base address.
+* @param channel Channel number.
+* @return none.
+*/
+static inline void TSI_SetLowPowerChannel(TSI_Type *base, uint16_t channel)
+{
+ assert(channel < FSL_FEATURE_TSI_CHANNEL_COUNT);
+
+ base->PEN = ((base->PEN) & ~TSI_PEN_LPSP_MASK) | (TSI_PEN_LPSP(channel));
+}
+
+/*!
+ * @brief Gets the enabled channel in low power modes.
+ * @note Only one channel can be enabled in low power mode.
+ *
+ * @param base TSI peripheral base address.
+ * @return Channel number.
+ */
+static inline uint32_t TSI_GetLowPowerChannel(TSI_Type *base)
+{
+ return ((base->PEN & TSI_PEN_LPSP_MASK) >> TSI_PEN_LPSP_SHIFT);
+}
+
+/*!
+* @brief Enables/disables a channel.
+*
+* @param base TSI peripheral base address.
+* @param channel Channel to be enabled.
+* @param enable Choose whether to enable specific channel.
+* - true Enable the specific channel;
+* - false Disable the specific channel;
+* @return none.
+*/
+static inline void TSI_EnableChannel(TSI_Type *base, uint16_t channel, bool enable)
+{
+ assert(channel < FSL_FEATURE_TSI_CHANNEL_COUNT);
+
+ if (enable)
+ {
+ base->PEN |= (1U << channel); /* Enable this specific channel */
+ }
+ else
+ {
+ base->PEN &= ~(1U << channel); /* Disable this specific channel */
+ }
+}
+
+/*!
+* @brief Enables/disables channels.
+* The function enables or disables channels by mask. It can enable/disable all channels at once.
+*
+* @param base TSI peripheral base address.
+* @param channelsMask Channels mask that indicate channels that are to be enabled/disabled.
+* @param enable Choose to enable or disable the specified channels.
+* - true Enable the specified channels;
+* - false Disable the specified channels;
+* @return none.
+*/
+static inline void TSI_EnableChannels(TSI_Type *base, uint16_t channelsMask, bool enable)
+{
+ if (enable)
+ {
+ base->PEN |= channelsMask; /* Enable these specified channels */
+ }
+ else
+ {
+ base->PEN &= ~(0x0000FFFFU & (uint32_t)channelsMask); /* Disable these specified channels */
+ }
+}
+
+/*!
+ * @brief Returns if a channel is enabled.
+ *
+ * @param base TSI peripheral base address.
+ * @param channel Channel to be checked.
+ *
+ * @return true - if the channel is enabled;
+ * false - if the channel is disabled;
+ */
+static inline bool TSI_IsChannelEnabled(TSI_Type *base, uint16_t channel)
+{
+ assert(channel < FSL_FEATURE_TSI_CHANNEL_COUNT);
+
+ return ((base->PEN) & (1U << channel));
+}
+
+/*!
+* @brief Returns the mask of enabled channels.
+*
+* @param base TSI peripheral base address.
+* @return Channels mask that indicates currently enabled channels.
+*/
+static inline uint16_t TSI_GetEnabledChannels(TSI_Type *base)
+{
+ return (uint16_t)(base->PEN & 0x0000FFFFU);
+}
+
+/*!
+* @brief Gets the wake up channel counter for low-power mode usage.
+*
+* @param base TSI peripheral base address.
+* @return Wake up counter value.
+*/
+static inline uint16_t TSI_GetWakeUpChannelCounter(TSI_Type *base)
+{
+ return (uint16_t)base->WUCNTR;
+}
+
+/*!
+* @brief Gets the TSI conversion counter of a specific channel in normal mode.
+* @note This API can only be used in normal active modes.
+*
+* @param base TSI peripheral base address.
+* @param channel Index of the specific TSI channel.
+*
+* @return The counter value of the specific channel.
+*/
+static inline uint16_t TSI_GetNormalModeCounter(TSI_Type *base, uint16_t channel)
+{
+ assert(channel < FSL_FEATURE_TSI_CHANNEL_COUNT);
+
+ uint16_t *counter = (uint16_t *)((uint32_t)(&(((base)->CNTR1))) + (channel * 2U));
+ return (uint16_t)(*counter);
+}
+
+/*!
+* @brief Sets a low threshold.
+*
+* @param base TSI peripheral base address.
+* @param low_threshold Low counter threshold.
+* @return none.
+*/
+static inline void TSI_SetLowThreshold(TSI_Type *base, uint16_t low_threshold)
+{
+ base->THRESHOLD = ((base->THRESHOLD) & ~TSI_THRESHOLD_LTHH_MASK) | (TSI_THRESHOLD_LTHH(low_threshold));
+}
+
+/*!
+* @brief Sets a high threshold.
+*
+* @param base TSI peripheral base address.
+* @param high_threshold High counter threshold.
+* @return none.
+*/
+static inline void TSI_SetHighThreshold(TSI_Type *base, uint16_t high_threshold)
+{
+ base->THRESHOLD = ((base->THRESHOLD) & ~TSI_THRESHOLD_HTHH_MASK) | (TSI_THRESHOLD_HTHH(high_threshold));
+}
+
+#ifdef __cplusplus
+}
+#endif /* __cplusplus */
+
+/*! @}*/
+
+#endif /* _FSL_TSI_V2_H_*/
diff --git a/drivers/fsl_uart.c b/drivers/fsl_uart.c
new file mode 100644
index 0000000..121be44
--- /dev/null
+++ b/drivers/fsl_uart.c
@@ -0,0 +1,1128 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_uart.h"
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+/* UART transfer state. */
+enum _uart_tansfer_states
+{
+ kUART_TxIdle, /* TX idle. */
+ kUART_TxBusy, /* TX busy. */
+ kUART_RxIdle, /* RX idle. */
+ kUART_RxBusy /* RX busy. */
+};
+
+/* Typedef for interrupt handler. */
+typedef void (*uart_isr_t)(UART_Type *base, uart_handle_t *handle);
+
+/*******************************************************************************
+ * Prototypes
+ ******************************************************************************/
+
+/*!
+ * @brief Get the UART instance from peripheral base address.
+ *
+ * @param base UART peripheral base address.
+ * @return UART instance.
+ */
+uint32_t UART_GetInstance(UART_Type *base);
+
+/*!
+ * @brief Get the length of received data in RX ring buffer.
+ *
+ * @param handle UART handle pointer.
+ * @return Length of received data in RX ring buffer.
+ */
+static size_t UART_TransferGetRxRingBufferLength(uart_handle_t *handle);
+
+/*!
+ * @brief Check whether the RX ring buffer is full.
+ *
+ * @param handle UART handle pointer.
+ * @retval true RX ring buffer is full.
+ * @retval false RX ring buffer is not full.
+ */
+static bool UART_TransferIsRxRingBufferFull(uart_handle_t *handle);
+
+/*!
+ * @brief Read RX register using non-blocking method.
+ *
+ * This function reads data from the TX register directly, upper layer must make
+ * sure the RX register is full or TX FIFO has data before calling this function.
+ *
+ * @param base UART peripheral base address.
+ * @param data Start addresss of the buffer to store the received data.
+ * @param length Size of the buffer.
+ */
+static void UART_ReadNonBlocking(UART_Type *base, uint8_t *data, size_t length);
+
+/*!
+ * @brief Write to TX register using non-blocking method.
+ *
+ * This function writes data to the TX register directly, upper layer must make
+ * sure the TX register is empty or TX FIFO has empty room before calling this function.
+ *
+ * @note This function does not check whether all the data has been sent out to bus,
+ * so before disable TX, check kUART_TransmissionCompleteFlag to ensure the TX is
+ * finished.
+ *
+ * @param base UART peripheral base address.
+ * @param data Start addresss of the data to write.
+ * @param length Size of the buffer to be sent.
+ */
+static void UART_WriteNonBlocking(UART_Type *base, const uint8_t *data, size_t length);
+
+/*******************************************************************************
+ * Variables
+ ******************************************************************************/
+/* Array of UART handle. */
+#if (defined(UART5))
+#define UART_HANDLE_ARRAY_SIZE 6
+#else /* UART5 */
+#if (defined(UART4))
+#define UART_HANDLE_ARRAY_SIZE 5
+#else /* UART4 */
+#if (defined(UART3))
+#define UART_HANDLE_ARRAY_SIZE 4
+#else /* UART3 */
+#if (defined(UART2))
+#define UART_HANDLE_ARRAY_SIZE 3
+#else /* UART2 */
+#if (defined(UART1))
+#define UART_HANDLE_ARRAY_SIZE 2
+#else /* UART1 */
+#if (defined(UART0))
+#define UART_HANDLE_ARRAY_SIZE 1
+#else /* UART0 */
+#error No UART instance.
+#endif /* UART 0 */
+#endif /* UART 1 */
+#endif /* UART 2 */
+#endif /* UART 3 */
+#endif /* UART 4 */
+#endif /* UART 5 */
+static uart_handle_t *s_uartHandle[UART_HANDLE_ARRAY_SIZE];
+/* Array of UART peripheral base address. */
+static UART_Type *const s_uartBases[] = UART_BASE_PTRS;
+
+/* Array of UART IRQ number. */
+static const IRQn_Type s_uartIRQ[] = UART_RX_TX_IRQS;
+/* Array of UART clock name. */
+static const clock_ip_name_t s_uartClock[] = UART_CLOCKS;
+
+/* UART ISR for transactional APIs. */
+static uart_isr_t s_uartIsr;
+
+/*******************************************************************************
+ * Code
+ ******************************************************************************/
+
+uint32_t UART_GetInstance(UART_Type *base)
+{
+ uint32_t instance;
+ uint32_t uartArrayCount = (sizeof(s_uartBases) / sizeof(s_uartBases[0]));
+
+ /* Find the instance index from base address mappings. */
+ for (instance = 0; instance < uartArrayCount; instance++)
+ {
+ if (s_uartBases[instance] == base)
+ {
+ break;
+ }
+ }
+
+ assert(instance < uartArrayCount);
+
+ return instance;
+}
+
+static size_t UART_TransferGetRxRingBufferLength(uart_handle_t *handle)
+{
+ assert(handle);
+
+ size_t size;
+
+ if (handle->rxRingBufferTail > handle->rxRingBufferHead)
+ {
+ size = (size_t)(handle->rxRingBufferHead + handle->rxRingBufferSize - handle->rxRingBufferTail);
+ }
+ else
+ {
+ size = (size_t)(handle->rxRingBufferHead - handle->rxRingBufferTail);
+ }
+
+ return size;
+}
+
+static bool UART_TransferIsRxRingBufferFull(uart_handle_t *handle)
+{
+ assert(handle);
+
+ bool full;
+
+ if (UART_TransferGetRxRingBufferLength(handle) == (handle->rxRingBufferSize - 1U))
+ {
+ full = true;
+ }
+ else
+ {
+ full = false;
+ }
+
+ return full;
+}
+
+status_t UART_Init(UART_Type *base, const uart_config_t *config, uint32_t srcClock_Hz)
+{
+ assert(config);
+ assert(config->baudRate_Bps);
+#if defined(FSL_FEATURE_UART_HAS_FIFO) && FSL_FEATURE_UART_HAS_FIFO
+ assert(FSL_FEATURE_UART_FIFO_SIZEn(base) >= config->txFifoWatermark);
+ assert(FSL_FEATURE_UART_FIFO_SIZEn(base) >= config->rxFifoWatermark);
+#endif
+
+ uint16_t sbr = 0;
+ uint8_t temp = 0;
+ uint32_t baudDiff = 0;
+
+ /* Calculate the baud rate modulo divisor, sbr*/
+ sbr = srcClock_Hz / (config->baudRate_Bps * 16);
+ /* set sbrTemp to 1 if the sourceClockInHz can not satisfy the desired baud rate */
+ if (sbr == 0)
+ {
+ sbr = 1;
+ }
+#if defined(FSL_FEATURE_UART_HAS_BAUD_RATE_FINE_ADJUST_SUPPORT) && FSL_FEATURE_UART_HAS_BAUD_RATE_FINE_ADJUST_SUPPORT
+ /* Determine if a fractional divider is needed to fine tune closer to the
+ * desired baud, each value of brfa is in 1/32 increments,
+ * hence the multiply-by-32. */
+ uint16_t brfa = (32 * srcClock_Hz / (config->baudRate_Bps * 16)) - 32 * sbr;
+
+ /* Calculate the baud rate based on the temporary SBR values and BRFA */
+ baudDiff = (srcClock_Hz * 2 / ((sbr * 32 + brfa))) - config->baudRate_Bps;
+
+#else
+ /* Calculate the baud rate based on the temporary SBR values */
+ baudDiff = (srcClock_Hz / (sbr * 16)) - config->baudRate_Bps;
+
+ /* Select the better value between sbr and (sbr + 1) */
+ if (baudDiff > (config->baudRate_Bps - (srcClock_Hz / (16 * (sbr + 1)))))
+ {
+ baudDiff = config->baudRate_Bps - (srcClock_Hz / (16 * (sbr + 1)));
+ sbr++;
+ }
+#endif
+
+ /* next, check to see if actual baud rate is within 3% of desired baud rate
+ * based on the calculate SBR value */
+ if (baudDiff > ((config->baudRate_Bps / 100) * 3))
+ {
+ /* Unacceptable baud rate difference of more than 3%*/
+ return kStatus_UART_BaudrateNotSupport;
+ }
+
+ /* Enable uart clock */
+ CLOCK_EnableClock(s_uartClock[UART_GetInstance(base)]);
+
+ /* Disable UART TX RX before setting. */
+ base->C2 &= ~(UART_C2_TE_MASK | UART_C2_RE_MASK);
+
+ /* Write the sbr value to the BDH and BDL registers*/
+ base->BDH = (base->BDH & ~UART_BDH_SBR_MASK) | (uint8_t)(sbr >> 8);
+ base->BDL = (uint8_t)sbr;
+
+#if defined(FSL_FEATURE_UART_HAS_BAUD_RATE_FINE_ADJUST_SUPPORT) && FSL_FEATURE_UART_HAS_BAUD_RATE_FINE_ADJUST_SUPPORT
+ /* Write the brfa value to the register*/
+ base->C4 = (base->C4 & ~UART_C4_BRFA_MASK) | (brfa & UART_C4_BRFA_MASK);
+#endif
+
+ /* Set bit count and parity mode. */
+ temp = base->C1 & ~(UART_C1_PE_MASK | UART_C1_PT_MASK | UART_C1_M_MASK);
+
+ if (kUART_ParityDisabled != config->parityMode)
+ {
+ temp |= (UART_C1_M_MASK | (uint8_t)config->parityMode);
+ }
+
+ base->C1 = temp;
+
+#if defined(FSL_FEATURE_UART_HAS_STOP_BIT_CONFIG_SUPPORT) && FSL_FEATURE_UART_HAS_STOP_BIT_CONFIG_SUPPORT
+ /* Set stop bit per char */
+ base->BDH = (base->BDH & ~UART_BDH_SBNS_MASK) | UART_BDH_SBNS((uint8_t)config->stopBitCount);
+#endif
+
+#if defined(FSL_FEATURE_UART_HAS_FIFO) && FSL_FEATURE_UART_HAS_FIFO
+ /* Set tx/rx FIFO watermark */
+ base->TWFIFO = config->txFifoWatermark;
+ base->RWFIFO = config->rxFifoWatermark;
+
+ /* Enable tx/rx FIFO */
+ base->PFIFO |= (UART_PFIFO_TXFE_MASK | UART_PFIFO_RXFE_MASK);
+
+ /* Flush FIFO */
+ base->CFIFO |= (UART_CFIFO_TXFLUSH_MASK | UART_CFIFO_RXFLUSH_MASK);
+#endif
+
+ /* Enable TX/RX base on configure structure. */
+ temp = base->C2;
+
+ if (config->enableTx)
+ {
+ temp |= UART_C2_TE_MASK;
+ }
+
+ if (config->enableRx)
+ {
+ temp |= UART_C2_RE_MASK;
+ }
+
+ base->C2 = temp;
+
+ return kStatus_Success;
+}
+
+void UART_Deinit(UART_Type *base)
+{
+#if defined(FSL_FEATURE_UART_HAS_FIFO) && FSL_FEATURE_UART_HAS_FIFO
+ /* Wait tx FIFO send out*/
+ while (0 != base->TCFIFO)
+ {
+ }
+#endif
+ /* Wait last char shoft out */
+ while (0 == (base->S1 & UART_S1_TC_MASK))
+ {
+ }
+
+ /* Disable the module. */
+ base->C2 = 0;
+
+ /* Disable uart clock */
+ CLOCK_DisableClock(s_uartClock[UART_GetInstance(base)]);
+}
+
+void UART_GetDefaultConfig(uart_config_t *config)
+{
+ assert(config);
+
+ config->baudRate_Bps = 115200U;
+ config->parityMode = kUART_ParityDisabled;
+#if defined(FSL_FEATURE_UART_HAS_STOP_BIT_CONFIG_SUPPORT) && FSL_FEATURE_UART_HAS_STOP_BIT_CONFIG_SUPPORT
+ config->stopBitCount = kUART_OneStopBit;
+#endif
+#if defined(FSL_FEATURE_UART_HAS_FIFO) && FSL_FEATURE_UART_HAS_FIFO
+ config->txFifoWatermark = 0;
+ config->rxFifoWatermark = 1;
+#endif
+ config->enableTx = false;
+ config->enableRx = false;
+}
+
+status_t UART_SetBaudRate(UART_Type *base, uint32_t baudRate_Bps, uint32_t srcClock_Hz)
+{
+ assert(baudRate_Bps);
+
+ uint16_t sbr = 0;
+ uint32_t baudDiff = 0;
+ uint8_t oldCtrl;
+
+ /* Calculate the baud rate modulo divisor, sbr*/
+ sbr = srcClock_Hz / (baudRate_Bps * 16);
+ /* set sbrTemp to 1 if the sourceClockInHz can not satisfy the desired baud rate */
+ if (sbr == 0)
+ {
+ sbr = 1;
+ }
+#if defined(FSL_FEATURE_UART_HAS_BAUD_RATE_FINE_ADJUST_SUPPORT) && FSL_FEATURE_UART_HAS_BAUD_RATE_FINE_ADJUST_SUPPORT
+ /* Determine if a fractional divider is needed to fine tune closer to the
+ * desired baud, each value of brfa is in 1/32 increments,
+ * hence the multiply-by-32. */
+ uint16_t brfa = (32 * srcClock_Hz / (baudRate_Bps * 16)) - 32 * sbr;
+
+ /* Calculate the baud rate based on the temporary SBR values and BRFA */
+ baudDiff = (srcClock_Hz * 2 / ((sbr * 32 + brfa))) - baudRate_Bps;
+
+#else
+ /* Calculate the baud rate based on the temporary SBR values */
+ baudDiff = (srcClock_Hz / (sbr * 16)) - baudRate_Bps;
+
+ /* Select the better value between sbr and (sbr + 1) */
+ if (baudDiff > (baudRate_Bps - (srcClock_Hz / (16 * (sbr + 1)))))
+ {
+ baudDiff = baudRate_Bps - (srcClock_Hz / (16 * (sbr + 1)));
+ sbr++;
+ }
+#endif
+
+ /* next, check to see if actual baud rate is within 3% of desired baud rate
+ * based on the calculate SBR value */
+ if (baudDiff < ((baudRate_Bps / 100) * 3))
+ {
+ /* Store C2 before disable Tx and Rx */
+ oldCtrl = base->C2;
+
+ /* Disable UART TX RX before setting. */
+ base->C2 &= ~(UART_C2_TE_MASK | UART_C2_RE_MASK);
+
+ /* Write the sbr value to the BDH and BDL registers*/
+ base->BDH = (base->BDH & ~UART_BDH_SBR_MASK) | (uint8_t)(sbr >> 8);
+ base->BDL = (uint8_t)sbr;
+
+#if defined(FSL_FEATURE_UART_HAS_BAUD_RATE_FINE_ADJUST_SUPPORT) && FSL_FEATURE_UART_HAS_BAUD_RATE_FINE_ADJUST_SUPPORT
+ /* Write the brfa value to the register*/
+ base->C4 = (base->C4 & ~UART_C4_BRFA_MASK) | (brfa & UART_C4_BRFA_MASK);
+#endif
+ /* Restore C2. */
+ base->C2 = oldCtrl;
+
+ return kStatus_Success;
+ }
+ else
+ {
+ /* Unacceptable baud rate difference of more than 3%*/
+ return kStatus_UART_BaudrateNotSupport;
+ }
+}
+
+void UART_EnableInterrupts(UART_Type *base, uint32_t mask)
+{
+ mask &= kUART_AllInterruptsEnable;
+
+ /* The interrupt mask is combined by control bits from several register: ((CFIFO<<24) | (C3<<16) | (C2<<8) |(BDH))
+ */
+ base->BDH |= mask;
+ base->C2 |= (mask >> 8);
+ base->C3 |= (mask >> 16);
+
+#if defined(FSL_FEATURE_UART_HAS_FIFO) && FSL_FEATURE_UART_HAS_FIFO
+ base->CFIFO |= (mask >> 24);
+#endif
+}
+
+void UART_DisableInterrupts(UART_Type *base, uint32_t mask)
+{
+ mask &= kUART_AllInterruptsEnable;
+
+ /* The interrupt mask is combined by control bits from several register: ((CFIFO<<24) | (C3<<16) | (C2<<8) |(BDH))
+ */
+ base->BDH &= ~mask;
+ base->C2 &= ~(mask >> 8);
+ base->C3 &= ~(mask >> 16);
+
+#if defined(FSL_FEATURE_UART_HAS_FIFO) && FSL_FEATURE_UART_HAS_FIFO
+ base->CFIFO &= ~(mask >> 24);
+#endif
+}
+
+uint32_t UART_GetEnabledInterrupts(UART_Type *base)
+{
+ uint32_t temp;
+
+ temp = base->BDH | ((uint32_t)(base->C2) << 8) | ((uint32_t)(base->C3) << 16);
+
+#if defined(FSL_FEATURE_UART_HAS_FIFO) && FSL_FEATURE_UART_HAS_FIFO
+ temp |= ((uint32_t)(base->CFIFO) << 24);
+#endif
+
+ return temp & kUART_AllInterruptsEnable;
+}
+
+uint32_t UART_GetStatusFlags(UART_Type *base)
+{
+ uint32_t status_flag;
+
+ status_flag = base->S1 | ((uint32_t)(base->S2) << 8);
+
+#if defined(FSL_FEATURE_UART_HAS_EXTENDED_DATA_REGISTER_FLAGS) && FSL_FEATURE_UART_HAS_EXTENDED_DATA_REGISTER_FLAGS
+ status_flag |= ((uint32_t)(base->ED) << 16);
+#endif
+
+#if defined(FSL_FEATURE_UART_HAS_FIFO) && FSL_FEATURE_UART_HAS_FIFO
+ status_flag |= ((uint32_t)(base->SFIFO) << 24);
+#endif
+
+ return status_flag;
+}
+
+status_t UART_ClearStatusFlags(UART_Type *base, uint32_t mask)
+{
+ uint8_t reg = base->S2;
+ status_t status;
+
+#if defined(FSL_FEATURE_UART_HAS_LIN_BREAK_DETECT) && FSL_FEATURE_UART_HAS_LIN_BREAK_DETECT
+ reg &= ~(UART_S2_RXEDGIF_MASK | UART_S2_LBKDIF_MASK);
+#else
+ reg &= ~UART_S2_RXEDGIF_MASK;
+#endif
+
+ base->S2 = reg | (uint8_t)(mask >> 8);
+
+#if defined(FSL_FEATURE_UART_HAS_FIFO) && FSL_FEATURE_UART_HAS_FIFO
+ base->SFIFO = (uint8_t)(mask >> 24);
+#endif
+
+ if (mask & (kUART_IdleLineFlag | kUART_NoiseErrorFlag | kUART_FramingErrorFlag |
+ kUART_ParityErrorFlag))
+ {
+ /* Read base->D to clear the flags. */
+ (void)base->S1;
+ (void)base->D;
+ }
+
+ if (mask & kUART_RxOverrunFlag)
+ {
+ /* Read base->D to clear the flags and Flush all data in FIFO. */
+ (void)base->S1;
+ (void)base->D;
+#if defined(FSL_FEATURE_UART_HAS_FIFO) && FSL_FEATURE_UART_HAS_FIFO
+ /* Flush FIFO date, otherwise FIFO pointer will be in unknown state. */
+ base->CFIFO |= UART_CFIFO_RXFLUSH_MASK;
+#endif
+ }
+
+ /* If some flags still pending. */
+ if (mask & UART_GetStatusFlags(base))
+ {
+ /* Some flags can only clear or set by the hardware itself, these flags are: kUART_TxDataRegEmptyFlag,
+ kUART_TransmissionCompleteFlag, kUART_RxDataRegFullFlag, kUART_RxActiveFlag, kUART_NoiseErrorInRxDataRegFlag,
+ kUART_ParityErrorInRxDataRegFlag, kUART_TxFifoEmptyFlag, kUART_RxFifoEmptyFlag. */
+ status = kStatus_UART_FlagCannotClearManually;
+ }
+ else
+ {
+ status = kStatus_Success;
+ }
+
+ return status;
+}
+
+void UART_WriteBlocking(UART_Type *base, const uint8_t *data, size_t length)
+{
+ /* This API can only ensure that the data is written into the data buffer but can't
+ ensure all data in the data buffer are sent into the transmit shift buffer. */
+ while (length--)
+ {
+ while (!(base->S1 & UART_S1_TDRE_MASK))
+ {
+ }
+ base->D = *(data++);
+ }
+}
+
+static void UART_WriteNonBlocking(UART_Type *base, const uint8_t *data, size_t length)
+{
+ assert(data);
+
+ size_t i;
+
+ /* The Non Blocking write data API assume user have ensured there is enough space in
+ peripheral to write. */
+ for (i = 0; i < length; i++)
+ {
+ base->D = data[i];
+ }
+}
+
+status_t UART_ReadBlocking(UART_Type *base, uint8_t *data, size_t length)
+{
+ assert(data);
+
+ uint32_t statusFlag;
+
+ while (length--)
+ {
+#if defined(FSL_FEATURE_UART_HAS_FIFO) && FSL_FEATURE_UART_HAS_FIFO
+ while (!base->RCFIFO)
+#else
+ while (!(base->S1 & UART_S1_RDRF_MASK))
+#endif
+ {
+ statusFlag = UART_GetStatusFlags(base);
+
+ if (statusFlag & kUART_RxOverrunFlag)
+ {
+ return kStatus_UART_RxHardwareOverrun;
+ }
+
+ if (statusFlag & kUART_NoiseErrorFlag)
+ {
+ return kStatus_UART_NoiseError;
+ }
+
+ if (statusFlag & kUART_FramingErrorFlag)
+ {
+ return kStatus_UART_FramingError;
+ }
+
+ if (statusFlag & kUART_ParityErrorFlag)
+ {
+ return kStatus_UART_ParityError;
+ }
+ }
+ *(data++) = base->D;
+ }
+
+ return kStatus_Success;
+}
+
+static void UART_ReadNonBlocking(UART_Type *base, uint8_t *data, size_t length)
+{
+ assert(data);
+
+ size_t i;
+
+ /* The Non Blocking read data API assume user have ensured there is enough space in
+ peripheral to write. */
+ for (i = 0; i < length; i++)
+ {
+ data[i] = base->D;
+ }
+}
+
+void UART_TransferCreateHandle(UART_Type *base,
+ uart_handle_t *handle,
+ uart_transfer_callback_t callback,
+ void *userData)
+{
+ assert(handle);
+
+ uint32_t instance;
+
+ /* Zero the handle. */
+ memset(handle, 0, sizeof(*handle));
+
+ /* Set the TX/RX state. */
+ handle->rxState = kUART_RxIdle;
+ handle->txState = kUART_TxIdle;
+
+ /* Set the callback and user data. */
+ handle->callback = callback;
+ handle->userData = userData;
+
+#if defined(FSL_FEATURE_UART_HAS_FIFO) && FSL_FEATURE_UART_HAS_FIFO
+ /* Note:
+ Take care of the RX FIFO, RX interrupt request only assert when received bytes
+ equal or more than RX water mark, there is potential issue if RX water
+ mark larger than 1.
+ For example, if RX FIFO water mark is 2, upper layer needs 5 bytes and
+ 5 bytes are received. the last byte will be saved in FIFO but not trigger
+ RX interrupt because the water mark is 2.
+ */
+ base->RWFIFO = 1U;
+#endif
+
+ /* Get instance from peripheral base address. */
+ instance = UART_GetInstance(base);
+
+ /* Save the handle in global variables to support the double weak mechanism. */
+ s_uartHandle[instance] = handle;
+
+ s_uartIsr = UART_TransferHandleIRQ;
+
+ /* Enable interrupt in NVIC. */
+ EnableIRQ(s_uartIRQ[instance]);
+}
+
+void UART_TransferStartRingBuffer(UART_Type *base, uart_handle_t *handle, uint8_t *ringBuffer, size_t ringBufferSize)
+{
+ assert(handle);
+ assert(ringBuffer);
+
+ /* Setup the ringbuffer address */
+ handle->rxRingBuffer = ringBuffer;
+ handle->rxRingBufferSize = ringBufferSize;
+ handle->rxRingBufferHead = 0U;
+ handle->rxRingBufferTail = 0U;
+
+ /* Enable the interrupt to accept the data when user need the ring buffer. */
+ UART_EnableInterrupts(base, kUART_RxDataRegFullInterruptEnable | kUART_RxOverrunInterruptEnable);
+}
+
+void UART_TransferStopRingBuffer(UART_Type *base, uart_handle_t *handle)
+{
+ assert(handle);
+
+ if (handle->rxState == kUART_RxIdle)
+ {
+ UART_DisableInterrupts(base, kUART_RxDataRegFullInterruptEnable | kUART_RxOverrunInterruptEnable);
+ }
+
+ handle->rxRingBuffer = NULL;
+ handle->rxRingBufferSize = 0U;
+ handle->rxRingBufferHead = 0U;
+ handle->rxRingBufferTail = 0U;
+}
+
+status_t UART_TransferSendNonBlocking(UART_Type *base, uart_handle_t *handle, uart_transfer_t *xfer)
+{
+ assert(handle);
+ assert(xfer);
+ assert(xfer->dataSize);
+ assert(xfer->data);
+
+ status_t status;
+
+ /* Return error if current TX busy. */
+ if (kUART_TxBusy == handle->txState)
+ {
+ status = kStatus_UART_TxBusy;
+ }
+ else
+ {
+ handle->txData = xfer->data;
+ handle->txDataSize = xfer->dataSize;
+ handle->txDataSizeAll = xfer->dataSize;
+ handle->txState = kUART_TxBusy;
+
+ /* Enable transmiter interrupt. */
+ UART_EnableInterrupts(base, kUART_TxDataRegEmptyInterruptEnable);
+
+ status = kStatus_Success;
+ }
+
+ return status;
+}
+
+void UART_TransferAbortSend(UART_Type *base, uart_handle_t *handle)
+{
+ assert(handle);
+
+ UART_DisableInterrupts(base, kUART_TxDataRegEmptyInterruptEnable | kUART_TransmissionCompleteInterruptEnable);
+
+ handle->txDataSize = 0;
+ handle->txState = kUART_TxIdle;
+}
+
+status_t UART_TransferGetSendCount(UART_Type *base, uart_handle_t *handle, uint32_t *count)
+{
+ assert(handle);
+ assert(count);
+
+ if (kUART_TxIdle == handle->txState)
+ {
+ return kStatus_NoTransferInProgress;
+ }
+
+ *count = handle->txDataSizeAll - handle->txDataSize;
+
+ return kStatus_Success;
+}
+
+status_t UART_TransferReceiveNonBlocking(UART_Type *base,
+ uart_handle_t *handle,
+ uart_transfer_t *xfer,
+ size_t *receivedBytes)
+{
+ assert(handle);
+ assert(xfer);
+ assert(xfer->data);
+ assert(xfer->dataSize);
+
+ uint32_t i;
+ status_t status;
+ /* How many bytes to copy from ring buffer to user memory. */
+ size_t bytesToCopy = 0U;
+ /* How many bytes to receive. */
+ size_t bytesToReceive;
+ /* How many bytes currently have received. */
+ size_t bytesCurrentReceived;
+ uint32_t regPrimask = 0U;
+
+ /* How to get data:
+ 1. If RX ring buffer is not enabled, then save xfer->data and xfer->dataSize
+ to uart handle, enable interrupt to store received data to xfer->data. When
+ all data received, trigger callback.
+ 2. If RX ring buffer is enabled and not empty, get data from ring buffer first.
+ If there are enough data in ring buffer, copy them to xfer->data and return.
+ If there are not enough data in ring buffer, copy all of them to xfer->data,
+ save the xfer->data remained empty space to uart handle, receive data
+ to this empty space and trigger callback when finished. */
+
+ if (kUART_RxBusy == handle->rxState)
+ {
+ status = kStatus_UART_RxBusy;
+ }
+ else
+ {
+ bytesToReceive = xfer->dataSize;
+ bytesCurrentReceived = 0U;
+
+ /* If RX ring buffer is used. */
+ if (handle->rxRingBuffer)
+ {
+ /* Disable IRQ, protect ring buffer. */
+ regPrimask = DisableGlobalIRQ();
+
+ /* How many bytes in RX ring buffer currently. */
+ bytesToCopy = UART_TransferGetRxRingBufferLength(handle);
+
+ if (bytesToCopy)
+ {
+ bytesToCopy = MIN(bytesToReceive, bytesToCopy);
+
+ bytesToReceive -= bytesToCopy;
+
+ /* Copy data from ring buffer to user memory. */
+ for (i = 0U; i < bytesToCopy; i++)
+ {
+ xfer->data[bytesCurrentReceived++] = handle->rxRingBuffer[handle->rxRingBufferTail];
+
+ /* Wrap to 0. Not use modulo (%) because it might be large and slow. */
+ if (handle->rxRingBufferTail + 1U == handle->rxRingBufferSize)
+ {
+ handle->rxRingBufferTail = 0U;
+ }
+ else
+ {
+ handle->rxRingBufferTail++;
+ }
+ }
+ }
+
+ /* If ring buffer does not have enough data, still need to read more data. */
+ if (bytesToReceive)
+ {
+ /* No data in ring buffer, save the request to UART handle. */
+ handle->rxData = xfer->data + bytesCurrentReceived;
+ handle->rxDataSize = bytesToReceive;
+ handle->rxDataSizeAll = bytesToReceive;
+ handle->rxState = kUART_RxBusy;
+ }
+
+ /* Enable IRQ if previously enabled. */
+ EnableGlobalIRQ(regPrimask);
+
+ /* Call user callback since all data are received. */
+ if (0 == bytesToReceive)
+ {
+ if (handle->callback)
+ {
+ handle->callback(base, handle, kStatus_UART_RxIdle, handle->userData);
+ }
+ }
+ }
+ /* Ring buffer not used. */
+ else
+ {
+ handle->rxData = xfer->data + bytesCurrentReceived;
+ handle->rxDataSize = bytesToReceive;
+ handle->rxDataSizeAll = bytesToReceive;
+ handle->rxState = kUART_RxBusy;
+
+ /* Enable RX interrupt. */
+ UART_EnableInterrupts(base, kUART_RxDataRegFullInterruptEnable | kUART_RxOverrunInterruptEnable);
+ }
+
+ /* Return the how many bytes have read. */
+ if (receivedBytes)
+ {
+ *receivedBytes = bytesCurrentReceived;
+ }
+
+ status = kStatus_Success;
+ }
+
+ return status;
+}
+
+void UART_TransferAbortReceive(UART_Type *base, uart_handle_t *handle)
+{
+ assert(handle);
+
+ /* Only abort the receive to handle->rxData, the RX ring buffer is still working. */
+ if (!handle->rxRingBuffer)
+ {
+ /* Disable RX interrupt. */
+ UART_DisableInterrupts(base, kUART_RxDataRegFullInterruptEnable | kUART_RxOverrunInterruptEnable);
+ }
+
+ handle->rxDataSize = 0U;
+ handle->rxState = kUART_RxIdle;
+}
+
+status_t UART_TransferGetReceiveCount(UART_Type *base, uart_handle_t *handle, uint32_t *count)
+{
+ assert(handle);
+ assert(count);
+
+ if (kUART_RxIdle == handle->rxState)
+ {
+ return kStatus_NoTransferInProgress;
+ }
+
+ if (!count)
+ {
+ return kStatus_InvalidArgument;
+ }
+
+ *count = handle->rxDataSizeAll - handle->rxDataSize;
+
+ return kStatus_Success;
+}
+
+void UART_TransferHandleIRQ(UART_Type *base, uart_handle_t *handle)
+{
+ assert(handle);
+
+ uint8_t count;
+ uint8_t tempCount;
+
+ /* If RX overrun. */
+ if (UART_S1_OR_MASK & base->S1)
+ {
+ /* Read base->D to clear overrun flag, otherwise the RX does not work. */
+ (void)base->D;
+#if defined(FSL_FEATURE_UART_HAS_FIFO) && FSL_FEATURE_UART_HAS_FIFO
+ /* Flush FIFO date, otherwise FIFO pointer will be in unknown state. */
+ base->CFIFO |= UART_CFIFO_RXFLUSH_MASK;
+#endif
+
+ /* Trigger callback. */
+ if (handle->callback)
+ {
+ handle->callback(base, handle, kStatus_UART_RxHardwareOverrun, handle->userData);
+ }
+ }
+
+ /* Receive data register full */
+ if ((UART_S1_RDRF_MASK & base->S1) && (UART_C2_RIE_MASK & base->C2))
+ {
+/* Get the size that can be stored into buffer for this interrupt. */
+#if defined(FSL_FEATURE_UART_HAS_FIFO) && FSL_FEATURE_UART_HAS_FIFO
+ count = base->RCFIFO;
+#else
+ count = 1;
+#endif
+
+ /* If handle->rxDataSize is not 0, first save data to handle->rxData. */
+ while ((count) && (handle->rxDataSize))
+ {
+#if defined(FSL_FEATURE_UART_HAS_FIFO) && FSL_FEATURE_UART_HAS_FIFO
+ tempCount = MIN(handle->rxDataSize, count);
+#else
+ tempCount = 1;
+#endif
+
+ /* Using non block API to read the data from the registers. */
+ UART_ReadNonBlocking(base, handle->rxData, tempCount);
+ handle->rxData += tempCount;
+ handle->rxDataSize -= tempCount;
+ count -= tempCount;
+
+ /* If all the data required for upper layer is ready, trigger callback. */
+ if (!handle->rxDataSize)
+ {
+ handle->rxState = kUART_RxIdle;
+
+ if (handle->callback)
+ {
+ handle->callback(base, handle, kStatus_UART_RxIdle, handle->userData);
+ }
+ }
+ }
+
+ /* If use RX ring buffer, receive data to ring buffer. */
+ if (handle->rxRingBuffer)
+ {
+ while (count--)
+ {
+ /* If RX ring buffer is full, trigger callback to notify over run. */
+ if (UART_TransferIsRxRingBufferFull(handle))
+ {
+ if (handle->callback)
+ {
+ handle->callback(base, handle, kStatus_UART_RxRingBufferOverrun, handle->userData);
+ }
+ }
+
+ /* If ring buffer is still full after callback function, the oldest data is overrided. */
+ if (UART_TransferIsRxRingBufferFull(handle))
+ {
+ /* Increase handle->rxRingBufferTail to make room for new data. */
+ if (handle->rxRingBufferTail + 1U == handle->rxRingBufferSize)
+ {
+ handle->rxRingBufferTail = 0U;
+ }
+ else
+ {
+ handle->rxRingBufferTail++;
+ }
+ }
+
+ /* Read data. */
+ handle->rxRingBuffer[handle->rxRingBufferHead] = base->D;
+
+ /* Increase handle->rxRingBufferHead. */
+ if (handle->rxRingBufferHead + 1U == handle->rxRingBufferSize)
+ {
+ handle->rxRingBufferHead = 0U;
+ }
+ else
+ {
+ handle->rxRingBufferHead++;
+ }
+ }
+ }
+ /* If no receive requst pending, stop RX interrupt. */
+ else if (!handle->rxDataSize)
+ {
+ UART_DisableInterrupts(base, kUART_RxDataRegFullInterruptEnable | kUART_RxOverrunInterruptEnable);
+ }
+ else
+ {
+ }
+ }
+
+ /* Send data register empty and the interrupt is enabled. */
+ if ((base->S1 & UART_S1_TDRE_MASK) && (base->C2 & UART_C2_TIE_MASK))
+ {
+/* Get the bytes that available at this moment. */
+#if defined(FSL_FEATURE_UART_HAS_FIFO) && FSL_FEATURE_UART_HAS_FIFO
+ count = FSL_FEATURE_UART_FIFO_SIZEn(base) - base->TCFIFO;
+#else
+ count = 1;
+#endif
+
+ while ((count) && (handle->txDataSize))
+ {
+#if defined(FSL_FEATURE_UART_HAS_FIFO) && FSL_FEATURE_UART_HAS_FIFO
+ tempCount = MIN(handle->txDataSize, count);
+#else
+ tempCount = 1;
+#endif
+
+ /* Using non block API to write the data to the registers. */
+ UART_WriteNonBlocking(base, handle->txData, tempCount);
+ handle->txData += tempCount;
+ handle->txDataSize -= tempCount;
+ count -= tempCount;
+
+ /* If all the data are written to data register, TX finished. */
+ if (!handle->txDataSize)
+ {
+ handle->txState = kUART_TxIdle;
+
+ /* Disable TX register empty interrupt. */
+ base->C2 = (base->C2 & ~UART_C2_TIE_MASK);
+
+ /* Trigger callback. */
+ if (handle->callback)
+ {
+ handle->callback(base, handle, kStatus_UART_TxIdle, handle->userData);
+ }
+ }
+ }
+ }
+}
+
+void UART_TransferHandleErrorIRQ(UART_Type *base, uart_handle_t *handle)
+{
+ /* To be implemented by User. */
+}
+
+#if defined(UART0)
+#if ((!(defined(FSL_FEATURE_SOC_LPSCI_COUNT))) || \
+ ((defined(FSL_FEATURE_SOC_LPSCI_COUNT)) && (FSL_FEATURE_SOC_LPSCI_COUNT == 0)))
+void UART0_DriverIRQHandler(void)
+{
+ s_uartIsr(UART0, s_uartHandle[0]);
+}
+
+void UART0_RX_TX_DriverIRQHandler(void)
+{
+ UART0_DriverIRQHandler();
+}
+#endif
+#endif
+
+#if defined(UART1)
+void UART1_DriverIRQHandler(void)
+{
+ s_uartIsr(UART1, s_uartHandle[1]);
+}
+
+void UART1_RX_TX_DriverIRQHandler(void)
+{
+ UART1_DriverIRQHandler();
+}
+#endif
+
+#if defined(UART2)
+void UART2_DriverIRQHandler(void)
+{
+ s_uartIsr(UART2, s_uartHandle[2]);
+}
+
+void UART2_RX_TX_DriverIRQHandler(void)
+{
+ UART2_DriverIRQHandler();
+}
+
+#endif
+
+#if defined(UART3)
+void UART3_DriverIRQHandler(void)
+{
+ s_uartIsr(UART3, s_uartHandle[3]);
+}
+
+void UART3_RX_TX_DriverIRQHandler(void)
+{
+ UART3_DriverIRQHandler();
+}
+#endif
+
+#if defined(UART4)
+void UART4_DriverIRQHandler(void)
+{
+ s_uartIsr(UART4, s_uartHandle[4]);
+}
+
+void UART4_RX_TX_DriverIRQHandler(void)
+{
+ UART4_DriverIRQHandler();
+}
+#endif
+
+#if defined(UART5)
+void UART5_DriverIRQHandler(void)
+{
+ s_uartIsr(UART5, s_uartHandle[5]);
+}
+
+void UART5_RX_TX_DriverIRQHandler(void)
+{
+ UART5_DriverIRQHandler();
+}
+#endif
diff --git a/drivers/fsl_uart.h b/drivers/fsl_uart.h
new file mode 100644
index 0000000..16f486a
--- /dev/null
+++ b/drivers/fsl_uart.h
@@ -0,0 +1,774 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_UART_H_
+#define _FSL_UART_H_
+
+#include "fsl_common.h"
+
+/*!
+ * @addtogroup uart_driver
+ * @{
+ */
+
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+/*! @name Driver version */
+/*@{*/
+/*! @brief UART driver version 2.1.1. */
+#define FSL_UART_DRIVER_VERSION (MAKE_VERSION(2, 1, 1))
+/*@}*/
+
+/*! @brief Error codes for the UART driver. */
+enum _uart_status
+{
+ kStatus_UART_TxBusy = MAKE_STATUS(kStatusGroup_UART, 0), /*!< Transmitter is busy. */
+ kStatus_UART_RxBusy = MAKE_STATUS(kStatusGroup_UART, 1), /*!< Receiver is busy. */
+ kStatus_UART_TxIdle = MAKE_STATUS(kStatusGroup_UART, 2), /*!< UART transmitter is idle. */
+ kStatus_UART_RxIdle = MAKE_STATUS(kStatusGroup_UART, 3), /*!< UART receiver is idle. */
+ kStatus_UART_TxWatermarkTooLarge = MAKE_STATUS(kStatusGroup_UART, 4), /*!< TX FIFO watermark too large */
+ kStatus_UART_RxWatermarkTooLarge = MAKE_STATUS(kStatusGroup_UART, 5), /*!< RX FIFO watermark too large */
+ kStatus_UART_FlagCannotClearManually =
+ MAKE_STATUS(kStatusGroup_UART, 6), /*!< UART flag can't be manually cleared. */
+ kStatus_UART_Error = MAKE_STATUS(kStatusGroup_UART, 7), /*!< Error happens on UART. */
+ kStatus_UART_RxRingBufferOverrun = MAKE_STATUS(kStatusGroup_UART, 8), /*!< UART RX software ring buffer overrun. */
+ kStatus_UART_RxHardwareOverrun = MAKE_STATUS(kStatusGroup_UART, 9), /*!< UART RX receiver overrun. */
+ kStatus_UART_NoiseError = MAKE_STATUS(kStatusGroup_UART, 10), /*!< UART noise error. */
+ kStatus_UART_FramingError = MAKE_STATUS(kStatusGroup_UART, 11), /*!< UART framing error. */
+ kStatus_UART_ParityError = MAKE_STATUS(kStatusGroup_UART, 12), /*!< UART parity error. */
+ kStatus_UART_BaudrateNotSupport = MAKE_STATUS(kStatusGroup_UART, 13), /*!< Baudrate is not support in current clock source */
+};
+
+/*! @brief UART parity mode. */
+typedef enum _uart_parity_mode
+{
+ kUART_ParityDisabled = 0x0U, /*!< Parity disabled */
+ kUART_ParityEven = 0x2U, /*!< Parity enabled, type even, bit setting: PE|PT = 10 */
+ kUART_ParityOdd = 0x3U, /*!< Parity enabled, type odd, bit setting: PE|PT = 11 */
+} uart_parity_mode_t;
+
+/*! @brief UART stop bit count. */
+typedef enum _uart_stop_bit_count
+{
+ kUART_OneStopBit = 0U, /*!< One stop bit */
+ kUART_TwoStopBit = 1U, /*!< Two stop bits */
+} uart_stop_bit_count_t;
+
+/*!
+ * @brief UART interrupt configuration structure, default settings all disabled.
+ *
+ * This structure contains the settings for all of the UART interrupt configurations.
+ */
+enum _uart_interrupt_enable
+{
+#if defined(FSL_FEATURE_UART_HAS_LIN_BREAK_DETECT) && FSL_FEATURE_UART_HAS_LIN_BREAK_DETECT
+ kUART_LinBreakInterruptEnable = (UART_BDH_LBKDIE_MASK), /*!< LIN break detect interrupt. */
+#endif
+ kUART_RxActiveEdgeInterruptEnable = (UART_BDH_RXEDGIE_MASK), /*!< RX active edge interrupt. */
+ kUART_TxDataRegEmptyInterruptEnable = (UART_C2_TIE_MASK << 8), /*!< Transmit data register empty interrupt. */
+ kUART_TransmissionCompleteInterruptEnable = (UART_C2_TCIE_MASK << 8), /*!< Transmission complete interrupt. */
+ kUART_RxDataRegFullInterruptEnable = (UART_C2_RIE_MASK << 8), /*!< Receiver data register full interrupt. */
+ kUART_IdleLineInterruptEnable = (UART_C2_ILIE_MASK << 8), /*!< Idle line interrupt. */
+ kUART_RxOverrunInterruptEnable = (UART_C3_ORIE_MASK << 16), /*!< Receiver overrun interrupt. */
+ kUART_NoiseErrorInterruptEnable = (UART_C3_NEIE_MASK << 16), /*!< Noise error flag interrupt. */
+ kUART_FramingErrorInterruptEnable = (UART_C3_FEIE_MASK << 16), /*!< Framing error flag interrupt. */
+ kUART_ParityErrorInterruptEnable = (UART_C3_PEIE_MASK << 16), /*!< Parity error flag interrupt. */
+#if defined(FSL_FEATURE_UART_HAS_FIFO) && FSL_FEATURE_UART_HAS_FIFO
+ kUART_RxFifoOverflowInterruptEnable = (UART_CFIFO_RXOFE_MASK << 24), /*!< RX FIFO overflow interrupt. */
+ kUART_TxFifoOverflowInterruptEnable = (UART_CFIFO_TXOFE_MASK << 24), /*!< TX FIFO overflow interrupt. */
+ kUART_RxFifoUnderflowInterruptEnable = (UART_CFIFO_RXUFE_MASK << 24), /*!< RX FIFO underflow interrupt. */
+#endif
+ kUART_AllInterruptsEnable =
+#if defined(FSL_FEATURE_UART_HAS_LIN_BREAK_DETECT) && FSL_FEATURE_UART_HAS_LIN_BREAK_DETECT
+ kUART_LinBreakInterruptEnable |
+#endif
+ kUART_RxActiveEdgeInterruptEnable | kUART_TxDataRegEmptyInterruptEnable |
+ kUART_TransmissionCompleteInterruptEnable | kUART_RxDataRegFullInterruptEnable |
+ kUART_IdleLineInterruptEnable | kUART_RxOverrunInterruptEnable | kUART_NoiseErrorInterruptEnable |
+ kUART_FramingErrorInterruptEnable | kUART_ParityErrorInterruptEnable
+#if defined(FSL_FEATURE_UART_HAS_FIFO) && FSL_FEATURE_UART_HAS_FIFO
+ | kUART_RxFifoOverflowInterruptEnable | kUART_TxFifoOverflowInterruptEnable
+ | kUART_RxFifoUnderflowInterruptEnable
+#endif
+ ,
+};
+
+/*!
+ * @brief UART status flags.
+ *
+ * This provides constants for the UART status flags for use in the UART functions.
+ */
+enum _uart_flags
+{
+ kUART_TxDataRegEmptyFlag = (UART_S1_TDRE_MASK), /*!< TX data register empty flag. */
+ kUART_TransmissionCompleteFlag = (UART_S1_TC_MASK), /*!< Transmission complete flag. */
+ kUART_RxDataRegFullFlag = (UART_S1_RDRF_MASK), /*!< RX data register full flag. */
+ kUART_IdleLineFlag = (UART_S1_IDLE_MASK), /*!< Idle line detect flag. */
+ kUART_RxOverrunFlag = (UART_S1_OR_MASK), /*!< RX overrun flag. */
+ kUART_NoiseErrorFlag = (UART_S1_NF_MASK), /*!< RX takes 3 samples of each received bit.
+ If any of these samples differ, noise flag sets */
+ kUART_FramingErrorFlag = (UART_S1_FE_MASK), /*!< Frame error flag, sets if logic 0 was detected
+ where stop bit expected */
+ kUART_ParityErrorFlag = (UART_S1_PF_MASK), /*!< If parity enabled, sets upon parity error detection */
+#if defined(FSL_FEATURE_UART_HAS_LIN_BREAK_DETECT) && FSL_FEATURE_UART_HAS_LIN_BREAK_DETECT
+ kUART_LinBreakFlag =
+ (UART_S2_LBKDIF_MASK << 8), /*!< LIN break detect interrupt flag, sets when
+ LIN break char detected and LIN circuit enabled */
+#endif
+ kUART_RxActiveEdgeFlag = (UART_S2_RXEDGIF_MASK << 8), /*!< RX pin active edge interrupt flag,
+ sets when active edge detected */
+ kUART_RxActiveFlag = (UART_S2_RAF_MASK << 8), /*!< Receiver Active Flag (RAF),
+ sets at beginning of valid start bit */
+#if defined(FSL_FEATURE_UART_HAS_EXTENDED_DATA_REGISTER_FLAGS) && FSL_FEATURE_UART_HAS_EXTENDED_DATA_REGISTER_FLAGS
+ kUART_NoiseErrorInRxDataRegFlag = (UART_ED_NOISY_MASK << 16), /*!< Noisy bit, sets if noise detected. */
+ kUART_ParityErrorInRxDataRegFlag = (UART_ED_PARITYE_MASK << 16), /*!< Paritye bit, sets if parity error detected. */
+#endif
+#if defined(FSL_FEATURE_UART_HAS_FIFO) && FSL_FEATURE_UART_HAS_FIFO
+ kUART_TxFifoEmptyFlag = (UART_SFIFO_TXEMPT_MASK << 24), /*!< TXEMPT bit, sets if TX buffer is empty */
+ kUART_RxFifoEmptyFlag = (UART_SFIFO_RXEMPT_MASK << 24), /*!< RXEMPT bit, sets if RX buffer is empty */
+ kUART_TxFifoOverflowFlag = (UART_SFIFO_TXOF_MASK << 24), /*!< TXOF bit, sets if TX buffer overflow occurred */
+ kUART_RxFifoOverflowFlag = (UART_SFIFO_RXOF_MASK << 24), /*!< RXOF bit, sets if receive buffer overflow */
+ kUART_RxFifoUnderflowFlag = (UART_SFIFO_RXUF_MASK << 24), /*!< RXUF bit, sets if receive buffer underflow */
+#endif
+};
+
+/*! @brief UART configuration structure. */
+typedef struct _uart_config
+{
+ uint32_t baudRate_Bps; /*!< UART baud rate */
+ uart_parity_mode_t parityMode; /*!< Parity mode, disabled (default), even, odd */
+#if defined(FSL_FEATURE_UART_HAS_STOP_BIT_CONFIG_SUPPORT) && FSL_FEATURE_UART_HAS_STOP_BIT_CONFIG_SUPPORT
+ uart_stop_bit_count_t stopBitCount; /*!< Number of stop bits, 1 stop bit (default) or 2 stop bits */
+#endif
+#if defined(FSL_FEATURE_UART_HAS_FIFO) && FSL_FEATURE_UART_HAS_FIFO
+ uint8_t txFifoWatermark; /*!< TX FIFO watermark */
+ uint8_t rxFifoWatermark; /*!< RX FIFO watermark */
+#endif
+ bool enableTx; /*!< Enable TX */
+ bool enableRx; /*!< Enable RX */
+} uart_config_t;
+
+/*! @brief UART transfer structure. */
+typedef struct _uart_transfer
+{
+ uint8_t *data; /*!< The buffer of data to be transfer.*/
+ size_t dataSize; /*!< The byte count to be transfer. */
+} uart_transfer_t;
+
+/* Forward declaration of the handle typedef. */
+typedef struct _uart_handle uart_handle_t;
+
+/*! @brief UART transfer callback function. */
+typedef void (*uart_transfer_callback_t)(UART_Type *base, uart_handle_t *handle, status_t status, void *userData);
+
+/*! @brief UART handle structure. */
+struct _uart_handle
+{
+ uint8_t *volatile txData; /*!< Address of remaining data to send. */
+ volatile size_t txDataSize; /*!< Size of the remaining data to send. */
+ size_t txDataSizeAll; /*!< Size of the data to send out. */
+ uint8_t *volatile rxData; /*!< Address of remaining data to receive. */
+ volatile size_t rxDataSize; /*!< Size of the remaining data to receive. */
+ size_t rxDataSizeAll; /*!< Size of the data to receive. */
+
+ uint8_t *rxRingBuffer; /*!< Start address of the receiver ring buffer. */
+ size_t rxRingBufferSize; /*!< Size of the ring buffer. */
+ volatile uint16_t rxRingBufferHead; /*!< Index for the driver to store received data into ring buffer. */
+ volatile uint16_t rxRingBufferTail; /*!< Index for the user to get data from the ring buffer. */
+
+ uart_transfer_callback_t callback; /*!< Callback function. */
+ void *userData; /*!< UART callback function parameter.*/
+
+ volatile uint8_t txState; /*!< TX transfer state. */
+ volatile uint8_t rxState; /*!< RX transfer state */
+};
+
+/*******************************************************************************
+ * API
+ ******************************************************************************/
+
+#if defined(__cplusplus)
+extern "C" {
+#endif /* _cplusplus */
+
+/*!
+ * @name Initialization and deinitialization
+ * @{
+ */
+
+/*!
+ * @brief Initializes a UART instance with user configuration structure and peripheral clock.
+ *
+ * This function configures the UART module with the user-defined settings. The user can configure the configuration
+ * structure and also get the default configuration by using the UART_GetDefaultConfig() function.
+ * Example below shows how to use this API to configure UART.
+ * @code
+ * uart_config_t uartConfig;
+ * uartConfig.baudRate_Bps = 115200U;
+ * uartConfig.parityMode = kUART_ParityDisabled;
+ * uartConfig.stopBitCount = kUART_OneStopBit;
+ * uartConfig.txFifoWatermark = 0;
+ * uartConfig.rxFifoWatermark = 1;
+ * UART_Init(UART1, &uartConfig, 20000000U);
+ * @endcode
+ *
+ * @param base UART peripheral base address.
+ * @param config Pointer to user-defined configuration structure.
+ * @param srcClock_Hz UART clock source frequency in HZ.
+ * @retval kStatus_UART_BaudrateNotSupport Baudrate is not support in current clock source.
+ * @retval kStatus_Success Status UART initialize succeed
+ */
+status_t UART_Init(UART_Type *base, const uart_config_t *config, uint32_t srcClock_Hz);
+
+/*!
+ * @brief Deinitializes a UART instance.
+ *
+ * This function waits for TX complete, disables TX and RX, and disables the UART clock.
+ *
+ * @param base UART peripheral base address.
+ */
+void UART_Deinit(UART_Type *base);
+
+/*!
+ * @brief Gets the default configuration structure.
+ *
+ * This function initializes the UART configuration structure to a default value. The default
+ * values are:
+ * uartConfig->baudRate_Bps = 115200U;
+ * uartConfig->bitCountPerChar = kUART_8BitsPerChar;
+ * uartConfig->parityMode = kUART_ParityDisabled;
+ * uartConfig->stopBitCount = kUART_OneStopBit;
+ * uartConfig->txFifoWatermark = 0;
+ * uartConfig->rxFifoWatermark = 1;
+ * uartConfig->enableTx = false;
+ * uartConfig->enableRx = false;
+ *
+ * @param config Pointer to configuration structure.
+ */
+void UART_GetDefaultConfig(uart_config_t *config);
+
+/*!
+ * @brief Sets the UART instance baud rate.
+ *
+ * This function configures the UART module baud rate. This function is used to update
+ * the UART module baud rate after the UART module is initialized by the UART_Init.
+ * @code
+ * UART_SetBaudRate(UART1, 115200U, 20000000U);
+ * @endcode
+ *
+ * @param base UART peripheral base address.
+ * @param baudRate_Bps UART baudrate to be set.
+ * @param srcClock_Hz UART clock source freqency in HZ.
+ * @retval kStatus_UART_BaudrateNotSupport Baudrate is not support in current clock source.
+ * @retval kStatus_Success Set baudrate succeed
+ */
+status_t UART_SetBaudRate(UART_Type *base, uint32_t baudRate_Bps, uint32_t srcClock_Hz);
+
+/* @} */
+
+/*!
+ * @name Status
+ * @{
+ */
+
+/*!
+ * @brief Get UART status flags.
+ *
+ * This function get all UART status flags, the flags are returned as the logical
+ * OR value of the enumerators @ref _uart_flags. To check a specific status,
+ * compare the return value with enumerators in @ref _uart_flags.
+ * For example, to check whether the TX is empty:
+ * @code
+ * if (kUART_TxDataRegEmptyFlag & UART_GetStatusFlags(UART1))
+ * {
+ * ...
+ * }
+ * @endcode
+ *
+ * @param base UART peripheral base address.
+ * @return UART status flags which are ORed by the enumerators in the _uart_flags.
+ */
+uint32_t UART_GetStatusFlags(UART_Type *base);
+
+/*!
+ * @brief Clears status flags with the provided mask.
+ *
+ * This function clears UART status flags with a provided mask. Automatically cleared flag
+ * can't be cleared by this function.
+ * Some flags can only be cleared or set by hardware itself. These flags are:
+ * kUART_TxDataRegEmptyFlag, kUART_TransmissionCompleteFlag, kUART_RxDataRegFullFlag,
+ * kUART_RxActiveFlag, kUART_NoiseErrorInRxDataRegFlag, kUART_ParityErrorInRxDataRegFlag,
+ * kUART_TxFifoEmptyFlag,kUART_RxFifoEmptyFlag
+ * Note: This API should be called when the Tx/Rx is idle, otherwise it takes no effects.
+ *
+ * @param base UART peripheral base address.
+ * @param mask The status flags to be cleared, it is logical OR value of @ref _uart_flags.
+ * @retval kStatus_UART_FlagCannotClearManually The flag can't be cleared by this function but
+ * it is cleared automatically by hardware.
+ * @retval kStatus_Success Status in the mask are cleared.
+ */
+status_t UART_ClearStatusFlags(UART_Type *base, uint32_t mask);
+
+/* @} */
+
+/*!
+ * @name Interrupts
+ * @{
+ */
+
+/*!
+ * @brief Enables UART interrupts according to the provided mask.
+ *
+ * This function enables the UART interrupts according to the provided mask. The mask
+ * is a logical OR of enumeration members. See @ref _uart_interrupt_enable.
+ * For example, to enable TX empty interrupt and RX full interrupt:
+ * @code
+ * UART_EnableInterrupts(UART1,kUART_TxDataRegEmptyInterruptEnable | kUART_RxDataRegFullInterruptEnable);
+ * @endcode
+ *
+ * @param base UART peripheral base address.
+ * @param mask The interrupts to enable. Logical OR of @ref _uart_interrupt_enable.
+ */
+void UART_EnableInterrupts(UART_Type *base, uint32_t mask);
+
+/*!
+ * @brief Disables the UART interrupts according to the provided mask.
+ *
+ * This function disables the UART interrupts according to the provided mask. The mask
+ * is a logical OR of enumeration members. See @ref _uart_interrupt_enable.
+ * For example, to disable TX empty interrupt and RX full interrupt:
+ * @code
+ * UART_DisableInterrupts(UART1,kUART_TxDataRegEmptyInterruptEnable | kUART_RxDataRegFullInterruptEnable);
+ * @endcode
+ *
+ * @param base UART peripheral base address.
+ * @param mask The interrupts to disable. Logical OR of @ref _uart_interrupt_enable.
+ */
+void UART_DisableInterrupts(UART_Type *base, uint32_t mask);
+
+/*!
+ * @brief Gets the enabled UART interrupts.
+ *
+ * This function gets the enabled UART interrupts. The enabled interrupts are returned
+ * as the logical OR value of the enumerators @ref _uart_interrupt_enable. To check
+ * a specific interrupts enable status, compare the return value with enumerators
+ * in @ref _uart_interrupt_enable.
+ * For example, to check whether TX empty interrupt is enabled:
+ * @code
+ * uint32_t enabledInterrupts = UART_GetEnabledInterrupts(UART1);
+ *
+ * if (kUART_TxDataRegEmptyInterruptEnable & enabledInterrupts)
+ * {
+ * ...
+ * }
+ * @endcode
+ *
+ * @param base UART peripheral base address.
+ * @return UART interrupt flags which are logical OR of the enumerators in @ref _uart_interrupt_enable.
+ */
+uint32_t UART_GetEnabledInterrupts(UART_Type *base);
+
+/* @} */
+
+#if defined(FSL_FEATURE_UART_HAS_DMA_SELECT) && FSL_FEATURE_UART_HAS_DMA_SELECT
+/*!
+ * @name DMA Control
+ * @{
+ */
+
+/*!
+ * @brief Gets the UART data register address.
+ *
+ * This function returns the UART data register address, which is mainly used by DMA/eDMA.
+ *
+ * @param base UART peripheral base address.
+ * @return UART data register address which are used both by transmitter and receiver.
+ */
+static inline uint32_t UART_GetDataRegisterAddress(UART_Type *base)
+{
+ return (uint32_t) & (base->D);
+}
+
+/*!
+ * @brief Enables or disables the UART transmitter DMA request.
+ *
+ * This function enables or disables the transmit data register empty flag, S1[TDRE], to generate the DMA requests.
+ *
+ * @param base UART peripheral base address.
+ * @param enable True to enable, false to disable.
+ */
+static inline void UART_EnableTxDMA(UART_Type *base, bool enable)
+{
+ if (enable)
+ {
+#if (defined(FSL_FEATURE_UART_IS_SCI) && FSL_FEATURE_UART_IS_SCI)
+ base->C4 |= UART_C4_TDMAS_MASK;
+#else
+ base->C5 |= UART_C5_TDMAS_MASK;
+#endif
+ base->C2 |= UART_C2_TIE_MASK;
+ }
+ else
+ {
+#if (defined(FSL_FEATURE_UART_IS_SCI) && FSL_FEATURE_UART_IS_SCI)
+ base->C4 &= ~UART_C4_TDMAS_MASK;
+#else
+ base->C5 &= ~UART_C5_TDMAS_MASK;
+#endif
+ base->C2 &= ~UART_C2_TIE_MASK;
+ }
+}
+
+/*!
+ * @brief Enables or disables the UART receiver DMA.
+ *
+ * This function enables or disables the receiver data register full flag, S1[RDRF], to generate DMA requests.
+ *
+ * @param base UART peripheral base address.
+ * @param enable True to enable, false to disable.
+ */
+static inline void UART_EnableRxDMA(UART_Type *base, bool enable)
+{
+ if (enable)
+ {
+#if (defined(FSL_FEATURE_UART_IS_SCI) && FSL_FEATURE_UART_IS_SCI)
+ base->C4 |= UART_C4_RDMAS_MASK;
+#else
+ base->C5 |= UART_C5_RDMAS_MASK;
+#endif
+ base->C2 |= UART_C2_RIE_MASK;
+ }
+ else
+ {
+#if (defined(FSL_FEATURE_UART_IS_SCI) && FSL_FEATURE_UART_IS_SCI)
+ base->C4 &= ~UART_C4_RDMAS_MASK;
+#else
+ base->C5 &= ~UART_C5_RDMAS_MASK;
+#endif
+ base->C2 &= ~UART_C2_RIE_MASK;
+ }
+}
+
+/* @} */
+#endif /* FSL_FEATURE_UART_HAS_DMA_SELECT */
+
+/*!
+ * @name Bus Operations
+ * @{
+ */
+
+/*!
+ * @brief Enables or disables the UART transmitter.
+ *
+ * This function enables or disables the UART transmitter.
+ *
+ * @param base UART peripheral base address.
+ * @param enable True to enable, false to disable.
+ */
+static inline void UART_EnableTx(UART_Type *base, bool enable)
+{
+ if (enable)
+ {
+ base->C2 |= UART_C2_TE_MASK;
+ }
+ else
+ {
+ base->C2 &= ~UART_C2_TE_MASK;
+ }
+}
+
+/*!
+ * @brief Enables or disables the UART receiver.
+ *
+ * This function enables or disables the UART receiver.
+ *
+ * @param base UART peripheral base address.
+ * @param enable True to enable, false to disable.
+ */
+static inline void UART_EnableRx(UART_Type *base, bool enable)
+{
+ if (enable)
+ {
+ base->C2 |= UART_C2_RE_MASK;
+ }
+ else
+ {
+ base->C2 &= ~UART_C2_RE_MASK;
+ }
+}
+
+/*!
+ * @brief Writes to the TX register.
+ *
+ * This function writes data to the TX register directly. The upper layer must ensure
+ * that the TX register is empty or TX FIFO has empty room before calling this function.
+ *
+ * @param base UART peripheral base address.
+ * @param data The byte to write.
+ */
+static inline void UART_WriteByte(UART_Type *base, uint8_t data)
+{
+ base->D = data;
+}
+
+/*!
+ * @brief Reads the RX register directly.
+ *
+ * This function reads data from the TX register directly. The upper layer must
+ * ensure that the RX register is full or that the TX FIFO has data before calling this function.
+ *
+ * @param base UART peripheral base address.
+ * @return The byte read from UART data register.
+ */
+static inline uint8_t UART_ReadByte(UART_Type *base)
+{
+ return base->D;
+}
+
+/*!
+ * @brief Writes to the TX register using a blocking method.
+ *
+ * This function polls the TX register, waits for the TX register to be empty or for the TX FIFO
+ * to have room and writes data to the TX buffer.
+ *
+ * @note This function does not check whether all the data has been sent out to the bus.
+ * Before disabling the TX, check kUART_TransmissionCompleteFlag to ensure that the TX is
+ * finished.
+ *
+ * @param base UART peripheral base address.
+ * @param data Start address of the data to write.
+ * @param length Size of the data to write.
+ */
+void UART_WriteBlocking(UART_Type *base, const uint8_t *data, size_t length);
+
+/*!
+ * @brief Read RX data register using a blocking method.
+ *
+ * This function polls the RX register, waits for the RX register to be full or for RX FIFO to
+ * have data and read data from the TX register.
+ *
+ * @param base UART peripheral base address.
+ * @param data Start address of the buffer to store the received data.
+ * @param length Size of the buffer.
+ * @retval kStatus_UART_RxHardwareOverrun Receiver overrun happened while receiving data.
+ * @retval kStatus_UART_NoiseError Noise error happened while receiving data.
+ * @retval kStatus_UART_FramingError Framing error happened while receiving data.
+ * @retval kStatus_UART_ParityError Parity error happened while receiving data.
+ * @retval kStatus_Success Successfully received all data.
+ */
+status_t UART_ReadBlocking(UART_Type *base, uint8_t *data, size_t length);
+
+/* @} */
+
+/*!
+ * @name Transactional
+ * @{
+ */
+
+/*!
+ * @brief Initializes the UART handle.
+ *
+ * This function initializes the UART handle which can be used for other UART
+ * transactional APIs. Usually, for a specified UART instance,
+ * call this API once to get the initialized handle.
+ *
+ * @param base UART peripheral base address.
+ * @param handle UART handle pointer.
+ * @param callback The callback function.
+ * @param userData The parameter of the callback function.
+ */
+void UART_TransferCreateHandle(UART_Type *base,
+ uart_handle_t *handle,
+ uart_transfer_callback_t callback,
+ void *userData);
+
+/*!
+ * @brief Sets up the RX ring buffer.
+ *
+ * This function sets up the RX ring buffer to a specific UART handle.
+ *
+ * When the RX ring buffer is used, data received are stored into the ring buffer even when the
+ * user doesn't call the UART_TransferReceiveNonBlocking() API. If there is already data received
+ * in the ring buffer, the user can get the received data from the ring buffer directly.
+ *
+ * @note When using the RX ring buffer, one byte is reserved for internal use. In other
+ * words, if @p ringBufferSize is 32, then only 31 bytes are used for saving data.
+ *
+ * @param base UART peripheral base address.
+ * @param handle UART handle pointer.
+ * @param ringBuffer Start address of the ring buffer for background receiving. Pass NULL to disable the ring buffer.
+ * @param ringBufferSize size of the ring buffer.
+ */
+void UART_TransferStartRingBuffer(UART_Type *base, uart_handle_t *handle, uint8_t *ringBuffer, size_t ringBufferSize);
+
+/*!
+ * @brief Aborts the background transfer and uninstalls the ring buffer.
+ *
+ * This function aborts the background transfer and uninstalls the ring buffer.
+ *
+ * @param base UART peripheral base address.
+ * @param handle UART handle pointer.
+ */
+void UART_TransferStopRingBuffer(UART_Type *base, uart_handle_t *handle);
+
+/*!
+ * @brief Transmits a buffer of data using the interrupt method.
+ *
+ * This function sends data using an interrupt method. This is a non-blocking function, which
+ * returns directly without waiting for all data to be written to the TX register. When
+ * all data is written to the TX register in the ISR, the UART driver calls the callback
+ * function and passes the @ref kStatus_UART_TxIdle as status parameter.
+ *
+ * @note The kStatus_UART_TxIdle is passed to the upper layer when all data is written
+ * to the TX register. However it does not ensure that all data are sent out. Before disabling the TX,
+ * check the kUART_TransmissionCompleteFlag to ensure that the TX is finished.
+ *
+ * @param base UART peripheral base address.
+ * @param handle UART handle pointer.
+ * @param xfer UART transfer structure. See #uart_transfer_t.
+ * @retval kStatus_Success Successfully start the data transmission.
+ * @retval kStatus_UART_TxBusy Previous transmission still not finished, data not all written to TX register yet.
+ * @retval kStatus_InvalidArgument Invalid argument.
+ */
+status_t UART_TransferSendNonBlocking(UART_Type *base, uart_handle_t *handle, uart_transfer_t *xfer);
+
+/*!
+ * @brief Aborts the interrupt driven data transmit.
+ *
+ * This function aborts the interrupt driven data sending. The user can get the remainBytes to find out
+ * how many bytes are still not sent out.
+ *
+ * @param base UART peripheral base address.
+ * @param handle UART handle pointer.
+ */
+void UART_TransferAbortSend(UART_Type *base, uart_handle_t *handle);
+
+/*!
+ * @brief Get the number of bytes that have been written to UART TX register.
+ *
+ * This function gets the number of bytes that have been written to UART TX
+ * register by interrupt method.
+ *
+ * @param base UART peripheral base address.
+ * @param handle UART handle pointer.
+ * @param count Send bytes count.
+ * @retval kStatus_NoTransferInProgress No send in progress.
+ * @retval kStatus_InvalidArgument Parameter is invalid.
+ * @retval kStatus_Success Get successfully through the parameter \p count;
+ */
+status_t UART_TransferGetSendCount(UART_Type *base, uart_handle_t *handle, uint32_t *count);
+
+/*!
+ * @brief Receives a buffer of data using an interrupt method.
+ *
+ * This function receives data using an interrupt method. This is a non-blocking function, which
+ * returns without waiting for all data to be received.
+ * If the RX ring buffer is used and not empty, the data in the ring buffer is copied and
+ * the parameter @p receivedBytes shows how many bytes are copied from the ring buffer.
+ * After copying, if the data in the ring buffer is not enough to read, the receive
+ * request is saved by the UART driver. When the new data arrives, the receive request
+ * is serviced first. When all data is received, the UART driver notifies the upper layer
+ * through a callback function and passes the status parameter @ref kStatus_UART_RxIdle.
+ * For example, the upper layer needs 10 bytes but there are only 5 bytes in the ring buffer.
+ * The 5 bytes are copied to the xfer->data and this function returns with the
+ * parameter @p receivedBytes set to 5. For the left 5 bytes, newly arrived data is
+ * saved from the xfer->data[5]. When 5 bytes are received, the UART driver notifies the upper layer.
+ * If the RX ring buffer is not enabled, this function enables the RX and RX interrupt
+ * to receive data to the xfer->data. When all data is received, the upper layer is notified.
+ *
+ * @param base UART peripheral base address.
+ * @param handle UART handle pointer.
+ * @param xfer UART transfer structure, see #uart_transfer_t.
+ * @param receivedBytes Bytes received from the ring buffer directly.
+ * @retval kStatus_Success Successfully queue the transfer into transmit queue.
+ * @retval kStatus_UART_RxBusy Previous receive request is not finished.
+ * @retval kStatus_InvalidArgument Invalid argument.
+ */
+status_t UART_TransferReceiveNonBlocking(UART_Type *base,
+ uart_handle_t *handle,
+ uart_transfer_t *xfer,
+ size_t *receivedBytes);
+
+/*!
+ * @brief Aborts the interrupt-driven data receiving.
+ *
+ * This function aborts the interrupt-driven data receiving. The user can get the remainBytes to know
+ * how many bytes not received yet.
+ *
+ * @param base UART peripheral base address.
+ * @param handle UART handle pointer.
+ */
+void UART_TransferAbortReceive(UART_Type *base, uart_handle_t *handle);
+
+/*!
+ * @brief Get the number of bytes that have been received.
+ *
+ * This function gets the number of bytes that have been received.
+ *
+ * @param base UART peripheral base address.
+ * @param handle UART handle pointer.
+ * @param count Receive bytes count.
+ * @retval kStatus_NoTransferInProgress No receive in progress.
+ * @retval kStatus_InvalidArgument Parameter is invalid.
+ * @retval kStatus_Success Get successfully through the parameter \p count;
+ */
+status_t UART_TransferGetReceiveCount(UART_Type *base, uart_handle_t *handle, uint32_t *count);
+
+/*!
+ * @brief UART IRQ handle function.
+ *
+ * This function handles the UART transmit and receive IRQ request.
+ *
+ * @param base UART peripheral base address.
+ * @param handle UART handle pointer.
+ */
+void UART_TransferHandleIRQ(UART_Type *base, uart_handle_t *handle);
+
+/*!
+ * @brief UART Error IRQ handle function.
+ *
+ * This function handle the UART error IRQ request.
+ *
+ * @param base UART peripheral base address.
+ * @param handle UART handle pointer.
+ */
+void UART_TransferHandleErrorIRQ(UART_Type *base, uart_handle_t *handle);
+
+/* @} */
+
+#if defined(__cplusplus)
+}
+#endif
+
+/*! @}*/
+
+#endif /* _FSL_UART_H_ */
diff --git a/drivers/fsl_uart_edma.c b/drivers/fsl_uart_edma.c
new file mode 100644
index 0000000..a4faa94
--- /dev/null
+++ b/drivers/fsl_uart_edma.c
@@ -0,0 +1,358 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_uart_edma.h"
+#include "fsl_dmamux.h"
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+/* Array of UART handle. */
+#if (defined(UART5))
+#define UART_HANDLE_ARRAY_SIZE 6
+#else /* UART5 */
+#if (defined(UART4))
+#define UART_HANDLE_ARRAY_SIZE 5
+#else /* UART4 */
+#if (defined(UART3))
+#define UART_HANDLE_ARRAY_SIZE 4
+#else /* UART3 */
+#if (defined(UART2))
+#define UART_HANDLE_ARRAY_SIZE 3
+#else /* UART2 */
+#if (defined(UART1))
+#define UART_HANDLE_ARRAY_SIZE 2
+#else /* UART1 */
+#if (defined(UART0))
+#define UART_HANDLE_ARRAY_SIZE 1
+#else /* UART0 */
+#error No UART instance.
+#endif /* UART 0 */
+#endif /* UART 1 */
+#endif /* UART 2 */
+#endif /* UART 3 */
+#endif /* UART 4 */
+#endif /* UART 5 */
+
+/*<! Structure definition for uart_edma_private_handle_t. The structure is private. */
+typedef struct _uart_edma_private_handle
+{
+ UART_Type *base;
+ uart_edma_handle_t *handle;
+} uart_edma_private_handle_t;
+
+/* UART EDMA transfer handle. */
+enum _uart_edma_tansfer_states
+{
+ kUART_TxIdle, /* TX idle. */
+ kUART_TxBusy, /* TX busy. */
+ kUART_RxIdle, /* RX idle. */
+ kUART_RxBusy /* RX busy. */
+};
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+/*<! Private handle only used for internally. */
+static uart_edma_private_handle_t s_edmaPrivateHandle[UART_HANDLE_ARRAY_SIZE];
+
+/*******************************************************************************
+ * Prototypes
+ ******************************************************************************/
+
+/*!
+ * @brief UART EDMA send finished callback function.
+ *
+ * This function is called when UART EDMA send finished. It disables the UART
+ * TX EDMA request and sends @ref kStatus_UART_TxIdle to UART callback.
+ *
+ * @param handle The EDMA handle.
+ * @param param Callback function parameter.
+ */
+static void UART_SendEDMACallback(edma_handle_t *handle, void *param, bool transferDone, uint32_t tcds);
+
+/*!
+ * @brief UART EDMA receive finished callback function.
+ *
+ * This function is called when UART EDMA receive finished. It disables the UART
+ * RX EDMA request and sends @ref kStatus_UART_RxIdle to UART callback.
+ *
+ * @param handle The EDMA handle.
+ * @param param Callback function parameter.
+ */
+static void UART_ReceiveEDMACallback(edma_handle_t *handle, void *param, bool transferDone, uint32_t tcds);
+
+/*!
+ * @brief Get the UART instance from peripheral base address.
+ *
+ * @param base UART peripheral base address.
+ * @return UART instance.
+ */
+extern uint32_t UART_GetInstance(UART_Type *base);
+
+/*******************************************************************************
+ * Code
+ ******************************************************************************/
+
+static void UART_SendEDMACallback(edma_handle_t *handle, void *param, bool transferDone, uint32_t tcds)
+{
+ assert(param);
+
+ uart_edma_private_handle_t *uartPrivateHandle = (uart_edma_private_handle_t *)param;
+
+ /* Avoid the warning for unused variables. */
+ handle = handle;
+ tcds = tcds;
+
+ if (transferDone)
+ {
+ UART_TransferAbortSendEDMA(uartPrivateHandle->base, uartPrivateHandle->handle);
+
+ if (uartPrivateHandle->handle->callback)
+ {
+ uartPrivateHandle->handle->callback(uartPrivateHandle->base, uartPrivateHandle->handle, kStatus_UART_TxIdle,
+ uartPrivateHandle->handle->userData);
+ }
+ }
+}
+
+static void UART_ReceiveEDMACallback(edma_handle_t *handle, void *param, bool transferDone, uint32_t tcds)
+{
+ assert(param);
+
+ uart_edma_private_handle_t *uartPrivateHandle = (uart_edma_private_handle_t *)param;
+
+ /* Avoid warning for unused parameters. */
+ handle = handle;
+ tcds = tcds;
+
+ if (transferDone)
+ {
+ /* Disable transfer. */
+ UART_TransferAbortReceiveEDMA(uartPrivateHandle->base, uartPrivateHandle->handle);
+
+ if (uartPrivateHandle->handle->callback)
+ {
+ uartPrivateHandle->handle->callback(uartPrivateHandle->base, uartPrivateHandle->handle, kStatus_UART_RxIdle,
+ uartPrivateHandle->handle->userData);
+ }
+ }
+}
+
+void UART_TransferCreateHandleEDMA(UART_Type *base,
+ uart_edma_handle_t *handle,
+ uart_edma_transfer_callback_t callback,
+ void *userData,
+ edma_handle_t *txEdmaHandle,
+ edma_handle_t *rxEdmaHandle)
+{
+ assert(handle);
+
+ uint32_t instance = UART_GetInstance(base);
+
+ s_edmaPrivateHandle[instance].base = base;
+ s_edmaPrivateHandle[instance].handle = handle;
+
+ memset(handle, 0, sizeof(*handle));
+
+ handle->rxState = kUART_RxIdle;
+ handle->txState = kUART_TxIdle;
+
+ handle->rxEdmaHandle = rxEdmaHandle;
+ handle->txEdmaHandle = txEdmaHandle;
+
+ handle->callback = callback;
+ handle->userData = userData;
+
+#if defined(FSL_FEATURE_UART_HAS_FIFO) && FSL_FEATURE_UART_HAS_FIFO
+ /* Note:
+ Take care of the RX FIFO, EDMA request only assert when received bytes
+ equal or more than RX water mark, there is potential issue if RX water
+ mark larger than 1.
+ For example, if RX FIFO water mark is 2, upper layer needs 5 bytes and
+ 5 bytes are received. the last byte will be saved in FIFO but not trigger
+ EDMA transfer because the water mark is 2.
+ */
+ if (rxEdmaHandle)
+ {
+ base->RWFIFO = 1U;
+ }
+#endif
+
+ /* Configure TX. */
+ if (txEdmaHandle)
+ {
+ EDMA_SetCallback(handle->txEdmaHandle, UART_SendEDMACallback, &s_edmaPrivateHandle[instance]);
+ }
+
+ /* Configure RX. */
+ if (rxEdmaHandle)
+ {
+ EDMA_SetCallback(handle->rxEdmaHandle, UART_ReceiveEDMACallback, &s_edmaPrivateHandle[instance]);
+ }
+}
+
+status_t UART_SendEDMA(UART_Type *base, uart_edma_handle_t *handle, uart_transfer_t *xfer)
+{
+ assert(handle);
+ assert(handle->txEdmaHandle);
+ assert(xfer);
+ assert(xfer->data);
+ assert(xfer->dataSize);
+
+ edma_transfer_config_t xferConfig;
+ status_t status;
+
+ /* If previous TX not finished. */
+ if (kUART_TxBusy == handle->txState)
+ {
+ status = kStatus_UART_TxBusy;
+ }
+ else
+ {
+ handle->txState = kUART_TxBusy;
+ handle->txDataSizeAll = xfer->dataSize;
+
+ /* Prepare transfer. */
+ EDMA_PrepareTransfer(&xferConfig, xfer->data, sizeof(uint8_t), (void *)UART_GetDataRegisterAddress(base),
+ sizeof(uint8_t), sizeof(uint8_t), xfer->dataSize, kEDMA_MemoryToPeripheral);
+
+ /* Submit transfer. */
+ EDMA_SubmitTransfer(handle->txEdmaHandle, &xferConfig);
+ EDMA_StartTransfer(handle->txEdmaHandle);
+
+ /* Enable UART TX EDMA. */
+ UART_EnableTxDMA(base, true);
+
+ status = kStatus_Success;
+ }
+
+ return status;
+}
+
+status_t UART_ReceiveEDMA(UART_Type *base, uart_edma_handle_t *handle, uart_transfer_t *xfer)
+{
+ assert(handle);
+ assert(handle->rxEdmaHandle);
+ assert(xfer);
+ assert(xfer->data);
+ assert(xfer->dataSize);
+
+ edma_transfer_config_t xferConfig;
+ status_t status;
+
+ /* If previous RX not finished. */
+ if (kUART_RxBusy == handle->rxState)
+ {
+ status = kStatus_UART_RxBusy;
+ }
+ else
+ {
+ handle->rxState = kUART_RxBusy;
+ handle->rxDataSizeAll = xfer->dataSize;
+
+ /* Prepare transfer. */
+ EDMA_PrepareTransfer(&xferConfig, (void *)UART_GetDataRegisterAddress(base), sizeof(uint8_t), xfer->data,
+ sizeof(uint8_t), sizeof(uint8_t), xfer->dataSize, kEDMA_PeripheralToMemory);
+
+ /* Submit transfer. */
+ EDMA_SubmitTransfer(handle->rxEdmaHandle, &xferConfig);
+ EDMA_StartTransfer(handle->rxEdmaHandle);
+
+ /* Enable UART RX EDMA. */
+ UART_EnableRxDMA(base, true);
+
+ status = kStatus_Success;
+ }
+
+ return status;
+}
+
+void UART_TransferAbortSendEDMA(UART_Type *base, uart_edma_handle_t *handle)
+{
+ assert(handle);
+ assert(handle->txEdmaHandle);
+
+ /* Disable UART TX EDMA. */
+ UART_EnableTxDMA(base, false);
+
+ /* Stop transfer. */
+ EDMA_AbortTransfer(handle->txEdmaHandle);
+
+ handle->txState = kUART_TxIdle;
+}
+
+void UART_TransferAbortReceiveEDMA(UART_Type *base, uart_edma_handle_t *handle)
+{
+ assert(handle);
+ assert(handle->rxEdmaHandle);
+
+ /* Disable UART RX EDMA. */
+ UART_EnableRxDMA(base, false);
+
+ /* Stop transfer. */
+ EDMA_AbortTransfer(handle->rxEdmaHandle);
+
+ handle->rxState = kUART_RxIdle;
+}
+
+status_t UART_TransferGetReceiveCountEDMA(UART_Type *base, uart_edma_handle_t *handle, uint32_t *count)
+{
+ assert(handle);
+ assert(handle->rxEdmaHandle);
+ assert(count);
+
+ if (kUART_RxIdle == handle->rxState)
+ {
+ return kStatus_NoTransferInProgress;
+ }
+
+ *count = handle->rxDataSizeAll - EDMA_GetRemainingBytes(handle->rxEdmaHandle->base, handle->rxEdmaHandle->channel);
+
+ return kStatus_Success;
+}
+
+status_t UART_TransferGetSendCountEDMA(UART_Type *base, uart_edma_handle_t *handle, uint32_t *count)
+{
+ assert(handle);
+ assert(handle->txEdmaHandle);
+ assert(count);
+
+ if (kUART_TxIdle == handle->txState)
+ {
+ return kStatus_NoTransferInProgress;
+ }
+
+ *count = handle->txDataSizeAll - EDMA_GetRemainingBytes(handle->txEdmaHandle->base, handle->txEdmaHandle->channel);
+
+ return kStatus_Success;
+}
diff --git a/drivers/fsl_uart_edma.h b/drivers/fsl_uart_edma.h
new file mode 100644
index 0000000..ea0974a
--- /dev/null
+++ b/drivers/fsl_uart_edma.h
@@ -0,0 +1,189 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_UART_EDMA_H_
+#define _FSL_UART_EDMA_H_
+
+#include "fsl_uart.h"
+#include "fsl_dmamux.h"
+#include "fsl_edma.h"
+
+/*!
+ * @addtogroup uart_edma_driver
+ * @{
+ */
+
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+/* Forward declaration of the handle typedef. */
+typedef struct _uart_edma_handle uart_edma_handle_t;
+
+/*! @brief UART transfer callback function. */
+typedef void (*uart_edma_transfer_callback_t)(UART_Type *base,
+ uart_edma_handle_t *handle,
+ status_t status,
+ void *userData);
+
+/*!
+* @brief UART eDMA handle
+*/
+struct _uart_edma_handle
+{
+ uart_edma_transfer_callback_t callback; /*!< Callback function. */
+ void *userData; /*!< UART callback function parameter.*/
+ size_t rxDataSizeAll; /*!< Size of the data to receive. */
+ size_t txDataSizeAll; /*!< Size of the data to send out. */
+
+ edma_handle_t *txEdmaHandle; /*!< The eDMA TX channel used. */
+ edma_handle_t *rxEdmaHandle; /*!< The eDMA RX channel used. */
+
+ volatile uint8_t txState; /*!< TX transfer state. */
+ volatile uint8_t rxState; /*!< RX transfer state */
+};
+
+/*******************************************************************************
+ * API
+ ******************************************************************************/
+
+#if defined(__cplusplus)
+extern "C" {
+#endif
+
+/*!
+ * @name eDMA transactional
+ * @{
+ */
+
+/*!
+ * @brief Initializes the UART handle which is used in transactional functions.
+ * @param base UART peripheral base address.
+ * @param handle Pointer to uart_edma_handle_t structure.
+ * @param callback UART callback, NULL means no callback.
+ * @param userData User callback function data.
+ * @param rxEdmaHandle User requested DMA handle for RX DMA transfer.
+ * @param txEdmaHandle User requested DMA handle for TX DMA transfer.
+ */
+void UART_TransferCreateHandleEDMA(UART_Type *base,
+ uart_edma_handle_t *handle,
+ uart_edma_transfer_callback_t callback,
+ void *userData,
+ edma_handle_t *txEdmaHandle,
+ edma_handle_t *rxEdmaHandle);
+
+/*!
+ * @brief Sends data using eDMA.
+ *
+ * This function sends data using eDMA. This is a non-blocking function, which returns
+ * right away. When all data is sent, the send callback function is called.
+ *
+ * @param base UART peripheral base address.
+ * @param handle UART handle pointer.
+ * @param xfer UART eDMA transfer structure. See #uart_transfer_t.
+ * @retval kStatus_Success if succeed, others failed.
+ * @retval kStatus_UART_TxBusy Previous transfer on going.
+ * @retval kStatus_InvalidArgument Invalid argument.
+ */
+status_t UART_SendEDMA(UART_Type *base, uart_edma_handle_t *handle, uart_transfer_t *xfer);
+
+/*!
+ * @brief Receive data using eDMA.
+ *
+ * This function receives data using eDMA. This is a non-blocking function, which returns
+ * right away. When all data is received, the receive callback function is called.
+ *
+ * @param base UART peripheral base address.
+ * @param handle Pointer to uart_edma_handle_t structure.
+ * @param xfer UART eDMA transfer structure. See #uart_transfer_t.
+ * @retval kStatus_Success if succeed, others failed.
+ * @retval kStatus_UART_RxBusy Previous transfer on going.
+ * @retval kStatus_InvalidArgument Invalid argument.
+ */
+status_t UART_ReceiveEDMA(UART_Type *base, uart_edma_handle_t *handle, uart_transfer_t *xfer);
+
+/*!
+ * @brief Aborts the sent data using eDMA.
+ *
+ * This function aborts sent data using eDMA.
+ *
+ * @param base UART peripheral base address.
+ * @param handle Pointer to uart_edma_handle_t structure.
+ */
+void UART_TransferAbortSendEDMA(UART_Type *base, uart_edma_handle_t *handle);
+
+/*!
+ * @brief Aborts the receive data using eDMA.
+ *
+ * This function aborts receive data using eDMA.
+ *
+ * @param base UART peripheral base address.
+ * @param handle Pointer to uart_edma_handle_t structure.
+ */
+void UART_TransferAbortReceiveEDMA(UART_Type *base, uart_edma_handle_t *handle);
+
+/*!
+ * @brief Get the number of bytes that have been written to UART TX register.
+ *
+ * This function gets the number of bytes that have been written to UART TX
+ * register by DMA.
+ *
+ * @param base UART peripheral base address.
+ * @param handle UART handle pointer.
+ * @param count Send bytes count.
+ * @retval kStatus_NoTransferInProgress No send in progress.
+ * @retval kStatus_InvalidArgument Parameter is invalid.
+ * @retval kStatus_Success Get successfully through the parameter \p count;
+ */
+status_t UART_TransferGetSendCountEDMA(UART_Type *base, uart_edma_handle_t *handle, uint32_t *count);
+
+/*!
+ * @brief Get the number of bytes that have been received.
+ *
+ * This function gets the number of bytes that have been received.
+ *
+ * @param base UART peripheral base address.
+ * @param handle UART handle pointer.
+ * @param count Receive bytes count.
+ * @retval kStatus_NoTransferInProgress No receive in progress.
+ * @retval kStatus_InvalidArgument Parameter is invalid.
+ * @retval kStatus_Success Get successfully through the parameter \p count;
+ */
+status_t UART_TransferGetReceiveCountEDMA(UART_Type *base, uart_edma_handle_t *handle, uint32_t *count);
+
+/*@}*/
+
+#if defined(__cplusplus)
+}
+#endif
+
+/*! @}*/
+
+#endif /* _FSL_UART_EDMA_H_ */
diff --git a/drivers/fsl_vref.c b/drivers/fsl_vref.c
new file mode 100644
index 0000000..248132c
--- /dev/null
+++ b/drivers/fsl_vref.c
@@ -0,0 +1,224 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_vref.h"
+
+/*******************************************************************************
+ * Prototypes
+ ******************************************************************************/
+
+/*!
+ * @brief Gets the instance from the base address
+ *
+ * @param base VREF peripheral base address
+ *
+ * @return The VREF instance
+ */
+static uint32_t VREF_GetInstance(VREF_Type *base);
+
+/*******************************************************************************
+ * Variables
+ ******************************************************************************/
+
+/*! @brief Pointers to VREF bases for each instance. */
+static VREF_Type *const s_vrefBases[] = VREF_BASE_PTRS;
+
+/*! @brief Pointers to VREF clocks for each instance. */
+static const clock_ip_name_t s_vrefClocks[] = VREF_CLOCKS;
+
+/*******************************************************************************
+ * Code
+ ******************************************************************************/
+
+static uint32_t VREF_GetInstance(VREF_Type *base)
+{
+ uint32_t instance;
+
+ /* Find the instance index from base address mappings. */
+ for (instance = 0; instance < FSL_FEATURE_SOC_VREF_COUNT; instance++)
+ {
+ if (s_vrefBases[instance] == base)
+ {
+ break;
+ }
+ }
+
+ assert(instance < FSL_FEATURE_SOC_VREF_COUNT);
+
+ return instance;
+}
+
+void VREF_Init(VREF_Type *base, const vref_config_t *config)
+{
+ assert(config != NULL);
+
+ uint8_t reg = 0U;
+
+ /* Ungate clock for VREF */
+ CLOCK_EnableClock(s_vrefClocks[VREF_GetInstance(base)]);
+
+/* Configure VREF to a known state */
+#if defined(FSL_FEATURE_VREF_HAS_CHOP_OSC) && FSL_FEATURE_VREF_HAS_CHOP_OSC
+ /* Set chop oscillator bit */
+ base->TRM |= VREF_TRM_CHOPEN_MASK;
+#endif /* FSL_FEATURE_VREF_HAS_CHOP_OSC */
+ /* Get current SC register */
+#if defined(FSL_FEATURE_VREF_HAS_LOW_REFERENCE) && FSL_FEATURE_VREF_HAS_LOW_REFERENCE
+ reg = base->VREFH_SC;
+#else
+ reg = base->SC;
+#endif/* FSL_FEATURE_VREF_HAS_LOW_REFERENCE */
+ /* Clear old buffer mode selection bits */
+ reg &= ~VREF_SC_MODE_LV_MASK;
+ /* Set buffer Mode selection and Regulator enable bit */
+ reg |= VREF_SC_MODE_LV(config->bufferMode) | VREF_SC_REGEN(1U);
+#if defined(FSL_FEATURE_VREF_HAS_COMPENSATION) && FSL_FEATURE_VREF_HAS_COMPENSATION
+ /* Set second order curvature compensation enable bit */
+ reg |= VREF_SC_ICOMPEN(1U);
+#endif /* FSL_FEATURE_VREF_HAS_COMPENSATION */
+ /* Enable VREF module */
+ reg |= VREF_SC_VREFEN(1U);
+ /* Update bit-field from value to Status and Control register */
+#if defined(FSL_FEATURE_VREF_HAS_LOW_REFERENCE) && FSL_FEATURE_VREF_HAS_LOW_REFERENCE
+ base->VREFH_SC = reg;
+#else
+ base->SC = reg;
+#endif/* FSL_FEATURE_VREF_HAS_LOW_REFERENCE */
+#if defined(FSL_FEATURE_VREF_HAS_LOW_REFERENCE) && FSL_FEATURE_VREF_HAS_LOW_REFERENCE
+ reg = base->VREFL_TRM;
+ /* Clear old select external voltage reference and VREFL (0.4 V) reference buffer enable bits */
+ reg &= ~(VREF_VREFL_TRM_VREFL_EN_MASK | VREF_VREFL_TRM_VREFL_SEL_MASK);
+ /* Select external voltage reference and set VREFL (0.4 V) reference buffer enable */
+ reg |= VREF_VREFL_TRM_VREFL_SEL(config->enableExternalVoltRef) | VREF_VREFL_TRM_VREFL_EN(config->enableLowRef);
+ base->VREFL_TRM = reg;
+#endif /* FSL_FEATURE_VREF_HAS_LOW_REFERENCE */
+
+#if defined(FSL_FEATURE_VREF_HAS_TRM4) && FSL_FEATURE_VREF_HAS_TRM4
+ reg = base->TRM4;
+ /* Clear old select internal voltage reference bit (2.1V) */
+ reg &= ~VREF_TRM4_VREF2V1_EN_MASK;
+ /* Select internal voltage reference (2.1V) */
+ reg |= VREF_TRM4_VREF2V1_EN(config->enable2V1VoltRef);
+ base->TRM4 = reg;
+#endif /* FSL_FEATURE_VREF_HAS_TRM4 */
+
+ /* Wait until internal voltage stable */
+#if defined(FSL_FEATURE_VREF_HAS_LOW_REFERENCE) && FSL_FEATURE_VREF_HAS_LOW_REFERENCE
+ while ((base->VREFH_SC & VREF_SC_VREFST_MASK) == 0)
+#else
+ while ((base->SC & VREF_SC_VREFST_MASK) == 0)
+#endif/* FSL_FEATURE_VREF_HAS_LOW_REFERENCE */
+ {
+ }
+}
+
+void VREF_Deinit(VREF_Type *base)
+{
+ /* Gate clock for VREF */
+ CLOCK_DisableClock(s_vrefClocks[VREF_GetInstance(base)]);
+}
+
+void VREF_GetDefaultConfig(vref_config_t *config)
+{
+ assert(config);
+
+/* Set High power buffer mode in */
+#if defined(FSL_FEATURE_VREF_MODE_LV_TYPE) && FSL_FEATURE_VREF_MODE_LV_TYPE
+ config->bufferMode = kVREF_ModeHighPowerBuffer;
+#else
+ config->bufferMode = kVREF_ModeTightRegulationBuffer;
+#endif /* FSL_FEATURE_VREF_MODE_LV_TYPE */
+
+#if defined(FSL_FEATURE_VREF_HAS_LOW_REFERENCE) && FSL_FEATURE_VREF_HAS_LOW_REFERENCE
+ /* Select internal voltage reference */
+ config->enableExternalVoltRef = false;
+ /* Set VREFL (0.4 V) reference buffer disable */
+ config->enableLowRef = false;
+#endif /* FSL_FEATURE_VREF_HAS_LOW_REFERENCE */
+
+#if defined(FSL_FEATURE_VREF_HAS_TRM4) && FSL_FEATURE_VREF_HAS_TRM4
+ /* Disable internal voltage reference (2.1V) */
+ config->enable2V1VoltRef = false;
+#endif /* FSL_FEATURE_VREF_HAS_TRM4 */
+}
+
+void VREF_SetTrimVal(VREF_Type *base, uint8_t trimValue)
+{
+ uint8_t reg = 0U;
+
+ /* Set TRIM bits value in voltage reference */
+ reg = base->TRM;
+ reg = ((reg & ~VREF_TRM_TRIM_MASK) | VREF_TRM_TRIM(trimValue));
+ base->TRM = reg;
+ /* Wait until internal voltage stable */
+#if defined(FSL_FEATURE_VREF_HAS_LOW_REFERENCE) && FSL_FEATURE_VREF_HAS_LOW_REFERENCE
+ while ((base->VREFH_SC & VREF_SC_VREFST_MASK) == 0)
+#else
+ while ((base->SC & VREF_SC_VREFST_MASK) == 0)
+#endif/* FSL_FEATURE_VREF_HAS_LOW_REFERENCE */
+ {
+ }
+}
+
+#if defined(FSL_FEATURE_VREF_HAS_TRM4) && FSL_FEATURE_VREF_HAS_TRM4
+void VREF_SetTrim2V1Val(VREF_Type *base, uint8_t trimValue)
+{
+ uint8_t reg = 0U;
+
+ /* Set TRIM bits value in voltage reference (2V1) */
+ reg = base->TRM4;
+ reg = ((reg & ~VREF_TRM4_TRIM2V1_MASK) | VREF_TRM4_TRIM2V1(trimValue));
+ base->TRM4 = reg;
+ /* Wait until internal voltage stable */
+ while ((base->SC & VREF_SC_VREFST_MASK) == 0)
+ {
+ }
+}
+#endif /* FSL_FEATURE_VREF_HAS_TRM4 */
+
+#if defined(FSL_FEATURE_VREF_HAS_LOW_REFERENCE) && FSL_FEATURE_VREF_HAS_LOW_REFERENCE
+void VREF_SetLowReferenceTrimVal(VREF_Type *base, uint8_t trimValue)
+{
+ /* The values 111b and 110b are NOT valid/allowed */
+ assert((trimValue != 0x7U) && (trimValue != 0x6U));
+
+ uint8_t reg = 0U;
+
+ /* Set TRIM bits value in low voltage reference */
+ reg = base->VREFL_TRM;
+ reg = ((reg & ~VREF_VREFL_TRM_VREFL_TRIM_MASK) | VREF_VREFL_TRM_VREFL_TRIM(trimValue));
+ base->VREFL_TRM = reg;
+ /* Wait until internal voltage stable */
+
+ while ((base->VREFH_SC & VREF_SC_VREFST_MASK) == 0)
+ {
+ }
+}
+#endif /* FSL_FEATURE_VREF_HAS_LOW_REFERENCE */
diff --git a/drivers/fsl_vref.h b/drivers/fsl_vref.h
new file mode 100644
index 0000000..349c124
--- /dev/null
+++ b/drivers/fsl_vref.h
@@ -0,0 +1,256 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_VREF_H_
+#define _FSL_VREF_H_
+
+#include "fsl_common.h"
+
+/*!
+ * @addtogroup vref
+ * @{
+ */
+
+
+/******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+/*! @name Driver version */
+/*@{*/
+#define FSL_VREF_DRIVER_VERSION (MAKE_VERSION(2, 1, 0)) /*!< Version 2.1.0. */
+/*@}*/
+
+/* Those macros below defined to support SoC family which have VREFL (0.4V) reference */
+#if defined(FSL_FEATURE_VREF_HAS_LOW_REFERENCE) && FSL_FEATURE_VREF_HAS_LOW_REFERENCE
+#define VREF_SC_MODE_LV VREF_VREFH_SC_MODE_LV
+#define VREF_SC_REGEN VREF_VREFH_SC_REGEN
+#define VREF_SC_VREFEN VREF_VREFH_SC_VREFEN
+#define VREF_SC_ICOMPEN VREF_VREFH_SC_ICOMPEN
+#define VREF_SC_REGEN_MASK VREF_VREFH_SC_REGEN_MASK
+#define VREF_SC_VREFST_MASK VREF_VREFH_SC_VREFST_MASK
+#define VREF_SC_VREFEN_MASK VREF_VREFH_SC_VREFEN_MASK
+#define VREF_SC_MODE_LV_MASK VREF_VREFH_SC_MODE_LV_MASK
+#define VREF_SC_ICOMPEN_MASK VREF_VREFH_SC_ICOMPEN_MASK
+#define TRM VREFH_TRM
+#define VREF_TRM_TRIM VREF_VREFH_TRM_TRIM
+#define VREF_TRM_CHOPEN_MASK VREF_VREFH_TRM_CHOPEN_MASK
+#define VREF_TRM_TRIM_MASK VREF_VREFH_TRM_TRIM_MASK
+#define VREF_TRM_CHOPEN_SHIFT VREF_VREFH_TRM_CHOPEN_SHIFT
+#define VREF_TRM_TRIM_SHIFT VREF_VREFH_TRM_TRIM_SHIFT
+#define VREF_SC_MODE_LV_SHIFT VREF_VREFH_SC_MODE_LV_SHIFT
+#define VREF_SC_REGEN_SHIFT VREF_VREFH_SC_REGEN_SHIFT
+#define VREF_SC_VREFST_SHIFT VREF_VREFH_SC_VREFST_SHIFT
+#define VREF_SC_ICOMPEN_SHIFT VREF_VREFH_SC_ICOMPEN_SHIFT
+#endif /* FSL_FEATURE_VREF_HAS_LOW_REFERENCE */
+
+/*!
+ * @brief VREF modes.
+ */
+typedef enum _vref_buffer_mode
+{
+ kVREF_ModeBandgapOnly = 0U, /*!< Bandgap on only, for stabilization and startup */
+#if defined(FSL_FEATURE_VREF_MODE_LV_TYPE) && FSL_FEATURE_VREF_MODE_LV_TYPE
+ kVREF_ModeHighPowerBuffer = 1U, /*!< High power buffer mode enabled */
+ kVREF_ModeLowPowerBuffer = 2U /*!< Low power buffer mode enabled */
+#else
+ kVREF_ModeTightRegulationBuffer = 2U /*!< Tight regulation buffer enabled */
+#endif /* FSL_FEATURE_VREF_MODE_LV_TYPE */
+} vref_buffer_mode_t;
+
+/*!
+ * @brief The description structure for the VREF module.
+ */
+typedef struct _vref_config
+{
+ vref_buffer_mode_t bufferMode; /*!< Buffer mode selection */
+#if defined(FSL_FEATURE_VREF_HAS_LOW_REFERENCE) && FSL_FEATURE_VREF_HAS_LOW_REFERENCE
+ bool enableLowRef; /*!< Set VREFL (0.4 V) reference buffer enable or disable */
+ bool enableExternalVoltRef; /*!< Select external voltage reference or not (internal) */
+#endif /* FSL_FEATURE_VREF_HAS_LOW_REFERENCE */
+#if defined(FSL_FEATURE_VREF_HAS_TRM4) && FSL_FEATURE_VREF_HAS_TRM4
+ bool enable2V1VoltRef; /*!< Enable Internal Voltage Reference (2.1V) */
+#endif /* FSL_FEATURE_VREF_HAS_TRM4 */
+} vref_config_t;
+
+/******************************************************************************
+ * API
+ ******************************************************************************/
+
+#if defined(__cplusplus)
+extern "C" {
+#endif /* __cplusplus */
+
+/*!
+ * @name VREF functional operation
+ * @{
+ */
+
+/*!
+ * @brief Enables the clock gate and configures the VREF module according to the configuration structure.
+ *
+ * This function must be called before calling all the other VREF driver functions,
+ * read/write registers, and configurations with user-defined settings.
+ * The example below shows how to set up vref_config_t parameters and
+ * how to call the VREF_Init function by passing in these parameters:
+ * Example:
+ * @code
+ * vref_config_t vrefConfig;
+ * vrefConfig.bufferMode = kVREF_ModeHighPowerBuffer;
+ * vrefConfig.enableExternalVoltRef = false;
+ * vrefConfig.enableLowRef = false;
+ * VREF_Init(VREF, &vrefConfig);
+ * @endcode
+ *
+ * @param base VREF peripheral address.
+ * @param config Pointer to the configuration structure.
+ */
+void VREF_Init(VREF_Type *base, const vref_config_t *config);
+
+/*!
+ * @brief Stops and disables the clock for the VREF module.
+ *
+ * This function should be called to shut down the module.
+ * Example:
+ * @code
+ * vref_config_t vrefUserConfig;
+ * VREF_Init(VREF);
+ * VREF_GetDefaultConfig(&vrefUserConfig);
+ * ...
+ * VREF_Deinit(VREF);
+ * @endcode
+ *
+ * @param base VREF peripheral address.
+ */
+void VREF_Deinit(VREF_Type *base);
+
+/*!
+ * @brief Initializes the VREF configuration structure.
+ *
+ * This function initializes the VREF configuration structure to a default value.
+ * Example:
+ * @code
+ * vrefConfig->bufferMode = kVREF_ModeHighPowerBuffer;
+ * vrefConfig->enableExternalVoltRef = false;
+ * vrefConfig->enableLowRef = false;
+ * @endcode
+ *
+ * @param config Pointer to the initialization structure.
+ */
+void VREF_GetDefaultConfig(vref_config_t *config);
+
+/*!
+ * @brief Sets a TRIM value for reference voltage.
+ *
+ * This function sets a TRIM value for reference voltage.
+ * Note that the TRIM value maximum is 0x3F.
+ *
+ * @param base VREF peripheral address.
+ * @param trimValue Value of the trim register to set the output reference voltage (maximum 0x3F (6-bit)).
+ */
+void VREF_SetTrimVal(VREF_Type *base, uint8_t trimValue);
+
+/*!
+ * @brief Reads the value of the TRIM meaning output voltage.
+ *
+ * This function gets the TRIM value from the TRM register.
+ *
+ * @param base VREF peripheral address.
+ * @return Six-bit value of trim setting.
+ */
+static inline uint8_t VREF_GetTrimVal(VREF_Type *base)
+{
+ return (base->TRM & VREF_TRM_TRIM_MASK);
+}
+
+#if defined(FSL_FEATURE_VREF_HAS_TRM4) && FSL_FEATURE_VREF_HAS_TRM4
+/*!
+ * @brief Sets a TRIM value for reference voltage (2V1).
+ *
+ * This function sets a TRIM value for reference voltage (2V1).
+ * Note that the TRIM value maximum is 0x3F.
+ *
+ * @param base VREF peripheral address.
+ * @param trimValue Value of the trim register to set the output reference voltage (maximum 0x3F (6-bit)).
+ */
+void VREF_SetTrim2V1Val(VREF_Type *base, uint8_t trimValue);
+
+/*!
+ * @brief Reads the value of the TRIM meaning output voltage (2V1).
+ *
+ * This function gets the TRIM value from the VREF_TRM4 register.
+ *
+ * @param base VREF peripheral address.
+ * @return Six-bit value of trim setting.
+ */
+static inline uint8_t VREF_GetTrim2V1Val(VREF_Type *base)
+{
+ return (base->TRM4 & VREF_TRM4_TRIM2V1_MASK);
+}
+#endif /* FSL_FEATURE_VREF_HAS_TRM4 */
+
+#if defined(FSL_FEATURE_VREF_HAS_LOW_REFERENCE) && FSL_FEATURE_VREF_HAS_LOW_REFERENCE
+
+/*!
+ * @brief Sets the TRIM value for low voltage reference.
+ *
+ * This function sets the TRIM value for low reference voltage.
+ * NOTE:
+ * - The TRIM value maximum is 0x05U
+ * - The values 111b and 110b are not valid/allowed.
+ *
+ * @param base VREF peripheral address.
+ * @param trimValue Value of the trim register to set output low reference voltage (maximum 0x05U (3-bit)).
+ */
+void VREF_SetLowReferenceTrimVal(VREF_Type *base, uint8_t trimValue);
+
+/*!
+ * @brief Reads the value of the TRIM meaning output voltage.
+ *
+ * This function gets the TRIM value from the VREFL_TRM register.
+ *
+ * @param base VREF peripheral address.
+ * @return Three-bit value of the trim setting.
+ */
+static inline uint8_t VREF_GetLowReferenceTrimVal(VREF_Type *base)
+{
+ return (base->VREFL_TRM & VREF_VREFL_TRM_VREFL_TRIM_MASK);
+}
+#endif /* FSL_FEATURE_VREF_HAS_LOW_REFERENCE */
+
+/*@}*/
+
+#if defined(__cplusplus)
+}
+#endif /* __cplusplus */
+
+/*! @}*/
+
+#endif /* _FSL_VREF_H_ */
diff --git a/drivers/fsl_wdog.c b/drivers/fsl_wdog.c
new file mode 100644
index 0000000..489798c
--- /dev/null
+++ b/drivers/fsl_wdog.c
@@ -0,0 +1,153 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_wdog.h"
+
+/*******************************************************************************
+ * Code
+ ******************************************************************************/
+
+void WDOG_GetDefaultConfig(wdog_config_t *config)
+{
+ assert(config);
+
+ config->enableWdog = true;
+ config->clockSource = kWDOG_LpoClockSource;
+ config->prescaler = kWDOG_ClockPrescalerDivide1;
+#if defined(FSL_FEATURE_WDOG_HAS_WAITEN) && FSL_FEATURE_WDOG_HAS_WAITEN
+ config->workMode.enableWait = true;
+#endif /* FSL_FEATURE_WDOG_HAS_WAITEN */
+ config->workMode.enableStop = false;
+ config->workMode.enableDebug = false;
+ config->enableUpdate = true;
+ config->enableInterrupt = false;
+ config->enableWindowMode = false;
+ config->windowValue = 0U;
+ config->timeoutValue = 0xFFFFU;
+}
+
+void WDOG_Init(WDOG_Type *base, const wdog_config_t *config)
+{
+ assert(config);
+
+ uint32_t value = 0U;
+ uint32_t primaskValue = 0U;
+
+ value = WDOG_STCTRLH_WDOGEN(config->enableWdog) | WDOG_STCTRLH_CLKSRC(config->clockSource) |
+ WDOG_STCTRLH_IRQRSTEN(config->enableInterrupt) | WDOG_STCTRLH_WINEN(config->enableWindowMode) |
+ WDOG_STCTRLH_ALLOWUPDATE(config->enableUpdate) | WDOG_STCTRLH_DBGEN(config->workMode.enableDebug) |
+ WDOG_STCTRLH_STOPEN(config->workMode.enableStop) |
+#if defined(FSL_FEATURE_WDOG_HAS_WAITEN) && FSL_FEATURE_WDOG_HAS_WAITEN
+ WDOG_STCTRLH_WAITEN(config->workMode.enableWait) |
+#endif /* FSL_FEATURE_WDOG_HAS_WAITEN */
+ WDOG_STCTRLH_DISTESTWDOG(1U);
+
+ /* Disable the global interrupts. Otherwise, an interrupt could effectively invalidate the unlock sequence
+ * and the WCT may expire. After the configuration finishes, re-enable the global interrupts. */
+ primaskValue = DisableGlobalIRQ();
+ WDOG_Unlock(base);
+ /* Wait one bus clock cycle */
+ base->RSTCNT = 0U;
+ /* Set configruation */
+ base->PRESC = WDOG_PRESC_PRESCVAL(config->prescaler);
+ base->WINH = (uint16_t)((config->windowValue >> 16U) & 0xFFFFU);
+ base->WINL = (uint16_t)((config->windowValue) & 0xFFFFU);
+ base->TOVALH = (uint16_t)((config->timeoutValue >> 16U) & 0xFFFFU);
+ base->TOVALL = (uint16_t)((config->timeoutValue) & 0xFFFFU);
+ base->STCTRLH = value;
+ EnableGlobalIRQ(primaskValue);
+}
+
+void WDOG_Deinit(WDOG_Type *base)
+{
+ uint32_t primaskValue = 0U;
+
+ /* Disable the global interrupts */
+ primaskValue = DisableGlobalIRQ();
+ WDOG_Unlock(base);
+ /* Wait one bus clock cycle */
+ base->RSTCNT = 0U;
+ WDOG_Disable(base);
+ EnableGlobalIRQ(primaskValue);
+ WDOG_ClearResetCount(base);
+}
+
+void WDOG_SetTestModeConfig(WDOG_Type *base, wdog_test_config_t *config)
+{
+ assert(config);
+
+ uint32_t value = 0U;
+ uint32_t primaskValue = 0U;
+
+ value = WDOG_STCTRLH_DISTESTWDOG(0U) | WDOG_STCTRLH_TESTWDOG(1U) | WDOG_STCTRLH_TESTSEL(config->testMode) |
+ WDOG_STCTRLH_BYTESEL(config->testedByte) | WDOG_STCTRLH_IRQRSTEN(0U) | WDOG_STCTRLH_WDOGEN(1U) |
+ WDOG_STCTRLH_ALLOWUPDATE(1U);
+
+ /* Disable the global interrupts. Otherwise, an interrupt could effectively invalidate the unlock sequence
+ * and the WCT may expire. After the configuration finishes, re-enable the global interrupts. */
+ primaskValue = DisableGlobalIRQ();
+ WDOG_Unlock(base);
+ /* Wait one bus clock cycle */
+ base->RSTCNT = 0U;
+ /* Set configruation */
+ base->TOVALH = (uint16_t)((config->timeoutValue >> 16U) & 0xFFFFU);
+ base->TOVALL = (uint16_t)((config->timeoutValue) & 0xFFFFU);
+ base->STCTRLH = value;
+ EnableGlobalIRQ(primaskValue);
+}
+
+uint32_t WDOG_GetStatusFlags(WDOG_Type *base)
+{
+ uint32_t status_flag = 0U;
+
+ status_flag |= (base->STCTRLH & WDOG_STCTRLH_WDOGEN_MASK);
+ status_flag |= (base->STCTRLL & WDOG_STCTRLL_INTFLG_MASK);
+
+ return status_flag;
+}
+
+void WDOG_ClearStatusFlags(WDOG_Type *base, uint32_t mask)
+{
+ if (mask & kWDOG_TimeoutFlag)
+ {
+ base->STCTRLL |= WDOG_STCTRLL_INTFLG_MASK;
+ }
+}
+
+void WDOG_Refresh(WDOG_Type *base)
+{
+ uint32_t primaskValue = 0U;
+
+ /* Disable the global interrupt to protect refresh sequence */
+ primaskValue = DisableGlobalIRQ();
+ base->REFRESH = WDOG_FIRST_WORD_OF_REFRESH;
+ base->REFRESH = WDOG_SECOND_WORD_OF_REFRESH;
+ EnableGlobalIRQ(primaskValue);
+}
diff --git a/drivers/fsl_wdog.h b/drivers/fsl_wdog.h
new file mode 100644
index 0000000..f497406
--- /dev/null
+++ b/drivers/fsl_wdog.h
@@ -0,0 +1,433 @@
+/*
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * 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 Freescale Semiconductor, Inc. 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_WDOG_H_
+#define _FSL_WDOG_H_
+
+#include "fsl_common.h"
+
+/*!
+ * @addtogroup wdog
+ * @{
+ */
+
+
+/*******************************************************************************
+ * Definitions
+ *******************************************************************************/
+
+/*! @name Driver version */
+/*@{*/
+/*! @brief Defines WDOG driver version 2.0.0. */
+#define FSL_WDOG_DRIVER_VERSION (MAKE_VERSION(2, 0, 0))
+/*@}*/
+
+/*! @name Unlock sequence */
+/*@{*/
+#define WDOG_FIRST_WORD_OF_UNLOCK (0xC520U) /*!< First word of unlock sequence */
+#define WDOG_SECOND_WORD_OF_UNLOCK (0xD928U) /*!< Second word of unlock sequence */
+/*@}*/
+
+/*! @name Refresh sequence */
+/*@{*/
+#define WDOG_FIRST_WORD_OF_REFRESH (0xA602U) /*!< First word of refresh sequence */
+#define WDOG_SECOND_WORD_OF_REFRESH (0xB480U) /*!< Second word of refresh sequence */
+/*@}*/
+
+/*! @brief Describes WDOG clock source. */
+typedef enum _wdog_clock_source
+{
+ kWDOG_LpoClockSource = 0U, /*!< WDOG clock sourced from LPO*/
+ kWDOG_AlternateClockSource = 1U, /*!< WDOG clock sourced from alternate clock source*/
+} wdog_clock_source_t;
+
+/*! @brief Defines WDOG work mode. */
+typedef struct _wdog_work_mode
+{
+#if defined(FSL_FEATURE_WDOG_HAS_WAITEN) && FSL_FEATURE_WDOG_HAS_WAITEN
+ bool enableWait; /*!< Enables or disables WDOG in wait mode */
+#endif /* FSL_FEATURE_WDOG_HAS_WAITEN */
+ bool enableStop; /*!< Enables or disables WDOG in stop mode */
+ bool enableDebug; /*!< Enables or disables WDOG in debug mode */
+} wdog_work_mode_t;
+
+/*! @brief Describes the selection of the clock prescaler. */
+typedef enum _wdog_clock_prescaler
+{
+ kWDOG_ClockPrescalerDivide1 = 0x0U, /*!< Divided by 1 */
+ kWDOG_ClockPrescalerDivide2 = 0x1U, /*!< Divided by 2 */
+ kWDOG_ClockPrescalerDivide3 = 0x2U, /*!< Divided by 3 */
+ kWDOG_ClockPrescalerDivide4 = 0x3U, /*!< Divided by 4 */
+ kWDOG_ClockPrescalerDivide5 = 0x4U, /*!< Divided by 5 */
+ kWDOG_ClockPrescalerDivide6 = 0x5U, /*!< Divided by 6 */
+ kWDOG_ClockPrescalerDivide7 = 0x6U, /*!< Divided by 7 */
+ kWDOG_ClockPrescalerDivide8 = 0x7U, /*!< Divided by 8 */
+} wdog_clock_prescaler_t;
+
+/*! @brief Describes WDOG configuration structure. */
+typedef struct _wdog_config
+{
+ bool enableWdog; /*!< Enables or disables WDOG */
+ wdog_clock_source_t clockSource; /*!< Clock source select */
+ wdog_clock_prescaler_t prescaler; /*!< Clock prescaler value */
+ wdog_work_mode_t workMode; /*!< Configures WDOG work mode in debug stop and wait mode */
+ bool enableUpdate; /*!< Update write-once register enable */
+ bool enableInterrupt; /*!< Enables or disables WDOG interrupt */
+ bool enableWindowMode; /*!< Enables or disables WDOG window mode */
+ uint32_t windowValue; /*!< Window value */
+ uint32_t timeoutValue; /*!< Timeout value */
+} wdog_config_t;
+
+/*! @brief Describes WDOG test mode. */
+typedef enum _wdog_test_mode
+{
+ kWDOG_QuickTest = 0U, /*!< Selects quick test */
+ kWDOG_ByteTest = 1U, /*!< Selects byte test */
+} wdog_test_mode_t;
+
+/*! @brief Describes WDOG tested byte selection in byte test mode. */
+typedef enum _wdog_tested_byte
+{
+ kWDOG_TestByte0 = 0U, /*!< Byte 0 selected in byte test mode */
+ kWDOG_TestByte1 = 1U, /*!< Byte 1 selected in byte test mode */
+ kWDOG_TestByte2 = 2U, /*!< Byte 2 selected in byte test mode */
+ kWDOG_TestByte3 = 3U, /*!< Byte 3 selected in byte test mode */
+} wdog_tested_byte_t;
+
+/*! @brief Describes WDOG test mode configuration structure. */
+typedef struct _wdog_test_config
+{
+ wdog_test_mode_t testMode; /*!< Selects test mode */
+ wdog_tested_byte_t testedByte; /*!< Selects tested byte in byte test mode */
+ uint32_t timeoutValue; /*!< Timeout value */
+} wdog_test_config_t;
+
+/*!
+ * @brief WDOG interrupt configuration structure, default settings all disabled.
+ *
+ * This structure contains the settings for all of the WDOG interrupt configurations.
+ */
+enum _wdog_interrupt_enable_t
+{
+ kWDOG_InterruptEnable = WDOG_STCTRLH_IRQRSTEN_MASK, /*!< WDOG timeout generates an interrupt before reset*/
+};
+
+/*!
+ * @brief WDOG status flags.
+ *
+ * This structure contains the WDOG status flags for use in the WDOG functions.
+ */
+enum _wdog_status_flags_t
+{
+ kWDOG_RunningFlag = WDOG_STCTRLH_WDOGEN_MASK, /*!< Running flag, set when WDOG is enabled*/
+ kWDOG_TimeoutFlag = WDOG_STCTRLL_INTFLG_MASK, /*!< Interrupt flag, set when an exception occurs*/
+};
+
+/*******************************************************************************
+ * API
+ *******************************************************************************/
+
+#if defined(__cplusplus)
+extern "C" {
+#endif /* __cplusplus */
+
+/*!
+ * @name WDOG Initialization and De-initialization
+ * @{
+ */
+
+/*!
+ * @brief Initializes WDOG configure sturcture.
+ *
+ * This function initializes the WDOG configuration structure to default value. The default
+ * values are:
+ * @code
+ * wdogConfig->enableWdog = true;
+ * wdogConfig->clockSource = kWDOG_LpoClockSource;
+ * wdogConfig->prescaler = kWDOG_ClockPrescalerDivide1;
+ * wdogConfig->workMode.enableWait = true;
+ * wdogConfig->workMode.enableStop = false;
+ * wdogConfig->workMode.enableDebug = false;
+ * wdogConfig->enableUpdate = true;
+ * wdogConfig->enableInterrupt = false;
+ * wdogConfig->enableWindowMode = false;
+ * wdogConfig->windowValue = 0;
+ * wdogConfig->timeoutValue = 0xFFFFU;
+ * @endcode
+ *
+ * @param config Pointer to WDOG config structure.
+ * @see wdog_config_t
+ */
+void WDOG_GetDefaultConfig(wdog_config_t *config);
+
+/*!
+ * @brief Initializes the WDOG.
+ *
+ * This function initializes the WDOG. When called, the WDOG runs according to the configuration.
+ * If user wants to reconfigure WDOG without forcing a reset first, enableUpdate must be set to true
+ * in configuration.
+ *
+ * Example:
+ * @code
+ * wdog_config_t config;
+ * WDOG_GetDefaultConfig(&config);
+ * config.timeoutValue = 0x7ffU;
+ * config.enableUpdate = true;
+ * WDOG_Init(wdog_base,&config);
+ * @endcode
+ *
+ * @param base WDOG peripheral base address
+ * @param config The configuration of WDOG
+ */
+void WDOG_Init(WDOG_Type *base, const wdog_config_t *config);
+
+/*!
+ * @brief Shuts down the WDOG.
+ *
+ * This function shuts down the WDOG.
+ * Make sure that the WDOG_STCTRLH.ALLOWUPDATE is 1 which means that the register update is enabled.
+ */
+void WDOG_Deinit(WDOG_Type *base);
+
+/*!
+ * @brief Configures WDOG functional test.
+ *
+ * This function is used to configure the WDOG functional test. When called, the WDOG goes into test mode
+ * and runs according to the configuration.
+ * Make sure that the WDOG_STCTRLH.ALLOWUPDATE is 1 which means that the register update is enabled.
+ *
+ * Example:
+ * @code
+ * wdog_test_config_t test_config;
+ * test_config.testMode = kWDOG_QuickTest;
+ * test_config.timeoutValue = 0xfffffu;
+ * WDOG_SetTestModeConfig(wdog_base, &test_config);
+ * @endcode
+ * @param base WDOG peripheral base address
+ * @param config The functional test configuration of WDOG
+ */
+void WDOG_SetTestModeConfig(WDOG_Type *base, wdog_test_config_t *config);
+
+/* @} */
+
+/*!
+ * @name WDOG Functional Operation
+ * @{
+ */
+
+/*!
+ * @brief Enables the WDOG module.
+ *
+ * This function write value into WDOG_STCTRLH register to enable the WDOG, it is a write-once register,
+ * make sure that the WCT window is still open and this register has not been written in this WCT
+ * while this function is called.
+ *
+ * @param base WDOG peripheral base address
+ */
+static inline void WDOG_Enable(WDOG_Type *base)
+{
+ base->STCTRLH |= WDOG_STCTRLH_WDOGEN_MASK;
+}
+
+/*!
+ * @brief Disables the WDOG module.
+ *
+ * This function write value into WDOG_STCTRLH register to disable the WDOG, it is a write-once register,
+ * make sure that the WCT window is still open and this register has not been written in this WCT
+ * while this function is called.
+ *
+ * @param base WDOG peripheral base address
+ */
+static inline void WDOG_Disable(WDOG_Type *base)
+{
+ base->STCTRLH &= ~WDOG_STCTRLH_WDOGEN_MASK;
+}
+
+/*!
+ * @brief Enable WDOG interrupt.
+ *
+ * This function write value into WDOG_STCTRLH register to enable WDOG interrupt, it is a write-once register,
+ * make sure that the WCT window is still open and this register has not been written in this WCT
+ * while this function is called.
+ *
+ * @param base WDOG peripheral base address
+ * @param mask The interrupts to enable
+ * The parameter can be combination of the following source if defined:
+ * @arg kWDOG_InterruptEnable
+ */
+static inline void WDOG_EnableInterrupts(WDOG_Type *base, uint32_t mask)
+{
+ base->STCTRLH |= mask;
+}
+
+/*!
+ * @brief Disable WDOG interrupt.
+ *
+ * This function write value into WDOG_STCTRLH register to disable WDOG interrupt, it is a write-once register,
+ * make sure that the WCT window is still open and this register has not been written in this WCT
+ * while this function is called.
+ *
+ * @param base WDOG peripheral base address
+ * @param mask The interrupts to disable
+ * The parameter can be combination of the following source if defined:
+ * @arg kWDOG_InterruptEnable
+ */
+static inline void WDOG_DisableInterrupts(WDOG_Type *base, uint32_t mask)
+{
+ base->STCTRLH &= ~mask;
+}
+
+/*!
+ * @brief Gets WDOG all status flags.
+ *
+ * This function gets all status flags.
+ *
+ * Example for getting Running Flag:
+ * @code
+ * uint32_t status;
+ * status = WDOG_GetStatusFlags(wdog_base) & kWDOG_RunningFlag;
+ * @endcode
+ * @param base WDOG peripheral base address
+ * @return State of the status flag: asserted (true) or not-asserted (false).@see _wdog_status_flags_t
+ * - true: a related status flag has been set.
+ * - false: a related status flag is not set.
+ */
+uint32_t WDOG_GetStatusFlags(WDOG_Type *base);
+
+/*!
+ * @brief Clear WDOG flag.
+ *
+ * This function clears WDOG status flag.
+ *
+ * Example for clearing timeout(interrupt) flag:
+ * @code
+ * WDOG_ClearStatusFlags(wdog_base,kWDOG_TimeoutFlag);
+ * @endcode
+ * @param base WDOG peripheral base address
+ * @param mask The status flags to clear.
+ * The parameter could be any combination of the following values:
+ * kWDOG_TimeoutFlag
+ */
+void WDOG_ClearStatusFlags(WDOG_Type *base, uint32_t mask);
+
+/*!
+ * @brief Set the WDOG timeout value.
+ *
+ * This function sets the timeout value.
+ * It should be ensured that the time-out value for the WDOG is always greater than
+ * 2xWCT time + 20 bus clock cycles.
+ * This function write value into WDOG_TOVALH and WDOG_TOVALL registers which are wirte-once.
+ * Make sure the WCT window is still open and these two registers have not been written in this WCT
+ * while this function is called.
+ *
+ * @param base WDOG peripheral base address
+ * @param timeoutCount WDOG timeout value, count of WDOG clock tick.
+ */
+static inline void WDOG_SetTimeoutValue(WDOG_Type *base, uint32_t timeoutCount)
+{
+ base->TOVALH = (uint16_t)((timeoutCount >> 16U) & 0xFFFFU);
+ base->TOVALL = (uint16_t)((timeoutCount)&0xFFFFU);
+}
+
+/*!
+ * @brief Sets the WDOG window value.
+ *
+ * This function sets the WDOG window value.
+ * This function write value into WDOG_WINH and WDOG_WINL registers which are wirte-once.
+ * Make sure the WCT window is still open and these two registers have not been written in this WCT
+ * while this function is called.
+ *
+ * @param base WDOG peripheral base address
+ * @param windowValue WDOG window value.
+ */
+static inline void WDOG_SetWindowValue(WDOG_Type *base, uint32_t windowValue)
+{
+ base->WINH = (uint16_t)((windowValue >> 16U) & 0xFFFFU);
+ base->WINL = (uint16_t)((windowValue)&0xFFFFU);
+}
+
+/*!
+ * @brief Unlocks the WDOG register written.
+ *
+ * This function unlocks the WDOG register written.
+ * Before starting the unlock sequence and following congfiguration, disable the global interrupts.
+ * Otherwise, an interrupt could effectively invalidate the unlock sequence and the WCT may expire,
+ * After the configuration finishes, re-enable the global interrupts.
+ *
+ * @param base WDOG peripheral base address
+ */
+static inline void WDOG_Unlock(WDOG_Type *base)
+{
+ base->UNLOCK = WDOG_FIRST_WORD_OF_UNLOCK;
+ base->UNLOCK = WDOG_SECOND_WORD_OF_UNLOCK;
+}
+
+/*!
+ * @brief Refreshes the WDOG timer.
+ *
+ * This function feeds the WDOG.
+ * This function should be called before WDOG timer is in timeout. Otherwise, a reset is asserted.
+ *
+ * @param base WDOG peripheral base address
+ */
+void WDOG_Refresh(WDOG_Type *base);
+
+/*!
+ * @brief Gets the WDOG reset count.
+ *
+ * This function gets the WDOG reset count value.
+ *
+ * @param base WDOG peripheral base address
+ * @return WDOG reset count value
+ */
+static inline uint16_t WDOG_GetResetCount(WDOG_Type *base)
+{
+ return base->RSTCNT;
+}
+/*!
+ * @brief Clears the WDOG reset count.
+ *
+ * This function clears the WDOG reset count value.
+ *
+ * @param base WDOG peripheral base address
+ */
+static inline void WDOG_ClearResetCount(WDOG_Type *base)
+{
+ base->RSTCNT |= UINT16_MAX;
+}
+
+/*@}*/
+
+#if defined(__cplusplus)
+}
+#endif /* __cplusplus */
+
+/*! @}*/
+
+#endif /* _FSL_WDOG_H_ */