summaryrefslogtreecommitdiffhomepage
path: root/drivers
diff options
context:
space:
mode:
Diffstat (limited to 'drivers')
-rw-r--r--drivers/fsl_adc16.c380
-rw-r--r--drivers/fsl_adc16.h529
-rw-r--r--drivers/fsl_clock.c1397
-rw-r--r--drivers/fsl_clock.h1286
-rw-r--r--drivers/fsl_cmp.c295
-rw-r--r--drivers/fsl_cmp.h347
-rw-r--r--drivers/fsl_common.c192
-rw-r--r--drivers/fsl_common.h576
-rw-r--r--drivers/fsl_crc.c292
-rw-r--r--drivers/fsl_crc.h197
-rw-r--r--drivers/fsl_dac.c230
-rw-r--r--drivers/fsl_dac.h382
-rw-r--r--drivers/fsl_dmamux.c103
-rw-r--r--drivers/fsl_dmamux.h204
-rw-r--r--drivers/fsl_dspi.c1807
-rw-r--r--drivers/fsl_dspi.h1248
-rw-r--r--drivers/fsl_dspi_edma.c1446
-rw-r--r--drivers/fsl_dspi_edma.h306
-rw-r--r--drivers/fsl_edma.c2299
-rw-r--r--drivers/fsl_edma.h957
-rw-r--r--drivers/fsl_gpio.c235
-rw-r--r--drivers/fsl_gpio.h594
-rw-r--r--drivers/fsl_i2c.c2005
-rw-r--r--drivers/fsl_i2c.h821
-rw-r--r--drivers/fsl_i2c_edma.c570
-rw-r--r--drivers/fsl_i2c_edma.h141
-rw-r--r--drivers/fsl_pit.c138
-rw-r--r--drivers/fsl_pit.h358
-rw-r--r--drivers/fsl_port.h497
-rw-r--r--drivers/fsl_uart.c1356
-rw-r--r--drivers/fsl_uart.h808
31 files changed, 21996 insertions, 0 deletions
diff --git a/drivers/fsl_adc16.c b/drivers/fsl_adc16.c
new file mode 100644
index 0000000..dcafbf8
--- /dev/null
+++ b/drivers/fsl_adc16.c
@@ -0,0 +1,380 @@
+/*
+ * The Clear BSD License
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * Copyright 2016-2017 NXP
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted (subject to the limitations in the disclaimer below) provided
+ * that the following conditions are met:
+ *
+ * o Redistributions of source code must retain the above copyright notice, this list
+ * of conditions and the following disclaimer.
+ *
+ * o Redistributions in binary form must reproduce the above copyright notice, this
+ * list of conditions and the following disclaimer in the documentation and/or
+ * other materials provided with the distribution.
+ *
+ * o Neither the name of the copyright holder nor the names of its
+ * contributors may be used to endorse or promote products derived from this
+ * software without specific prior written permission.
+ *
+ * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS LICENSE.
+ * 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"
+
+/* Component ID definition, used by tools. */
+#ifndef FSL_COMPONENT_ID
+#define FSL_COMPONENT_ID "platform.drivers.adc16"
+#endif
+
+
+/*******************************************************************************
+ * 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;
+
+#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
+/*! @brief Pointers to ADC16 clocks for each instance. */
+static const clock_ip_name_t s_adc16Clocks[] = ADC16_CLOCKS;
+#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
+
+/*******************************************************************************
+ * Code
+ ******************************************************************************/
+static uint32_t ADC16_GetInstance(ADC_Type *base)
+{
+ uint32_t instance;
+
+ /* Find the instance index from base address mappings. */
+ for (instance = 0; instance < ARRAY_SIZE(s_adc16Bases); instance++)
+ {
+ if (s_adc16Bases[instance] == base)
+ {
+ break;
+ }
+ }
+
+ assert(instance < ARRAY_SIZE(s_adc16Bases));
+
+ return instance;
+}
+
+void ADC16_Init(ADC_Type *base, const adc16_config_t *config)
+{
+ assert(NULL != config);
+
+ uint32_t tmp32;
+
+#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
+ /* Enable the clock. */
+ CLOCK_EnableClock(s_adc16Clocks[ADC16_GetInstance(base)]);
+#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
+
+ /* 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)
+{
+#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
+ /* Disable the clock. */
+ CLOCK_DisableClock(s_adc16Clocks[ADC16_GetInstance(base)]);
+#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
+}
+
+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..da0604f
--- /dev/null
+++ b/drivers/fsl_adc16.h
@@ -0,0 +1,529 @@
+/*
+ * The Clear BSD License
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * Copyright 2016-2017 NXP
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted (subject to the limitations in the disclaimer below) provided
+ * that the following conditions are met:
+ *
+ * o Redistributions of source code must retain the above copyright notice, this list
+ * of conditions and the following disclaimer.
+ *
+ * o Redistributions in binary form must reproduce the above copyright notice, this
+ * list of conditions and the following disclaimer in the documentation and/or
+ * other materials provided with the distribution.
+ *
+ * o Neither the name of the copyright holder nor the names of its
+ * contributors may be used to endorse or promote products derived from this
+ * software without specific prior written permission.
+ *
+ * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS LICENSE.
+ * 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 that 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 a 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 comparison 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 the converter's configuration.
+ *
+ * This function initializes the converter configuration structure with available settings. The default values are as follows.
+ * @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 the 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.
+ * Execute the calibration before using the converter. Note that the hardware trigger should be used
+ * during the calibration.
+ *
+ * @param base ADC16 peripheral base address.
+ *
+ * @return Execution status.
+ * @retval kStatus_Success Calibration is done successfully.
+ * @retval kStatus_Fail Calibration has 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 Features
+ * @{
+ */
+
+#if defined(FSL_FEATURE_ADC16_HAS_DMA) && FSL_FEATURE_ADC16_HAS_DMA
+/*!
+ * @brief Enables generating the DMA trigger when the conversion is complete.
+ *
+ * @param base ADC16 peripheral base address.
+ * @param enable Switcher of the DMA feature. "true" means enabled, "false" means not enabled.
+ */
+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 the hardware trigger feature. "true" means enabled, "false" means not enabled.
+ */
+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 using hardware. Only the result
+ * in the compare range is available. To compare the range, see "adc16_hardware_compare_mode_t" or the appopriate reference
+ * manual for more information.
+ *
+ * @param base ADC16 peripheral base address.
+ * @param config Pointer to the "adc16_hardware_compare_config_t" structure. Passing "NULL" disables 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.
+ *
+ * The hardware average mode provides a way to process the conversion result automatically by using hardware. The multiple
+ * conversion results are accumulated and averaged internally making them easier to read.
+ *
+ * @param base ADC16 peripheral base address.
+ * @param mode Setting the 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 the converter's front end.
+ *
+ * @param base ADC16 peripheral base address.
+ * @param config Pointer to the "adc16_pga_config_t" structure. Passing "NULL" disables 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 when 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 has more than one
+ * group of status and control registers, one for each conversion. The channel group parameter indicates which group of
+ * registers are used, for example, 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. The channel group 0 is used for both software and hardware
+ * trigger modes. Channel group 1 and greater indicates multiple channel group registers for
+ * use only in hardware trigger mode. See the chip configuration information in the appropriate MCU reference manual for the
+ * number of SC1n registers (channel groups) specific to this device. Channel group 1 or greater are not used
+ * for software trigger operation. Therefore, writing to these channel groups does not initiate a new conversion.
+ * Updating the 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 the "adc16_channel_config_t" structure for the 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..c00f8dd
--- /dev/null
+++ b/drivers/fsl_clock.c
@@ -0,0 +1,1397 @@
+/*
+ * The Clear BSD License
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * Copyright (c) 2016 - 2017 , NXP
+ * All rights reserved.
+ *
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted (subject to the limitations in the disclaimer below) 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 copyright holder nor the names of its
+ * contributors may be used to endorse or promote products derived from this
+ * software without specific prior written permission.
+ *
+ * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS LICENSE.
+ * 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_clock.h"
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+/* Component ID definition, used by tools. */
+#ifndef FSL_COMPONENT_ID
+#define FSL_COMPONENT_ID "platform.drivers.clock"
+#endif
+
+/* 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_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 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);
+
+#ifndef MCG_USER_CONFIG_FLL_STABLE_DELAY_EN
+/*!
+ * @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);
+#endif
+
+/*******************************************************************************
+ * Code
+ ******************************************************************************/
+
+#ifndef MCG_USER_CONFIG_FLL_STABLE_DELAY_EN
+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();
+ }
+}
+#else /* With MCG_USER_CONFIG_FLL_STABLE_DELAY_EN defined. */
+/* Once user defines the MCG_USER_CONFIG_FLL_STABLE_DELAY_EN to use their own delay function, he has to
+ * create his own CLOCK_FllStableDelay() function in application code. Since the clock functions in this
+ * file would call the CLOCK_FllStableDelay() regardness how it is defined.
+ */
+extern void CLOCK_FllStableDelay(void);
+#endif /* MCG_USER_CONFIG_FLL_STABLE_DELAY_EN */
+
+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;
+ case 2U:
+ freq = MCG_INTERNAL_IRC_48M;
+ 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)) || (kMCG_OscselIrc == 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 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;
+}
+
+uint32_t CLOCK_GetOsc0ErClkUndivFreq(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_GetOsc0ErClkDivFreq(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 >> ((OSC0->DIV & OSC_DIV_ERPS_MASK) >> OSC_DIV_ERPS_SHIFT);
+ }
+ else
+ {
+ return 0U;
+ }
+}
+
+uint32_t CLOCK_GetEr32kClkFreq(void)
+{
+ uint32_t freq;
+
+ switch (SIM_SOPT1_OSC32KSEL_VAL)
+ {
+ case 0U: /* OSC 32k clock */
+ freq = (CLOCK_GetOsc0ErClkUndivFreq() == 32768U) ? 32768U : 0U;
+ 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 3U: /* MCG IRC48M. */
+ freq = MCG_INTERNAL_IRC_48M;
+ break;
+ default:
+ freq = 0U;
+ break;
+ }
+
+ return freq;
+}
+
+uint32_t CLOCK_GetOsc0ErClkFreq(void)
+{
+ return CLOCK_GetOsc0ErClkDivFreq();
+}
+
+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_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_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_McgFixedFreqClk:
+ freq = CLOCK_GetFixedFreqClkFreq();
+ break;
+ case kCLOCK_McgInternalRefClk:
+ freq = CLOCK_GetInternalRefClkFreq();
+ break;
+ case kCLOCK_McgFllClk:
+ freq = CLOCK_GetFllFreq();
+ break;
+ case kCLOCK_McgIrc48MClk:
+ freq = MCG_INTERNAL_IRC_48M;
+ break;
+ case kCLOCK_LpoClk:
+ freq = LPO_CLK_FREQ;
+ break;
+ case kCLOCK_Osc0ErClkUndiv:
+ freq = CLOCK_GetOsc0ErClkUndivFreq();
+ break;
+ case kCLOCK_Osc0ErClk:
+ freq = CLOCK_GetOsc0ErClkDivFreq();
+ 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);
+}
+
+uint32_t CLOCK_GetOutClkFreq(void)
+{
+ uint32_t mcgoutclk;
+ uint32_t clkst = MCG_S_CLKST_VAL;
+
+ switch (clkst)
+ {
+ 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))
+ {
+ 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;
+ }
+}
+
+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 (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;
+}
+
+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;
+ }
+}
+
+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;
+ }
+ return ret;
+}
+
+void CLOCK_ClearStatusFlags(uint32_t mask)
+{
+ if (mask & kMCG_Osc0LostFlag)
+ {
+ MCG->SC &= ~MCG_SC_ATMF_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;
+
+ /*------------------------------------------------------------------
+ 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
+ {
+ {
+ mode = kMCG_ModeFBE;
+ }
+ }
+ 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 */
+
+ /* If use external crystal as clock source, wait for it stable. */
+ if (MCG_C7_OSCSEL(kMCG_OscselOsc) == (MCG->C7 & MCG_C7_OSCSEL_MASK))
+ {
+ if (MCG->C2 & MCG_C2_EREFS_MASK)
+ {
+ while (!(MCG->S & MCG_S_OSCINIT0_MASK))
+ {
+ }
+ }
+ }
+
+ /* 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_ModeBLPE == mode)))
+ {
+ return kStatus_MCG_ModeUnreachable;
+ }
+#endif
+
+ /* 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 */
+
+ /* If use external crystal as clock source, wait for it stable. */
+ if (MCG_C7_OSCSEL(kMCG_OscselOsc) == (MCG->C7 & MCG_C7_OSCSEL_MASK))
+ {
+ if (MCG->C2 & MCG_C2_EREFS_MASK)
+ {
+ while (!(MCG->S & MCG_S_OSCINIT0_MASK))
+ {
+ }
+ }
+ }
+
+ /* 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_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)
+ {
+ }
+
+ 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 */
+
+ /* If use external crystal as clock source, wait for it stable. */
+ if (MCG_C7_OSCSEL(kMCG_OscselOsc) == (MCG->C7 & MCG_C7_OSCSEL_MASK))
+ {
+ if (MCG->C2 & MCG_C2_EREFS_MASK)
+ {
+ while (!(MCG->S & MCG_S_OSCINIT0_MASK))
+ {
+ }
+ }
+ }
+
+ /* 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;
+}
+
+/*
+ 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[6][6] = {
+ {kMCG_ModeFEI, kMCG_ModeFBI, kMCG_ModeFBI, kMCG_ModeFEE, kMCG_ModeFBE, kMCG_ModeFBE}, /* FEI */
+ {kMCG_ModeFEI, kMCG_ModeFBI, kMCG_ModeBLPI, kMCG_ModeFEE, kMCG_ModeFBE, kMCG_ModeFBE}, /* FBI */
+ {kMCG_ModeFBI, kMCG_ModeFBI, kMCG_ModeBLPI, kMCG_ModeFBI, kMCG_ModeFBI, kMCG_ModeFBI}, /* BLPI */
+ {kMCG_ModeFEI, kMCG_ModeFBI, kMCG_ModeFBI, kMCG_ModeFEE, kMCG_ModeFBE, kMCG_ModeFBE}, /* FEE */
+ {kMCG_ModeFEI, kMCG_ModeFBI, kMCG_ModeFBI, kMCG_ModeFEE, kMCG_ModeFBE, kMCG_ModeBLPE}, /* FBE */
+ {kMCG_ModeFBE, kMCG_ModeFBE, kMCG_ModeFBE, kMCG_ModeFBE, kMCG_ModeFBE, kMCG_ModeBLPE}, /* BLPE */
+ /* FEI FBI BLPI FEE FBE BLPE */
+};
+
+status_t CLOCK_SetMcgConfig(const mcg_config_t *config)
+{
+ mcg_mode_t next_mode;
+ status_t status = kStatus_Success;
+
+ /* 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 (kMCG_FllSrcExternal == MCG_S_IREFST_VAL)
+ {
+ CLOCK_ExternalModeToFbeModeQuick();
+ CLOCK_SetFeiMode(config->dmx32, config->drs, NULL);
+ }
+
+ 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, NULL);
+ break;
+ case kMCG_ModeFBE:
+ status = CLOCK_SetFbeMode(config->frdiv, config->dmx32, config->drs, NULL);
+ break;
+ case kMCG_ModeBLPI:
+ status = CLOCK_SetBlpiMode();
+ break;
+ case kMCG_ModeBLPE:
+ status = CLOCK_SetBlpeMode();
+ break;
+ default:
+ break;
+ }
+ if (kStatus_Success != status)
+ {
+ return status;
+ }
+ } while (next_mode != config->mcgMode);
+
+ return kStatus_Success;
+}
diff --git a/drivers/fsl_clock.h b/drivers/fsl_clock.h
new file mode 100644
index 0000000..3e0f384
--- /dev/null
+++ b/drivers/fsl_clock.h
@@ -0,0 +1,1286 @@
+/*
+ * The Clear BSD License
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * Copyright (c) 2016 - 2017 , NXP
+ * All rights reserved.
+ *
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted (subject to the limitations in the disclaimer below) 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 copyright holder nor the names of its
+ * contributors may be used to endorse or promote products derived from this
+ * software without specific prior written permission.
+ *
+ * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS LICENSE.
+ * 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_common.h"
+
+/*! @addtogroup clock */
+/*! @{ */
+
+/*! @file */
+
+/*******************************************************************************
+ * Configurations
+ ******************************************************************************/
+
+/*! @brief Configures whether to check a parameter in a function.
+ *
+ * Some MCG settings must be changed with conditions, for example:
+ * 1. MCGIRCLK settings, such as the source, divider, and the trim value should not change when
+ * MCGIRCLK is used as a system clock source.
+ * 2. MCG_C7[OSCSEL] should not be changed when the external reference clock is used
+ * as a system clock source. For example, in FBE/BLPE/PBE modes.
+ * 3. The users should only switch between the supported clock modes.
+ *
+ * MCG functions check the parameter and MCG status before setting, if not allowed
+ * to change, the functions return error. The parameter checking increases code size,
+ * if code size is a critical requirement, change #MCG_CONFIG_CHECK_PARAM to 0 to
+ * disable parameter checking.
+ */
+#ifndef MCG_CONFIG_CHECK_PARAM
+#define MCG_CONFIG_CHECK_PARAM 0U
+#endif
+
+/*! @brief Configure whether driver controls clock
+ *
+ * When set to 0, peripheral drivers will enable clock in initialize function
+ * and disable clock in de-initialize function. When set to 1, peripheral
+ * driver will not control the clock, application could contol the clock out of
+ * the driver.
+ *
+ * @note All drivers share this feature switcher. If it is set to 1, application
+ * should handle clock enable and disable for all drivers.
+ */
+#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL))
+#define FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL 0
+#endif
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+/*! @name Driver version */
+/*@{*/
+/*! @brief CLOCK driver version 2.2.1. */
+#define FSL_CLOCK_DRIVER_VERSION (MAKE_VERSION(2, 2, 1))
+/*@}*/
+
+/*! @brief External XTAL0 (OSC0) clock frequency.
+ *
+ * The XTAL0/EXTAL0 (OSC0) clock frequency in Hz. When the clock is set up, use the
+ * function CLOCK_SetXtal0Freq to set the value in the clock driver. For example,
+ * if XTAL0 is 8 MHz:
+ * @code
+ * CLOCK_InitOsc0(...); // Set up the OSC0
+ * CLOCK_SetXtal0Freq(80000000); // Set the XTAL0 value to the clock driver.
+ * @endcode
+ *
+ * This is important for the multicore platforms where only one core needs to set up the
+ * OSC0 using the CLOCK_InitOsc0. All other cores need to call the CLOCK_SetXtal0Freq
+ * to get a 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 set up, use the
+ * function CLOCK_SetXtal32Freq to set the value in the clock driver.
+ *
+ * This is important for the multicore platforms where only one core needs to set up
+ * the clock. All other cores need to call the CLOCK_SetXtal32Freq
+ * to get a valid clock frequency.
+ */
+extern uint32_t g_xtal32Freq;
+
+/*! @brief IRC48M clock frequency in Hz. */
+#define MCG_INTERNAL_IRC_48M 48000000U
+
+#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 PORT. */
+#define PORT_CLOCKS \
+ { \
+ kCLOCK_PortA, kCLOCK_PortB, kCLOCK_PortC, kCLOCK_PortD, kCLOCK_PortE \
+ }
+
+/*! @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 \
+ }
+
+/*! @brief Clock ip name array for LPTMR. */
+#define LPTMR_CLOCKS \
+ { \
+ kCLOCK_Lptmr0 \
+ }
+
+/*! @brief Clock ip name array for FTM. */
+#define FTM_CLOCKS \
+ { \
+ kCLOCK_Ftm0, kCLOCK_Ftm1, kCLOCK_Ftm2 \
+ }
+
+/*! @brief Clock ip name array for EDMA. */
+#define EDMA_CLOCKS \
+ { \
+ kCLOCK_Dma0 \
+ }
+
+/*! @brief Clock ip name array for DAC. */
+#define DAC_CLOCKS \
+ { \
+ kCLOCK_Dac0 \
+ }
+
+/*! @brief Clock ip name array for ADC16. */
+#define ADC16_CLOCKS \
+ { \
+ kCLOCK_Adc0 \
+ }
+
+/*! @brief Clock ip name array for VREF. */
+#define VREF_CLOCKS \
+ { \
+ kCLOCK_Vref0 \
+ }
+
+/*! @brief Clock ip name array for UART. */
+#define UART_CLOCKS \
+ { \
+ kCLOCK_Uart0, kCLOCK_Uart1 \
+ }
+
+/*! @brief Clock ip name array for CRC. */
+#define CRC_CLOCKS \
+ { \
+ kCLOCK_Crc0 \
+ }
+
+/*! @brief Clock ip name array for I2C. */
+#define I2C_CLOCKS \
+ { \
+ kCLOCK_I2c0 \
+ }
+
+/*! @brief Clock ip name array for FTF. */
+#define FTF_CLOCKS \
+ { \
+ kCLOCK_Ftf0 \
+ }
+
+/*! @brief Clock ip name array for PDB. */
+#define PDB_CLOCKS \
+ { \
+ kCLOCK_Pdb0 \
+ }
+
+/*! @brief Clock ip name array for CMP. */
+#define CMP_CLOCKS \
+ { \
+ kCLOCK_Cmp0, kCLOCK_Cmp1 \
+ }
+
+/*!
+ * @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 FAST_CLK kCLOCK_FastPeriphClk
+
+#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 UART0_CLK_SRC SYS_CLK
+#define UART1_CLK_SRC SYS_CLK
+#define UART2_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;
+
+/*------------------------------------------------------------------------------
+
+ 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_Ewm0 = CLK_GATE_DEFINE(0x1034U, 1U),
+ kCLOCK_I2c0 = CLK_GATE_DEFINE(0x1034U, 6U),
+ kCLOCK_Uart0 = CLK_GATE_DEFINE(0x1034U, 10U),
+ kCLOCK_Uart1 = CLK_GATE_DEFINE(0x1034U, 11U),
+ kCLOCK_Cmp0 = CLK_GATE_DEFINE(0x1034U, 19U),
+ kCLOCK_Cmp1 = CLK_GATE_DEFINE(0x1034U, 19U),
+ kCLOCK_Vref0 = CLK_GATE_DEFINE(0x1034U, 20U),
+
+ kCLOCK_Lptmr0 = CLK_GATE_DEFINE(0x1038U, 0U),
+ 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_Spi0 = CLK_GATE_DEFINE(0x103CU, 12U),
+ kCLOCK_Crc0 = CLK_GATE_DEFINE(0x103CU, 18U),
+ 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_Ftm2 = CLK_GATE_DEFINE(0x103CU, 26U),
+ kCLOCK_Adc0 = CLK_GATE_DEFINE(0x103CU, 27U),
+ kCLOCK_Dac0 = CLK_GATE_DEFINE(0x103CU, 31U),
+
+ kCLOCK_Dma0 = CLK_GATE_DEFINE(0x1040U, 1U),
+} 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 an 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. */
+
+ uint8_t erclkDiv; /*!< Divider for OSCERCLK.*/
+} oscer_config_t;
+
+/*!
+ * @brief OSC Initialization Configuration Structure
+ *
+ * Defines the configuration data structure to initialize the OSC.
+ * When porting to a new board, set the following members
+ * according to the 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 */
+ kMCG_OscselIrc /*!< Selects 48 MHz IRC 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) /*!< Can't change the clock source because
+ it is in use. */
+};
+
+/*! @brief MCG status flags. */
+enum _mcg_status_flags_t
+{
+ kMCG_Osc0LostFlag = (1U << 0U), /*!< OSC0 lost. */
+ kMCG_Osc0InitFlag = (1U << 1U), /*!< OSC0 crystal initialized. */
+};
+
+/*! @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 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_ModeError /*!< Unknown mode */
+} mcg_mode_t;
+
+/*! @brief MCG mode change configuration structure
+ *
+ * When porting to a new board, set the following members
+ * according to the board setting:
+ * 1. frdiv: If the FLL uses the external reference clock, set this
+ * value to ensure that the external reference clock divided by frdiv is
+ * in the 31.25 kHz to 39.0625 kHz range.
+ * 2. The PLL reference clock divider PRDIV: PLL reference clock frequency after
+ * PRDIV should be in the FSL_FEATURE_MCG_PLL_REF_MIN to
+ * FSL_FEATURE_MCG_PLL_REF_MAX range.
+ */
+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_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 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 System clock divider
+ *
+ * Set the SIM_CLKDIV1[OUTDIV1], SIM_CLKDIV1[OUTDIV2], SIM_CLKDIV1[OUTDIV4].
+ *
+ * @param outdiv1 Clock 1 output divider value.
+ *
+ * @param outdiv2 Clock 2 output divider value.
+ *
+ * @param outdiv4 Clock 4 output divider value.
+ */
+static inline void CLOCK_SetOutDiv(uint32_t outdiv1, uint32_t outdiv2, uint32_t outdiv4)
+{
+ SIM->CLKDIV1 = SIM_CLKDIV1_OUTDIV1(outdiv1) | SIM_CLKDIV1_OUTDIV2(outdiv2) | 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 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 undivided clock frequency (OSC0ERCLK_UNDIV).
+ *
+ * @return Clock frequency in Hz.
+ */
+uint32_t CLOCK_GetOsc0ErClkUndivFreq(void);
+
+/*!
+ * @brief Get the OSC0 external reference clock frequency (OSC0ERCLK).
+ *
+ * @return Clock frequency in Hz.
+ */
+
+uint32_t CLOCK_GetOsc0ErClkFreq(void);
+
+/*!
+ * @brief Get the OSC0 external reference divided clock frequency.
+ *
+ * @return Clock frequency in Hz.
+ */
+uint32_t CLOCK_GetOsc0ErClkDivFreq(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 = 0x11070000U;
+}
+
+/*! @name MCG frequency functions. */
+/*@{*/
+
+/*!
+ * @brief Gets the MCG output clock (MCGOUTCLK) frequency.
+ *
+ * This function gets the MCG output clock frequency in Hz based on the current MCG
+ * register value.
+ *
+ * @return The frequency of MCGOUTCLK.
+ */
+uint32_t CLOCK_GetOutClkFreq(void);
+
+/*!
+ * @brief Gets the MCG FLL clock (MCGFLLCLK) frequency.
+ *
+ * This function gets the MCG FLL clock frequency in Hz based on the current MCG
+ * register value. The FLL is enabled in FEI/FBI/FEE/FBE mode and
+ * disabled in low power state in other modes.
+ *
+ * @return The frequency of MCGFLLCLK.
+ */
+uint32_t CLOCK_GetFllFreq(void);
+
+/*!
+ * @brief Gets the MCG internal reference clock (MCGIRCLK) frequency.
+ *
+ * This function gets the MCG internal reference clock frequency in Hz based
+ * on the current MCG register value.
+ *
+ * @return The frequency of MCGIRCLK.
+ */
+uint32_t CLOCK_GetInternalRefClkFreq(void);
+
+/*!
+ * @brief Gets the MCG fixed frequency clock (MCGFFCLK) frequency.
+ *
+ * This function gets the MCG fixed frequency clock frequency in Hz based
+ * on the current MCG register value.
+ *
+ * @return The frequency of MCGFFCLK.
+ */
+uint32_t CLOCK_GetFixedFreqClkFreq(void);
+
+/*@}*/
+
+/*! @name MCG clock configuration. */
+/*@{*/
+
+/*!
+ * @brief Enables or disables the MCG low power.
+ *
+ * Enabling the MCG low power disables the PLL and FLL in bypass modes. In other words,
+ * in FBE and PBE modes, enabling low power sets the MCG to BLPE mode. In FBI and
+ * PBI modes, enabling low power sets the MCG to BLPI mode.
+ * When disabling the MCG low power, the PLL or FLL are enabled based on MCG settings.
+ *
+ * @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 Configures the Internal Reference clock (MCGIRCLK).
+ *
+ * This function sets the \c MCGIRCLK base on parameters. It also selects the IRC
+ * source. If the fast IRC is used, this function sets the fast IRC divider.
+ * This function also sets whether the \c MCGIRCLK is enabled in stop mode.
+ * Calling this function in FBI/PBI/BLPI modes may change the system clock. As a result,
+ * using the function in these modes it is not allowed.
+ *
+ * @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 Because the internall reference clock is used as a clock source,
+ * the confuration should not be changed. Otherwise, a glitch occurs.
+ * @retval kStatus_Success MCGIRCLK configuration finished successfully.
+ */
+status_t CLOCK_SetInternalRefClkConfig(uint8_t enableMode, mcg_irc_mode_t ircs, uint8_t fcrdiv);
+
+/*!
+ * @brief Selects the MCG external reference clock.
+ *
+ * Selects the MCG external reference clock source, changes the MCG_C7[OSCSEL],
+ * and waits for the clock source to be stable. Because the external reference
+ * clock should not be changed in FEE/FBE/BLPE/PBE/PEE modes, do not call this function in these modes.
+ *
+ * @param oscsel MCG external reference clock source, MCG_C7[OSCSEL].
+ * @retval kStatus_MCG_SourceUsed Because the external reference clock is used as a clock source,
+ * the confuration should not be changed. Otherwise, a glitch occurs.
+ * @retval kStatus_Success External reference clock set successfully.
+ */
+status_t CLOCK_SetExternalRefClkConfig(mcg_oscsel_t oscsel);
+
+/*!
+ * @brief Set the FLL external reference clock divider value.
+ *
+ * Sets the FLL external reference clock divider value, the register MCG_C1[FRDIV].
+ *
+ * @param frdiv The FLL external reference clock divider value, MCG_C1[FRDIV].
+ */
+static inline void CLOCK_SetFllExtRefDiv(uint8_t frdiv)
+{
+ MCG->C1 = (MCG->C1 & ~MCG_C1_FRDIV_MASK) | MCG_C1_FRDIV(frdiv);
+}
+
+/*@}*/
+
+/*! @name MCG clock lock monitor functions. */
+/*@{*/
+
+/*!
+ * @brief Sets the OSC0 clock monitor mode.
+ *
+ * This function sets the OSC0 clock monitor mode. See @ref mcg_monitor_mode_t for details.
+ *
+ * @param mode Monitor mode to set.
+ */
+void CLOCK_SetOsc0MonitorMode(mcg_monitor_mode_t mode);
+
+/*!
+ * @brief Gets the MCG status flags.
+ *
+ * This function gets the MCG clock status flags. All status flags are
+ * returned as a logical OR of the enumeration @ref _mcg_status_flags_t. To
+ * check a specific flag, compare the return value with the flag.
+ *
+ * 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 a 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).
+ * This is an example to enable the OSCERCLK in normal and stop modes and also set
+ * the output divider to 1:
+ *
+ @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;
+
+ base->DIV = OSC_DIV_ERPS(config->erclkDiv);
+}
+
+/*!
+ * @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 Initializes the OSC0.
+ *
+ * This function initializes the OSC0 according to the board configuration.
+ *
+ * @param config Pointer to the OSC0 configuration structure.
+ */
+void CLOCK_InitOsc0(osc_config_t const *config);
+
+/*!
+ * @brief Deinitializes the OSC0.
+ *
+ * This function deinitializes the OSC0.
+ */
+void CLOCK_DeinitOsc0(void);
+
+/* @} */
+
+/*!
+ * @name External clock frequency
+ * @{
+ */
+
+/*!
+ * @brief Sets the XTAL0 frequency based on board settings.
+ *
+ * @param freq The XTAL0/EXTAL0 input clock frequency in Hz.
+ */
+static inline void CLOCK_SetXtal0Freq(uint32_t freq)
+{
+ g_xtal0Freq = freq;
+}
+
+/*!
+ * @brief Sets the XTAL32/RTC_CLKIN frequency based on board settings.
+ *
+ * @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 trims the internal reference clock.
+ *
+ * This function trims the internal reference clock by using the 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, which should be a bus clock.
+ * @param desireFreq Frequency to trim to.
+ * @param actualFreq Actual frequency after trimming.
+ * @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 the 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 a bus clock source.
+ * @retval kStatus_MCG_AtmHardwareFail Hardware fails while trimming.
+ */
+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 determines the current MCG mode.
+ *
+ * @return Current MCG mode or error code; See @ref mcg_mode_t.
+ */
+mcg_mode_t CLOCK_GetMode(void);
+
+/*!
+ * @brief Sets the MCG to FEI mode.
+ *
+ * This function sets the MCG to FEI mode. If setting to FEI mode fails
+ * from the current mode, this function returns an error.
+ *
+ * @param dmx32 DMX32 in FEI mode.
+ * @param drs The DCO range selection.
+ * @param fllStableDelay Delay function to ensure that the FLL is stable. Passing
+ * NULL does not cause a delay.
+ * @retval kStatus_MCG_ModeUnreachable Could not switch to the target mode.
+ * @retval kStatus_Success Switched to the target mode successfully.
+ * @note If @p dmx32 is set to kMCG_Dmx32Fine, the slow IRC must not be trimmed
+ * to a frequency above 32768 Hz.
+ */
+status_t CLOCK_SetFeiMode(mcg_dmx32_t dmx32, mcg_drs_t drs, void (*fllStableDelay)(void));
+
+/*!
+ * @brief Sets the MCG to FEE mode.
+ *
+ * This function sets the MCG to FEE mode. If setting to FEE mode fails
+ * from the current mode, this function returns an 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. Passing
+ * NULL does not cause a delay.
+ *
+ * @retval kStatus_MCG_ModeUnreachable Could not switch to the target mode.
+ * @retval kStatus_Success Switched to the target mode successfully.
+ */
+status_t CLOCK_SetFeeMode(uint8_t frdiv, mcg_dmx32_t dmx32, mcg_drs_t drs, void (*fllStableDelay)(void));
+
+/*!
+ * @brief Sets the MCG to FBI mode.
+ *
+ * This function sets the MCG to FBI mode. If setting to FBI mode fails
+ * from the current mode, this function returns an error.
+ *
+ * @param dmx32 DMX32 in FBI mode.
+ * @param drs The DCO range selection.
+ * @param fllStableDelay Delay function to make sure FLL is stable. If the FLL
+ * is not used in FBI mode, this parameter can be NULL. Passing
+ * NULL does not cause a delay.
+ * @retval kStatus_MCG_ModeUnreachable Could not switch to the target mode.
+ * @retval kStatus_Success Switched to the target mode successfully.
+ * @note If @p dmx32 is set to kMCG_Dmx32Fine, the slow IRC must not be trimmed
+ * to frequency above 32768 Hz.
+ */
+status_t CLOCK_SetFbiMode(mcg_dmx32_t dmx32, mcg_drs_t drs, void (*fllStableDelay)(void));
+
+/*!
+ * @brief Sets the MCG to FBE mode.
+ *
+ * This function sets the MCG to FBE mode. If setting to FBE mode fails
+ * from the current mode, this function returns an 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 the FLL
+ * is not used in FBE mode, this parameter can be NULL. Passing NULL
+ * does not cause a delay.
+ * @retval kStatus_MCG_ModeUnreachable Could not switch to the target mode.
+ * @retval kStatus_Success Switched to the target mode successfully.
+ */
+status_t CLOCK_SetFbeMode(uint8_t frdiv, mcg_dmx32_t dmx32, mcg_drs_t drs, void (*fllStableDelay)(void));
+
+/*!
+ * @brief Sets the MCG to BLPI mode.
+ *
+ * This function sets the MCG to BLPI mode. If setting to BLPI mode fails
+ * from the current mode, this function returns an error.
+ *
+ * @retval kStatus_MCG_ModeUnreachable Could not switch to the target mode.
+ * @retval kStatus_Success Switched to the target mode successfully.
+ */
+status_t CLOCK_SetBlpiMode(void);
+
+/*!
+ * @brief Sets the MCG to BLPE mode.
+ *
+ * This function sets the MCG to BLPE mode. If setting to BLPE mode fails
+ * from the current mode, this function returns an error.
+ *
+ * @retval kStatus_MCG_ModeUnreachable Could not switch to the target mode.
+ * @retval kStatus_Success Switched to the target mode successfully.
+ */
+status_t CLOCK_SetBlpeMode(void);
+
+/*!
+ * @brief Switches the MCG to FBE mode from the external mode.
+ *
+ * This function switches the MCG from external modes (PEE/PBE/BLPE/FEE) to the FBE mode quickly.
+ * The external clock is used as the system clock souce and PLL is disabled. However,
+ * the FLL settings are not configured. This is a lite function with a small code size, which is useful
+ * during the mode switch. For example, to switch from PEE mode to FEI mode:
+ *
+ * @code
+ * CLOCK_ExternalModeToFbeModeQuick();
+ * CLOCK_SetFeiMode(...);
+ * @endcode
+ *
+ * @retval kStatus_Success Switched successfully.
+ * @retval kStatus_MCG_ModeInvalid If the current mode is not an external mode, do not call this function.
+ */
+status_t CLOCK_ExternalModeToFbeModeQuick(void);
+
+/*!
+ * @brief Switches the MCG to FBI mode from internal modes.
+ *
+ * This function switches the MCG from internal modes (PEI/PBI/BLPI/FEI) to the FBI mode quickly.
+ * The MCGIRCLK is used as the system clock souce and PLL is disabled. However,
+ * FLL settings are not configured. This is a lite function with a small code size, which is useful
+ * during the mode switch. For example, to switch from PEI mode to FEE mode:
+ *
+ * @code
+ * CLOCK_InternalModeToFbiModeQuick();
+ * CLOCK_SetFeeMode(...);
+ * @endcode
+ *
+ * @retval kStatus_Success Switched successfully.
+ * @retval kStatus_MCG_ModeInvalid If the current mode is not an internal mode, do not call this function.
+ */
+status_t CLOCK_InternalModeToFbiModeQuick(void);
+
+/*!
+ * @brief Sets the MCG to FEI mode during system boot up.
+ *
+ * This function sets the MCG to FEI mode from the reset mode. It can also 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 ensure that the FLL is stable.
+ *
+ * @retval kStatus_MCG_ModeUnreachable Could not switch to the target mode.
+ * @retval kStatus_Success Switched to the target mode successfully.
+ * @note If @p dmx32 is set to kMCG_Dmx32Fine, the slow IRC must not be trimmed
+ * to frequency above 32768 Hz.
+ */
+status_t CLOCK_BootToFeiMode(mcg_dmx32_t dmx32, mcg_drs_t drs, void (*fllStableDelay)(void));
+
+/*!
+ * @brief Sets the MCG to FEE mode during system bootup.
+ *
+ * This function sets MCG to FEE mode from the reset mode. It can also be used to
+ * set up the 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 ensure that the FLL is stable.
+ *
+ * @retval kStatus_MCG_ModeUnreachable Could not switch to the target mode.
+ * @retval kStatus_Success Switched to the 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 Sets the MCG to BLPI mode during system boot up.
+ *
+ * This function sets the MCG to BLPI mode from the reset mode. It can also be used to
+ * set up the 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 Switched to the target mode successfully.
+ */
+status_t CLOCK_BootToBlpiMode(uint8_t fcrdiv, mcg_irc_mode_t ircs, uint8_t ircEnableMode);
+
+/*!
+ * @brief Sets the MCG to BLPE mode during sytem boot up.
+ *
+ * This function sets the MCG to BLPE mode from the reset mode. It can also be used to
+ * set up the 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 Switched to the target mode successfully.
+ */
+status_t CLOCK_BootToBlpeMode(mcg_oscsel_t oscsel);
+
+/*!
+ * @brief Sets the MCG to a target mode.
+ *
+ * This function sets MCG to a target mode defined by the configuration
+ * structure. If switching to the target mode fails, this function
+ * chooses the correct path.
+ *
+ * @param config Pointer to the target MCG mode configuration structure.
+ * @return Return kStatus_Success if switched successfully; Otherwise, it returns an error code #_mcg_status.
+ *
+ * @note If the external clock is used in the target mode, ensure that it is
+ * enabled. For example, if the OSC0 is used, set up OSC0 correctly before calling this
+ * function.
+ */
+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..98039cd
--- /dev/null
+++ b/drivers/fsl_cmp.c
@@ -0,0 +1,295 @@
+/*
+ * The Clear BSD License
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * Copyright 2016-2017 NXP
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted (subject to the limitations in the disclaimer below) provided
+ * that the following conditions are met:
+ *
+ * o Redistributions of source code must retain the above copyright notice, this list
+ * of conditions and the following disclaimer.
+ *
+ * o Redistributions in binary form must reproduce the above copyright notice, this
+ * list of conditions and the following disclaimer in the documentation and/or
+ * other materials provided with the distribution.
+ *
+ * o Neither the name of the copyright holder nor the names of its
+ * contributors may be used to endorse or promote products derived from this
+ * software without specific prior written permission.
+ *
+ * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS LICENSE.
+ * 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"
+
+/* Component ID definition, used by tools. */
+#ifndef FSL_COMPONENT_ID
+#define FSL_COMPONENT_ID "platform.drivers.cmp"
+#endif
+
+
+/*******************************************************************************
+ * 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;
+#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
+/*! @brief Pointers to CMP clocks for each instance. */
+static const clock_ip_name_t s_cmpClocks[] = CMP_CLOCKS;
+#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
+
+/*******************************************************************************
+ * Codes
+ ******************************************************************************/
+static uint32_t CMP_GetInstance(CMP_Type *base)
+{
+ uint32_t instance;
+
+ /* Find the instance index from base address mappings. */
+ for (instance = 0; instance < ARRAY_SIZE(s_cmpBases); instance++)
+ {
+ if (s_cmpBases[instance] == base)
+ {
+ break;
+ }
+ }
+
+ assert(instance < ARRAY_SIZE(s_cmpBases));
+
+ return instance;
+}
+
+void CMP_Init(CMP_Type *base, const cmp_config_t *config)
+{
+ assert(NULL != config);
+
+ uint8_t tmp8;
+
+#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
+ /* Enable the clock. */
+ CLOCK_EnableClock(s_cmpClocks[CMP_GetInstance(base)]);
+#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
+
+ /* 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);
+
+#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
+ /* Disable the clock. */
+ CLOCK_DisableClock(s_cmpClocks[CMP_GetInstance(base)]);
+#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
+}
+
+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..e228413
--- /dev/null
+++ b/drivers/fsl_cmp.h
@@ -0,0 +1,347 @@
+/*
+ * The Clear BSD License
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * Copyright 2016-2017 NXP
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted (subject to the limitations in the disclaimer below) provided
+ * that the following conditions are met:
+ *
+ * o Redistributions of source code must retain the above copyright notice, this list
+ * of conditions and the following disclaimer.
+ *
+ * o Redistributions in binary form must reproduce the above copyright notice, this
+ * list of conditions and the following disclaimer in the documentation and/or
+ * other materials provided with the distribution.
+ *
+ * o Neither the name of the copyright holder nor the names of its
+ * contributors may be used to endorse or promote products derived from this
+ * software without specific prior written permission.
+ *
+ * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS LICENSE.
+ * 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 the comparison output has occurred. */
+ kCMP_OutputFallingEventFlag = CMP_SCR_CFF_MASK, /*!< Falling-edge on the comparison 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 a resistor ladder network supply reference Vin. */
+ kCMP_VrefSourceVin2 = 1U, /*!< Vin2 is selected as a resistor ladder network supply reference Vin. */
+} cmp_reference_voltage_source_t;
+
+/*!
+ * @brief Configures 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 (HS) comparison mode. */
+ bool enableInvertOutput; /*!< Enable the inverted comparator output. */
+ bool useUnfilteredOutput; /*!< Set the 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 Configures 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 the external SAMPLE as a sampling clock input or using a divided bus clock. */
+#endif /* FSL_FEATURE_CMP_HAS_EXTERNAL_SAMPLE_SUPPORT */
+ uint8_t filterCount; /*!< Filter Sample Count. Available range is 1-7; 0 disables the filter.*/
+ uint8_t filterPeriod; /*!< Filter Sample Period. The divider to the bus clock. Available range is 0-255. */
+} cmp_filter_config_t;
+
+/*!
+ * @brief Configures the internal DAC.
+ */
+typedef struct _cmp_dac_config
+{
+ cmp_reference_voltage_source_t referenceVoltageSource; /*!< Supply voltage reference source. */
+ uint8_t DACValue; /*!< Value for the 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 as follows.
+ * - Enabling the clock for CMP module.
+ * - Configuring the comparator.
+ * - Enabling the CMP module.
+ * Note that for some devices, multiple CMP instances share the same clock gate. In this case, to enable the clock for
+ * any instance enables all CMPs. See the appropriate MCU reference manual for the clock assignment of the CMP.
+ *
+ * @param base CMP peripheral base address.
+ * @param config Pointer to the 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 as follows.
+ * - Disabling the CMP module.
+ * - Disabling the clock for CMP module.
+ *
+ * This function disables the clock for the CMP.
+ * Note that for some devices, multiple CMP instances share 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 Enables or disables the module.
+ */
+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 the same way 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 Enables or disables the feature.
+ */
+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 Enables or disables the feature.
+ */
+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 Enables or disables the feature.
+ */
+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 the 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 the configuration structure. "NULL" disables 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_common.c b/drivers/fsl_common.c
new file mode 100644
index 0000000..903faf5
--- /dev/null
+++ b/drivers/fsl_common.c
@@ -0,0 +1,192 @@
+/*
+* The Clear BSD License
+* Copyright (c) 2015-2016, Freescale Semiconductor, Inc.
+ * Copyright 2016 NXP
+* All rights reserved.
+*
+*
+* Redistribution and use in source and binary forms, with or without modification,
+* are permitted (subject to the limitations in the disclaimer below) provided
+* that the following conditions are met:
+*
+* o Redistributions of source code must retain the above copyright notice, this list
+* of conditions and the following disclaimer.
+*
+* o Redistributions in binary form must reproduce the above copyright notice, this
+* list of conditions and the following disclaimer in the documentation and/or
+* other materials provided with the distribution.
+*
+* o Neither the name of the copyright holder nor the names of its
+* contributors may be used to endorse or promote products derived from this
+* software without specific prior written permission.
+*
+* NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS LICENSE.
+* 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"
+#define SDK_MEM_MAGIC_NUMBER 12345U
+
+typedef struct _mem_align_control_block
+{
+ uint16_t identifier; /*!< Identifier for the memory control block. */
+ uint16_t offset; /*!< offset from aligned adress to real address */
+} mem_align_cb_t;
+
+/* Component ID definition, used by tools. */
+#ifndef FSL_COMPONENT_ID
+#define FSL_COMPONENT_ID "platform.drivers.common"
+#endif
+
+
+#ifndef __GIC_PRIO_BITS
+#if defined(ENABLE_RAM_VECTOR_TABLE)
+uint32_t 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;
+ uint32_t ret;
+ uint32_t irqMaskValue;
+
+ irqMaskValue = DisableGlobalIRQ();
+ 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;
+ }
+
+ ret = __VECTOR_RAM[irq + 16];
+ /* make sure the __VECTOR_RAM is noncachable */
+ __VECTOR_RAM[irq + 16] = irqHandler;
+
+ EnableGlobalIRQ(irqMaskValue);
+
+/* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+
+ return ret;
+}
+#endif /* ENABLE_RAM_VECTOR_TABLE. */
+#endif /* __GIC_PRIO_BITS. */
+
+#ifndef QN908XC_SERIES
+#if (defined(FSL_FEATURE_SOC_SYSCON_COUNT) && (FSL_FEATURE_SOC_SYSCON_COUNT > 0))
+
+void EnableDeepSleepIRQ(IRQn_Type interrupt)
+{
+ uint32_t intNumber = (uint32_t)interrupt;
+
+#if (defined(FSL_FEATURE_SYSCON_STARTER_DISCONTINUOUS) && (FSL_FEATURE_SYSCON_STARTER_DISCONTINUOUS == 1))
+ {
+ SYSCON->STARTERP1 = 1u << intNumber;
+ }
+#else
+ {
+ uint32_t index = 0;
+
+ while (intNumber >= 32u)
+ {
+ index++;
+ intNumber -= 32u;
+ }
+
+ SYSCON->STARTERSET[index] = 1u << intNumber;
+ }
+#endif /* FSL_FEATURE_STARTER_DISCONTINUOUS */
+ EnableIRQ(interrupt); /* also enable interrupt at NVIC */
+}
+
+void DisableDeepSleepIRQ(IRQn_Type interrupt)
+{
+ uint32_t intNumber = (uint32_t)interrupt;
+
+ DisableIRQ(interrupt); /* also disable interrupt at NVIC */
+#if (defined(FSL_FEATURE_SYSCON_STARTER_DISCONTINUOUS) && (FSL_FEATURE_SYSCON_STARTER_DISCONTINUOUS == 1))
+ {
+ SYSCON->STARTERP1 &= ~(1u << intNumber);
+ }
+#else
+ {
+ uint32_t index = 0;
+
+ while (intNumber >= 32u)
+ {
+ index++;
+ intNumber -= 32u;
+ }
+
+ SYSCON->STARTERCLR[index] = 1u << intNumber;
+ }
+#endif /* FSL_FEATURE_STARTER_DISCONTINUOUS */
+}
+#endif /* FSL_FEATURE_SOC_SYSCON_COUNT */
+
+#endif /* QN908XC_SERIES */
+
+void *SDK_Malloc(size_t size, size_t alignbytes)
+{
+ mem_align_cb_t *p_cb = NULL;
+ uint32_t alignedsize = SDK_SIZEALIGN(size, alignbytes) + alignbytes + sizeof(mem_align_cb_t);
+ void *p_align_addr, *p_addr = malloc(alignedsize);
+
+ if (!p_addr)
+ {
+ return NULL;
+ }
+
+ p_align_addr = (void *)SDK_SIZEALIGN((uint32_t)p_addr + sizeof(mem_align_cb_t), alignbytes);
+
+ p_cb = (mem_align_cb_t *)((uint32_t)p_align_addr - 4);
+ p_cb->identifier = SDK_MEM_MAGIC_NUMBER;
+ p_cb->offset = (uint32_t)p_align_addr - (uint32_t)p_addr;
+
+ return (void *)p_align_addr;
+}
+
+void SDK_Free(void *ptr)
+{
+ mem_align_cb_t *p_cb = (mem_align_cb_t *)((uint32_t)ptr - 4);
+
+ if (p_cb->identifier != SDK_MEM_MAGIC_NUMBER)
+ {
+ return;
+ }
+
+ free((void *)((uint32_t)ptr - p_cb->offset));
+}
+
diff --git a/drivers/fsl_common.h b/drivers/fsl_common.h
new file mode 100644
index 0000000..a53dbc2
--- /dev/null
+++ b/drivers/fsl_common.h
@@ -0,0 +1,576 @@
+/*
+ * The Clear BSD License
+ * Copyright (c) 2015-2016, Freescale Semiconductor, Inc.
+ * Copyright 2016-2017 NXP
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted (subject to the limitations in the disclaimer below) provided
+ * that the following conditions are met:
+ *
+ * o Redistributions of source code must retain the above copyright notice, this list
+ * of conditions and the following disclaimer.
+ *
+ * o Redistributions in binary form must reproduce the above copyright notice, this
+ * list of conditions and the following disclaimer in the documentation and/or
+ * other materials provided with the distribution.
+ *
+ * o Neither the name of the copyright holder nor the names of its
+ * contributors may be used to endorse or promote products derived from this
+ * software without specific prior written permission.
+ *
+ * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS LICENSE.
+ * 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 <stdlib.h>
+
+#if defined(__ICCARM__)
+#include <stddef.h>
+#endif
+
+#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))
+
+/*! @name Driver version */
+/*@{*/
+/*! @brief common driver version 2.0.0. */
+#define FSL_COMMON_DRIVER_VERSION (MAKE_VERSION(2, 0, 0))
+/*@}*/
+
+/* 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. */
+#define DEBUG_CONSOLE_DEVICE_TYPE_FLEXCOMM 5U /*!< Debug console base on USBCDC. */
+#define DEBUG_CONSOLE_DEVICE_TYPE_IUART 6U /*!< Debug console base on i.MX UART. */
+#define DEBUG_CONSOLE_DEVICE_TYPE_VUSART 7U /*!< Debug console base on LPC_USART. */
+#define DEBUG_CONSOLE_DEVICE_TYPE_MINI_USART 8U /*!< Debug console base on LPC_USART. */
+#define DEBUG_CONSOLE_DEVICE_TYPE_SWO 9U /*!< Debug console base on SWO. */
+
+/*! @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_FLEXIO_MCULCD = 24, /*!< Group number for FLEXIO LCD status codes */
+ kStatusGroup_FLASHIAP = 25, /*!< Group number for FLASHIAP status codes */
+ kStatusGroup_FLEXCOMM_I2C = 26, /*!< Group number for FLEXCOMM I2C status codes */
+ kStatusGroup_I2S = 27, /*!< Group number for I2S status codes */
+ kStatusGroup_IUART = 28, /*!< Group number for IUART status codes */
+ kStatusGroup_CSI = 29, /*!< Group number for CSI status codes */
+ kStatusGroup_MIPI_DSI = 30, /*!< Group number for MIPI DSI 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_LPC_SPI = 56, /*!< Group number for LPC_SPI status codes. */
+ kStatusGroup_LPC_USART = 57, /*!< Group number for LPC_USART status codes. */
+ kStatusGroup_DMIC = 58, /*!< Group number for DMIC status codes. */
+ kStatusGroup_SDIF = 59, /*!< Group number for SDIF status codes.*/
+ kStatusGroup_SPIFI = 60, /*!< Group number for SPIFI status codes. */
+ kStatusGroup_OTP = 61, /*!< Group number for OTP status codes. */
+ kStatusGroup_MCAN = 62, /*!< Group number for MCAN status codes. */
+ kStatusGroup_CAAM = 63, /*!< Group number for CAAM status codes. */
+ kStatusGroup_ECSPI = 64, /*!< Group number for ECSPI status codes. */
+ kStatusGroup_USDHC = 65, /*!< Group number for USDHC status codes.*/
+ kStatusGroup_LPC_I2C = 66, /*!< Group number for LPC_I2C status codes.*/
+ kStatusGroup_DCP = 67, /*!< Group number for DCP status codes.*/
+ kStatusGroup_MSCAN = 68, /*!< Group number for MSCAN status codes.*/
+ kStatusGroup_ESAI = 69, /*!< Group number for ESAI status codes. */
+ kStatusGroup_FLEXSPI = 70, /*!< Group number for FLEXSPI status codes. */
+ kStatusGroup_MMDC = 71, /*!< Group number for MMDC status codes. */
+ kStatusGroup_MICFIL = 72, /*!< Group number for MIC status codes. */
+ kStatusGroup_SDMA = 73, /*!< Group number for SDMA status codes. */
+ kStatusGroup_ICS = 74, /*!< Group number for ICS status codes. */
+ kStatusGroup_SPDIF = 75, /*!< Group number for SPDIF status codes. */
+ kStatusGroup_LPC_MINISPI = 76, /*!< Group number for LPC_MINISPI status codes. */
+ kStatusGroup_NOTIFIER = 98, /*!< Group number for NOTIFIER status codes. */
+ kStatusGroup_DebugConsole = 99, /*!< Group number for debug console status codes. */
+ kStatusGroup_SEMC = 100, /*!< Group number for SEMC status codes. */
+ kStatusGroup_ApplicationRangeStart = 101, /*!< 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"
+
+/*
+ * Chip level peripheral reset API, for MCUs that implement peripheral reset control external to a peripheral
+ */
+#if ((defined(FSL_FEATURE_SOC_SYSCON_COUNT) && (FSL_FEATURE_SOC_SYSCON_COUNT > 0)) || \
+ (defined(FSL_FEATURE_SOC_ASYNC_SYSCON_COUNT) && (FSL_FEATURE_SOC_ASYNC_SYSCON_COUNT > 0)))
+#include "fsl_reset.h"
+#endif
+
+/*
+ * Macro guard for whether to use default weak IRQ implementation in drivers
+ */
+#ifndef FSL_DRIVER_TRANSFER_DOUBLE_WEAK_IRQ
+#define FSL_DRIVER_TRANSFER_DOUBLE_WEAK_IRQ 1
+#endif
+
+/*! @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. */
+#if !defined(ARRAY_SIZE)
+#define ARRAY_SIZE(x) (sizeof(x) / sizeof((x)[0]))
+#endif
+
+/*! @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)
+/* @} */
+
+/*! @name Alignment variable definition macros */
+/* @{ */
+#if (defined(__ICCARM__))
+/**
+ * Workaround to disable MISRA C message suppress warnings for IAR compiler.
+ * http://supp.iar.com/Support/?note=24725
+ */
+_Pragma("diag_suppress=Pm120")
+#define SDK_PRAGMA(x) _Pragma(#x)
+ _Pragma("diag_error=Pm120")
+/*! Macro to define a variable with alignbytes alignment */
+#define SDK_ALIGN(var, alignbytes) SDK_PRAGMA(data_alignment = alignbytes) var
+/*! Macro to define a variable with L1 d-cache line size alignment */
+#if defined(FSL_FEATURE_L1DCACHE_LINESIZE_BYTE)
+#define SDK_L1DCACHE_ALIGN(var) SDK_PRAGMA(data_alignment = FSL_FEATURE_L1DCACHE_LINESIZE_BYTE) var
+#endif
+/*! Macro to define a variable with L2 cache line size alignment */
+#if defined(FSL_FEATURE_L2CACHE_LINESIZE_BYTE)
+#define SDK_L2CACHE_ALIGN(var) SDK_PRAGMA(data_alignment = FSL_FEATURE_L2CACHE_LINESIZE_BYTE) var
+#endif
+#elif defined(__ARMCC_VERSION)
+/*! Macro to define a variable with alignbytes alignment */
+#define SDK_ALIGN(var, alignbytes) __align(alignbytes) var
+/*! Macro to define a variable with L1 d-cache line size alignment */
+#if defined(FSL_FEATURE_L1DCACHE_LINESIZE_BYTE)
+#define SDK_L1DCACHE_ALIGN(var) __align(FSL_FEATURE_L1DCACHE_LINESIZE_BYTE) var
+#endif
+/*! Macro to define a variable with L2 cache line size alignment */
+#if defined(FSL_FEATURE_L2CACHE_LINESIZE_BYTE)
+#define SDK_L2CACHE_ALIGN(var) __align(FSL_FEATURE_L2CACHE_LINESIZE_BYTE) var
+#endif
+#elif defined(__GNUC__)
+/*! Macro to define a variable with alignbytes alignment */
+#define SDK_ALIGN(var, alignbytes) var __attribute__((aligned(alignbytes)))
+/*! Macro to define a variable with L1 d-cache line size alignment */
+#if defined(FSL_FEATURE_L1DCACHE_LINESIZE_BYTE)
+#define SDK_L1DCACHE_ALIGN(var) var __attribute__((aligned(FSL_FEATURE_L1DCACHE_LINESIZE_BYTE)))
+#endif
+/*! Macro to define a variable with L2 cache line size alignment */
+#if defined(FSL_FEATURE_L2CACHE_LINESIZE_BYTE)
+#define SDK_L2CACHE_ALIGN(var) var __attribute__((aligned(FSL_FEATURE_L2CACHE_LINESIZE_BYTE)))
+#endif
+#else
+#error Toolchain not supported
+#define SDK_ALIGN(var, alignbytes) var
+#if defined(FSL_FEATURE_L1DCACHE_LINESIZE_BYTE)
+#define SDK_L1DCACHE_ALIGN(var) var
+#endif
+#if defined(FSL_FEATURE_L2CACHE_LINESIZE_BYTE)
+#define SDK_L2CACHE_ALIGN(var) var
+#endif
+#endif
+
+/*! Macro to change a value to a given size aligned value */
+#define SDK_SIZEALIGN(var, alignbytes) \
+ ((unsigned int)((var) + ((alignbytes)-1)) & (unsigned int)(~(unsigned int)((alignbytes)-1)))
+/* @} */
+
+/*! @name Non-cacheable region definition macros */
+/* For initialized non-zero non-cacheable variables, please using "AT_NONCACHEABLE_SECTION_INIT(var) ={xx};" or
+ * "AT_NONCACHEABLE_SECTION_ALIGN_INIT(var) ={xx};" in your projects to define them, for zero-inited non-cacheable variables,
+ * please using "AT_NONCACHEABLE_SECTION(var);" or "AT_NONCACHEABLE_SECTION_ALIGN(var);" to define them, these zero-inited variables
+ * will be initialized to zero in system startup.
+ */
+/* @{ */
+#if (defined(__ICCARM__))
+#if defined(FSL_FEATURE_L1ICACHE_LINESIZE_BYTE)
+#define AT_NONCACHEABLE_SECTION(var) var @"NonCacheable"
+#define AT_NONCACHEABLE_SECTION_ALIGN(var, alignbytes) SDK_PRAGMA(data_alignment = alignbytes) var @"NonCacheable"
+#define AT_NONCACHEABLE_SECTION_INIT(var) var @"NonCacheable.init"
+#define AT_NONCACHEABLE_SECTION_ALIGN_INIT(var, alignbytes) SDK_PRAGMA(data_alignment = alignbytes) var @"NonCacheable.init"
+#else
+#define AT_NONCACHEABLE_SECTION(var) var
+#define AT_NONCACHEABLE_SECTION_ALIGN(var, alignbytes) SDK_PRAGMA(data_alignment = alignbytes) var
+#define AT_NONCACHEABLE_SECTION_INIT(var) var
+#define AT_NONCACHEABLE_SECTION_ALIGN_INIT(var, alignbytes) SDK_PRAGMA(data_alignment = alignbytes) var
+#endif
+#elif(defined(__ARMCC_VERSION))
+#if defined(FSL_FEATURE_L1ICACHE_LINESIZE_BYTE)
+#define AT_NONCACHEABLE_SECTION(var) __attribute__((section("NonCacheable"), zero_init)) var
+#define AT_NONCACHEABLE_SECTION_ALIGN(var, alignbytes) \
+ __attribute__((section("NonCacheable"), zero_init)) __align(alignbytes) var
+#define AT_NONCACHEABLE_SECTION_INIT(var) __attribute__((section("NonCacheable.init"))) var
+#define AT_NONCACHEABLE_SECTION_ALIGN_INIT(var, alignbytes) \
+ __attribute__((section("NonCacheable.init"))) __align(alignbytes) var
+#else
+#define AT_NONCACHEABLE_SECTION(var) var
+#define AT_NONCACHEABLE_SECTION_ALIGN(var, alignbytes) __align(alignbytes) var
+#define AT_NONCACHEABLE_SECTION_INIT(var) var
+#define AT_NONCACHEABLE_SECTION_ALIGN_INIT(var, alignbytes) __align(alignbytes) var
+#endif
+#elif(defined(__GNUC__))
+/* For GCC, when the non-cacheable section is required, please define "__STARTUP_INITIALIZE_NONCACHEDATA"
+ * in your projects to make sure the non-cacheable section variables will be initialized in system startup.
+ */
+#if defined(FSL_FEATURE_L1ICACHE_LINESIZE_BYTE)
+#define AT_NONCACHEABLE_SECTION_INIT(var) __attribute__((section("NonCacheable.init"))) var
+#define AT_NONCACHEABLE_SECTION_ALIGN_INIT(var, alignbytes) \
+ __attribute__((section("NonCacheable.init"))) var __attribute__((aligned(alignbytes)))
+#define AT_NONCACHEABLE_SECTION(var) __attribute__((section("NonCacheable,\"aw\",%nobits @"))) var
+#define AT_NONCACHEABLE_SECTION_ALIGN(var, alignbytes) \
+ __attribute__((section("NonCacheable,\"aw\",%nobits @"))) var __attribute__((aligned(alignbytes)))
+#else
+#define AT_NONCACHEABLE_SECTION(var) var
+#define AT_NONCACHEABLE_SECTION_ALIGN(var, alignbytes) var __attribute__((aligned(alignbytes)))
+#define AT_NONCACHEABLE_SECTION_INIT(var) var
+#define AT_NONCACHEABLE_SECTION_ALIGN_INIT(var, alignbytes) var __attribute__((aligned(alignbytes)))
+#endif
+#else
+#error Toolchain not supported.
+#define AT_NONCACHEABLE_SECTION(var) var
+#define AT_NONCACHEABLE_SECTION_ALIGN(var, alignbytes) var
+#define AT_NONCACHEABLE_SECTION_INIT(var) var
+#define AT_NONCACHEABLE_SECTION_ALIGN_INIT(var, alignbytes) var
+#endif
+/* @} */
+
+/*! @name Time sensitive region */
+/* @{ */
+#if defined(FSL_SDK_DRIVER_QUICK_ACCESS_ENABLE) && FSL_SDK_DRIVER_QUICK_ACCESS_ENABLE
+#if (defined(__ICCARM__))
+#define AT_QUICKACCESS_SECTION_CODE(func) func @"CodeQuickAccess"
+#define AT_QUICKACCESS_SECTION_DATA(func) func @"DataQuickAccess"
+#elif(defined(__ARMCC_VERSION))
+#define AT_QUICKACCESS_SECTION_CODE(func) __attribute__((section("CodeQuickAccess"))) func
+#define AT_QUICKACCESS_SECTION_DATA(func) __attribute__((section("DataQuickAccess"))) func
+#elif(defined(__GNUC__))
+#define AT_QUICKACCESS_SECTION_CODE(func) __attribute__((section("CodeQuickAccess"))) func
+#define AT_QUICKACCESS_SECTION_DATA(func) __attribute__((section("DataQuickAccess"))) func
+#else
+#error Toolchain not supported.
+#endif /* defined(__ICCARM__) */
+#else
+#if (defined(__ICCARM__))
+#define AT_QUICKACCESS_SECTION_CODE(func) func
+#define AT_QUICKACCESS_SECTION_DATA(func) func
+#elif(defined(__ARMCC_VERSION))
+#define AT_QUICKACCESS_SECTION_CODE(func) func
+#define AT_QUICKACCESS_SECTION_DATA(func) func
+#elif(defined(__GNUC__))
+#define AT_QUICKACCESS_SECTION_CODE(func) func
+#define AT_QUICKACCESS_SECTION_DATA(func) func
+#else
+#error Toolchain not supported.
+#endif
+#endif /* __FSL_SDK_DRIVER_QUICK_ACCESS_ENABLE */
+/* @} */
+
+/*******************************************************************************
+ * API
+ ******************************************************************************/
+
+#if defined(__cplusplus)
+ extern "C"
+{
+#endif
+
+ /*!
+ * @brief Enable specific interrupt.
+ *
+ * Enable LEVEL1 interrupt. For some devices, there might be multiple interrupt
+ * levels. For example, there are NVIC and intmux. Here the interrupts connected
+ * to NVIC are the LEVEL1 interrupts, because they are routed to the core directly.
+ * The interrupts connected to intmux are the LEVEL2 interrupts, they are routed
+ * to NVIC first then routed to core.
+ *
+ * This function only enables the LEVEL1 interrupts. The number of LEVEL1 interrupts
+ * is indicated by the feature macro FSL_FEATURE_NUMBER_OF_LEVEL1_INT_VECTORS.
+ *
+ * @param interrupt The IRQ number.
+ * @retval kStatus_Success Interrupt enabled successfully
+ * @retval kStatus_Fail Failed to enable the interrupt
+ */
+ static inline status_t EnableIRQ(IRQn_Type interrupt)
+ {
+ if (NotAvail_IRQn == interrupt)
+ {
+ return kStatus_Fail;
+ }
+
+#if defined(FSL_FEATURE_NUMBER_OF_LEVEL1_INT_VECTORS) && (FSL_FEATURE_NUMBER_OF_LEVEL1_INT_VECTORS > 0)
+ if (interrupt >= FSL_FEATURE_NUMBER_OF_LEVEL1_INT_VECTORS)
+ {
+ return kStatus_Fail;
+ }
+#endif
+
+#if defined(__GIC_PRIO_BITS)
+ GIC_EnableIRQ(interrupt);
+#else
+ NVIC_EnableIRQ(interrupt);
+#endif
+ return kStatus_Success;
+ }
+
+ /*!
+ * @brief Disable specific interrupt.
+ *
+ * Disable LEVEL1 interrupt. For some devices, there might be multiple interrupt
+ * levels. For example, there are NVIC and intmux. Here the interrupts connected
+ * to NVIC are the LEVEL1 interrupts, because they are routed to the core directly.
+ * The interrupts connected to intmux are the LEVEL2 interrupts, they are routed
+ * to NVIC first then routed to core.
+ *
+ * This function only disables the LEVEL1 interrupts. The number of LEVEL1 interrupts
+ * is indicated by the feature macro FSL_FEATURE_NUMBER_OF_LEVEL1_INT_VECTORS.
+ *
+ * @param interrupt The IRQ number.
+ * @retval kStatus_Success Interrupt disabled successfully
+ * @retval kStatus_Fail Failed to disable the interrupt
+ */
+ static inline status_t DisableIRQ(IRQn_Type interrupt)
+ {
+ if (NotAvail_IRQn == interrupt)
+ {
+ return kStatus_Fail;
+ }
+
+#if defined(FSL_FEATURE_NUMBER_OF_LEVEL1_INT_VECTORS) && (FSL_FEATURE_NUMBER_OF_LEVEL1_INT_VECTORS > 0)
+ if (interrupt >= FSL_FEATURE_NUMBER_OF_LEVEL1_INT_VECTORS)
+ {
+ return kStatus_Fail;
+ }
+#endif
+
+#if defined(__GIC_PRIO_BITS)
+ GIC_DisableIRQ(interrupt);
+#else
+ NVIC_DisableIRQ(interrupt);
+#endif
+ return kStatus_Success;
+ }
+
+ /*!
+ * @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)
+ {
+#if defined(CPSR_I_Msk)
+ uint32_t cpsr = __get_CPSR() & CPSR_I_Msk;
+
+ __disable_irq();
+
+ return cpsr;
+#else
+ uint32_t regPrimask = __get_PRIMASK();
+
+ __disable_irq();
+
+ return regPrimask;
+#endif
+ }
+
+ /*!
+ * @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)
+ {
+#if defined(CPSR_I_Msk)
+ __set_CPSR((__get_CPSR() & ~CPSR_I_Msk) | primask);
+#else
+ __set_PRIMASK(primask);
+#endif
+ }
+
+#if defined(ENABLE_RAM_VECTOR_TABLE)
+ /*!
+ * @brief install IRQ handler
+ *
+ * @param irq IRQ number
+ * @param irqHandler IRQ handler address
+ * @return The old IRQ handler address
+ */
+ uint32_t InstallIRQHandler(IRQn_Type irq, uint32_t irqHandler);
+#endif /* ENABLE_RAM_VECTOR_TABLE. */
+
+#if (defined(FSL_FEATURE_SOC_SYSCON_COUNT) && (FSL_FEATURE_SOC_SYSCON_COUNT > 0))
+ /*!
+ * @brief Enable specific interrupt for wake-up from deep-sleep mode.
+ *
+ * Enable the interrupt for wake-up from deep sleep mode.
+ * Some interrupts are typically used in sleep mode only and will not occur during
+ * deep-sleep mode because relevant clocks are stopped. However, it is possible to enable
+ * those clocks (significantly increasing power consumption in the reduced power mode),
+ * making these wake-ups possible.
+ *
+ * @note This function also enables the interrupt in the NVIC (EnableIRQ() is called internally).
+ *
+ * @param interrupt The IRQ number.
+ */
+ void EnableDeepSleepIRQ(IRQn_Type interrupt);
+
+ /*!
+ * @brief Disable specific interrupt for wake-up from deep-sleep mode.
+ *
+ * Disable the interrupt for wake-up from deep sleep mode.
+ * Some interrupts are typically used in sleep mode only and will not occur during
+ * deep-sleep mode because relevant clocks are stopped. However, it is possible to enable
+ * those clocks (significantly increasing power consumption in the reduced power mode),
+ * making these wake-ups possible.
+ *
+ * @note This function also disables the interrupt in the NVIC (DisableIRQ() is called internally).
+ *
+ * @param interrupt The IRQ number.
+ */
+ void DisableDeepSleepIRQ(IRQn_Type interrupt);
+#endif /* FSL_FEATURE_SOC_SYSCON_COUNT */
+
+ /*!
+ * @brief Allocate memory with given alignment and aligned size.
+ *
+ * This is provided to support the dynamically allocated memory
+ * used in cache-able region.
+ * @param size The length required to malloc.
+ * @param alignbytes The alignment size.
+ * @retval The allocated memory.
+ */
+ void *SDK_Malloc(size_t size, size_t alignbytes);
+
+ /*!
+ * @brief Free memory.
+ *
+ * @param ptr The memory to be release.
+ */
+ void SDK_Free(void *ptr);
+
+#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..4c942a5
--- /dev/null
+++ b/drivers/fsl_crc.c
@@ -0,0 +1,292 @@
+/*
+ * The Clear BSD License
+ * Copyright (c) 2015-2016, Freescale Semiconductor, Inc.
+ * Copyright 2016-2017 NXP
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted (subject to the limitations in the disclaimer below) provided
+ * that the following conditions are met:
+ *
+ * o Redistributions of source code must retain the above copyright notice, this list
+ * of conditions and the following disclaimer.
+ *
+ * o Redistributions in binary form must reproduce the above copyright notice, this
+ * list of conditions and the following disclaimer in the documentation and/or
+ * other materials provided with the distribution.
+ *
+ * o Neither the name of the copyright holder nor the names of its
+ * contributors may be used to endorse or promote products derived from this
+ * software without specific prior written permission.
+ *
+ * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS LICENSE.
+ * 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
+ ******************************************************************************/
+
+/* Component ID definition, used by tools. */
+#ifndef FSL_COMPONENT_ID
+#define FSL_COMPONENT_ID "platform.drivers.crc"
+#endif
+
+/*! @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)
+{
+#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
+ /* ungate clock */
+ CLOCK_EnableClock(kCLOCK_Crc0);
+#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
+ /* 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..7a2e8ab
--- /dev/null
+++ b/drivers/fsl_crc.h
@@ -0,0 +1,197 @@
+/*
+ * The Clear BSD License
+ * Copyright (c) 2015-2016, Freescale Semiconductor, Inc.
+ * Copyright 2016-2017 NXP
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted (subject to the limitations in the disclaimer below) provided
+ * that the following conditions are met:
+ *
+ * o Redistributions of source code must retain the above copyright notice, this list
+ * of conditions and the following disclaimer.
+ *
+ * o Redistributions in binary form must reproduce the above copyright notice, this
+ * list of conditions and the following disclaimer in the documentation and/or
+ * other materials provided with the distribution.
+ *
+ * o Neither the name of the copyright holder nor the names of its
+ * contributors may be used to endorse or promote products derived from this
+ * software without specific prior written permission.
+ *
+ * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS LICENSE.
+ * 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 function enables the clock gate in the SIM module for the CRC peripheral.
+ * It also configures the CRC module and starts a 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 function disables the clock gate in the SIM module for the CRC peripheral.
+ *
+ * @param base CRC peripheral address.
+ */
+static inline void CRC_Deinit(CRC_Type *base)
+{
+#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
+ /* gate clock */
+ CLOCK_DisableClock(kCLOCK_Crc0);
+#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
+}
+
+/*!
+ * @brief Loads default values to the CRC protocol configuration structure.
+ *
+ * Loads default values to the CRC protocol configuration structure. The default values are as follows.
+ * @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 the 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 the 32-bit checksum from the CRC module.
+ *
+ * Reads the CRC data register (either an intermediate or the final checksum).
+ * The configured type of transpose and complement is applied.
+ *
+ * @param base CRC peripheral address.
+ * @return An intermediate or the final 32-bit checksum, after configured transpose and complement operations.
+ */
+uint32_t CRC_Get32bitResult(CRC_Type *base);
+
+/*!
+ * @brief Reads a 16-bit checksum from the CRC module.
+ *
+ * Reads the CRC data register (either an intermediate or the final checksum).
+ * The configured type of transpose and complement is applied.
+ *
+ * @param base CRC peripheral address.
+ * @return An intermediate or the 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..74ac6eb
--- /dev/null
+++ b/drivers/fsl_dac.c
@@ -0,0 +1,230 @@
+/*
+ * The Clear BSD License
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * Copyright 2016-2017 NXP
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted (subject to the limitations in the disclaimer below) provided
+ * that the following conditions are met:
+ *
+ * o Redistributions of source code must retain the above copyright notice, this list
+ * of conditions and the following disclaimer.
+ *
+ * o Redistributions in binary form must reproduce the above copyright notice, this
+ * list of conditions and the following disclaimer in the documentation and/or
+ * other materials provided with the distribution.
+ *
+ * o Neither the name of the copyright holder nor the names of its
+ * contributors may be used to endorse or promote products derived from this
+ * software without specific prior written permission.
+ *
+ * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS LICENSE.
+ * 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"
+
+/* Component ID definition, used by tools. */
+#ifndef FSL_COMPONENT_ID
+#define FSL_COMPONENT_ID "platform.drivers.dac"
+#endif
+
+
+/*******************************************************************************
+ * 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;
+#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
+/*! @brief Pointers to DAC clocks for each instance. */
+static const clock_ip_name_t s_dacClocks[] = DAC_CLOCKS;
+#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
+
+/*******************************************************************************
+ * Codes
+ ******************************************************************************/
+static uint32_t DAC_GetInstance(DAC_Type *base)
+{
+ uint32_t instance;
+
+ /* Find the instance index from base address mappings. */
+ for (instance = 0; instance < ARRAY_SIZE(s_dacBases); instance++)
+ {
+ if (s_dacBases[instance] == base)
+ {
+ break;
+ }
+ }
+
+ assert(instance < ARRAY_SIZE(s_dacBases));
+
+ return instance;
+}
+
+void DAC_Init(DAC_Type *base, const dac_config_t *config)
+{
+ assert(NULL != config);
+
+ uint8_t tmp8;
+
+#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
+ /* Enable the clock. */
+ CLOCK_EnableClock(s_dacClocks[DAC_GetInstance(base)]);
+#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
+
+ /* 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);
+
+#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
+ /* Disable the clock. */
+ CLOCK_DisableClock(s_dacClocks[DAC_GetInstance(base)]);
+#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
+}
+
+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..2fd2afe
--- /dev/null
+++ b/drivers/fsl_dac.h
@@ -0,0 +1,382 @@
+/*
+ * The Clear BSD License
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * Copyright 2016-2017 NXP
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted (subject to the limitations in the disclaimer below) provided
+ * that the following conditions are met:
+ *
+ * o Redistributions of source code must retain the above copyright notice, this list
+ * of conditions and the following disclaimer.
+ *
+ * o Redistributions in binary form must reproduce the above copyright notice, this
+ * list of conditions and the following disclaimer in the documentation and/or
+ * other materials provided with the distribution.
+ *
+ * o Neither the name of the copyright holder nor the names of its
+ * contributors may be used to endorse or promote products derived from this
+ * software without specific prior written permission.
+ *
+ * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS LICENSE.
+ * 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 the buffer index.
+ Normally, 0-15 is available for a buffer with 16 items. */
+} 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 the following operations.
+ * - 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 the following operations.
+ * - 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 as follows.
+ * @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 or 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 or 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 default values. The default values are as follows.
+ * @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 or 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 the index for items in the buffer. The available index should not exceed the size of the DAC buffer.
+ * @param value Setting the 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 using software and updates the read pointer of the DAC buffer.
+ *
+ * This function triggers the function using 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 either
+ * by a software trigger or a hardware trigger.
+ *
+ * @param base DAC peripheral base address.
+ *
+ * @return The current read pointer of the 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 either by a
+ * software trigger or a hardware trigger. After the read pointer changes, the DAC output value also changes.
+ *
+ * @param base DAC peripheral base address.
+ * @param index Setting an 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..155531d
--- /dev/null
+++ b/drivers/fsl_dmamux.c
@@ -0,0 +1,103 @@
+/*
+ * The Clear BSD License
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * Copyright 2016-2017 NXP
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted (subject to the limitations in the disclaimer below) provided
+ * that the following conditions are met:
+ *
+ * o Redistributions of source code must retain the above copyright notice, this list
+ * of conditions and the following disclaimer.
+ *
+ * o Redistributions in binary form must reproduce the above copyright notice, this
+ * list of conditions and the following disclaimer in the documentation and/or
+ * other materials provided with the distribution.
+ *
+ * o Neither the name of the copyright holder nor the names of its
+ * contributors may be used to endorse or promote products derived from this
+ * software without specific prior written permission.
+ *
+ * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS LICENSE.
+ * 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
+ ******************************************************************************/
+
+/* Component ID definition, used by tools. */
+#ifndef FSL_COMPONENT_ID
+#define FSL_COMPONENT_ID "platform.drivers.dmamux"
+#endif
+
+
+/*******************************************************************************
+ * 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;
+
+#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
+/*! @brief Array to map DMAMUX instance number to clock name. */
+static const clock_ip_name_t s_dmamuxClockName[] = DMAMUX_CLOCKS;
+#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
+
+/*******************************************************************************
+ * Code
+ ******************************************************************************/
+static uint32_t DMAMUX_GetInstance(DMAMUX_Type *base)
+{
+ uint32_t instance;
+
+ /* Find the instance index from base address mappings. */
+ for (instance = 0; instance < ARRAY_SIZE(s_dmamuxBases); instance++)
+ {
+ if (s_dmamuxBases[instance] == base)
+ {
+ break;
+ }
+ }
+
+ assert(instance < ARRAY_SIZE(s_dmamuxBases));
+
+ return instance;
+}
+
+void DMAMUX_Init(DMAMUX_Type *base)
+{
+#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
+ CLOCK_EnableClock(s_dmamuxClockName[DMAMUX_GetInstance(base)]);
+#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
+}
+
+void DMAMUX_Deinit(DMAMUX_Type *base)
+{
+#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
+ CLOCK_DisableClock(s_dmamuxClockName[DMAMUX_GetInstance(base)]);
+#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
+}
diff --git a/drivers/fsl_dmamux.h b/drivers/fsl_dmamux.h
new file mode 100644
index 0000000..17f32ee
--- /dev/null
+++ b/drivers/fsl_dmamux.h
@@ -0,0 +1,204 @@
+/*
+ * The Clear BSD License
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * Copyright 2016-2017 NXP
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted (subject to the limitations in the disclaimer below) provided
+ * that the following conditions are met:
+ *
+ * o Redistributions of source code must retain the above copyright notice, this list
+ * of conditions and the following disclaimer.
+ *
+ * o Redistributions in binary form must reproduce the above copyright notice, this
+ * list of conditions and the following disclaimer in the documentation and/or
+ * other materials provided with the distribution.
+ *
+ * o Neither the name of the copyright holder nor the names of its
+ * contributors may be used to endorse or promote products derived from this
+ * software without specific prior written permission.
+ *
+ * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS LICENSE.
+ * 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.2. */
+#define FSL_DMAMUX_DRIVER_VERSION (MAKE_VERSION(2, 0, 2))
+/*@}*/
+
+/*******************************************************************************
+ * API
+ ******************************************************************************/
+
+#if defined(__cplusplus)
+extern "C" {
+#endif /* __cplusplus */
+
+/*!
+ * @name DMAMUX Initialization and de-initialization
+ * @{
+ */
+
+/*!
+ * @brief Initializes the DMAMUX peripheral.
+ *
+ * This function ungates the DMAMUX clock.
+ *
+ * @param base DMAMUX peripheral base address.
+ *
+ */
+void DMAMUX_Init(DMAMUX_Type *base);
+
+/*!
+ * @brief Deinitializes the DMAMUX peripheral.
+ *
+ * This function gates the DMAMUX clock.
+ *
+ * @param base DMAMUX peripheral base address.
+ */
+void DMAMUX_Deinit(DMAMUX_Type *base);
+
+/* @} */
+/*!
+ * @name DMAMUX Channel Operation
+ * @{
+ */
+
+/*!
+ * @brief Enables the DMAMUX channel.
+ *
+ * This function enables the DMAMUX channel.
+ *
+ * @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 Disables the DMAMUX channel.
+ *
+ * This function disables the DMAMUX channel.
+ *
+ * @note The user must disable the 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 Configures the DMAMUX channel source.
+ *
+ * @param base DMAMUX peripheral base address.
+ * @param channel DMAMUX channel number.
+ * @param source Channel source, which is used to trigger the 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 Enables the DMAMUX period trigger.
+ *
+ * This function enables the 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 Disables the DMAMUX period trigger.
+ *
+ * This function disables the 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(FSL_FEATURE_DMAMUX_HAS_A_ON) && FSL_FEATURE_DMAMUX_HAS_A_ON)
+/*!
+ * @brief Enables the DMA channel to be always ON.
+ *
+ * This function enables the DMAMUX channel always ON feature.
+ *
+ * @param base DMAMUX peripheral base address.
+ * @param channel DMAMUX channel number.
+ * @param enable Switcher of the always ON feature. "true" means enabled, "false" means disabled.
+ */
+static inline void DMAMUX_EnableAlwaysOn(DMAMUX_Type *base, uint32_t channel, bool enable)
+{
+ assert(channel < FSL_FEATURE_DMAMUX_MODULE_CHANNEL);
+
+ if (enable)
+ {
+ base->CHCFG[channel] |= DMAMUX_CHCFG_A_ON_MASK;
+ }
+ else
+ {
+ base->CHCFG[channel] &= ~DMAMUX_CHCFG_A_ON_MASK;
+ }
+}
+#endif /* FSL_FEATURE_DMAMUX_HAS_A_ON */
+
+/* @} */
+
+#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..620335b
--- /dev/null
+++ b/drivers/fsl_dspi.c
@@ -0,0 +1,1807 @@
+/*
+ * The Clear BSD License
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * Copyright 2016-2017 NXP
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted (subject to the limitations in the disclaimer below) provided
+ * that the following conditions are met:
+ *
+ * o Redistributions of source code must retain the above copyright notice, this list
+ * of conditions and the following disclaimer.
+ *
+ * o Redistributions in binary form must reproduce the above copyright notice, this
+ * list of conditions and the following disclaimer in the documentation and/or
+ * other materials provided with the distribution.
+ *
+ * o Neither the name of the copyright holder nor the names of its
+ * contributors may be used to endorse or promote products derived from this
+ * software without specific prior written permission.
+ *
+ * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS LICENSE.
+ * 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
+ ******************************************************************************/
+
+/* Component ID definition, used by tools. */
+#ifndef FSL_COMPONENT_ID
+#define FSL_COMPONENT_ID "platform.drivers.dspi"
+#endif
+
+/*! @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 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.
+ */
+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.
+ */
+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.
+ */
+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.
+ */
+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.
+ */
+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;
+
+#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
+/*! @brief Pointers to dspi clocks for each instance. */
+static clock_ip_name_t const s_dspiClock[] = DSPI_CLOCKS;
+#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
+
+/*! @brief Pointers to dspi handles for each instance. */
+static void *g_dspiHandle[ARRAY_SIZE(s_dspiBases)];
+
+/*! @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;
+
+/* @brief Dummy data for each instance. This data is used when user's tx buffer is NULL*/
+volatile uint8_t g_dspiDummyData[ARRAY_SIZE(s_dspiBases)] = {0};
+/**********************************************************************************************************************
+* Code
+*********************************************************************************************************************/
+uint32_t DSPI_GetInstance(SPI_Type *base)
+{
+ uint32_t instance;
+
+ /* Find the instance index from base address mappings. */
+ for (instance = 0; instance < ARRAY_SIZE(s_dspiBases); instance++)
+ {
+ if (s_dspiBases[instance] == base)
+ {
+ break;
+ }
+ }
+
+ assert(instance < ARRAY_SIZE(s_dspiBases));
+
+ return instance;
+}
+
+void DSPI_SetDummyData(SPI_Type *base, uint8_t dummyData)
+{
+ uint32_t instance = DSPI_GetInstance(base);
+ g_dspiDummyData[instance] = dummyData;
+}
+
+void DSPI_MasterInit(SPI_Type *base, const dspi_master_config_t *masterConfig, uint32_t srcClock_Hz)
+{
+ assert(masterConfig);
+
+ uint32_t temp;
+#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
+ /* enable DSPI clock */
+ CLOCK_EnableClock(s_dspiClock[DSPI_GetInstance(base)]);
+#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
+
+ 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_SetDummyData(base, DSPI_DUMMY_DATA);
+ DSPI_StartTransfer(base);
+}
+
+void DSPI_MasterGetDefaultConfig(dspi_master_config_t *masterConfig)
+{
+ assert(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)
+{
+ assert(slaveConfig);
+
+ uint32_t temp = 0;
+
+#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
+ /* enable DSPI clock */
+ CLOCK_EnableClock(s_dspiClock[DSPI_GetInstance(base)]);
+#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
+
+ 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_SetDummyData(base, DSPI_DUMMY_DATA);
+
+ DSPI_StartTransfer(base);
+}
+
+void DSPI_SlaveGetDefaultConfig(dspi_slave_config_t *slaveConfig)
+{
+ assert(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);
+
+#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
+ /* disable DSPI clock */
+ CLOCK_DisableClock(s_dspiClock[DSPI_GetInstance(base)]);
+#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
+}
+
+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)
+{
+ assert(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)
+{
+ assert(command);
+
+ /* 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 = g_dspiDummyData[DSPI_GetInstance(base)];
+ 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 (!(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);
+
+ 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);
+ }
+ }
+ }
+ }
+ }
+ else
+ {
+ while (remainingSendByteCount > 0)
+ {
+ if (remainingSendByteCount <= 2)
+ {
+ 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);
+
+ 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);
+ }
+ }
+ }
+ }
+ }
+
+ return kStatus_Success;
+}
+
+static void DSPI_MasterTransferPrepare(SPI_Type *base, dspi_master_handle_t *handle, dspi_transfer_t *transfer)
+{
+ assert(handle);
+ assert(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);
+ assert(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;
+
+ /* Disable the NVIC for DSPI peripheral. */
+ DisableIRQ(s_dspiIRQ[DSPI_GetInstance(base)]);
+
+ DSPI_MasterTransferPrepare(base, handle, transfer);
+
+ /* 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);
+ DSPI_StartTransfer(base);
+
+ /* Fill up the Tx FIFO to trigger the transfer. */
+ DSPI_MasterTransferFillUpTxFifo(base, handle);
+
+ /* Enable the NVIC for DSPI peripheral. */
+ EnableIRQ(s_dspiIRQ[DSPI_GetInstance(base)]);
+
+ return kStatus_Success;
+}
+
+status_t DSPI_MasterHalfDuplexTransferBlocking(SPI_Type *base, dspi_half_duplex_transfer_t *xfer)
+{
+ assert(xfer);
+
+ dspi_transfer_t tempXfer = {0};
+ status_t status;
+
+ if (xfer->isTransmitFirst)
+ {
+ tempXfer.txData = xfer->txData;
+ tempXfer.rxData = NULL;
+ tempXfer.dataSize = xfer->txDataSize;
+ }
+ else
+ {
+ tempXfer.txData = NULL;
+ tempXfer.rxData = xfer->rxData;
+ tempXfer.dataSize = xfer->rxDataSize;
+ }
+ /* If the pcs pin keep assert between transmit and receive. */
+ if (xfer->isPcsAssertInTransfer)
+ {
+ tempXfer.configFlags = (xfer->configFlags) | kDSPI_MasterActiveAfterTransfer;
+ }
+ else
+ {
+ tempXfer.configFlags = (xfer->configFlags) & (uint32_t)(~kDSPI_MasterActiveAfterTransfer);
+ }
+
+ status = DSPI_MasterTransferBlocking(base, &tempXfer);
+ if (status != kStatus_Success)
+ {
+ return status;
+ }
+
+ if (xfer->isTransmitFirst)
+ {
+ tempXfer.txData = NULL;
+ tempXfer.rxData = xfer->rxData;
+ tempXfer.dataSize = xfer->rxDataSize;
+ }
+ else
+ {
+ tempXfer.txData = xfer->txData;
+ tempXfer.rxData = NULL;
+ tempXfer.dataSize = xfer->txDataSize;
+ }
+ tempXfer.configFlags = xfer->configFlags;
+
+ /* DSPI transfer blocking. */
+ status = DSPI_MasterTransferBlocking(base, &tempXfer);
+
+ return status;
+}
+
+status_t DSPI_MasterHalfDuplexTransferNonBlocking(SPI_Type *base,
+ dspi_master_handle_t *handle,
+ dspi_half_duplex_transfer_t *xfer)
+{
+ assert(xfer);
+ assert(handle);
+ dspi_transfer_t tempXfer = {0};
+ status_t status;
+
+ if (xfer->isTransmitFirst)
+ {
+ tempXfer.txData = xfer->txData;
+ tempXfer.rxData = NULL;
+ tempXfer.dataSize = xfer->txDataSize;
+ }
+ else
+ {
+ tempXfer.txData = NULL;
+ tempXfer.rxData = xfer->rxData;
+ tempXfer.dataSize = xfer->rxDataSize;
+ }
+ /* If the pcs pin keep assert between transmit and receive. */
+ if (xfer->isPcsAssertInTransfer)
+ {
+ tempXfer.configFlags = (xfer->configFlags) | kDSPI_MasterActiveAfterTransfer;
+ }
+ else
+ {
+ tempXfer.configFlags = (xfer->configFlags) & (uint32_t)(~kDSPI_MasterActiveAfterTransfer);
+ }
+
+ status = DSPI_MasterTransferBlocking(base, &tempXfer);
+ if (status != kStatus_Success)
+ {
+ return status;
+ }
+
+ if (xfer->isTransmitFirst)
+ {
+ tempXfer.txData = NULL;
+ tempXfer.rxData = xfer->rxData;
+ tempXfer.dataSize = xfer->rxDataSize;
+ }
+ else
+ {
+ tempXfer.txData = xfer->txData;
+ tempXfer.rxData = NULL;
+ tempXfer.dataSize = xfer->txDataSize;
+ }
+ tempXfer.configFlags = xfer->configFlags;
+
+ status = DSPI_MasterTransferNonBlocking(base, handle, &tempXfer);
+
+ return status;
+}
+
+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)
+{
+ assert(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;
+ }
+
+ handle->state = kDSPI_Idle;
+
+ if (handle->callback)
+ {
+ handle->callback(base, handle, status, handle->userData);
+ }
+}
+
+static void DSPI_MasterTransferFillUpTxFifo(SPI_Type *base, dspi_master_handle_t *handle)
+{
+ assert(handle);
+
+ uint16_t wordToSend = 0;
+ uint8_t dummyData = g_dspiDummyData[DSPI_GetInstance(base)];
+
+ /* 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 this is the first time write to the PUSHR, write only once.
+ */
+ if ((handle->remainingSendByteCount == 0) || (handle->remainingSendByteCount == handle->totalByteCount - 2))
+ {
+ 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 this is the first time write to the PUSHR, write only once.
+ */
+ if ((handle->remainingSendByteCount == 0) || (handle->remainingSendByteCount == handle->totalByteCount - 1))
+ {
+ break;
+ }
+ }
+ }
+}
+
+void DSPI_MasterTransferAbort(SPI_Type *base, dspi_master_handle_t *handle)
+{
+ assert(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)
+{
+ assert(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 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);
+ assert(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);
+
+ 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);
+ }
+
+ DSPI_StartTransfer(base);
+
+ /* Prepare data to transmit */
+ DSPI_SlaveTransferFillUpTxFifo(base, handle);
+
+ 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)
+{
+ assert(handle);
+
+ uint16_t transmitData = 0;
+ uint8_t dummyPattern = g_dspiDummyData[DSPI_GetInstance(base)];
+
+ /* 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)
+{
+ assert(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;
+ }
+
+ handle->state = kDSPI_Idle;
+
+ if (handle->callback)
+ {
+ handle->callback(base, handle, status, handle->userData);
+ }
+}
+
+void DSPI_SlaveTransferAbort(SPI_Type *base, dspi_slave_handle_t *handle)
+{
+ assert(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)
+{
+ assert(handle);
+
+ uint8_t dummyPattern = g_dspiDummyData[DSPI_GetInstance(base)];
+ 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);
+ }
+/* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+#if defined(SPI0)
+void SPI0_DriverIRQHandler(void)
+{
+ assert(g_dspiHandle[0]);
+ DSPI_CommonIRQHandler(SPI0, g_dspiHandle[0]);
+}
+#endif
+
+#if defined(SPI1)
+void SPI1_DriverIRQHandler(void)
+{
+ assert(g_dspiHandle[1]);
+ DSPI_CommonIRQHandler(SPI1, g_dspiHandle[1]);
+}
+#endif
+
+#if defined(SPI2)
+void SPI2_DriverIRQHandler(void)
+{
+ assert(g_dspiHandle[2]);
+ DSPI_CommonIRQHandler(SPI2, g_dspiHandle[2]);
+}
+#endif
+
+#if defined(SPI3)
+void SPI3_DriverIRQHandler(void)
+{
+ assert(g_dspiHandle[3]);
+ DSPI_CommonIRQHandler(SPI3, g_dspiHandle[3]);
+}
+#endif
+
+#if defined(SPI4)
+void SPI4_DriverIRQHandler(void)
+{
+ assert(g_dspiHandle[4]);
+ DSPI_CommonIRQHandler(SPI4, g_dspiHandle[4]);
+}
+#endif
+
+#if defined(SPI5)
+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..39bac8b
--- /dev/null
+++ b/drivers/fsl_dspi.h
@@ -0,0 +1,1248 @@
+/*
+ * The Clear BSD License
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * Copyright 2016-2017 NXP
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted (subject to the limitations in the disclaimer below) provided
+ * that the following conditions are met:
+ *
+ * o Redistributions of source code must retain the above copyright notice, this list
+ * of conditions and the following disclaimer.
+ *
+ * o Redistributions in binary form must reproduce the above copyright notice, this
+ * list of conditions and the following disclaimer in the documentation and/or
+ * other materials provided with the distribution.
+ *
+ * o Neither the name of the copyright holder nor the names of its
+ * contributors may be used to endorse or promote products derived from this
+ * software without specific prior written permission.
+ *
+ * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS LICENSE.
+ * 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.2.0. */
+#define FSL_DSPI_DRIVER_VERSION (MAKE_VERSION(2, 2, 0))
+/*@}*/
+
+#ifndef DSPI_DUMMY_DATA
+/*! @brief DSPI dummy data if there is no Tx data.*/
+#define DSPI_DUMMY_DATA (0x00U) /*!< Dummy data used for Tx if there is no txData. */
+#endif
+
+/*! @brief Global variable for dummy data value setting. */
+extern volatile uint8_t g_dspiDummyData[];
+
+/*! @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 statuses 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 the Modified Transfer Format. This field is
+ * valid
+ * only when the CPHA bit in the 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.
+ Shifting out of LSB is not supported for slave */
+} dspi_shift_direction_t;
+
+/*! @brief DSPI delay type selection.*/
+typedef enum _dspi_delay_type
+{
+ kDSPI_PcsToSck = 1U, /*!< Pcs-to-SCK delay. */
+ kDSPI_LastSckToPcs, /*!< The 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 devices do not support CTAR2. */
+ kDSPI_Ctar3 = 3U, /*!< CTAR3 selection option for master mode only; note that some devices do not support CTAR3. */
+ kDSPI_Ctar4 = 4U, /*!< CTAR4 selection option for master mode only; note that some devices do not support CTAR4. */
+ kDSPI_Ctar5 = 5U, /*!< CTAR5 selection option for master mode only; note that some devices do not support CTAR5. */
+ kDSPI_Ctar6 = 6U, /*!< CTAR6 selection option for master mode only; note that some devices do not support CTAR6. */
+ kDSPI_Ctar7 = 7U /*!< CTAR7 selection option for master mode only; note that some devices do not support CTAR7. */
+} dspi_ctar_selection_t;
+
+#define DSPI_MASTER_CTAR_SHIFT (0U) /*!< DSPI master CTAR shift macro; used internally. */
+#define DSPI_MASTER_CTAR_MASK (0x0FU) /*!< DSPI master CTAR mask macro; used internally. */
+#define DSPI_MASTER_PCS_SHIFT (4U) /*!< DSPI master PCS shift macro; used internally. */
+#define DSPI_MASTER_PCS_MASK (0xF0U) /*!< DSPI master PCS mask macro; used internally. */
+/*! @brief Use this enumeration for the 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, /*!< Indicates whether the PCS signal is continuous. */
+ kDSPI_MasterActiveAfterTransfer =
+ 1U << 21, /*!< Indicates whether the PCS signal is active after the last frame transfer.*/
+};
+
+#define DSPI_SLAVE_CTAR_SHIFT (0U) /*!< DSPI slave CTAR shift macro; used internally. */
+#define DSPI_SLAVE_CTAR_MASK (0x07U) /*!< DSPI slave CTAR mask macro; used internally. */
+/*! @brief Use this enumeration for the 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 the SPIx_PUSHR.*/
+typedef struct _dspi_command_data_config
+{
+ bool isPcsContinuous; /*!< Option to enable the continuous assertion of the 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 the 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 in nanoseconds; setting to 0 sets the minimum
+ delay. It also sets the boundary value if out of range.*/
+ uint32_t lastSckToPcsDelayInNanoSec; /*!< The last SCK to PCS delay time in nanoseconds; setting to 0 sets the
+ minimum delay. It also sets the boundary value if out of range.*/
+
+ uint32_t betweenTransferDelayInNanoSec; /*!< After the SCK delay time in nanoseconds; setting to 0 sets the minimum
+ delay. It also sets the boundary value if out of range.*/
+} dspi_master_ctar_config_t;
+
+/*! @brief DSPI master configuration structure.*/
+typedef struct _dspi_master_config
+{
+ dspi_ctar_selection_t whichCtar; /*!< The desired CTAR to use. */
+ dspi_master_ctar_config_t ctarConfig; /*!< Set the ctarConfig to the desired CTAR. */
+
+ dspi_which_pcs_t whichPcs; /*!< The desired Peripheral Chip Select (pcs). */
+ dspi_pcs_polarity_config_t pcsActiveHighOrLow; /*!< The desired PCS active high or low. */
+
+ bool enableContinuousSCK; /*!< CONT_SCKE, continuous SCK enable. Note that the continuous SCK is only
+ supported for CPHA = 1.*/
+ bool enableRxFifoOverWrite; /*!< ROOE, receive FIFO overflow overwrite enable. If ROOE = 0, the incoming
+ data is ignored and the data from the transfer that generated the overflow
+ is also ignored. If ROOE = 1, the incoming data is shifted to the
+ shift register. */
+
+ bool enableModifiedTimingFormat; /*!< Enables a modified transfer format to be used if true.*/
+ dspi_master_sample_point_t samplePoint; /*!< Controls when the module master samples SIN in the 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 and does not support LSB.*/
+} dspi_slave_ctar_config_t;
+
+/*! @brief DSPI slave configuration structure.*/
+typedef struct _dspi_slave_config
+{
+ dspi_ctar_selection_t whichCtar; /*!< The 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 the continuous SCK is only
+ supported for CPHA = 1.*/
+ bool enableRxFifoOverWrite; /*!< ROOE, receive FIFO overflow overwrite enable. If ROOE = 0, the incoming
+ data is ignored and the data from the transfer that generated the overflow
+ is also ignored. If ROOE = 1, the incoming data is shifted to the
+ shift register. */
+ bool enableModifiedTimingFormat; /*!< Enables a modified transfer format to be used if true.*/
+ dspi_master_sample_point_t samplePoint; /*!< Controls when the module master samples SIN in the 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 half-duplex(master) transfer structure */
+typedef struct _dspi_half_duplex_transfer
+{
+ uint8_t *txData; /*!< Send buffer */
+ uint8_t *rxData; /*!< Receive buffer */
+ size_t txDataSize; /*!< Transfer bytes for transmit */
+ size_t rxDataSize; /*!< Transfer bytes */
+ uint32_t configFlags; /*!< Transfer configuration flags; set from _dspi_transfer_config_flag_for_master. */
+ bool isPcsAssertInTransfer; /*!< If Pcs pin keep assert between transmit and receive. true for assert and false for
+ deassert. */
+ bool isTransmitFirst; /*!< True for transmit first and false for receive first. */
+} dspi_half_duplex_transfer_t;
+
+/*! @brief DSPI master transfer handle structure used for transactional API. */
+struct _dspi_master_handle
+{
+ uint32_t bitsPerFrame; /*!< The desired number of bits per frame. */
+ volatile uint32_t command; /*!< The desired data command. */
+ volatile uint32_t lastCommand; /*!< The desired last data command. */
+
+ uint8_t fifoSize; /*!< FIFO dataSize. */
+
+ volatile bool
+ isPcsActiveAfterTransfer; /*!< Indicates whether the PCS signal is active after the last frame transfer.*/
+ volatile bool isThereExtraByte; /*!< Indicates whether there are extra bytes.*/
+
+ uint8_t *volatile txData; /*!< Send buffer. */
+ uint8_t *volatile rxData; /*!< Receive buffer. */
+ volatile size_t remainingSendByteCount; /*!< A number of bytes remaining to send.*/
+ volatile size_t remainingReceiveByteCount; /*!< A number of bytes remaining to receive.*/
+ size_t totalByteCount; /*!< A number of transfer bytes*/
+
+ volatile uint8_t state; /*!< DSPI transfer state, see _dspi_transfer_state.*/
+
+ dspi_master_transfer_callback_t callback; /*!< Completion callback. */
+ void *userData; /*!< Callback user data. */
+};
+
+/*! @brief DSPI slave transfer handle structure used for the transactional API. */
+struct _dspi_slave_handle
+{
+ uint32_t bitsPerFrame; /*!< The desired number of bits per frame. */
+ volatile bool isThereExtraByte; /*!< Indicates whether there are extra bytes.*/
+
+ uint8_t *volatile txData; /*!< Send buffer. */
+ uint8_t *volatile rxData; /*!< Receive buffer. */
+ volatile size_t remainingSendByteCount; /*!< A number of bytes remaining to send.*/
+ volatile size_t remainingReceiveByteCount; /*!< A number of bytes remaining to receive.*/
+ size_t totalByteCount; /*!< A 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. This is an example use case.
+ * @code
+ * dspi_master_config_t masterConfig;
+ * masterConfig.whichCtar = kDSPI_Ctar0;
+ * masterConfig.ctarConfig.baudRate = 500000000U;
+ * masterConfig.ctarConfig.bitsPerFrame = 8;
+ * masterConfig.ctarConfig.cpol = kDSPI_ClockPolarityActiveHigh;
+ * masterConfig.ctarConfig.cpha = kDSPI_ClockPhaseFirstEdge;
+ * masterConfig.ctarConfig.direction = kDSPI_MsbFirst;
+ * masterConfig.ctarConfig.pcsToSckDelayInNanoSec = 1000000000U / masterConfig.ctarConfig.baudRate ;
+ * masterConfig.ctarConfig.lastSckToPcsDelayInNanoSec = 1000000000U / masterConfig.ctarConfig.baudRate ;
+ * masterConfig.ctarConfig.betweenTransferDelayInNanoSec = 1000000000U / 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 the 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().
+ * Users may use the initialized structure unchanged in the DSPI_MasterInit() or modify the structure
+ * before calling the 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. This is an example use case.
+ * @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 the 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 a default value.
+ *
+ * The purpose of this API is to get the configuration structure initialized for the DSPI_SlaveInit().
+ * Users may use the initialized structure unchanged in the DSPI_SlaveInit() or modify the structure
+ * before calling the DSPI_SlaveInit().
+ * This is an example.
+ * @code
+ * dspi_slave_config_t slaveConfig;
+ * DSPI_SlaveGetDefaultConfig(&slaveConfig);
+ * @endcode
+ * @param slaveConfig Pointer to the 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 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.
+ * This is an example.
+ * @code
+ * DSPI_ClearStatusFlags(base, kDSPI_TxCompleteFlag|kDSPI_EndOfQueueFlag);
+ * @endcode
+ *
+ * @param base DSPI peripheral address.
+ * @param statusFlags The status flag used from the 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 a base and an interrupt mask.
+ * Note, for Tx Fill and Rx FIFO drain requests, enable the interrupt request and disable the DMA request.
+ * Do not use this API(write to RSER register) while DSPI is in running state.
+ *
+ * @code
+ * DSPI_EnableInterrupts(base, kDSPI_TxCompleteInterruptEnable | kDSPI_EndOfQueueInterruptEnable );
+ * @endcode
+ *
+ * @param base DSPI peripheral address.
+ * @param mask The interrupt mask; 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; 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 a base and a DMA mask.
+ * @code
+ * DSPI_EnableDMA(base, kDSPI_TxDmaEnable | kDSPI_RxDmaEnable);
+ * @endcode
+ *
+ * @param base DSPI peripheral address.
+ * @param mask The interrupt mask; 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 a base and a DMA mask.
+ * @code
+ * SPI_DisableDMA(base, kDSPI_TxDmaEnable | kDSPI_RxDmaEnable);
+ * @endcode
+ *
+ * @param base DSPI peripheral address.
+ * @param mask The interrupt mask; 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 Get instance number for DSPI module.
+ *
+ * @param base DSPI peripheral base address.
+ */
+uint32_t DSPI_GetInstance(SPI_Type *base);
+
+/*!
+ * @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 start 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 DSPI transfers and sets the HALT bit in MCR.
+ *
+ * This function stops data transfers in either master or slave modes.
+ *
+ * @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, pass in a logic 0 (false) for the particular FIFO configuration. To enable,
+ * pass in a logic 1 (true).
+ *
+ * @param base DSPI peripheral address.
+ * @param enableTxFifo Disables (false) the TX FIFO; Otherwise, enables (true) the TX FIFO
+ * @param enableRxFifo Disables (false) the RX FIFO; Otherwise, 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; Otherwise, does not flush (false) the Tx FIFO
+ * @param flushRxFifo Flushes (true) the Rx FIFO; Otherwise, does 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 are set to active low and other PCS is 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; 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 the type dspi_delay_type_t.
+ *
+ * The user passes the delay to the configuration along with the prescaler and scaler value.
+ * This allows the user to directly set the prescaler/scaler values if pre-calculated or
+ * 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 the following.
+ * 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 the type dspi_delay_type_t.
+ *
+ * The user passes which delay to configure along with the desired delay value in nanoseconds. The function
+ * calculates the values needed for the prescaler and scaler. Note that returning the 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 the 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().
+ * Users may use the initialized structure unchanged in the DSPI_MasterWrite_xx() or modify the structure
+ * before calling the DSPI_MasterWrite_xx().
+ * This is an example.
+ * @code
+ * dspi_command_data_config_t command;
+ * DSPI_GetDefaultDataCommandConfig(&command);
+ * @endcode
+ * @param command Pointer to the 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,
+ * the received data is available when the transmit completes.
+ *
+ * @param base DSPI peripheral address.
+ * @param command Pointer to the 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 the 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 information and 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_MasterWriteCommandDataBlocking(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 received data is available when the 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);
+}
+
+/*!
+ * @brief Set up the dummy data.
+ *
+ * @param base DSPI peripheral address.
+ * @param dummyData Data to be transferred when tx buffer is NULL.
+ */
+void DSPI_SetDummyData(SPI_Type *base, uint8_t dummyData);
+
+/*!
+ *@}
+*/
+
+/*!
+ * @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 using 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 the 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 is transferred, the callback function is called.
+
+ * @param base DSPI peripheral base address.
+ * @param handle Pointer to the dspi_master_handle_t structure which stores the transfer state.
+ * @param transfer Pointer to the 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 Transfers a block of data using a polling method.
+ *
+ * This function will do a half-duplex transfer for DSPI master, This is a blocking function,
+ * which does not retuen until all transfer have been completed. And data transfer will be half-duplex,
+ * users can set transmit first or receive first.
+ *
+ * @param base DSPI base pointer
+ * @param xfer pointer to dspi_half_duplex_transfer_t structure
+ * @return status of status_t.
+ */
+status_t DSPI_MasterHalfDuplexTransferBlocking(SPI_Type *base, dspi_half_duplex_transfer_t *xfer);
+
+/*!
+ * @brief Performs a non-blocking DSPI interrupt transfer.
+ *
+ * This function transfers data using interrupts, the transfer mechanism is half-duplex. This is a non-blocking
+ * function,
+ * which returns right away. When all data is 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 xfer pointer to dspi_half_duplex_transfer_t structure
+ * @return status of status_t.
+ */
+status_t DSPI_MasterHalfDuplexTransferNonBlocking(SPI_Type *base,
+ dspi_master_handle_t *handle,
+ dspi_half_duplex_transfer_t *xfer);
+
+/*!
+ * @brief Gets the master transfer count.
+ *
+ * This function gets the master transfer count.
+ *
+ * @param base DSPI peripheral base address.
+ * @param handle Pointer to the dspi_master_handle_t structure which stores the transfer state.
+ * @param count The number of bytes transferred by using 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 a transfer using an interrupt.
+ *
+ * This function aborts a transfer using an interrupt.
+ *
+ * @param base DSPI peripheral base address.
+ * @param handle Pointer to the 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 the 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 the 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 is transferred, the callback function is called.
+ *
+ * @param base DSPI peripheral base address.
+ * @param handle Pointer to the dspi_slave_handle_t structure which stores the transfer state.
+ * @param transfer Pointer to the 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 the dspi_master_handle_t structure which stores the transfer state.
+ * @param count The number of bytes transferred by using 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 a transfer using an interrupt.
+ *
+ * @param base DSPI peripheral base address.
+ * @param handle Pointer to the 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 the 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..bbd560e
--- /dev/null
+++ b/drivers/fsl_dspi_edma.c
@@ -0,0 +1,1446 @@
+/*
+ * The Clear BSD License
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * Copyright 2016-2017 NXP
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted (subject to the limitations in the disclaimer below) provided
+ * that the following conditions are met:
+ *
+ * o Redistributions of source code must retain the above copyright notice, this list
+ * of conditions and the following disclaimer.
+ *
+ * o Redistributions in binary form must reproduce the above copyright notice, this
+ * list of conditions and the following disclaimer in the documentation and/or
+ * other materials provided with the distribution.
+ *
+ * o Neither the name of the copyright holder nor the names of its
+ * contributors may be used to endorse or promote products derived from this
+ * software without specific prior written permission.
+ *
+ * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS LICENSE.
+ * 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"
+
+/***********************************************************************************************************************
+* Definitions
+***********************************************************************************************************************/
+
+/* Component ID definition, used by tools. */
+#ifndef FSL_COMPONENT_ID
+#define FSL_COMPONENT_ID "platform.drivers.dspi_edma"
+#endif
+
+/*!
+* @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.
+*/
+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.
+*/
+static void EDMA_DspiSlaveCallback(edma_handle_t *edmaHandle,
+ void *g_dspiEdmaPrivateHandle,
+ bool transferDone,
+ uint32_t tcds);
+
+/***********************************************************************************************************************
+* 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);
+ assert(edmaRxRegToRxDataHandle);
+#if (!(defined(FSL_FEATURE_DSPI_HAS_GASKET) && FSL_FEATURE_DSPI_HAS_GASKET))
+ assert(edmaTxDataToIntermediaryHandle);
+#endif
+ assert(edmaIntermediaryToTxRegHandle);
+
+ /* 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);
+ assert(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;
+ }
+
+ handle->state = kDSPI_Busy;
+
+ uint32_t instance = DSPI_GetInstance(base);
+ uint16_t wordToSend = 0;
+ uint8_t dummyData = g_dspiDummyData[DSPI_GetInstance(base)];
+ 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;
+
+ handle->txBuffIfNull = ((uint32_t)dummyData << 8) | dummyData;
+
+ 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;
+
+ /* 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
+ */
+ uint32_t limited_size = 0;
+ if (1 == FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base))
+ {
+ limited_size = 32767u;
+ }
+ else
+ {
+ limited_size = 511u;
+ }
+
+ if (handle->bitsPerFrame > 8)
+ {
+ if (transfer->dataSize > (limited_size << 1u))
+ {
+ handle->state = kDSPI_Idle;
+ return kStatus_DSPI_OutOfRange;
+ }
+ }
+ else
+ {
+ if (transfer->dataSize > limited_size)
+ {
+ handle->state = kDSPI_Idle;
+ return kStatus_DSPI_OutOfRange;
+ }
+ }
+
+ /*The data size should be even if the bitsPerFrame is greater than 8 (that is 2 bytes per frame in dspi) */
+ if ((handle->bitsPerFrame > 8) && (transfer->dataSize & 0x1))
+ {
+ handle->state = kDSPI_Idle;
+ return kStatus_InvalidArgument;
+ }
+
+ DSPI_DisableDMA(base, kDSPI_RxDmaEnable | kDSPI_TxDmaEnable);
+
+ EDMA_SetCallback(handle->edmaRxRegToRxDataHandle, EDMA_DspiMasterCallback,
+ &s_dspiMasterEdmaPrivateHandle[instance]);
+
+ /*
+ (1)For DSPI instances with shared RX/TX DMA requests: Rx DMA request -> channel_A -> channel_B-> channel_C.
+ channel_A minor link to channel_B , channel_B minor link to channel_C.
+
+ Already pushed 1 or 2 data in SPI_PUSHR , then start the DMA tansfer.
+ channel_A:SPI_POPR to rxData,
+ channel_B:next txData to handle->command (low 16 bits),
+ channel_C:handle->command (32 bits) to SPI_PUSHR, and use the scatter/gather to transfer the last data
+ (handle->lastCommand to SPI_PUSHR).
+
+ (2)For DSPI instances with separate RX and TX DMA requests:
+ Rx DMA request -> channel_A
+ Tx DMA request -> channel_C -> channel_B .
+ channel_C major link to 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"
+
+ channel_A:SPI_POPR to rxData,
+ channel_C: handle->command (32 bits) to SPI_PUSHR,
+ channel_B: next txData to handle->command (low 16 bits), and use the scatter/gather to prepare the last data
+ (handle->lastCommand to handle->Command).
+ */
+
+ /*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)
+ {
+ 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;
+ handle->command = handle->lastCommand;
+ }
+ 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;
+ handle->command = handle->lastCommand;
+ }
+ 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)
+ {
+ 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(rxData)*/
+ 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;
+ }
+
+ /* Store the initially configured eDMA minor byte transfer count into the DSPI handle */
+ handle->nbytes = transferConfigA.minorLoopBytes;
+
+ EDMA_SetTransferConfig(handle->edmaRxRegToRxDataHandle->base, handle->edmaRxRegToRxDataHandle->channel,
+ &transferConfigA, NULL);
+ EDMA_EnableChannelInterrupts(handle->edmaRxRegToRxDataHandle->base, handle->edmaRxRegToRxDataHandle->channel,
+ kEDMA_MajorInterruptEnable);
+
+ /*Calculate the last data : handle->lastCommand*/
+ 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
+ {
+ 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;
+ }
+ }
+
+/* The feature of GASKET is that the SPI supports 8-bit or 16-bit writes to the PUSH TX FIFO,
+ * allowing a single write to the command word followed by multiple writes to the transmit word.
+ * The TX FIFO will save the last command word written, and convert a 8-bit/16-bit write to the
+ * transmit word into a 32-bit write that pushes both the command word and transmit word into
+ * the TX FIFO (PUSH TX FIFO Register In Master Mode)
+ * So, if this feature is supported, we can use use one channel to carry the receive data from
+ * receive regsiter to user data buffer, use the other channel to carry the data from user data buffer
+ * to transmit register,and use the scatter/gather function to prepare the last data.
+ * That is to say, if GASKET feature is supported, we can use only two channels for tansferring data.
+ */
+#if defined(FSL_FEATURE_DSPI_HAS_GASKET) && FSL_FEATURE_DSPI_HAS_GASKET
+ /* For DSPI instances with separate RX and TX DMA requests: use the scatter/gather to prepare the last data
+ * (handle->lastCommand) to PUSHR register.
+ */
+
+ EDMA_ResetChannel(handle->edmaIntermediaryToTxRegHandle->base, handle->edmaIntermediaryToTxRegHandle->channel);
+
+ if ((1 == FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base)) ||
+ ((handle->remainingSendByteCount > 0) && (1 != FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base))))
+ {
+ transferConfigB.srcAddr = (uint32_t) & (handle->lastCommand);
+ transferConfigB.destAddr = (uint32_t)txAddr;
+ transferConfigB.srcTransferSize = kEDMA_TransferSize4Bytes;
+ transferConfigB.destTransferSize = kEDMA_TransferSize4Bytes;
+ transferConfigB.srcOffset = 0;
+ transferConfigB.destOffset = 0;
+ transferConfigB.minorLoopBytes = 4;
+ transferConfigB.majorLoopCounts = 1;
+
+ EDMA_TcdReset(softwareTCD);
+ EDMA_TcdSetTransferConfig(softwareTCD, &transferConfigB, NULL);
+ }
+
+ /*User_Send_Buffer(txData) to PUSHR register. */
+ if (((handle->remainingSendByteCount > 2) && (handle->bitsPerFrame <= 8)) ||
+ ((handle->remainingSendByteCount > 4) && (handle->bitsPerFrame > 8)))
+ {
+ if (handle->txData)
+ {
+ if (1 == FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base))
+ {
+ /* For DSPI with separate RX and TX DMA requests, one frame data has been carry
+ * to handle->command, so need to reduce the pointer of txData.
+ */
+ transferConfigB.srcAddr =
+ (uint32_t)((uint8_t *)(handle->txData) - ((handle->bitsPerFrame <= 8) ? (1U) : (2U)));
+ transferConfigB.srcOffset = 1;
+ }
+ else
+ {
+ /* For DSPI with shared RX and TX DMA requests, one or two frame data have been carry
+ * to PUSHR register, so no need to change the pointer of txData.
+ */
+ transferConfigB.srcAddr = (uint32_t)((uint8_t *)(handle->txData));
+ transferConfigB.srcOffset = 1;
+ }
+ }
+ else
+ {
+ transferConfigB.srcAddr = (uint32_t)(&handle->txBuffIfNull);
+ transferConfigB.srcOffset = 0;
+ }
+
+ transferConfigB.destAddr = (uint32_t)txAddr;
+ transferConfigB.destOffset = 0;
+
+ transferConfigB.srcTransferSize = kEDMA_TransferSize1Bytes;
+
+ if (handle->bitsPerFrame <= 8)
+ {
+ transferConfigB.destTransferSize = kEDMA_TransferSize1Bytes;
+ transferConfigB.minorLoopBytes = 1;
+
+ transferConfigB.majorLoopCounts = handle->remainingSendByteCount - 1;
+ }
+ else
+ {
+ transferConfigB.destTransferSize = kEDMA_TransferSize2Bytes;
+ transferConfigB.minorLoopBytes = 2;
+ transferConfigB.majorLoopCounts = (handle->remainingSendByteCount / 2) - 1;
+ }
+
+ EDMA_SetTransferConfig(handle->edmaIntermediaryToTxRegHandle->base,
+ handle->edmaIntermediaryToTxRegHandle->channel, &transferConfigB, softwareTCD);
+ }
+ /* If only one word to transmit, only carry the lastcommand. */
+ else
+ {
+ EDMA_SetTransferConfig(handle->edmaIntermediaryToTxRegHandle->base,
+ handle->edmaIntermediaryToTxRegHandle->channel, &transferConfigB, NULL);
+ }
+
+ /*Start the EDMA channel_A , channel_C. */
+ EDMA_StartTransfer(handle->edmaRxRegToRxDataHandle);
+ EDMA_StartTransfer(handle->edmaIntermediaryToTxRegHandle);
+
+ /* Set the channel link.
+ * For DSPI instances with shared TX and RX DMA requests, setup channel minor link, first receive data from the
+ * receive register, and then carry transmit data to PUSHER register.
+ * For DSPI instance with separate TX and RX DMA requests, there is no need to set up channel link.
+ */
+ if (1 != FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base))
+ {
+ /*Set channel priority*/
+ uint8_t channelPriorityLow = handle->edmaRxRegToRxDataHandle->channel;
+ uint8_t channelPriorityHigh = handle->edmaIntermediaryToTxRegHandle->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;
+
+ EDMA_SetChannelPreemptionConfig(handle->edmaRxRegToRxDataHandle->base, handle->edmaRxRegToRxDataHandle->channel,
+ &preemption_config_t);
+
+ preemption_config_t.channelPriority = channelPriorityHigh;
+ EDMA_SetChannelPreemptionConfig(handle->edmaIntermediaryToTxRegHandle->base,
+ handle->edmaIntermediaryToTxRegHandle->channel, &preemption_config_t);
+ /*if there is Rx DMA request , carry the 32bits data (handle->command) to user data first , then link to
+ channelC to carry the next data to PUSHER register.(txData to PUSHER) */
+ if (handle->remainingSendByteCount > 0)
+ {
+ EDMA_SetChannelLink(handle->edmaRxRegToRxDataHandle->base, handle->edmaRxRegToRxDataHandle->channel,
+ kEDMA_MinorLink, handle->edmaIntermediaryToTxRegHandle->channel);
+ }
+ }
+
+ DSPI_EnableDMA(base, kDSPI_RxDmaEnable | kDSPI_TxDmaEnable);
+
+ /* Setup control info to PUSHER register. */
+ *((uint16_t *)&(base->PUSHR) + 1) = (handle->command >> 16U);
+#else
+
+ /***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);
+
+ /*For DSPI instances with separate RX and TX DMA requests: use the scatter/gather to prepare the last data
+ * (handle->lastCommand) to handle->Command*/
+ if (1 == FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base))
+ {
+ transferConfigB.srcAddr = (uint32_t) & (handle->lastCommand);
+ transferConfigB.destAddr = (uint32_t) & (handle->command);
+ transferConfigB.srcTransferSize = kEDMA_TransferSize4Bytes;
+ transferConfigB.destTransferSize = kEDMA_TransferSize4Bytes;
+ transferConfigB.srcOffset = 0;
+ transferConfigB.destOffset = 0;
+ transferConfigB.minorLoopBytes = 4;
+ transferConfigB.majorLoopCounts = 1;
+
+ EDMA_TcdReset(softwareTCD);
+ EDMA_TcdSetTransferConfig(softwareTCD, &transferConfigB, NULL);
+ }
+
+ /*User_Send_Buffer(txData) to intermediary(handle->command)*/
+ if (((((handle->remainingSendByteCount > 2) && (handle->bitsPerFrame <= 8)) ||
+ ((handle->remainingSendByteCount > 4) && (handle->bitsPerFrame > 8))) &&
+ (1 == FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base))) ||
+ (1 != FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base)))
+ {
+ 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))
+ {
+ transferConfigB.majorLoopCounts = handle->remainingSendByteCount - 2;
+ }
+ 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))
+ {
+ transferConfigB.majorLoopCounts = handle->remainingSendByteCount / 2 - 2;
+ }
+ 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;
+ }
+ }
+
+ if (1 == FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base))
+ {
+ EDMA_SetTransferConfig(handle->edmaTxDataToIntermediaryHandle->base,
+ handle->edmaTxDataToIntermediaryHandle->channel, &transferConfigB, softwareTCD);
+ EDMA_EnableAutoStopRequest(handle->edmaIntermediaryToTxRegHandle->base,
+ handle->edmaIntermediaryToTxRegHandle->channel, false);
+ }
+ else
+ {
+ EDMA_SetTransferConfig(handle->edmaTxDataToIntermediaryHandle->base,
+ handle->edmaTxDataToIntermediaryHandle->channel, &transferConfigB, NULL);
+ }
+ }
+ else
+ {
+ 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_transfer_config_t transferConfigC;
+ EDMA_ResetChannel(handle->edmaIntermediaryToTxRegHandle->base, handle->edmaIntermediaryToTxRegHandle->channel);
+
+ /*For DSPI instances with shared RX/TX DMA requests: use the scatter/gather to prepare the last data
+ * (handle->lastCommand) to SPI_PUSHR*/
+ if (((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)) ||
+ (1 == FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base)))
+ {
+ 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 (1 != FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base))
+ {
+ 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);
+ }
+ else
+ {
+ transferConfigC.majorLoopCounts = 1;
+
+ EDMA_SetTransferConfig(handle->edmaIntermediaryToTxRegHandle->base,
+ handle->edmaIntermediaryToTxRegHandle->channel, &transferConfigC, NULL);
+ }
+
+ 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.*/
+ 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 (txData to handle->command) */
+ if (handle->remainingSendByteCount > 1)
+ {
+ EDMA_SetChannelLink(handle->edmaIntermediaryToTxRegHandle->base,
+ handle->edmaIntermediaryToTxRegHandle->channel, kEDMA_MajorLink,
+ 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);
+
+ EDMA_SetChannelLink(handle->edmaTxDataToIntermediaryHandle->base,
+ handle->edmaTxDataToIntermediaryHandle->channel, kEDMA_MinorLink,
+ handle->edmaIntermediaryToTxRegHandle->channel);
+ }
+
+ DSPI_EnableDMA(base, kDSPI_RxDmaEnable);
+ }
+#endif
+ DSPI_StartTransfer(base);
+
+ return kStatus_Success;
+}
+
+status_t DSPI_MasterHalfDuplexTransferEDMA(SPI_Type *base,
+ dspi_master_edma_handle_t *handle,
+ dspi_half_duplex_transfer_t *xfer)
+{
+ assert(xfer);
+ assert(handle);
+ dspi_transfer_t tempXfer = {0};
+ status_t status;
+
+ if (xfer->isTransmitFirst)
+ {
+ tempXfer.txData = xfer->txData;
+ tempXfer.rxData = NULL;
+ tempXfer.dataSize = xfer->txDataSize;
+ }
+ else
+ {
+ tempXfer.txData = NULL;
+ tempXfer.rxData = xfer->rxData;
+ tempXfer.dataSize = xfer->rxDataSize;
+ }
+ /* If the pcs pin keep assert between transmit and receive. */
+ if (xfer->isPcsAssertInTransfer)
+ {
+ tempXfer.configFlags = (xfer->configFlags) | kDSPI_MasterActiveAfterTransfer;
+ }
+ else
+ {
+ tempXfer.configFlags = (xfer->configFlags) & (uint32_t)(~kDSPI_MasterActiveAfterTransfer);
+ }
+
+ status = DSPI_MasterTransferBlocking(base, &tempXfer);
+ if (status != kStatus_Success)
+ {
+ return status;
+ }
+
+ if (xfer->isTransmitFirst)
+ {
+ tempXfer.txData = NULL;
+ tempXfer.rxData = xfer->rxData;
+ tempXfer.dataSize = xfer->rxDataSize;
+ }
+ else
+ {
+ tempXfer.txData = xfer->txData;
+ tempXfer.rxData = NULL;
+ tempXfer.dataSize = xfer->txDataSize;
+ }
+ tempXfer.configFlags = xfer->configFlags;
+
+ status = DSPI_MasterTransferEDMA(base, handle, &tempXfer);
+
+ return status;
+}
+static void EDMA_DspiMasterCallback(edma_handle_t *edmaHandle,
+ void *g_dspiEdmaPrivateHandle,
+ bool transferDone,
+ uint32_t tcds)
+{
+ assert(edmaHandle);
+ assert(g_dspiEdmaPrivateHandle);
+
+ dspi_master_edma_private_handle_t *dspiEdmaPrivateHandle;
+
+ dspiEdmaPrivateHandle = (dspi_master_edma_private_handle_t *)g_dspiEdmaPrivateHandle;
+
+ DSPI_DisableDMA((dspiEdmaPrivateHandle->base), kDSPI_RxDmaEnable | kDSPI_TxDmaEnable);
+
+ dspiEdmaPrivateHandle->handle->state = kDSPI_Idle;
+
+ if (dspiEdmaPrivateHandle->handle->callback)
+ {
+ dspiEdmaPrivateHandle->handle->callback(dspiEdmaPrivateHandle->base, dspiEdmaPrivateHandle->handle,
+ kStatus_Success, dspiEdmaPrivateHandle->handle->userData);
+ }
+}
+
+void DSPI_MasterTransferAbortEDMA(SPI_Type *base, dspi_master_edma_handle_t *handle)
+{
+ assert(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 = (uint32_t)handle->nbytes * EDMA_GetRemainingMajorLoopCount(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);
+ assert(edmaRxRegToRxDataHandle);
+ assert(edmaTxDataToTxRegHandle);
+
+ /* 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);
+ assert(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;
+ }
+
+ handle->state = kDSPI_Busy;
+
+ 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
+ */
+ uint32_t limited_size = 0;
+ if (1 == FSL_FEATURE_DSPI_HAS_SEPARATE_DMA_RX_TX_REQn(base))
+ {
+ limited_size = 32767u;
+ }
+ else
+ {
+ limited_size = 511u;
+ }
+
+ if (handle->bitsPerFrame > 8)
+ {
+ if (transfer->dataSize > (limited_size << 1u))
+ {
+ handle->state = kDSPI_Idle;
+ return kStatus_DSPI_OutOfRange;
+ }
+ }
+ else
+ {
+ if (transfer->dataSize > limited_size)
+ {
+ handle->state = kDSPI_Idle;
+ return kStatus_DSPI_OutOfRange;
+ }
+ }
+
+ /*The data size should be even if the bitsPerFrame is greater than 8 (that is 2 bytes per frame in dspi) */
+ if ((handle->bitsPerFrame > 8) && (transfer->dataSize & 0x1))
+ {
+ handle->state = kDSPI_Idle;
+ return kStatus_InvalidArgument;
+ }
+
+ EDMA_SetCallback(handle->edmaRxRegToRxDataHandle, EDMA_DspiSlaveCallback, &s_dspiSlaveEdmaPrivateHandle[instance]);
+
+ /* Store transfer information */
+ handle->txData = transfer->txData;
+ handle->rxData = transfer->rxData;
+ handle->remainingSendByteCount = transfer->dataSize;
+ handle->remainingReceiveByteCount = transfer->dataSize;
+ handle->totalByteCount = transfer->dataSize;
+
+ uint16_t wordToSend = 0;
+ uint8_t dummyData = g_dspiDummyData[DSPI_GetInstance(base)];
+ 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 */
+
+ 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;
+ }
+
+ /* Store the initially configured eDMA minor byte transfer count into the DSPI handle */
+ handle->nbytes = transferConfigA.minorLoopBytes;
+
+ 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);
+
+ 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 = dummyData;
+ }
+ else
+ {
+ handle->txBuffIfNull = ((uint32_t)dummyData << 8) | dummyData;
+ }
+ }
+
+ 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;
+ transferConfigC.majorLoopCounts = handle->remainingSendByteCount / 2;
+ }
+
+ 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)
+{
+ assert(edmaHandle);
+ assert(g_dspiEdmaPrivateHandle);
+
+ dspi_slave_edma_private_handle_t *dspiEdmaPrivateHandle;
+
+ dspiEdmaPrivateHandle = (dspi_slave_edma_private_handle_t *)g_dspiEdmaPrivateHandle;
+
+ DSPI_DisableDMA((dspiEdmaPrivateHandle->base), kDSPI_RxDmaEnable | kDSPI_TxDmaEnable);
+
+ dspiEdmaPrivateHandle->handle->state = kDSPI_Idle;
+
+ if (dspiEdmaPrivateHandle->handle->callback)
+ {
+ dspiEdmaPrivateHandle->handle->callback(dspiEdmaPrivateHandle->base, dspiEdmaPrivateHandle->handle,
+ kStatus_Success, dspiEdmaPrivateHandle->handle->userData);
+ }
+}
+
+void DSPI_SlaveTransferAbortEDMA(SPI_Type *base, dspi_slave_edma_handle_t *handle)
+{
+ assert(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 = (uint32_t)handle->nbytes * EDMA_GetRemainingMajorLoopCount(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..aa9656c
--- /dev/null
+++ b/drivers/fsl_dspi_edma.h
@@ -0,0 +1,306 @@
+/*
+ * The Clear BSD License
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * Copyright 2016-2017 NXP
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted (subject to the limitations in the disclaimer below) provided
+ * that the following conditions are met:
+ *
+ * o Redistributions of source code must retain the above copyright notice, this list
+ * of conditions and the following disclaimer.
+ *
+ * o Redistributions in binary form must reproduce the above copyright notice, this
+ * list of conditions and the following disclaimer in the documentation and/or
+ * other materials provided with the distribution.
+ *
+ * o Neither the name of the copyright holder nor the names of its
+ * contributors may be used to endorse or promote products derived from this
+ * software without specific prior written permission.
+ *
+ * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS LICENSE.
+ * 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
+ **********************************************************************************************************************/
+
+/*! @name Driver version */
+/*@{*/
+/*! @brief DSPI EDMA driver version 2.2.0. */
+#define FSL_DSPI_EDMA_DRIVER_VERSION (MAKE_VERSION(2, 2, 0))
+/*@}*/
+
+/*!
+* @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 A pointer to the handle for the DSPI master.
+ * @param status Success or error code describing whether the transfer completed.
+ * @param userData An 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 A pointer to the handle for the DSPI slave.
+ * @param status Success or error code describing whether the transfer completed.
+ * @param userData An 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 the transactional API. */
+struct _dspi_master_edma_handle
+{
+ uint32_t bitsPerFrame; /*!< The desired number of bits per frame. */
+ volatile uint32_t command; /*!< The desired data command. */
+ volatile uint32_t lastCommand; /*!< The desired last data command. */
+
+ uint8_t fifoSize; /*!< FIFO dataSize. */
+
+ volatile bool
+ isPcsActiveAfterTransfer; /*!< Indicates whether the PCS signal keeps active after the last frame transfer.*/
+
+ uint8_t nbytes; /*!< eDMA minor byte transfer count initially configured. */
+ volatile uint8_t state; /*!< DSPI transfer state , _dspi_transfer_state.*/
+
+ uint8_t *volatile txData; /*!< Send buffer. */
+ uint8_t *volatile rxData; /*!< Receive buffer. */
+ volatile size_t remainingSendByteCount; /*!< A number of bytes remaining to send.*/
+ volatile size_t remainingReceiveByteCount; /*!< A number of bytes remaining to receive.*/
+ size_t totalByteCount; /*!< A 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.*/
+
+ 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 the transactional API.*/
+struct _dspi_slave_edma_handle
+{
+ uint32_t bitsPerFrame; /*!< The desired number of bits per frame. */
+
+ uint8_t *volatile txData; /*!< Send buffer. */
+ uint8_t *volatile rxData; /*!< Receive buffer. */
+ volatile size_t remainingSendByteCount; /*!< A number of bytes remaining to send.*/
+ volatile size_t remainingReceiveByteCount; /*!< A number of bytes remaining to receive.*/
+ size_t totalByteCount; /*!< A 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.*/
+
+ uint8_t nbytes; /*!< eDMA minor byte transfer count initially configured. */
+
+ volatile uint8_t state; /*!< DSPI transfer state.*/
+
+ 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*/
+};
+
+/***********************************************************************************************************************
+ * 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, 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 A 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 transfers data using eDMA. This is a non-blocking function, which returns right away. When all data
+ * is transferred, the callback function is called.
+ *
+ * @param base DSPI peripheral base address.
+ * @param handle A pointer to the dspi_master_edma_handle_t structure which stores the transfer state.
+ * @param transfer A pointer to the 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 Transfers a block of data using a eDMA method.
+ *
+ * This function transfers data using eDNA, the transfer mechanism is half-duplex. This is a non-blocking function,
+ * which returns right away. When all data is transferred, the callback function is called.
+ *
+ * @param base DSPI base pointer
+ * @param handle A pointer to the dspi_master_edma_handle_t structure which stores the transfer state.
+ * @param transfer A pointer to the dspi_half_duplex_transfer_t structure.
+ * @return status of status_t.
+ */
+status_t DSPI_MasterHalfDuplexTransferEDMA(SPI_Type *base,
+ dspi_master_edma_handle_t *handle,
+ dspi_half_duplex_transfer_t *xfer);
+
+/*!
+ * @brief DSPI master aborts a transfer which is using eDMA.
+ *
+ * This function aborts a transfer which is using eDMA.
+ *
+ * @param base DSPI peripheral base address.
+ * @param handle A pointer to the 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 gets the master eDMA transfer count.
+ *
+ * @param base DSPI peripheral base address.
+ * @param handle A pointer to the dspi_master_edma_handle_t structure which stores the transfer state.
+ * @param count A number of bytes transferred 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 A 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 transfers data using eDMA. This is a non-blocking function, which returns right away. When all data
+ * is transferred, the callback function is called.
+ * Note that the slave eDMA transfer doesn't support transfer_size is 1 when the bitsPerFrame is greater
+ * than eight.
+
+ * @param base DSPI peripheral base address.
+ * @param handle A pointer to the dspi_slave_edma_handle_t structure which stores the transfer state.
+ * @param transfer A pointer to the 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 is using eDMA.
+ *
+ * This function aborts a transfer which is using eDMA.
+ *
+ * @param base DSPI peripheral base address.
+ * @param handle A pointer to the 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 A pointer to the dspi_slave_edma_handle_t structure which stores the transfer state.
+ * @param count A 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..96b0f80
--- /dev/null
+++ b/drivers/fsl_edma.c
@@ -0,0 +1,2299 @@
+/*
+ * The Clear BSD License
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * Copyright 2016-2017 NXP
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted (subject to the limitations in the disclaimer below) provided
+ * that the following conditions are met:
+ *
+ * o Redistributions of source code must retain the above copyright notice, this list
+ * of conditions and the following disclaimer.
+ *
+ * o Redistributions in binary form must reproduce the above copyright notice, this
+ * list of conditions and the following disclaimer in the documentation and/or
+ * other materials provided with the distribution.
+ *
+ * o Neither the name of the copyright holder nor the names of its
+ * contributors may be used to endorse or promote products derived from this
+ * software without specific prior written permission.
+ *
+ * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS LICENSE.
+ * 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
+ ******************************************************************************/
+
+/* Component ID definition, used by tools. */
+#ifndef FSL_COMPONENT_ID
+#define FSL_COMPONENT_ID "platform.drivers.edma"
+#endif
+
+
+#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);
+
+/*******************************************************************************
+ * Variables
+ ******************************************************************************/
+
+/*! @brief Array to map EDMA instance number to base pointer. */
+static DMA_Type *const s_edmaBases[] = DMA_BASE_PTRS;
+
+#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
+/*! @brief Array to map EDMA instance number to clock name. */
+static const clock_ip_name_t s_edmaClockName[] = EDMA_CLOCKS;
+#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
+
+/*! @brief Array to map EDMA instance number to IRQ number. */
+static const IRQn_Type s_edmaIRQNumber[][FSL_FEATURE_EDMA_MODULE_CHANNEL] = 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 < ARRAY_SIZE(s_edmaBases); instance++)
+ {
+ if (s_edmaBases[instance] == base)
+ {
+ break;
+ }
+ }
+
+ assert(instance < ARRAY_SIZE(s_edmaBases));
+
+ return instance;
+}
+
+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;
+
+#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
+ /* Ungate EDMA periphral clock */
+ CLOCK_EnableClock(s_edmaClockName[EDMA_GetInstance(base)]);
+#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
+ /* 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)
+{
+#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
+ /* Gate EDMA periphral clock */
+ CLOCK_DisableClock(s_edmaClockName[EDMA_GetInstance(base)]);
+#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
+}
+
+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_GetRemainingMajorLoopCount(DMA_Type *base, uint32_t channel)
+{
+ assert(channel < FSL_FEATURE_EDMA_MODULE_CHANNEL);
+
+ uint32_t remainingCount = 0;
+
+ if (DMA_CSR_DONE_MASK & base->TCD[channel].CSR)
+ {
+ remainingCount = 0;
+ }
+ else
+ {
+ /* Calculate the unfinished bytes */
+ if (base->TCD[channel].CITER_ELINKNO & DMA_CITER_ELINKNO_ELINK_MASK)
+ {
+ remainingCount =
+ (base->TCD[channel].CITER_ELINKYES & DMA_CITER_ELINKYES_CITER_MASK) >> DMA_CITER_ELINKYES_CITER_SHIFT;
+ }
+ else
+ {
+ remainingCount =
+ (base->TCD[channel].CITER_ELINKNO & DMA_CITER_ELINKNO_CITER_MASK) >> DMA_CITER_ELINKNO_CITER_SHIFT;
+ }
+ }
+
+ return remainingCount;
+}
+
+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;
+ }
+}
+
+static uint8_t Get_StartInstance(void)
+{
+ static uint8_t StartInstanceNum;
+
+#if defined(DMA0)
+ StartInstanceNum = EDMA_GetInstance(DMA0);
+#elif defined(DMA1)
+ StartInstanceNum = EDMA_GetInstance(DMA1);
+#elif defined(DMA2)
+ StartInstanceNum = EDMA_GetInstance(DMA2);
+#elif defined(DMA3)
+ StartInstanceNum = EDMA_GetInstance(DMA3);
+#endif
+
+ return StartInstanceNum;
+}
+
+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;
+ uint8_t StartInstance;
+ edma_tcd_t *tcdRegs;
+
+ /* Zero the handle */
+ memset(handle, 0, sizeof(*handle));
+
+ handle->base = base;
+ handle->channel = channel;
+ /* Get the DMA instance number */
+ edmaInstance = EDMA_GetInstance(base);
+ StartInstance = Get_StartInstance();
+ channelIndex = ((edmaInstance - StartInstance) * FSL_FEATURE_EDMA_MODULE_CHANNEL) + channel;
+ s_EDMAHandle[channelIndex] = handle;
+
+ /* Enable NVIC interrupt */
+ EnableIRQ(s_edmaIRQNumber[edmaInstance][channel]);
+
+ /*
+ 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])
+ {
+ /* Clear the DREQ bits for the dynamic scatter gather */
+ tcdRegs->CSR |= DMA_CSR_DREQ_MASK;
+ /* Enable scatter/gather also in the TCD registers. */
+ csr = tcdRegs->CSR | DMA_CSR_ESG_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)
+ {
+ tcdRegs->CSR &= ~DMA_CSR_DREQ_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;
+
+ /* Handle the tcd */
+ if (handle->tcdPool != NULL)
+ {
+ handle->header = 0;
+ handle->tail = 0;
+ handle->tcdUsed = 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. Please refer to the API descriptions in the eDMA header file for detailed information. */
+ {
+ 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 next transfer TCD blcoks to be loaded into the eDMA engine. */
+ sga -= (uint32_t)handle->tcdPool;
+ /* Get the index of the next transfer TCD blcoks to be loaded into the eDMA engine. */
+ sga_index = sga / sizeof(edma_tcd_t);
+ /* Adjust header positions. */
+ if (transfer_done)
+ {
+ /* New header shall point to the next TCD to be loaded (current one is already finished) */
+ new_header = sga_index;
+ }
+ else
+ {
+ /* New header shall point to this descriptor currently loaded (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
+ {
+ /* No TCD in the memory are going to be loaded or internal error occurs. */
+ tcds_done = 0;
+ }
+ }
+ else
+ {
+ tcds_done = new_header - handle->header;
+ if (tcds_done < 0)
+ {
+ tcds_done += handle->tcdSize;
+ }
+ }
+ /* Advance header which points to the TCD to be loaded into the eDMA engine from memory. */
+ handle->header = new_header;
+ /* Release TCD blocks. tcdUsed is the TCD number which can be used/loaded in the memory pool. */
+ 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
+
+#if defined(DMA0)
+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]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+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]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+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]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+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]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+#endif
+
+#if defined(DMA1)
+
+#if defined(DMA0)
+void DMA1_04_DriverIRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA1, 0U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[8]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA1, 4U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[12]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA1_15_DriverIRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA1, 1U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[9]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA1, 5U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[13]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA1_26_DriverIRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA1, 2U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[10]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA1, 6U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[14]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA1_37_DriverIRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA1, 3U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[11]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA1, 7U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[15]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+#else
+void DMA1_04_DriverIRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA1, 0U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[0]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA1, 4U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[4]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA1_15_DriverIRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA1, 1U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[1]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA1, 5U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[5]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA1_26_DriverIRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA1, 2U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[2]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA1, 6U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[6]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA1_37_DriverIRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA1, 3U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[3]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA1, 7U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[7]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+#endif
+#endif
+#endif /* 8 channels (Shared) */
+
+/* 16 channels (Shared): K32H844P */
+#if defined(FSL_FEATURE_EDMA_MODULE_CHANNEL) && FSL_FEATURE_EDMA_MODULE_CHANNEL == 16U
+
+void DMA0_08_DriverIRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA0, 0U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[0]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA0, 8U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[8]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA0_19_DriverIRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA0, 1U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[1]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA0, 9U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[9]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA0_210_DriverIRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA0, 2U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[2]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA0, 10U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[10]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA0_311_DriverIRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA0, 3U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[3]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA0, 11U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[11]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA0_412_DriverIRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA0, 4U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[4]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA0, 12U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[12]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA0_513_DriverIRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA0, 5U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[5]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA0, 13U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[13]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA0_614_DriverIRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA0, 6U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[6]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA0, 14U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[14]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA0_715_DriverIRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA0, 7U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[7]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA0, 15U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[15]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+#if defined(DMA1)
+void DMA1_08_DriverIRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA1, 0U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[16]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA1, 8U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[24]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA1_19_DriverIRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA1, 1U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[17]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA1, 9U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[25]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA1_210_DriverIRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA1, 2U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[18]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA1, 10U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[26]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA1_311_DriverIRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA1, 3U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[19]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA1, 11U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[27]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA1_412_DriverIRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA1, 4U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[20]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA1, 12U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[28]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA1_513_DriverIRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA1, 5U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[21]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA1, 13U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[29]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA1_614_DriverIRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA1, 6U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[22]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA1, 14U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[30]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA1_715_DriverIRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA1, 7U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[23]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA1, 15U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[31]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+#endif
+#endif /* 16 channels (Shared) */
+
+/* 32 channels (Shared): k80 */
+#if defined(FSL_FEATURE_EDMA_MODULE_CHANNEL) && FSL_FEATURE_EDMA_MODULE_CHANNEL == 32U
+
+void DMA0_DMA16_DriverIRQHandler(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]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA1_DMA17_DriverIRQHandler(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]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA2_DMA18_DriverIRQHandler(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]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA3_DMA19_DriverIRQHandler(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]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA4_DMA20_DriverIRQHandler(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]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA5_DMA21_DriverIRQHandler(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]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA6_DMA22_DriverIRQHandler(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]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA7_DMA23_DriverIRQHandler(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]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA8_DMA24_DriverIRQHandler(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]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA9_DMA25_DriverIRQHandler(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]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA10_DMA26_DriverIRQHandler(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]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA11_DMA27_DriverIRQHandler(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]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA12_DMA28_DriverIRQHandler(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]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA13_DMA29_DriverIRQHandler(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]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA14_DMA30_DriverIRQHandler(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]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA15_DMA31_DriverIRQHandler(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]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+#endif /* 32 channels (Shared) */
+
+/* 32 channels (Shared): MCIMX7U5_M4 */
+#if defined(FSL_FEATURE_EDMA_MODULE_CHANNEL) && FSL_FEATURE_EDMA_MODULE_CHANNEL == 32U
+
+void DMA0_0_4_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]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA0_1_5_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]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA0_2_6_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]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA0_3_7_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]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA0_8_12_DriverIRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA0, 8U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[8]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA0, 12U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[12]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA0_9_13_DriverIRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA0, 9U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[9]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA0, 13U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[13]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA0_10_14_DriverIRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA0, 10U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[10]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA0, 14U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[14]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA0_11_15_DriverIRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA0, 11U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[11]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA0, 15U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[15]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA0_16_20_DriverIRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA0, 16U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[16]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA0, 20U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[20]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA0_17_21_DriverIRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA0, 17U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[17]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA0, 21U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[21]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA0_18_22_DriverIRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA0, 18U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[18]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA0, 22U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[22]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA0_19_23_DriverIRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA0, 19U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[19]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA0, 23U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[23]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA0_24_28_DriverIRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA0, 24U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[24]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA0, 28U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[28]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA0_25_29_DriverIRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA0, 25U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[25]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA0, 29U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[29]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA0_26_30_DriverIRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA0, 26U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[26]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA0, 30U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[30]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA0_27_31_DriverIRQHandler(void)
+{
+ if ((EDMA_GetChannelStatusFlags(DMA0, 27U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[27]);
+ }
+ if ((EDMA_GetChannelStatusFlags(DMA0, 31U) & kEDMA_InterruptFlag) != 0U)
+ {
+ EDMA_HandleIRQ(s_EDMAHandle[31]);
+ }
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+#endif /* 32 channels (Shared): MCIMX7U5 */
+
+/* 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]);
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA1_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[1]);
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA2_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[2]);
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA3_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[3]);
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+/* 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]);
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA5_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[5]);
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA6_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[6]);
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA7_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[7]);
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+#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]);
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA9_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[9]);
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA10_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[10]);
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA11_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[11]);
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA12_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[12]);
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA13_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[13]);
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA14_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[14]);
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA15_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[15]);
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+#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]);
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA17_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[17]);
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA18_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[18]);
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA19_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[19]);
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA20_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[20]);
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA21_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[21]);
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA22_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[22]);
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA23_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[23]);
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA24_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[24]);
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA25_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[25]);
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA26_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[26]);
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA27_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[27]);
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA28_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[28]);
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA29_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[29]);
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA30_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[30]);
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void DMA31_DriverIRQHandler(void)
+{
+ EDMA_HandleIRQ(s_EDMAHandle[31]);
+ /* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+#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..03bc8db
--- /dev/null
+++ b/drivers/fsl_edma.h
@@ -0,0 +1,957 @@
+/*
+ * The Clear BSD License
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * Copyright 2016-2017 NXP
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted (subject to the limitations in the disclaimer below) provided
+ * that the following conditions are met:
+ *
+ * o Redistributions of source code must retain the above copyright notice, this list
+ * of conditions and the following disclaimer.
+ *
+ * o Redistributions in binary form must reproduce the above copyright notice, this
+ * list of conditions and the following disclaimer in the documentation and/or
+ * other materials provided with the distribution.
+ *
+ * o Neither the name of the copyright holder nor the names of its
+ * contributors may be used to endorse or promote products derived from this
+ * software without specific prior written permission.
+ *
+ * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS LICENSE.
+ * 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, 1, 2)) /*!< Version 2.1.2. */
+/*@}*/
+
+/*! @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_TransferSize8Bytes = 0x3U, /*!< Source/Destination data transfer size is 8 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 1 K bytes. */
+ kEDMA_Modulo2Kbytes, /*!< Circular buffer size is 2 K bytes. */
+ kEDMA_Modulo4Kbytes, /*!< Circular buffer size is 4 K bytes. */
+ kEDMA_Modulo8Kbytes, /*!< Circular buffer size is 8 K bytes. */
+ kEDMA_Modulo16Kbytes, /*!< Circular buffer size is 16 K bytes. */
+ kEDMA_Modulo32Kbytes, /*!< Circular buffer size is 32 K bytes. */
+ kEDMA_Modulo64Kbytes, /*!< Circular buffer size is 64 K bytes. */
+ kEDMA_Modulo128Kbytes, /*!< Circular buffer size is 128 K bytes. */
+ kEDMA_Modulo256Kbytes, /*!< Circular buffer size is 256 K bytes. */
+ kEDMA_Modulo512Kbytes, /*!< Circular buffer size is 512 K bytes. */
+ kEDMA_Modulo1Mbytes, /*!< Circular buffer size is 1 M bytes. */
+ kEDMA_Modulo2Mbytes, /*!< Circular buffer size is 2 M bytes. */
+ kEDMA_Modulo4Mbytes, /*!< Circular buffer size is 4 M bytes. */
+ kEDMA_Modulo8Mbytes, /*!< Circular buffer size is 8 M bytes. */
+ kEDMA_Modulo16Mbytes, /*!< Circular buffer size is 16 M bytes. */
+ kEDMA_Modulo32Mbytes, /*!< Circular buffer size is 32 M bytes. */
+ kEDMA_Modulo64Mbytes, /*!< Circular buffer size is 64 M bytes. */
+ kEDMA_Modulo128Mbytes, /*!< Circular buffer size is 128 M bytes. */
+ kEDMA_Modulo256Mbytes, /*!< Circular buffer size is 256 M bytes. */
+ kEDMA_Modulo512Mbytes, /*!< Circular buffer size is 512 M bytes. */
+ kEDMA_Modulo1Gbytes, /*!< Circular buffer size is 1 G bytes. */
+ kEDMA_Modulo2Gbytes, /*!< Circular buffer size is 2 G 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.
+ */
+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. */
+ uint32_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: a channel can be suspended by other channel with higher priority */
+ bool enablePreemptAbility; /*!< If true: a 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 a 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.
+ *
+ * This callback function is called in the EDMA interrupt handle.
+ * In normal mode, run into callback function means the transfer users need is done.
+ * In scatter gather mode, run into callback function means a transfer control block (tcd) is finished. Not
+ * all transfer finished, users can get the finished tcd numbers using interface EDMA_GetUnusedTCDNumber.
+ *
+ * @param handle EDMA handle pointer, users shall not touch the values inside.
+ * @param userData The callback user paramter pointer. Users can use this paramter to involve things users need to
+ * change in EDMA callback function.
+ * @param transferDone If the current loaded transfer done. In normal mode it means if all transfer done. In scatter
+ * gather mode, this paramter shows is the current transfer block in EDMA regsiter is done. As the
+ * load of core is different, it will be different if the new tcd loaded into EDMA registers while
+ * this callback called. If true, it always means new tcd still not loaded into registers, while
+ * false means new tcd already loaded into registers.
+ * @param tcds How many tcds are done from the last callback. This parameter only used in scatter gather mode. It
+ * tells user how many tcds are finished between the last callback and this.
+ */
+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. Should point to the next TCD to be loaded into the eDMA engine. */
+ volatile int8_t tail; /*!< The last TCD index. Should point to the next TCD to be stored into the memory pool. */
+ volatile int8_t tcdUsed; /*!< The number of used TCD slots. Should reflect the number of TCDs can be used/loaded in
+ the memory. */
+ 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 the 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 A pointer to the configuration structure, see "edma_config_t".
+ * @note This function enables the minor loop map feature.
+ */
+void EDMA_Init(DMA_Type *base, const edma_config_t *config);
+
+/*!
+ * @brief Deinitializes the eDMA peripheral.
+ *
+ * This function gates the eDMA clock.
+ *
+ * @param base eDMA peripheral base address.
+ */
+void EDMA_Deinit(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.
+ */
+void EDMA_InstallTCD(DMA_Type *base, uint32_t channel, edma_tcd_t *tcd);
+
+/*!
+ * @brief Gets the eDMA default configuration structure.
+ *
+ * This function sets the configuration structure to default values.
+ * The default configuration is set to the following values.
+ * @code
+ * config.enableContinuousLinkMode = false;
+ * config.enableHaltOnError = true;
+ * config.enableRoundRobinArbitration = false;
+ * config.enableDebugMode = false;
+ * @endcode
+ *
+ * @param config A pointer to the eDMA configuration structure.
+ */
+void EDMA_GetDefaultConfig(edma_config_t *config);
+
+/* @} */
+/*!
+ * @name eDMA Channel Operation
+ * @{
+ */
+
+/*!
+ * @brief Sets all TCD registers to default values.
+ *
+ * This function sets TCD registers for this channel to default values.
+ *
+ * @param base eDMA peripheral base address.
+ * @param channel eDMA channel number.
+ * @note This function must not be called while the channel transfer is ongoing
+ * 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 the 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.
+ *
+ * The minor offset means that the signed-extended value is added to the source address or destination
+ * address after each minor loop.
+ *
+ * @param base eDMA peripheral base address.
+ * @param channel eDMA channel number.
+ * @param config A pointer to the 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 A pointer to the 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 either the minor link or the 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 A channel link type, which can be one of the following:
+ * @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.
+ *
+ * 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 A bandwidth setting, which can be one of the following:
+ * @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 the destination modulo for the 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 A source modulo value.
+ * @param destModulo A 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 to enable (true) 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 to 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 the 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.
+ *
+ * The TCD is a transfer control descriptor. The content of the TCD is the same as the hardware TCD registers.
+ * The STCD is used in the 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.
+ *
+ * A minor offset is a signed-extended value added to the source address or a destination
+ * address after each minor loop.
+ *
+ * @param tcd A point to the TCD structure.
+ * @param config A pointer to the minor offset configuration structure.
+ */
+void EDMA_TcdSetMinorOffsetConfig(edma_tcd_t *tcd, const edma_minor_offset_config_t *config);
+
+/*!
+ * @brief Sets the channel link for the 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.
+ *
+ * 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 tcd A pointer to the TCD structure.
+ * @param bandWidth A bandwidth setting, which can be one of the following:
+ * @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 the destination modulo for the 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 A pointer to the TCD structure.
+ * @param srcModulo A source modulo value.
+ * @param destModulo A 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 A pointer to the TCD structure.
+ * @param enable The command to enable (true) 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 using the 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 major loop count from the eDMA current channel TCD.
+ *
+ * This function checks the TCD (Task Control Descriptor) status for a specified
+ * eDMA channel and returns the number of major loop count that has not finished.
+ *
+ * @param base eDMA peripheral base address.
+ * @param channel eDMA channel number.
+ * @return Major loop count which has not been transferred yet for the current TCD.
+ * @note 1. This function can only be used to get unfinished major loop count of transfer without
+ * the next TCD, or it might be inaccuracy.
+ * 2. The unfinished/remaining transfer bytes cannot be obtained directly from registers while
+ * the channel is running.
+ * Because to calculate the remaining bytes, the initial NBYTES configured in DMA_TCDn_NBYTES_MLNO
+ * register is needed while the eDMA IP does not support getting it while a channel is active.
+ * In another word, the NBYTES value reading is always the actual (decrementing) NBYTES value the dma_engine
+ * is working with while a channel is running.
+ * Consequently, to get the remaining transfer bytes, a software-saved initial value of NBYTES (for example
+ * copied before enabling the channel) is needed. The formula to calculate it is shown below:
+ * RemainingBytes = RemainingMajorLoopCount * NBYTES(initially configured)
+ */
+uint32_t EDMA_GetRemainingMajorLoopCount(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 the transactional API for eDMA. This function
+ * initializes the internal state of the 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 the eDMA handle.
+ *
+ * This function is called after the EDMA_CreateHandle to use scatter/gather feature. This function shall only be used
+ * while users need to use scatter gather mode. Scatter gather mode enables EDMA to load a new transfer control block
+ * (tcd) in hardware, and automatically reconfigure that DMA channel for a new transfer.
+ * Users need to preapre tcd memory and also configure tcds using interface EDMA_SubmitTransfer.
+ *
+ * @param handle eDMA handle pointer.
+ * @param tcdPool A 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 the eDMA IRQ handler. Use the callback to do something after
+ * the current major loop transfer completes. This function will be called every time one tcd finished transfer.
+ *
+ * @param handle eDMA handle pointer.
+ * @param callback eDMA callback function pointer.
+ * @param userData A parameter for the 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, the source address must be 4 bytes aligned, or it results 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.
+ * In scatter gather mode, call this function will add a configured tcd to the circular list of tcd pool.
+ * The tcd pools is setup by call function EDMA_InstallTCDMemory before.
+ *
+ * @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 starts 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 stops 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 aborts 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 Get unused TCD slot number.
+ *
+ * This function gets current tcd index which is run. If the TCD pool pointer is NULL, it will return 0.
+ *
+ * @param handle DMA handle pointer.
+ * @return The unused tcd slot number.
+ */
+static inline uint32_t EDMA_GetUnusedTCDNumber(edma_handle_t *handle)
+{
+ return (handle->tcdSize - handle->tcdUsed);
+}
+
+/*!
+ * @brief Get the next tcd address.
+ *
+ * This function gets the next tcd address. If this is last TCD, return 0.
+ *
+ * @param handle DMA handle pointer.
+ * @return The next TCD address.
+ */
+static inline uint32_t EDMA_GetNextTCDAddress(edma_handle_t *handle)
+{
+ return (handle->base->TCD[handle->channel].DLAST_SGA);
+}
+
+/*!
+ * @brief eDMA IRQ handler for the current major loop transfer completion.
+ *
+ * This function clears the channel major interrupt flag and calls
+ * the callback function if it is not NULL.
+ *
+ * Note:
+ * For the case using TCD queue, when the major iteration count is exhausted, additional operations are performed.
+ * These include the final address adjustments and reloading of the BITER field into the CITER.
+ * Assertion of an optional interrupt request also occurs at this time, as does a possible fetch of a new TCD from
+ * memory using the scatter/gather address pointer included in the descriptor (if scatter/gather is enabled).
+ *
+ * For instance, when the time interrupt of TCD[0] happens, the TCD[1] has already been loaded into the eDMA engine.
+ * As sga and sga_index are calculated based on the DLAST_SGA bitfield lies in the TCD_CSR register, the sga_index
+ * in this case should be 2 (DLAST_SGA of TCD[1] stores the address of TCD[2]). Thus, the "tcdUsed" updated should be
+ * (tcdUsed - 2U) which indicates the number of TCDs can be loaded in the memory pool (because TCD[0] and TCD[1] have
+ * been loaded into the eDMA engine at this point already.).
+ *
+ * For the last two continuous ISRs in a scatter/gather process, they both load the last TCD (The last ISR does not
+ * load a new TCD) from the memory pool to the eDMA engine when major loop completes.
+ * Therefore, ensure that the header and tcdUsed updated are identical for them.
+ * tcdUsed are both 0 in this case as no TCD to be loaded.
+ *
+ * See the "eDMA basic data flow" in the eDMA Functional description section of the Reference Manual for
+ * further details.
+ *
+ * @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_gpio.c b/drivers/fsl_gpio.c
new file mode 100644
index 0000000..93f09bb
--- /dev/null
+++ b/drivers/fsl_gpio.c
@@ -0,0 +1,235 @@
+/*
+ * The Clear BSD License
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * Copyright 2016-2017 NXP
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted (subject to the limitations in the disclaimer below) provided
+ * that the following conditions are met:
+ *
+ * o Redistributions of source code must retain the above copyright notice, this list
+ * of conditions and the following disclaimer.
+ *
+ * o Redistributions in binary form must reproduce the above copyright notice, this
+ * list of conditions and the following disclaimer in the documentation and/or
+ * other materials provided with the distribution.
+ *
+ * o Neither the name of the copyright holder nor the names of its
+ * contributors may be used to endorse or promote products derived from this
+ * software without specific prior written permission.
+ *
+ * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS LICENSE.
+ * 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"
+
+/* Component ID definition, used by tools. */
+#ifndef FSL_COMPONENT_ID
+#define FSL_COMPONENT_ID "platform.drivers.gpio"
+#endif
+
+
+/*******************************************************************************
+ * Variables
+ ******************************************************************************/
+
+#if !(defined(FSL_FEATURE_GPIO_HAS_NO_PORTINTERRUPT) && FSL_FEATURE_GPIO_HAS_NO_PORTINTERRUPT)
+static PORT_Type *const s_portBases[] = PORT_BASE_PTRS;
+static GPIO_Type *const s_gpioBases[] = GPIO_BASE_PTRS;
+#endif
+
+#if defined(FSL_FEATURE_SOC_FGPIO_COUNT) && FSL_FEATURE_SOC_FGPIO_COUNT
+
+#if defined(FSL_FEATURE_PCC_HAS_FGPIO_CLOCK_GATE_CONTROL) && FSL_FEATURE_PCC_HAS_FGPIO_CLOCK_GATE_CONTROL
+
+#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
+/*! @brief Array to map FGPIO instance number to clock name. */
+static const clock_ip_name_t s_fgpioClockName[] = FGPIO_CLOCKS;
+#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
+
+#endif /* FSL_FEATURE_PCC_HAS_FGPIO_CLOCK_GATE_CONTROL */
+
+#endif /* FSL_FEATURE_SOC_FGPIO_COUNT */
+
+/*******************************************************************************
+* Prototypes
+******************************************************************************/
+#if !(defined(FSL_FEATURE_GPIO_HAS_NO_PORTINTERRUPT) && FSL_FEATURE_GPIO_HAS_NO_PORTINTERRUPT)
+/*!
+* @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);
+#endif
+/*******************************************************************************
+ * Code
+ ******************************************************************************/
+#if !(defined(FSL_FEATURE_GPIO_HAS_NO_PORTINTERRUPT) && FSL_FEATURE_GPIO_HAS_NO_PORTINTERRUPT)
+static uint32_t GPIO_GetInstance(GPIO_Type *base)
+{
+ uint32_t instance;
+
+ /* Find the instance index from base address mappings. */
+ for (instance = 0; instance < ARRAY_SIZE(s_gpioBases); instance++)
+ {
+ if (s_gpioBases[instance] == base)
+ {
+ break;
+ }
+ }
+
+ assert(instance < ARRAY_SIZE(s_gpioBases));
+
+ return instance;
+}
+#endif
+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);
+ }
+}
+
+#if !(defined(FSL_FEATURE_GPIO_HAS_NO_PORTINTERRUPT) && FSL_FEATURE_GPIO_HAS_NO_PORTINTERRUPT)
+uint32_t GPIO_PortGetInterruptFlags(GPIO_Type *base)
+{
+ uint8_t instance;
+ PORT_Type *portBase;
+ instance = GPIO_GetInstance(base);
+ portBase = s_portBases[instance];
+ return portBase->ISFR;
+}
+
+void GPIO_PortClearInterruptFlags(GPIO_Type *base, uint32_t mask)
+{
+ uint8_t instance;
+ PORT_Type *portBase;
+ instance = GPIO_GetInstance(base);
+ portBase = s_portBases[instance];
+ portBase->ISFR = mask;
+}
+#endif
+
+#if defined(FSL_FEATURE_GPIO_HAS_ATTRIBUTE_CHECKER) && FSL_FEATURE_GPIO_HAS_ATTRIBUTE_CHECKER
+void GPIO_CheckAttributeBytes(GPIO_Type *base, gpio_checker_attribute_t attribute)
+{
+ base->GACR = ((uint32_t)attribute << GPIO_GACR_ACB0_SHIFT) | ((uint32_t)attribute << GPIO_GACR_ACB1_SHIFT) |
+ ((uint32_t)attribute << GPIO_GACR_ACB2_SHIFT) | ((uint32_t)attribute << GPIO_GACR_ACB3_SHIFT);
+}
+#endif
+
+#if defined(FSL_FEATURE_SOC_FGPIO_COUNT) && FSL_FEATURE_SOC_FGPIO_COUNT
+
+/*******************************************************************************
+ * Variables
+ ******************************************************************************/
+#if !(defined(FSL_FEATURE_GPIO_HAS_NO_PORTINTERRUPT) && FSL_FEATURE_GPIO_HAS_NO_PORTINTERRUPT)
+static FGPIO_Type *const s_fgpioBases[] = FGPIO_BASE_PTRS;
+#endif
+/*******************************************************************************
+* Prototypes
+******************************************************************************/
+#if !(defined(FSL_FEATURE_GPIO_HAS_NO_PORTINTERRUPT) && FSL_FEATURE_GPIO_HAS_NO_PORTINTERRUPT)
+/*!
+* @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);
+#endif
+/*******************************************************************************
+ * Code
+ ******************************************************************************/
+#if !(defined(FSL_FEATURE_GPIO_HAS_NO_PORTINTERRUPT) && FSL_FEATURE_GPIO_HAS_NO_PORTINTERRUPT)
+static uint32_t FGPIO_GetInstance(FGPIO_Type *base)
+{
+ uint32_t instance;
+
+ /* Find the instance index from base address mappings. */
+ for (instance = 0; instance < ARRAY_SIZE(s_fgpioBases); instance++)
+ {
+ if (s_fgpioBases[instance] == base)
+ {
+ break;
+ }
+ }
+
+ assert(instance < ARRAY_SIZE(s_fgpioBases));
+
+ return instance;
+}
+#endif
+#if defined(FSL_FEATURE_PCC_HAS_FGPIO_CLOCK_GATE_CONTROL) && FSL_FEATURE_PCC_HAS_FGPIO_CLOCK_GATE_CONTROL
+void FGPIO_PortInit(FGPIO_Type *base)
+{
+#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
+ /* Ungate FGPIO periphral clock */
+ CLOCK_EnableClock(s_fgpioClockName[FGPIO_GetInstance(base)]);
+#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
+}
+#endif /* FSL_FEATURE_PCC_HAS_FGPIO_CLOCK_GATE_CONTROL */
+
+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);
+ }
+}
+#if !(defined(FSL_FEATURE_GPIO_HAS_NO_PORTINTERRUPT) && FSL_FEATURE_GPIO_HAS_NO_PORTINTERRUPT)
+uint32_t FGPIO_PortGetInterruptFlags(FGPIO_Type *base)
+{
+ uint8_t instance;
+ instance = FGPIO_GetInstance(base);
+ PORT_Type *portBase;
+ portBase = s_portBases[instance];
+ return portBase->ISFR;
+}
+
+void FGPIO_PortClearInterruptFlags(FGPIO_Type *base, uint32_t mask)
+{
+ uint8_t instance;
+ instance = FGPIO_GetInstance(base);
+ PORT_Type *portBase;
+ portBase = s_portBases[instance];
+ portBase->ISFR = mask;
+}
+#endif
+#if defined(FSL_FEATURE_FGPIO_HAS_ATTRIBUTE_CHECKER) && FSL_FEATURE_FGPIO_HAS_ATTRIBUTE_CHECKER
+void FGPIO_CheckAttributeBytes(FGPIO_Type *base, gpio_checker_attribute_t attribute)
+{
+ base->GACR = (attribute << FGPIO_GACR_ACB0_SHIFT) | (attribute << FGPIO_GACR_ACB1_SHIFT) |
+ (attribute << FGPIO_GACR_ACB2_SHIFT) | (attribute << FGPIO_GACR_ACB3_SHIFT);
+}
+#endif
+
+#endif /* FSL_FEATURE_SOC_FGPIO_COUNT */
diff --git a/drivers/fsl_gpio.h b/drivers/fsl_gpio.h
new file mode 100644
index 0000000..794b472
--- /dev/null
+++ b/drivers/fsl_gpio.h
@@ -0,0 +1,594 @@
+/*
+ * The Clear BSD License
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * Copyright 2016-2017 NXP
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted (subject to the limitations in the disclaimer below) provided
+ * that the following conditions are met:
+ *
+ * o Redistributions of source code must retain the above copyright notice, this list
+ * of conditions and the following disclaimer.
+ *
+ * o Redistributions in binary form must reproduce the above copyright notice, this
+ * list of conditions and the following disclaimer in the documentation and/or
+ * other materials provided with the distribution.
+ *
+ * o Neither the name of the copyright holder nor the names of its
+ * contributors may be used to endorse or promote products derived from this
+ * software without specific prior written permission.
+ *
+ * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS LICENSE.
+ * 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_GPIO_H_
+#define _FSL_GPIO_H_
+
+#include "fsl_common.h"
+
+/*!
+ * @addtogroup gpio
+ * @{
+ */
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+/*! @name Driver version */
+/*@{*/
+/*! @brief GPIO driver version 2.2.1. */
+#define FSL_GPIO_DRIVER_VERSION (MAKE_VERSION(2, 2, 1))
+/*@}*/
+
+/*! @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;
+
+#if defined(FSL_FEATURE_GPIO_HAS_ATTRIBUTE_CHECKER) && FSL_FEATURE_GPIO_HAS_ATTRIBUTE_CHECKER
+/*! @brief GPIO checker attribute */
+typedef enum _gpio_checker_attribute
+{
+ kGPIO_UsernonsecureRWUsersecureRWPrivilegedsecureRW =
+ 0x00U, /*!< User nonsecure:Read+Write; User Secure:Read+Write; Privileged Secure:Read+Write */
+ kGPIO_UsernonsecureRUsersecureRWPrivilegedsecureRW =
+ 0x01U, /*!< User nonsecure:Read; User Secure:Read+Write; Privileged Secure:Read+Write */
+ kGPIO_UsernonsecureNUsersecureRWPrivilegedsecureRW =
+ 0x02U, /*!< User nonsecure:None; User Secure:Read+Write; Privileged Secure:Read+Write */
+ kGPIO_UsernonsecureRUsersecureRPrivilegedsecureRW =
+ 0x03U, /*!< User nonsecure:Read; User Secure:Read; Privileged Secure:Read+Write */
+ kGPIO_UsernonsecureNUsersecureRPrivilegedsecureRW =
+ 0x04U, /*!< User nonsecure:None; User Secure:Read; Privileged Secure:Read+Write */
+ kGPIO_UsernonsecureNUsersecureNPrivilegedsecureRW =
+ 0x05U, /*!< User nonsecure:None; User Secure:None; Privileged Secure:Read+Write */
+ kGPIO_UsernonsecureNUsersecureNPrivilegedsecureR =
+ 0x06U, /*!< User nonsecure:None; User Secure:None; Privileged Secure:Read */
+ kGPIO_UsernonsecureNUsersecureNPrivilegedsecureN =
+ 0x07U, /*!< User nonsecure:None; User Secure:None; Privileged Secure:None */
+ kGPIO_IgnoreAttributeCheck = 0x80U, /*!< Ignores the attribute check */
+} gpio_checker_attribute_t;
+#endif
+
+/*!
+ * @brief The GPIO pin configuration structure.
+ *
+ * Each pin can only be configured as either an output pin or an input pin at a time.
+ * If configured as an input pin, leave the outputConfig unused.
+ * Note that 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; ignore if configured as an input pin */
+ uint8_t outputLogic; /*!< Set a default output logic, which has 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, as either input or output, in the user file.
+ * Then, call the GPIO_PinInit() function.
+ *
+ * This is an example to define an input pin or an 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_PinWrite(GPIO_Type *base, uint32_t pin, uint8_t output)
+{
+ if (output == 0U)
+ {
+ base->PCOR = 1U << pin;
+ }
+ else
+ {
+ base->PSOR = 1U << pin;
+ }
+}
+
+/*!
+ * @brief Sets the output level of the multiple GPIO pins to the logic 1 or 0.
+ * @deprecated Do not use this function. It has been superceded by @ref GPIO_PinWrite.
+ */
+static inline void GPIO_WritePinOutput(GPIO_Type *base, uint32_t pin, uint8_t output)
+{
+ GPIO_PinWrite(base, pin, output);
+}
+
+/*!
+ * @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_PortSet(GPIO_Type *base, uint32_t mask)
+{
+ base->PSOR = mask;
+}
+
+/*!
+ * @brief Sets the output level of the multiple GPIO pins to the logic 1.
+ * @deprecated Do not use this function. It has been superceded by @ref GPIO_PortSet.
+ */
+static inline void GPIO_SetPinsOutput(GPIO_Type *base, uint32_t mask)
+{
+ GPIO_PortSet(base, 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_PortClear(GPIO_Type *base, uint32_t mask)
+{
+ base->PCOR = mask;
+}
+
+/*!
+ * @brief Sets the output level of the multiple GPIO pins to the logic 0.
+ * @deprecated Do not use this function. It has been superceded by @ref GPIO_PortClear.
+ *
+ * @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)
+{
+ GPIO_PortClear(base, mask);
+}
+
+/*!
+ * @brief Reverses the 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_PortToggle(GPIO_Type *base, uint32_t mask)
+{
+ base->PTOR = mask;
+}
+
+/*!
+ * @brief Reverses the current output logic of the multiple GPIO pins.
+ * @deprecated Do not use this function. It has been superceded by @ref GPIO_PortToggle.
+ */
+static inline void GPIO_TogglePinsOutput(GPIO_Type *base, uint32_t mask)
+{
+ GPIO_PortToggle(base, mask);
+}
+/*@}*/
+
+/*! @name GPIO Input Operations */
+/*@{*/
+
+/*!
+ * @brief Reads the current input value of the 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_PinRead(GPIO_Type *base, uint32_t pin)
+{
+ return (((base->PDIR) >> pin) & 0x01U);
+}
+
+/*!
+ * @brief Reads the current input value of the GPIO port.
+ * @deprecated Do not use this function. It has been superceded by @ref GPIO_PinRead.
+ */
+static inline uint32_t GPIO_ReadPinInput(GPIO_Type *base, uint32_t pin)
+{
+ return GPIO_PinRead(base, pin);
+}
+
+/*@}*/
+
+/*! @name GPIO Interrupt */
+/*@{*/
+#if !(defined(FSL_FEATURE_GPIO_HAS_NO_PORTINTERRUPT) && FSL_FEATURE_GPIO_HAS_NO_PORTINTERRUPT)
+
+/*!
+ * @brief Reads the 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 The current GPIO port interrupt status flag, for example, 0x00010001 means the
+ * pin 0 and 17 have the interrupt.
+ */
+uint32_t GPIO_PortGetInterruptFlags(GPIO_Type *base);
+
+/*!
+ * @brief Reads the GPIO port interrupt status flag.
+ * @deprecated Do not use this function. It has been superceded by @ref GPIO_PortGetInterruptFlags.
+ */
+static inline uint32_t GPIO_GetPinsInterruptFlags(GPIO_Type *base)
+{
+ return GPIO_PortGetInterruptFlags(base);
+}
+
+/*!
+ * @brief Clears multiple GPIO pin interrupt status flags.
+ *
+ * @param base GPIO peripheral base pointer (GPIOA, GPIOB, GPIOC, and so on.)
+ * @param mask GPIO pin number macro
+ */
+void GPIO_PortClearInterruptFlags(GPIO_Type *base, uint32_t mask);
+
+/*!
+ * @brief Clears multiple GPIO pin interrupt status flags.
+ * @deprecated Do not use this function. It has been superceded by @ref GPIO_PortClearInterruptFlags.
+ */
+static inline void GPIO_ClearPinsInterruptFlags(GPIO_Type *base, uint32_t mask)
+{
+ GPIO_PortClearInterruptFlags(base, mask);
+}
+#endif
+#if defined(FSL_FEATURE_GPIO_HAS_ATTRIBUTE_CHECKER) && FSL_FEATURE_GPIO_HAS_ATTRIBUTE_CHECKER
+/*!
+ * @brief The GPIO module supports a device-specific number of data ports, organized as 32-bit
+ * words. Each 32-bit data port includes a GACR register, which defines the byte-level
+ * attributes required for a successful access to the GPIO programming model. The attribute controls for the 4 data
+ * bytes in the GACR follow a standard little endian
+ * data convention.
+ *
+ * @param base GPIO peripheral base pointer (GPIOA, GPIOB, GPIOC, and so on.)
+ * @param mask GPIO pin number macro
+ */
+void GPIO_CheckAttributeBytes(GPIO_Type *base, gpio_checker_attribute_t attribute);
+#endif
+
+/*@}*/
+/*! @} */
+
+/*!
+ * @addtogroup fgpio_driver
+ * @{
+ */
+
+/*
+ * Introduces the FGPIO feature.
+ *
+ * The FGPIO features are only support on some Kinetis MCUs. The FGPIO registers are aliased to the IOPORT
+ * interface. Accesses via the IOPORT interface occur in parallel with any instruction fetches and
+ * 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 the FGPIO peripheral.
+ *
+ * This function ungates the FGPIO clock.
+ *
+ * @param base FGPIO peripheral base pointer (FGPIOA, FGPIOB, FGPIOC, and so on.)
+ */
+ void FGPIO_PortInit(FGPIO_Type *base);
+
+/*!
+ * @brief Initializes the FGPIO peripheral.
+ * @deprecated Do not use this function. It has been superceded by @ref FGPIO_PortInit.
+ */
+ static inline void FGPIO_Init(FGPIO_Type *base)
+ {
+ FGPIO_PortInit(base);
+ }
+
+/*!
+ * @brief Initializes a FGPIO pin used by the board.
+ *
+ * To initialize the FGPIO driver, define a pin configuration, as either input or output, in the user file.
+ * Then, call the FGPIO_PinInit() function.
+ *
+ * This is an example to define an input pin or an 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 (FGPIOA, FGPIOB, FGPIOC, 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 (FGPIOA, FGPIOB, FGPIOC, 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_PinWrite(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 or 0.
+ * @deprecated Do not use this function. It has been superceded by @ref FGPIO_PinWrite.
+ */
+static inline void FGPIO_WritePinOutput(FGPIO_Type *base, uint32_t pin, uint8_t output)
+{
+ FGPIO_PinWrite(base, pin, output);
+}
+
+/*!
+ * @brief Sets the output level of the multiple FGPIO pins to the logic 1.
+ *
+ * @param base FGPIO peripheral base pointer (FGPIOA, FGPIOB, FGPIOC, and so on.)
+ * @param mask FGPIO pin number macro
+ */
+static inline void FGPIO_PortSet(FGPIO_Type *base, uint32_t mask)
+{
+ base->PSOR = mask;
+}
+
+/*!
+ * @brief Sets the output level of the multiple FGPIO pins to the logic 1.
+ * @deprecated Do not use this function. It has been superceded by @ref FGPIO_PortSet.
+ */
+static inline void FGPIO_SetPinsOutput(FGPIO_Type *base, uint32_t mask)
+{
+ FGPIO_PortSet(base, mask);
+}
+
+/*!
+ * @brief Sets the output level of the multiple FGPIO pins to the logic 0.
+ *
+ * @param base FGPIO peripheral base pointer (FGPIOA, FGPIOB, FGPIOC, and so on.)
+ * @param mask FGPIO pin number macro
+ */
+static inline void FGPIO_PortClear(FGPIO_Type *base, uint32_t mask)
+{
+ base->PCOR = mask;
+}
+
+/*!
+ * @brief Sets the output level of the multiple FGPIO pins to the logic 0.
+ * @deprecated Do not use this function. It has been superceded by @ref FGPIO_PortClear.
+ */
+static inline void FGPIO_ClearPinsOutput(FGPIO_Type *base, uint32_t mask)
+{
+ FGPIO_PortClear(base, mask);
+}
+
+/*!
+ * @brief Reverses the current output logic of the multiple FGPIO pins.
+ *
+ * @param base FGPIO peripheral base pointer (FGPIOA, FGPIOB, FGPIOC, and so on.)
+ * @param mask FGPIO pin number macro
+ */
+static inline void FGPIO_PortToggle(FGPIO_Type *base, uint32_t mask)
+{
+ base->PTOR = mask;
+}
+
+/*!
+ * @brief Reverses the current output logic of the multiple FGPIO pins.
+ * @deprecated Do not use this function. It has been superceded by @ref FGPIO_PortToggle.
+ */
+static inline void FGPIO_TogglePinsOutput(FGPIO_Type *base, uint32_t mask)
+{
+ FGPIO_PortToggle(base, mask);
+}
+/*@}*/
+
+/*! @name FGPIO Input Operations */
+/*@{*/
+
+/*!
+ * @brief Reads the current input value of the FGPIO port.
+ *
+ * @param base FGPIO peripheral base pointer (FGPIOA, FGPIOB, FGPIOC, 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_PinRead(FGPIO_Type *base, uint32_t pin)
+{
+ return (((base->PDIR) >> pin) & 0x01U);
+}
+
+/*!
+ * @brief Reads the current input value of the FGPIO port.
+ * @deprecated Do not use this function. It has been superceded by @ref FGPIO_PinRead
+ */
+static inline uint32_t FGPIO_ReadPinInput(FGPIO_Type *base, uint32_t pin)
+{
+ return FGPIO_PinRead(base, pin);
+}
+/*@}*/
+
+/*! @name FGPIO Interrupt */
+/*@{*/
+#if !(defined(FSL_FEATURE_GPIO_HAS_NO_PORTINTERRUPT) && FSL_FEATURE_GPIO_HAS_NO_PORTINTERRUPT)
+
+/*!
+ * @brief Reads the 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 (FGPIOA, FGPIOB, FGPIOC, and so on.)
+ * @retval The current FGPIO port interrupt status flags, for example, 0x00010001 means the
+ * pin 0 and 17 have the interrupt.
+ */
+uint32_t FGPIO_PortGetInterruptFlags(FGPIO_Type *base);
+
+/*!
+ * @brief Reads the FGPIO port interrupt status flag.
+ * @deprecated Do not use this function. It has been superceded by @ref FGPIO_PortGetInterruptFlags.
+ */
+static inline uint32_t FGPIO_GetPinsInterruptFlags(FGPIO_Type *base)
+{
+ return FGPIO_PortGetInterruptFlags(base);
+}
+
+/*!
+ * @brief Clears the multiple FGPIO pin interrupt status flag.
+ *
+ * @param base FGPIO peripheral base pointer (FGPIOA, FGPIOB, FGPIOC, and so on.)
+ * @param mask FGPIO pin number macro
+ */
+void FGPIO_PortClearInterruptFlags(FGPIO_Type *base, uint32_t mask);
+
+/*!
+ * @brief Clears the multiple FGPIO pin interrupt status flag.
+ * @deprecated Do not use this function. It has been superceded by @ref FGPIO_PortClearInterruptFlags.
+ */
+static inline void FGPIO_ClearPinsInterruptFlags(FGPIO_Type *base, uint32_t mask)
+{
+ FGPIO_PortClearInterruptFlags(base, mask);
+}
+#endif
+#if defined(FSL_FEATURE_GPIO_HAS_ATTRIBUTE_CHECKER) && FSL_FEATURE_GPIO_HAS_ATTRIBUTE_CHECKER
+/*!
+ * @brief The FGPIO module supports a device-specific number of data ports, organized as 32-bit
+ * words. Each 32-bit data port includes a GACR register, which defines the byte-level
+ * attributes required for a successful access to the GPIO programming model. The attribute controls for the 4 data
+ * bytes in the GACR follow a standard little endian
+ * data convention.
+ *
+ * @param base FGPIO peripheral base pointer (FGPIOA, FGPIOB, FGPIOC, and so on.)
+ * @param mask FGPIO pin number macro
+ */
+void FGPIO_CheckAttributeBytes(FGPIO_Type *base, gpio_checker_attribute_t attribute);
+#endif
+
+/*@}*/
+
+#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..d3da84a
--- /dev/null
+++ b/drivers/fsl_i2c.c
@@ -0,0 +1,2005 @@
+/*
+ * The Clear BSD License
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * Copyright 2016-2017 NXP
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted (subject to the limitations in the disclaimer below) provided
+ * that the following conditions are met:
+ *
+ * o Redistributions of source code must retain the above copyright notice, this list
+ * of conditions and the following disclaimer.
+ *
+ * o Redistributions in binary form must reproduce the above copyright notice, this
+ * list of conditions and the following disclaimer in the documentation and/or
+ * other materials provided with the distribution.
+ *
+ * o Neither the name of the copyright holder nor the names of its
+ * contributors may be used to endorse or promote products derived from this
+ * software without specific prior written permission.
+ *
+ * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS LICENSE.
+ * 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
+ ******************************************************************************/
+
+/* Component ID definition, used by tools. */
+#ifndef FSL_COMPONENT_ID
+#define FSL_COMPONENT_ID "platform.drivers.i2c"
+#endif
+
+
+/*! @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 Set SCL/SDA hold time, this API receives SCL stop hold time, calculate the
+* closest SCL divider and MULT value for the SDA hold time, SCL start and SCL stop
+* hold time. To reduce the ROM size, SDA/SCL hold value mapping table is not provided,
+* assume SCL divider = SCL stop hold value *2 to get the closest SCL divider value and MULT
+* value, then the related SDA hold time, SCL start and SCL stop hold time is used.
+*
+* @param base I2C peripheral base address.
+* @param sourceClock_Hz I2C functional clock frequency in Hertz.
+* @param sclStopHoldTime_ns SCL stop hold time in ns.
+*/
+static void I2C_SetHoldTime(I2C_Type *base, uint32_t sclStopHoldTime_ns, uint32_t sourceClock_Hz);
+
+/*!
+ * @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 bases for each instance. */
+I2C_Type *const s_i2cBases[] = I2C_BASE_PTRS;
+
+/*! @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 IRQ number for each instance. */
+static const IRQn_Type s_i2cIrqs[] = I2C_IRQS;
+
+#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
+/*! @brief Pointers to i2c clocks for each instance. */
+static const clock_ip_name_t s_i2cClocks[] = I2C_CLOCKS;
+#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
+
+/*! @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 < ARRAY_SIZE(s_i2cBases); instance++)
+ {
+ if (s_i2cBases[instance] == base)
+ {
+ break;
+ }
+ }
+
+ assert(instance < ARRAY_SIZE(s_i2cBases));
+
+ return instance;
+}
+
+static void I2C_SetHoldTime(I2C_Type *base, uint32_t sclStopHoldTime_ns, uint32_t sourceClock_Hz)
+{
+ uint32_t multiplier;
+ uint32_t computedSclHoldTime;
+ 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. */
+ /* SDA hold time = bus period (s) * mul * SDA hold value. */
+ /* SCL start hold time = bus period (s) * mul * SCL start hold value. */
+ /* SCL stop hold time = bus period (s) * mul * SCL stop hold value. */
+
+ 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(s_i2cDividerTable[0]); ++i)
+ {
+ /* Assume SCL hold(stop) value = s_i2cDividerTable[i]/2. */
+ computedSclHoldTime = ((multiplier * s_i2cDividerTable[i]) * 500000U) / (sourceClock_Hz / 1000U);
+ absError = sclStopHoldTime_ns > computedSclHoldTime ? (sclStopHoldTime_ns - computedSclHoldTime) :
+ (computedSclHoldTime - sclStopHoldTime_ns);
+
+ 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);
+}
+
+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;
+
+ /* Initialize the handle transfer information. */
+ handle->transfer = *xfer;
+
+ /* Save total transfer size. */
+ handle->transferSize = xfer->dataSize;
+
+ /* Initial transfer state. */
+ if (handle->transfer.subaddressSize > 0)
+ {
+ if (xfer->direction == kI2C_Read)
+ {
+ direction = kI2C_Write;
+ }
+ }
+
+ handle->state = kCheckAddressState;
+
+ /* Clear all status before transfer. */
+ I2C_MasterClearStatusFlags(base, kClearFlags);
+
+ /* Handle no start option. */
+ if (handle->transfer.flags & kI2C_TransferNoStartFlag)
+ {
+ /* No need to send start flag, directly go to send command or data */
+ if (handle->transfer.subaddressSize > 0)
+ {
+ handle->state = kSendCommandState;
+ }
+ else
+ {
+ if (direction == kI2C_Write)
+ {
+ /* Next state, send data. */
+ handle->state = kSendDataState;
+ }
+ else
+ {
+ /* Only support write with no stop signal. */
+ return kStatus_InvalidArgument;
+ }
+ }
+
+ /* Wait for TCF bit and manually trigger tx interrupt. */
+ while (!(base->S & kI2C_TransferCompleteFlag))
+ {
+ }
+ I2C_MasterTransferHandleIRQ(base, handle);
+ }
+ /* If repeated start is requested, send repeated start. */
+ else 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;
+ }
+
+ /* Handle Check address state to check the slave address is Acked in slave
+ probe application. */
+ if (handle->state == kCheckAddressState)
+ {
+ if (statusFlags & kI2C_ReceiveNakFlag)
+ {
+ result = kStatus_I2C_Addr_Nak;
+ }
+ else
+ {
+ if (handle->transfer.subaddressSize > 0)
+ {
+ handle->state = kSendCommandState;
+ }
+ else
+ {
+ if (handle->transfer.direction == kI2C_Write)
+ {
+ /* Next state, send data. */
+ handle->state = kSendDataState;
+ }
+ else
+ {
+ /* Next state, receive data begin. */
+ handle->state = kReceiveDataBeginState;
+ }
+ }
+ }
+ }
+
+ if (result)
+ {
+ return result;
+ }
+
+ /* 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);
+ }
+ else
+ {
+ base->C1 |= I2C_C1_TX_MASK;
+ }
+ }
+
+ /* 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);
+ }
+ __DSB();
+}
+
+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_DOUBLE_BUFFER_ENABLE) && FSL_FEATURE_I2C_HAS_DOUBLE_BUFFER_ENABLE
+ uint8_t s2Reg;
+#endif
+#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
+ /* Enable I2C clock. */
+ CLOCK_EnableClock(s_i2cClocks[I2C_GetInstance(base)]);
+#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
+
+ /* Reset the module. */
+ base->A1 = 0;
+ base->F = 0;
+ base->C1 = 0;
+ base->S = 0xFFU;
+ base->C2 = 0;
+#if defined(FSL_FEATURE_I2C_HAS_START_STOP_DETECT) && FSL_FEATURE_I2C_HAS_START_STOP_DETECT
+ base->FLT = 0x50U;
+#elif defined(FSL_FEATURE_I2C_HAS_STOP_DETECT) && FSL_FEATURE_I2C_HAS_STOP_DETECT
+ base->FLT = 0x40U;
+#endif
+ base->RA = 0;
+
+ /* 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);
+
+ /* 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);
+
+#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
+ /* Disable I2C clock. */
+ CLOCK_DisableClock(s_i2cClocks[I2C_GetInstance(base)]);
+#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
+}
+
+void I2C_MasterGetDefaultConfig(i2c_master_config_t *masterConfig)
+{
+ assert(masterConfig);
+
+ /* Default baud rate at 100kbps. */
+ masterConfig->baudRate_Bps = 100000U;
+
+/* 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
+#if I2C_WAIT_TIMEOUT
+ uint32_t waitTimes = I2C_WAIT_TIMEOUT;
+ while ((!(base->S2 & I2C_S2_EMPTY_MASK)) && (--waitTimes))
+ {
+ }
+ if (waitTimes == 0)
+ {
+ return kStatus_I2C_Timeout;
+ }
+#else
+ while (!(base->S2 & I2C_S2_EMPTY_MASK))
+ {
+ }
+#endif
+#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 | I2C_C1_TX_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
+#if I2C_WAIT_TIMEOUT
+ uint32_t waitTimes = I2C_WAIT_TIMEOUT;
+ while ((!(base->S2 & I2C_S2_EMPTY_MASK)) && (--waitTimes))
+ {
+ }
+ if (waitTimes == 0)
+ {
+ return kStatus_I2C_Timeout;
+ }
+#else
+ while (!(base->S2 & I2C_S2_EMPTY_MASK))
+ {
+ }
+#endif
+#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;
+
+ /* Issue the STOP command on the bus. */
+ base->C1 &= ~(I2C_C1_MST_MASK | I2C_C1_TX_MASK | I2C_C1_TXAK_MASK);
+
+#if I2C_WAIT_TIMEOUT
+ uint32_t waitTimes = I2C_WAIT_TIMEOUT;
+ /* Wait until bus not busy. */
+ while ((base->S & kI2C_BusBusyFlag) && (--waitTimes))
+ {
+ }
+
+ if (waitTimes == 0)
+ {
+ result = kStatus_I2C_Timeout;
+ }
+#else
+ /* Wait until data transfer complete. */
+ while (base->S & kI2C_BusBusyFlag)
+ {
+ }
+#endif
+
+ 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, uint32_t flags)
+{
+ status_t result = kStatus_Success;
+ uint8_t statusFlags = 0;
+
+#if I2C_WAIT_TIMEOUT
+ uint32_t waitTimes = I2C_WAIT_TIMEOUT;
+ /* Wait until the data register is ready for transmit. */
+ while ((!(base->S & kI2C_TransferCompleteFlag)) && (--waitTimes))
+ {
+ }
+ if (waitTimes == 0)
+ {
+ return kStatus_I2C_Timeout;
+ }
+#else
+ /* Wait until the data register is ready for transmit. */
+ while (!(base->S & kI2C_TransferCompleteFlag))
+ {
+ }
+#endif
+
+ /* 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++;
+
+#if I2C_WAIT_TIMEOUT
+ waitTimes = I2C_WAIT_TIMEOUT;
+ /* Wait until data transfer complete. */
+ while ((!(base->S & kI2C_IntPendingFlag)) && (--waitTimes))
+ {
+ }
+ if (waitTimes == 0)
+ {
+ return kStatus_I2C_Timeout;
+ }
+#else
+ /* Wait until data transfer complete. */
+ while (!(base->S & kI2C_IntPendingFlag))
+ {
+ }
+#endif
+ 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;
+ }
+ }
+
+ if (((result == kStatus_Success) && (!(flags & kI2C_TransferNoStopFlag))) || (result == kStatus_I2C_Nak))
+ {
+ /* Clear the IICIF flag. */
+ base->S = kI2C_IntPendingFlag;
+
+ /* Send stop. */
+ result = I2C_MasterStop(base);
+ }
+
+ return result;
+}
+
+status_t I2C_MasterReadBlocking(I2C_Type *base, uint8_t *rxBuff, size_t rxSize, uint32_t flags)
+{
+ status_t result = kStatus_Success;
+ volatile uint8_t dummy = 0;
+
+ /* Add this to avoid build warning. */
+ dummy++;
+
+#if I2C_WAIT_TIMEOUT
+ uint32_t waitTimes = I2C_WAIT_TIMEOUT;
+ /* Wait until the data register is ready for transmit. */
+ while ((!(base->S & kI2C_TransferCompleteFlag)) && (--waitTimes))
+ {
+ }
+ if (waitTimes == 0)
+ {
+ return kStatus_I2C_Timeout;
+ }
+#else
+ /* Wait until the data register is ready for transmit. */
+ while (!(base->S & kI2C_TransferCompleteFlag))
+ {
+ }
+#endif
+
+ /* 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--))
+ {
+#if I2C_WAIT_TIMEOUT
+ waitTimes = I2C_WAIT_TIMEOUT;
+ /* Wait until data transfer complete. */
+ while ((!(base->S & kI2C_IntPendingFlag)) && (--waitTimes))
+ {
+ }
+ if (waitTimes == 0)
+ {
+ return kStatus_I2C_Timeout;
+ }
+#else
+ /* Wait until data transfer complete. */
+ while (!(base->S & kI2C_IntPendingFlag))
+ {
+ }
+#endif
+ /* Clear the IICIF flag. */
+ base->S = kI2C_IntPendingFlag;
+
+ /* Single byte use case. */
+ if (rxSize == 0)
+ {
+ if (!(flags & kI2C_TransferNoStopFlag))
+ {
+ /* Issue STOP command before reading last byte. */
+ result = I2C_MasterStop(base);
+ }
+ else
+ {
+ /* Change direction to Tx to avoid extra clocks. */
+ base->C1 |= I2C_C1_TX_MASK;
+ }
+ }
+
+ 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);
+
+#if I2C_WAIT_TIMEOUT
+ uint32_t waitTimes = I2C_WAIT_TIMEOUT;
+ /* Wait until the data register is ready for transmit. */
+ while ((!(base->S & kI2C_TransferCompleteFlag)) && (--waitTimes))
+ {
+ }
+ if (waitTimes == 0)
+ {
+ return kStatus_I2C_Timeout;
+ }
+#else
+ /* Wait until the data register is ready for transmit. */
+ while (!(base->S & kI2C_TransferCompleteFlag))
+ {
+ }
+#endif
+
+ /* Change to send write address when it's a read operation with command. */
+ if ((xfer->subaddressSize > 0) && (xfer->direction == kI2C_Read))
+ {
+ direction = kI2C_Write;
+ }
+
+ /* Handle no start option, only support write with no start signal. */
+ if (xfer->flags & kI2C_TransferNoStartFlag)
+ {
+ if (direction == kI2C_Read)
+ {
+ return kStatus_InvalidArgument;
+ }
+ }
+ /* If repeated start is requested, send repeated start. */
+ else 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);
+ }
+
+ if (!(xfer->flags & kI2C_TransferNoStartFlag))
+ {
+ /* Return if error. */
+ if (result)
+ {
+ return result;
+ }
+
+#if I2C_WAIT_TIMEOUT
+ waitTimes = I2C_WAIT_TIMEOUT;
+ /* Wait until data transfer complete. */
+ while ((!(base->S & kI2C_IntPendingFlag)) && (--waitTimes))
+ {
+ }
+ if (waitTimes == 0)
+ {
+ return kStatus_I2C_Timeout;
+ }
+#else
+ /* Wait until data transfer complete. */
+ while (!(base->S & kI2C_IntPendingFlag))
+ {
+ }
+#endif
+ /* Check if there's transfer error. */
+ result = I2C_CheckAndClearError(base, base->S);
+
+ /* Return if error. */
+ if (result)
+ {
+ if (result == kStatus_I2C_Nak)
+ {
+ result = kStatus_I2C_Addr_Nak;
+
+ I2C_MasterStop(base);
+ }
+
+ return result;
+ }
+ }
+
+ /* Send subaddress. */
+ if (xfer->subaddressSize)
+ {
+ do
+ {
+ /* Clear interrupt pending flag. */
+ base->S = kI2C_IntPendingFlag;
+
+ xfer->subaddressSize--;
+ base->D = ((xfer->subaddress) >> (8 * xfer->subaddressSize));
+
+#if I2C_WAIT_TIMEOUT
+ waitTimes = I2C_WAIT_TIMEOUT;
+ /* Wait until data transfer complete. */
+ while ((!(base->S & kI2C_IntPendingFlag)) && (--waitTimes))
+ {
+ }
+ if (waitTimes == 0)
+ {
+ return kStatus_I2C_Timeout;
+ }
+#else
+ /* Wait until data transfer complete. */
+ while (!(base->S & kI2C_IntPendingFlag))
+ {
+ }
+#endif
+
+ /* Check if there's transfer error. */
+ result = I2C_CheckAndClearError(base, base->S);
+
+ if (result)
+ {
+ if (result == kStatus_I2C_Nak)
+ {
+ I2C_MasterStop(base);
+ }
+
+ return result;
+ }
+
+ } while (xfer->subaddressSize > 0);
+
+ if (xfer->direction == kI2C_Read)
+ {
+ /* Clear pending flag. */
+ base->S = kI2C_IntPendingFlag;
+
+ /* Send repeated start and slave address. */
+ result = I2C_MasterRepeatedStart(base, xfer->slaveAddress, kI2C_Read);
+
+ /* Return if error. */
+ if (result)
+ {
+ return result;
+ }
+
+#if I2C_WAIT_TIMEOUT
+ waitTimes = I2C_WAIT_TIMEOUT;
+ /* Wait until data transfer complete. */
+ while ((!(base->S & kI2C_IntPendingFlag)) && (--waitTimes))
+ {
+ }
+ if (waitTimes == 0)
+ {
+ return kStatus_I2C_Timeout;
+ }
+#else
+ /* Wait until data transfer complete. */
+ while (!(base->S & kI2C_IntPendingFlag))
+ {
+ }
+#endif
+
+ /* Check if there's transfer error. */
+ result = I2C_CheckAndClearError(base, base->S);
+
+ if (result)
+ {
+ if (result == kStatus_I2C_Nak)
+ {
+ result = kStatus_I2C_Addr_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, xfer->flags);
+ }
+
+ /* Receive Data. */
+ if ((xfer->direction == kI2C_Read) && (xfer->dataSize > 0))
+ {
+ result = I2C_MasterReadBlocking(base, xfer->data, xfer->dataSize, xfer->flags);
+ }
+
+ 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;
+}
+
+status_t I2C_MasterTransferAbort(I2C_Type *base, i2c_master_handle_t *handle)
+{
+ assert(handle);
+
+ volatile uint8_t dummy = 0;
+#if I2C_WAIT_TIMEOUT
+ uint32_t waitTimes = I2C_WAIT_TIMEOUT;
+#endif
+
+ /* Add this to avoid build warning. */
+ dummy++;
+
+ /* Disable interrupt. */
+ I2C_DisableInterrupts(base, kI2C_GlobalInterruptEnable);
+
+ /* Reset the state to idle. */
+ handle->state = kIdleState;
+
+ /* If the bus is already in use, but not by us */
+ if (!(base->C1 & I2C_C1_MST_MASK))
+ {
+ return kStatus_I2C_Busy;
+ }
+
+ /* Send STOP signal. */
+ if (handle->transfer.direction == kI2C_Read)
+ {
+ base->C1 |= I2C_C1_TXAK_MASK;
+
+#if I2C_WAIT_TIMEOUT
+ /* Wait until data transfer complete. */
+ while ((!(base->S & kI2C_IntPendingFlag)) && (--waitTimes))
+ {
+ }
+ if (waitTimes == 0)
+ {
+ return kStatus_I2C_Timeout;
+ }
+#else
+ /* Wait until data transfer complete. */
+ while (!(base->S & kI2C_IntPendingFlag))
+ {
+ }
+#endif
+ base->S = kI2C_IntPendingFlag;
+
+ base->C1 &= ~(I2C_C1_MST_MASK | I2C_C1_TX_MASK | I2C_C1_TXAK_MASK);
+ dummy = base->D;
+ }
+ else
+ {
+#if I2C_WAIT_TIMEOUT
+ /* Wait until data transfer complete. */
+ while ((!(base->S & kI2C_IntPendingFlag)) && (--waitTimes))
+ {
+ }
+ if (waitTimes == 0)
+ {
+ return kStatus_I2C_Timeout;
+ }
+#else
+ /* Wait until data transfer complete. */
+ while (!(base->S & kI2C_IntPendingFlag))
+ {
+ }
+#endif
+ base->S = kI2C_IntPendingFlag;
+ base->C1 &= ~(I2C_C1_MST_MASK | I2C_C1_TX_MASK | I2C_C1_TXAK_MASK);
+ }
+
+ return kStatus_Success;
+}
+
+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) ||
+ (result == kStatus_I2C_Addr_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, uint32_t srcClock_Hz)
+{
+ assert(slaveConfig);
+
+ uint8_t tmpReg;
+
+#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
+ CLOCK_EnableClock(s_i2cClocks[I2C_GetInstance(base)]);
+#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
+
+ /* Reset the module. */
+ base->A1 = 0;
+ base->F = 0;
+ base->C1 = 0;
+ base->S = 0xFFU;
+ base->C2 = 0;
+#if defined(FSL_FEATURE_I2C_HAS_START_STOP_DETECT) && FSL_FEATURE_I2C_HAS_START_STOP_DETECT
+ base->FLT = 0x50U;
+#elif defined(FSL_FEATURE_I2C_HAS_STOP_DETECT) && FSL_FEATURE_I2C_HAS_STOP_DETECT
+ base->FLT = 0x40U;
+#endif
+ base->RA = 0;
+
+ /* 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. */
+ tmpReg = base->C2;
+ tmpReg &= ~(I2C_C2_SBRC_MASK | I2C_C2_GCAEN_MASK);
+ tmpReg |= I2C_C2_SBRC(slaveConfig->enableBaudRateCtl) | I2C_C2_GCAEN(slaveConfig->enableGeneralCall);
+ 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
+
+ /* Set hold time. */
+ I2C_SetHoldTime(base, slaveConfig->sclStopHoldTime_ns, srcClock_Hz);
+}
+
+void I2C_SlaveDeinit(I2C_Type *base)
+{
+ /* Disable I2C module. */
+ I2C_Enable(base, false);
+
+#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
+ /* Disable I2C clock. */
+ CLOCK_DisableClock(s_i2cClocks[I2C_GetInstance(base)]);
+#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
+}
+
+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;
+
+ /* 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
+
+ /* Set default SCL stop hold time to 4us which is minimum requirement in I2C spec. */
+ slaveConfig->sclStopHoldTime_ns = 4000;
+
+ /* 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 */
+
+#if I2C_WAIT_TIMEOUT
+ uint32_t waitTimes = I2C_WAIT_TIMEOUT;
+ /* Wait until data transfer complete. */
+ while ((!(base->S & kI2C_AddressMatchFlag)) && (--waitTimes))
+ {
+ }
+ if (waitTimes == 0)
+ {
+ return kStatus_I2C_Timeout;
+ }
+#else
+ /* Wait for address match flag. */
+ while (!(base->S & kI2C_AddressMatchFlag))
+ {
+ }
+#endif
+ /* Read dummy to release bus. */
+ dummy = base->D;
+
+ result = I2C_MasterWriteBlocking(base, txBuff, txSize, kI2C_TransferDefaultFlag);
+
+ /* Switch to receive mode. */
+ base->C1 &= ~(I2C_C1_TX_MASK | I2C_C1_TXAK_MASK);
+
+ /* Read dummy to release bus. */
+ dummy = base->D;
+
+ return result;
+}
+
+status_t I2C_SlaveReadBlocking(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 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 */
+
+#if I2C_WAIT_TIMEOUT
+ uint32_t waitTimes = I2C_WAIT_TIMEOUT;
+ /* Wait for address match and int pending flag. */
+ while ((!(base->S & kI2C_AddressMatchFlag)) && (--waitTimes))
+ {
+ }
+ if (waitTimes == 0)
+ {
+ return kStatus_I2C_Timeout;
+ }
+
+ waitTimes = I2C_WAIT_TIMEOUT;
+ while ((!(base->S & kI2C_IntPendingFlag)) && (--waitTimes))
+ {
+ }
+ if (waitTimes == 0)
+ {
+ return kStatus_I2C_Timeout;
+ }
+#else
+ /* Wait for address match and int pending flag. */
+ while (!(base->S & kI2C_AddressMatchFlag))
+ {
+ }
+ while (!(base->S & kI2C_IntPendingFlag))
+ {
+ }
+#endif
+
+ /* 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--)
+ {
+#if I2C_WAIT_TIMEOUT
+ waitTimes = I2C_WAIT_TIMEOUT;
+ /* Wait until data transfer complete. */
+ while ((!(base->S & kI2C_IntPendingFlag)) && (--waitTimes))
+ {
+ }
+ if (waitTimes == 0)
+ {
+ return kStatus_I2C_Timeout;
+ }
+#else
+ /* Wait until data transfer complete. */
+ while (!(base->S & kI2C_IntPendingFlag))
+ {
+ }
+#endif
+ /* Clear the IICIF flag. */
+ base->S = kI2C_IntPendingFlag;
+
+ /* Read from the data register. */
+ *rxBuff++ = base->D;
+ }
+
+ return result;
+}
+
+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 | kI2C_SlaveGenaralcallEvent;
+
+ /* 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);
+ }
+ }
+
+ if (!(status & kI2C_AddressMatchFlag))
+ {
+ 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;
+
+ /* 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;
+
+ if (dummy == 0)
+ {
+ xfer->event = kI2C_SlaveGenaralcallEvent;
+ }
+ }
+
+ if ((handle->eventMask & xfer->event) && (handle->callback))
+ {
+ handle->callback(base, xfer, handle->userData);
+ }
+ }
+ /* 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 */
+ }
+ }
+}
+
+#if defined(I2C0)
+void I2C0_DriverIRQHandler(void)
+{
+ I2C_TransferCommonIRQHandler(I2C0, s_i2cHandle[0]);
+}
+#endif
+
+#if defined(I2C1)
+void I2C1_DriverIRQHandler(void)
+{
+ I2C_TransferCommonIRQHandler(I2C1, s_i2cHandle[1]);
+}
+#endif
+
+#if defined(I2C2)
+void I2C2_DriverIRQHandler(void)
+{
+ I2C_TransferCommonIRQHandler(I2C2, s_i2cHandle[2]);
+}
+#endif
+
+#if defined(I2C3)
+void I2C3_DriverIRQHandler(void)
+{
+ I2C_TransferCommonIRQHandler(I2C3, s_i2cHandle[3]);
+}
+#endif
diff --git a/drivers/fsl_i2c.h b/drivers/fsl_i2c.h
new file mode 100644
index 0000000..04e3e5e
--- /dev/null
+++ b/drivers/fsl_i2c.h
@@ -0,0 +1,821 @@
+/*
+ * The Clear BSD License
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * Copyright 2016-2017 NXP
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted (subject to the limitations in the disclaimer below) provided
+ * that the following conditions are met:
+ *
+ * o Redistributions of source code must retain the above copyright notice, this list
+ * of conditions and the following disclaimer.
+ *
+ * o Redistributions in binary form must reproduce the above copyright notice, this
+ * list of conditions and the following disclaimer in the documentation and/or
+ * other materials provided with the distribution.
+ *
+ * o Neither the name of the copyright holder nor the names of its
+ * contributors may be used to endorse or promote products derived from this
+ * software without specific prior written permission.
+ *
+ * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS LICENSE.
+ * 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.5. */
+#define FSL_I2C_DRIVER_VERSION (MAKE_VERSION(2, 0, 5))
+/*@}*/
+
+/*! @brief Timeout times for waiting flag. */
+#ifndef I2C_WAIT_TIMEOUT
+#define I2C_WAIT_TIMEOUT 0U /* Define to zero means keep waiting until the flag is assert/deassert. */
+#endif
+
+#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), /*!< Timeout poling status flags. */
+ kStatus_I2C_Addr_Nak = MAKE_STATUS(kStatusGroup_I2C, 5), /*!< NAK received during the address probe. */
+};
+
+/*!
+ * @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 The direction of master and slave transfers. */
+typedef enum _i2c_direction
+{
+ kI2C_Write = 0x0U, /*!< Master transmits to the slave. */
+ kI2C_Read = 0x1U, /*!< Master receives from the 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, /*!< A transfer starts with a start signal, stops with a stop signal. */
+ kI2C_TransferNoStartFlag = 0x1U, /*!< A transfer starts without a start signal, only support write only or
+ write+read with no start flag, do not support read only with no start flag. */
+ kI2C_TransferRepeatedStartFlag = 0x2U, /*!< A transfer starts with a repeated start signal. */
+ kI2C_TransferNoStopFlag = 0x4U, /*!< A 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() 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, /*!< A callback is requested to provide data to transmit
+ (slave-transmitter role). */
+ kI2C_SlaveReceiveEvent = 0x04U, /*!< A callback is requested to provide a buffer in which to place received
+ data (slave-receiver role). */
+ kI2C_SlaveTransmitAckEvent = 0x08U, /*!< A 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. */
+ kI2C_SlaveGenaralcallEvent = 0x40U, /*!< Received the general call address after a start or repeated start. */
+
+ /*! A 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 | kI2C_SlaveGenaralcallEvent,
+} 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_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; /*!< Enables the general call addressing mode. */
+ bool enableWakeUp; /*!< Enables/disables waking up MCU from low-power mode. */
+#if defined(FSL_FEATURE_I2C_HAS_DOUBLE_BUFFER_ENABLE) && FSL_FEATURE_I2C_HAS_DOUBLE_BUFFER_ENABLE
+ bool enableDoubleBuffering; /*!< Controls a 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; /*!< A slave address configuration. */
+ uint16_t upperAddress; /*!< A maximum boundary slave address used in a range matching mode. */
+ i2c_slave_address_mode_t
+ addressingMode; /*!< An addressing mode configuration of i2c_slave_address_mode_config_t. */
+ uint32_t sclStopHoldTime_ns; /*!< the delay from the rising edge of SCL (I2C clock) to the rising edge of SDA (I2C
+ data) while SCL is high (stop condition), SDA hold time and SCL start hold time
+ are also configured according to the SCL stop hold time. */
+} 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; /*!< A transfer flag which controls the transfer. */
+ uint8_t slaveAddress; /*!< 7-bit slave address. */
+ i2c_direction_t direction; /*!< A transfer direction, read or write. */
+ uint32_t subaddress; /*!< A sub address. Transferred MSB first. */
+ uint8_t subaddressSize; /*!< A size of the command buffer. */
+ uint8_t *volatile data; /*!< A transfer buffer. */
+ volatile size_t dataSize; /*!< A 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; /*!< A transfer state maintained during transfer. */
+ i2c_master_transfer_callback_t completionCallback; /*!< A callback function called when the transfer is finished. */
+ void *userData; /*!< A callback parameter passed to the callback function. */
+};
+
+/*! @brief I2C slave transfer structure. */
+typedef struct _i2c_slave_transfer
+{
+ i2c_slave_transfer_event_t event; /*!< A reason that the callback is invoked. */
+ uint8_t *volatile data; /*!< A transfer buffer. */
+ volatile size_t dataSize; /*!< A transfer size. */
+ status_t completionStatus; /*!< Success or error code describing how the transfer completed. Only applies for
+ #kI2C_SlaveCompletionEvent. */
+ size_t transferredCount; /*!< A number of bytes actually transferred since the start or since the 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
+{
+ volatile bool isBusy; /*!< Indicates whether a transfer is busy. */
+ i2c_slave_transfer_t transfer; /*!< I2C slave transfer copy. */
+ uint32_t eventMask; /*!< A mask of enabled events. */
+ i2c_slave_transfer_callback_t callback; /*!< A callback function called at the transfer event. */
+ void *userData; /*!< A callback parameter passed to the callback. */
+};
+
+/*******************************************************************************
+ * Variables
+ ******************************************************************************/
+/*! @brief Pointers to i2c bases for each instance. */
+extern I2C_Type *const s_i2cBases[];
+
+/*******************************************************************************
+ * 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.
+ * Otherwise, any operation to the I2C module can cause a hard fault
+ * because the clock is not enabled. The configuration structure can be custom filled
+ * or it can be set with default values by using the I2C_MasterGetDefaultConfig().
+ * After calling this API, the master is ready to transfer.
+ * This is an 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 A pointer to the 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 initialize the I2C with the slave configuration.
+ *
+ * @note This API should be called at the beginning of the application.
+ * Otherwise, 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 it can be custom filled by the user.
+ * This is an example.
+ * @code
+ * i2c_slave_config_t config = {
+ * .enableSlave = true,
+ * .enableGeneralCall = false,
+ * .addressingMode = kI2C_Address7bit,
+ * .slaveAddress = 0x1DU,
+ * .enableWakeUp = false,
+ * .enablehighDrive = false,
+ * .enableBaudRateCtl = false,
+ * .sclStopHoldTime_ns = 4000
+ * };
+ * I2C_SlaveInit(I2C0, &config, 12000000U);
+ * @endcode
+ *
+ * @param base I2C base pointer
+ * @param slaveConfig A pointer to the slave configuration structure
+ * @param srcClock_Hz I2C peripheral clock frequency in Hz
+ */
+void I2C_SlaveInit(I2C_Type *base, const i2c_slave_config_t *slaveConfig, uint32_t srcClock_Hz);
+
+/*!
+ * @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 Get instance number for I2C module.
+ *
+ * @param base I2C peripheral base address.
+ */
+uint32_t I2C_GetInstance(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 the I2C_MasterConfigure() or modify
+ * the structure before calling the I2C_MasterConfigure().
+ * This is an example.
+ * @code
+ * i2c_master_config_t config;
+ * I2C_MasterGetDefaultConfig(&config);
+ * @endcode
+ * @param masterConfig A 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 the I2C_SlaveConfigure().
+ * Modify fields of the structure before calling the I2C_SlaveConfigure().
+ * This is an example.
+ * @code
+ * i2c_slave_config_t config;
+ * I2C_SlaveGetDefaultConfig(&config);
+ * @endcode
+ * @param slaveConfig A 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 and false to disable the 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.
+ *
+ * @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.
+ * @param flags Transfer control flag to decide whether need to send a stop, use kI2C_TransferDefaultFlag
+* to issue a stop and kI2C_TransferNoStop to not send a stop.
+ * @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, uint32_t flags);
+
+/*!
+ * @brief Performs a polling receive transaction on the I2C bus.
+ *
+ * @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.
+ * @param flags Transfer control flag to decide whether need to send a stop, use kI2C_TransferDefaultFlag
+* to issue a stop and kI2C_TransferNoStop to not send a stop.
+ * @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, uint32_t flags);
+
+/*!
+ * @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.
+ * @retval kStatus_Success Successfully complete data receive.
+ * @retval kStatus_I2C_Timeout Wait status flag timeout.
+ */
+status_t 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
+ * @retval kStatus_I2C_Timeout Timeout during polling flag.
+ * @retval kStatus_Success Successfully abort the transfer.
+ */
+status_t 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..6671149
--- /dev/null
+++ b/drivers/fsl_i2c_edma.c
@@ -0,0 +1,570 @@
+/*
+ * The Clear BSD License
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * Copyright 2016-2017 NXP
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted (subject to the limitations in the disclaimer below) provided
+ * that the following conditions are met:
+ *
+ * o Redistributions of source code must retain the above copyright notice, this list
+ * of conditions and the following disclaimer.
+ *
+ * o Redistributions in binary form must reproduce the above copyright notice, this
+ * list of conditions and the following disclaimer in the documentation and/or
+ * other materials provided with the distribution.
+ *
+ * o Neither the name of the copyright holder nor the names of its
+ * contributors may be used to endorse or promote products derived from this
+ * software without specific prior written permission.
+ *
+ * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS LICENSE.
+ * 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
+ ******************************************************************************/
+
+/* Component ID definition, used by tools. */
+#ifndef FSL_COMPONENT_ID
+#define FSL_COMPONENT_ID "platform.drivers.i2c_edma"
+#endif
+
+
+/*<! @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);
+
+/*******************************************************************************
+ * 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);
+ }
+ }
+ else
+ {
+ 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))
+ {
+ }
+
+ /* Change direction to send. */
+ i2cPrivateHandle->base->C1 |= I2C_C1_TX_MASK;
+
+ /* Read the last data byte. */
+ *(i2cPrivateHandle->handle->transfer.data + i2cPrivateHandle->handle->transfer.dataSize - 1) =
+ i2cPrivateHandle->base->D;
+ }
+ }
+
+ 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;
+
+ 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;
+
+ /* 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);
+ }
+
+ if (result)
+ {
+ return result;
+ }
+
+ 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)
+ {
+ result = kStatus_I2C_Addr_Nak;
+
+ if (I2C_MasterStop(base) != kStatus_Success)
+ {
+ result = kStatus_I2C_Timeout;
+ }
+
+ if (handle->completionCallback)
+ {
+ (handle->completionCallback)(base, handle, result, handle->userData);
+ }
+ }
+
+ return result;
+ }
+
+ /* Send subaddress. */
+ if (handle->transfer.subaddressSize)
+ {
+ do
+ {
+ /* Clear interrupt pending flag. */
+ base->S = kI2C_IntPendingFlag;
+
+ handle->transfer.subaddressSize--;
+ base->D = ((handle->transfer.subaddress) >> (8 * handle->transfer.subaddressSize));
+
+ /* Wait until data transfer complete. */
+ while (!(base->S & kI2C_IntPendingFlag))
+ {
+ }
+
+ /* Check if there's transfer error. */
+ result = I2C_CheckAndClearError(base, base->S);
+
+ if (result)
+ {
+ return result;
+ }
+
+ } while (handle->transfer.subaddressSize > 0);
+
+ if (handle->transfer.direction == kI2C_Read)
+ {
+ /* 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))
+ {
+ }
+
+ /* Check if there's transfer error. */
+ result = I2C_CheckAndClearError(base, base->S);
+
+ if (result)
+ {
+ return result;
+ }
+ }
+ }
+
+ /* Clear pending flag. */
+ base->S = kI2C_IntPendingFlag;
+ }
+
+ 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);
+ transfer_config.majorLoopCounts = (handle->transfer.dataSize - 1);
+ 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;
+ }
+
+ /* Store the initially configured eDMA minor byte transfer count into the I2C handle */
+ handle->nbytes = transfer_config.minorLoopBytes;
+
+ 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 | I2C_C1_TXAK_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);
+ }
+ else
+ {
+ /* Change direction to send. */
+ base->C1 |= I2C_C1_TX_MASK;
+ }
+
+ /* 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 -
+ (uint32_t)handle->nbytes *
+ EDMA_GetRemainingMajorLoopCount(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..d1c5620
--- /dev/null
+++ b/drivers/fsl_i2c_edma.h
@@ -0,0 +1,141 @@
+/*
+ * The Clear BSD License
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * Copyright 2016-2017 NXP
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted (subject to the limitations in the disclaimer below) provided
+ * that the following conditions are met:
+ *
+ * o Redistributions of source code must retain the above copyright notice, this list
+ * of conditions and the following disclaimer.
+ *
+ * o Redistributions in binary form must reproduce the above copyright notice, this
+ * list of conditions and the following disclaimer in the documentation and/or
+ * other materials provided with the distribution.
+ *
+ * o Neither the name of the copyright holder nor the names of its
+ * contributors may be used to endorse or promote products derived from this
+ * software without specific prior written permission.
+ *
+ * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS LICENSE.
+ * 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_edma.h"
+
+/*!
+ * @addtogroup i2c_edma_driver
+ * @{
+ */
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+/*! @name Driver version */
+/*@{*/
+/*! @brief I2C EDMA driver version 2.0.5. */
+#define FSL_I2C_EDMA_DRIVER_VERSION (MAKE_VERSION(2, 0, 5))
+/*@}*/
+
+/*! @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 structure. */
+ size_t transferSize; /*!< Total bytes to be transferred. */
+ uint8_t nbytes; /*!< eDMA minor byte transfer count initially configured. */
+ uint8_t state; /*!< I2C master transfer status. */
+ edma_handle_t *dmaHandle; /*!< The eDMA handler used. */
+ i2c_master_edma_transfer_callback_t
+ completionCallback; /*!< A callback function called after the eDMA transfer is finished. */
+ void *userData; /*!< A callback parameter passed to the callback function. */
+};
+
+/*******************************************************************************
+ * API
+ ******************************************************************************/
+
+#if defined(__cplusplus)
+extern "C" {
+#endif /*_cplusplus. */
+
+/*!
+ * @name I2C Block eDMA Transfer Operation
+ * @{
+ */
+
+/*!
+ * @brief Initializes the I2C handle which is used in transcational functions.
+ *
+ * @param base I2C peripheral base address.
+ * @param handle A pointer to the i2c_master_edma_handle_t structure.
+ * @param callback A pointer to the user callback function.
+ * @param userData A user parameter 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 A pointer to the i2c_master_edma_handle_t structure.
+ * @param xfer A pointer to the transfer structure of i2c_master_transfer_t.
+ * @retval kStatus_Success Sucessfully completed the data transmission.
+ * @retval kStatus_I2C_Busy A previous transmission is still not finished.
+ * @retval kStatus_I2C_Timeout Transfer error, waits for a 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 Gets a master transfer status during the eDMA non-blocking transfer.
+ *
+ * @param base I2C peripheral base address.
+ * @param handle A pointer to the i2c_master_edma_handle_t structure.
+ * @param count A number of bytes transferred by the non-blocking transaction.
+ */
+status_t I2C_MasterTransferGetCountEDMA(I2C_Type *base, i2c_master_edma_handle_t *handle, size_t *count);
+
+/*!
+ * @brief Aborts a master eDMA non-blocking transfer early.
+ *
+ * @param base I2C peripheral base address.
+ * @param handle A pointer to the 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_pit.c b/drivers/fsl_pit.c
new file mode 100644
index 0000000..e6ff9c8
--- /dev/null
+++ b/drivers/fsl_pit.c
@@ -0,0 +1,138 @@
+/*
+ * The Clear BSD License
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * Copyright 2016-2017 NXP
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted (subject to the limitations in the disclaimer below) provided
+ * that the following conditions are met:
+ *
+ * o Redistributions of source code must retain the above copyright notice, this list
+ * of conditions and the following disclaimer.
+ *
+ * o Redistributions in binary form must reproduce the above copyright notice, this
+ * list of conditions and the following disclaimer in the documentation and/or
+ * other materials provided with the distribution.
+ *
+ * o Neither the name of the copyright holder nor the names of its
+ * contributors may be used to endorse or promote products derived from this
+ * software without specific prior written permission.
+ *
+ * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS LICENSE.
+ * 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"
+
+/* Component ID definition, used by tools. */
+#ifndef FSL_COMPONENT_ID
+#define FSL_COMPONENT_ID "platform.drivers.pit"
+#endif
+
+
+/*******************************************************************************
+ * 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;
+
+#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
+/*! @brief Pointers to PIT clocks for each instance. */
+static const clock_ip_name_t s_pitClocks[] = PIT_CLOCKS;
+#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
+
+/*******************************************************************************
+ * Code
+ ******************************************************************************/
+static uint32_t PIT_GetInstance(PIT_Type *base)
+{
+ uint32_t instance;
+
+ /* Find the instance index from base address mappings. */
+ for (instance = 0; instance < ARRAY_SIZE(s_pitBases); instance++)
+ {
+ if (s_pitBases[instance] == base)
+ {
+ break;
+ }
+ }
+
+ assert(instance < ARRAY_SIZE(s_pitBases));
+
+ return instance;
+}
+
+void PIT_Init(PIT_Type *base, const pit_config_t *config)
+{
+ assert(config);
+
+#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
+ /* Ungate the PIT clock*/
+ CLOCK_EnableClock(s_pitClocks[PIT_GetInstance(base)]);
+#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
+
+#if defined(FSL_FEATURE_PIT_HAS_MDIS) && FSL_FEATURE_PIT_HAS_MDIS
+ /* Enable PIT timers */
+ base->MCR &= ~PIT_MCR_MDIS_MASK;
+#endif
+ /* 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)
+{
+#if defined(FSL_FEATURE_PIT_HAS_MDIS) && FSL_FEATURE_PIT_HAS_MDIS
+ /* Disable PIT timers */
+ base->MCR |= PIT_MCR_MDIS_MASK;
+#endif
+
+#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
+ /* Gate the PIT clock*/
+ CLOCK_DisableClock(s_pitClocks[PIT_GetInstance(base)]);
+#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
+}
+
+#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..55abdd5
--- /dev/null
+++ b/drivers/fsl_pit.h
@@ -0,0 +1,358 @@
+/*
+ * The Clear BSD License
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * Copyright 2016-2017 NXP
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted (subject to the limitations in the disclaimer below) provided
+ * that the following conditions are met:
+ *
+ * o Redistributions of source code must retain the above copyright notice, this list
+ * of conditions and the following disclaimer.
+ *
+ * o Redistributions in binary form must reproduce the above copyright notice, this
+ * list of conditions and the following disclaimer in the documentation and/or
+ * other materials provided with the distribution.
+ *
+ * o Neither the name of the copyright holder nor the names of its
+ * contributors may be used to endorse or promote products derived from this
+ * software without specific prior written permission.
+ *
+ * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS LICENSE.
+ * 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 configuration 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 configuration structure can be made constant 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 operations.
+ *
+ * @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 the user's PIT config structure
+ */
+void PIT_Init(PIT_Type *base, const pit_config_t *config);
+
+/*!
+ * @brief Gates the PIT clock and disables the PIT module.
+ *
+ * @param base PIT peripheral base address
+ */
+void PIT_Deinit(PIT_Type *base);
+
+/*!
+ * @brief Fills in the PIT configuration structure with the default settings.
+ *
+ * The default values are as follows.
+ * @code
+ * config->enableRunInDebug = false;
+ * @endcode
+ * @param config Pointer to the onfiguration 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, which allows the developers
+ * to chain timers together and form a longer timer (64-bits and larger). The first timer
+ * (timer 0) can't 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 Users 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 Users 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_port.h b/drivers/fsl_port.h
new file mode 100644
index 0000000..655e524
--- /dev/null
+++ b/drivers/fsl_port.h
@@ -0,0 +1,497 @@
+/*
+ * The Clear BSD License
+ * Copyright (c) 2015, Freescale Semiconductor, Inc.
+ * Copyright 2016-2017 NXP
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted (subject to the limitations in the disclaimer below) provided
+ * that the following conditions are met:
+ *
+ * o Redistributions of source code must retain the above copyright notice, this list
+ * of conditions and the following disclaimer.
+ *
+ * o Redistributions in binary form must reproduce the above copyright notice, this
+ * list of conditions and the following disclaimer in the documentation and/or
+ * other materials provided with the distribution.
+ *
+ * o Neither the name of the copyright holder nor the names of its
+ * contributors may be used to endorse or promote products derived from this
+ * software without specific prior written permission.
+ *
+ * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS LICENSE.
+ * 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_PORT_H_
+#define _FSL_PORT_H_
+
+#include "fsl_common.h"
+
+/*!
+ * @addtogroup port
+ * @{
+ */
+
+/*******************************************************************************
+ * Definitions
+ ******************************************************************************/
+
+/* Component ID definition, used by tools. */
+#ifndef FSL_COMPONENT_ID
+#define FSL_COMPONENT_ID "platform.drivers.port"
+#endif
+
+
+/*! @name Driver version */
+/*@{*/
+/*! Version 2.0.2. */
+#define FSL_PORT_DRIVER_VERSION (MAKE_VERSION(2, 0, 2))
+/*@}*/
+
+#if defined(FSL_FEATURE_PORT_HAS_PULL_ENABLE) && FSL_FEATURE_PORT_HAS_PULL_ENABLE
+/*! @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. */
+};
+#endif /* FSL_FEATURE_PORT_HAS_PULL_ENABLE */
+
+#if defined(FSL_FEATURE_PORT_HAS_SLEW_RATE) && FSL_FEATURE_PORT_HAS_SLEW_RATE
+/*! @brief Slew rate selection */
+enum _port_slew_rate
+{
+ kPORT_FastSlewRate = 0U, /*!< Fast slew rate is configured. */
+ kPORT_SlowSlewRate = 1U, /*!< Slow slew rate is configured. */
+};
+#endif /* FSL_FEATURE_PORT_HAS_SLEW_RATE */
+
+#if defined(FSL_FEATURE_PORT_HAS_OPEN_DRAIN) && FSL_FEATURE_PORT_HAS_OPEN_DRAIN
+/*! @brief Open Drain feature enable/disable */
+enum _port_open_drain_enable
+{
+ kPORT_OpenDrainDisable = 0U, /*!< Open drain output is disabled. */
+ kPORT_OpenDrainEnable = 1U, /*!< Open drain output is enabled. */
+};
+#endif /* FSL_FEATURE_PORT_HAS_OPEN_DRAIN */
+
+#if defined(FSL_FEATURE_PORT_HAS_PASSIVE_FILTER) && FSL_FEATURE_PORT_HAS_PASSIVE_FILTER
+/*! @brief Passive filter feature enable/disable */
+enum _port_passive_filter_enable
+{
+ kPORT_PassiveFilterDisable = 0U, /*!< Passive input filter is disabled. */
+ kPORT_PassiveFilterEnable = 1U, /*!< Passive input filter is enabled. */
+};
+#endif
+
+#if defined(FSL_FEATURE_PORT_HAS_DRIVE_STRENGTH) && FSL_FEATURE_PORT_HAS_DRIVE_STRENGTH
+/*! @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. */
+};
+#endif /* FSL_FEATURE_PORT_HAS_DRIVE_STRENGTH */
+
+#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 */
+
+#if defined(FSL_FEATURE_PORT_PCR_MUX_WIDTH) && FSL_FEATURE_PORT_PCR_MUX_WIDTH
+/*! @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 */
+ kPORT_MuxAlt8 = 8U, /*!< Chip-specific */
+ kPORT_MuxAlt9 = 9U, /*!< Chip-specific */
+ kPORT_MuxAlt10 = 10U, /*!< Chip-specific */
+ kPORT_MuxAlt11 = 11U, /*!< Chip-specific */
+ kPORT_MuxAlt12 = 12U, /*!< Chip-specific */
+ kPORT_MuxAlt13 = 13U, /*!< Chip-specific */
+ kPORT_MuxAlt14 = 14U, /*!< Chip-specific */
+ kPORT_MuxAlt15 = 15U, /*!< Chip-specific */
+} port_mux_t;
+#endif /* FSL_FEATURE_PORT_PCR_MUX_WIDTH */
+
+/*! @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 */
+
+#if defined(FSL_FEATURE_PORT_PCR_MUX_WIDTH) && FSL_FEATURE_PORT_PCR_MUX_WIDTH
+/*! @brief PORT pin configuration structure */
+typedef struct _port_pin_config
+{
+#if defined(FSL_FEATURE_PORT_HAS_PULL_ENABLE) && FSL_FEATURE_PORT_HAS_PULL_ENABLE
+ uint16_t pullSelect : 2; /*!< No-pull/pull-down/pull-up select */
+#else
+ uint16_t : 2;
+#endif /* FSL_FEATURE_PORT_HAS_PULL_ENABLE */
+
+#if defined(FSL_FEATURE_PORT_HAS_SLEW_RATE) && FSL_FEATURE_PORT_HAS_SLEW_RATE
+ uint16_t slewRate : 1; /*!< Fast/slow slew rate Configure */
+#else
+ uint16_t : 1;
+#endif /* FSL_FEATURE_PORT_HAS_SLEW_RATE */
+
+ uint16_t : 1;
+
+#if defined(FSL_FEATURE_PORT_HAS_PASSIVE_FILTER) && FSL_FEATURE_PORT_HAS_PASSIVE_FILTER
+ uint16_t passiveFilterEnable : 1; /*!< Passive filter enable/disable */
+#else
+ uint16_t : 1;
+#endif /* FSL_FEATURE_PORT_HAS_PASSIVE_FILTER */
+
+#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 */
+
+#if defined(FSL_FEATURE_PORT_HAS_DRIVE_STRENGTH) && FSL_FEATURE_PORT_HAS_DRIVE_STRENGTH
+ uint16_t driveStrength : 1; /*!< Fast/slow drive strength configure */
+#else
+ uint16_t : 1;
+#endif
+
+ uint16_t : 1;
+
+#if defined(FSL_FEATURE_PORT_PCR_MUX_WIDTH) && (FSL_FEATURE_PORT_PCR_MUX_WIDTH == 3)
+ uint16_t mux : 3; /*!< Pin mux Configure */
+ uint16_t : 4;
+#elif defined(FSL_FEATURE_PORT_PCR_MUX_WIDTH) && (FSL_FEATURE_PORT_PCR_MUX_WIDTH == 4)
+ uint16_t mux : 4; /*!< Pin mux Configure */
+ uint16_t : 3;
+#else
+ uint16_t : 7,
+#endif
+
+#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;
+#endif /* FSL_FEATURE_PORT_PCR_MUX_WIDTH */
+
+/*******************************************************************************
+* API
+******************************************************************************/
+
+#if defined(__cplusplus)
+extern "C" {
+#endif
+
+#if defined(FSL_FEATURE_PORT_PCR_MUX_WIDTH) && FSL_FEATURE_PORT_PCR_MUX_WIDTH
+/*! @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;
+ }
+}
+
+#if defined(FSL_FEATURE_PORT_HAS_MULTIPLE_IRQ_CONFIG) && FSL_FEATURE_PORT_HAS_MULTIPLE_IRQ_CONFIG
+/*!
+ * @brief Sets the port interrupt configuration in PCR register for multiple pins.
+ *
+ * @param base PORT peripheral base pointer.
+ * @param mask PORT pin number macro.
+ * @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_SetMultipleInterruptPinsConfig(PORT_Type *base, uint32_t mask, port_interrupt_t config)
+{
+ assert(config);
+
+ if (mask & 0xffffU)
+ {
+ base->GICLR = (config << 16) | (mask & 0xffffU);
+ }
+ mask = mask >> 16;
+ if (mask)
+ {
+ base->GICHR = (config << 16) | (mask & 0xffffU);
+ }
+}
+#endif
+
+/*!
+ * @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);
+}
+#endif /* FSL_FEATURE_PORT_PCR_MUX_WIDTH */
+
+#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);
+}
+
+#if defined(FSL_FEATURE_PORT_HAS_DRIVE_STRENGTH) && FSL_FEATURE_PORT_HAS_DRIVE_STRENGTH
+/*!
+ * @brief Configures the port pin drive strength.
+ *
+ * @param base PORT peripheral base pointer.
+ * @param pin PORT pin number.
+ * @param config PORT pin drive strength
+ * - #kPORT_LowDriveStrength = 0U - Low-drive strength is configured.
+ * - #kPORT_HighDriveStrength = 1U - High-drive strength is configured.
+ */
+static inline void PORT_SetPinDriveStrength(PORT_Type* base, uint32_t pin, uint8_t strength)
+{
+ base->PCR[pin] = (base->PCR[pin] & ~PORT_PCR_DSE_MASK) | PORT_PCR_DSE(strength);
+}
+#endif
+
+/*!
+ * @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 16 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_uart.c b/drivers/fsl_uart.c
new file mode 100644
index 0000000..c7a9f80
--- /dev/null
+++ b/drivers/fsl_uart.c
@@ -0,0 +1,1356 @@
+/*
+ * The Clear BSD License
+ * Copyright (c) 2015-2016, Freescale Semiconductor, Inc.
+ * Copyright 2016-2017 NXP
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted (subject to the limitations in the disclaimer below) provided
+ * that the following conditions are met:
+ *
+ * o Redistributions of source code must retain the above copyright notice, this list
+ * of conditions and the following disclaimer.
+ *
+ * o Redistributions in binary form must reproduce the above copyright notice, this
+ * list of conditions and the following disclaimer in the documentation and/or
+ * other materials provided with the distribution.
+ *
+ * o Neither the name of the copyright holder nor the names of its
+ * contributors may be used to endorse or promote products derived from this
+ * software without specific prior written permission.
+ *
+ * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS LICENSE.
+ * 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
+ ******************************************************************************/
+
+/* Component ID definition, used by tools. */
+#ifndef FSL_COMPONENT_ID
+#define FSL_COMPONENT_ID "platform.drivers.uart"
+#endif
+
+/* UART transfer state. */
+enum _uart_tansfer_states
+{
+ kUART_TxIdle, /* TX idle. */
+ kUART_TxBusy, /* TX busy. */
+ kUART_RxIdle, /* RX idle. */
+ kUART_RxBusy, /* RX busy. */
+ kUART_RxFramingError, /* Rx framing error */
+ kUART_RxParityError /* Rx parity error */
+};
+
+/* Typedef for interrupt handler. */
+typedef void (*uart_isr_t)(UART_Type *base, uart_handle_t *handle);
+
+/*******************************************************************************
+ * Prototypes
+ ******************************************************************************/
+/*!
+ * @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;
+#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
+/* Array of UART clock name. */
+static const clock_ip_name_t s_uartClock[] = UART_CLOCKS;
+#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
+
+/* 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;
+}
+
+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. */
+ uint32_t tempBaud = 0;
+
+ uint16_t brfa = (2 * srcClock_Hz / (config->baudRate_Bps)) - 32 * sbr;
+
+ /* Calculate the baud rate based on the temporary SBR values and BRFA */
+ tempBaud = (srcClock_Hz * 2 / ((sbr * 32 + brfa)));
+ baudDiff =
+ (tempBaud > config->baudRate_Bps) ? (tempBaud - config->baudRate_Bps) : (config->baudRate_Bps - tempBaud);
+
+#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;
+ }
+
+#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
+ /* Enable uart clock */
+ CLOCK_EnableClock(s_uartClock[UART_GetInstance(base)]);
+#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
+
+ /* 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/parity mode/idle type. */
+ temp = base->C1 & ~(UART_C1_PE_MASK | UART_C1_PT_MASK | UART_C1_M_MASK | UART_C1_ILT_MASK);
+
+ temp |= UART_C1_ILT(config->idleType);
+
+ 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
+ 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->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
+#if defined(FSL_FEATURE_UART_HAS_MODEM_SUPPORT) && FSL_FEATURE_UART_HAS_MODEM_SUPPORT
+ if (config->enableRxRTS)
+ {
+ /* Enable receiver RTS(request-to-send) function. */
+ base->MODEM |= UART_MODEM_RXRTSE_MASK;
+ }
+ if (config->enableTxCTS)
+ {
+ /* Enable transmiter CTS(clear-to-send) function. */
+ base->MODEM |= UART_MODEM_TXCTSE_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;
+
+#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
+ /* Disable uart clock */
+ CLOCK_DisableClock(s_uartClock[UART_GetInstance(base)]);
+#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
+}
+
+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
+#if defined(FSL_FEATURE_UART_HAS_MODEM_SUPPORT) && FSL_FEATURE_UART_HAS_MODEM_SUPPORT
+ config->enableRxRTS = false;
+ config->enableTxCTS = false;
+#endif
+ config->idleType = kUART_IdleTypeStartBit;
+ 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. */
+ uint32_t tempBaud = 0;
+
+ uint16_t brfa = (2 * srcClock_Hz / (baudRate_Bps)) - 32 * sbr;
+
+ /* Calculate the baud rate based on the temporary SBR values and BRFA */
+ tempBaud = (srcClock_Hz * 2 / ((sbr * 32 + brfa)));
+ baudDiff = (tempBaud > baudRate_Bps) ? (tempBaud - baudRate_Bps) : (baudRate_Bps - tempBaud);
+#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;
+
+ /* 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 | kUART_FramingErrorInterruptEnable);
+ /* Enable parity error interrupt when parity mode is enable*/
+ if (UART_C1_PE_MASK & base->C1)
+ {
+ UART_EnableInterrupts(base, kUART_ParityErrorInterruptEnable);
+ }
+}
+
+void UART_TransferStopRingBuffer(UART_Type *base, uart_handle_t *handle)
+{
+ assert(handle);
+
+ if (handle->rxState == kUART_RxIdle)
+ {
+ UART_DisableInterrupts(base, kUART_RxDataRegFullInterruptEnable | kUART_RxOverrunInterruptEnable |
+ kUART_FramingErrorInterruptEnable);
+ /* Disable parity error interrupt when parity mode is enable*/
+ if (UART_C1_PE_MASK & base->C1)
+ {
+ UART_DisableInterrupts(base, kUART_ParityErrorInterruptEnable);
+ }
+ }
+
+ 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;
+
+ /* 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 UART RX IRQ, protect ring buffer. */
+ UART_DisableInterrupts(base, kUART_RxDataRegFullInterruptEnable);
+
+ /* 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 UART RX IRQ if previously enabled. */
+ UART_EnableInterrupts(base, kUART_RxDataRegFullInterruptEnable);
+
+ /* 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/Rx overrun/framing error/idle line interrupt. */
+ UART_EnableInterrupts(base, kUART_RxDataRegFullInterruptEnable | kUART_RxOverrunInterruptEnable |
+ kUART_FramingErrorInterruptEnable | kUART_IdleLineInterruptEnable);
+ /* Enable parity error interrupt when parity mode is enable*/
+ if (UART_C1_PE_MASK & base->C1)
+ {
+ UART_EnableInterrupts(base, kUART_ParityErrorInterruptEnable);
+ }
+ }
+
+ /* 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 |
+ kUART_FramingErrorInterruptEnable | kUART_IdleLineInterruptEnable);
+ /* Disable parity error interrupt when parity mode is enable*/
+ if (UART_C1_PE_MASK & base->C1)
+ {
+ UART_DisableInterrupts(base, kUART_ParityErrorInterruptEnable);
+ }
+ }
+
+ 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 framing error */
+ if (UART_S1_FE_MASK & base->S1)
+ {
+ /* Read base->D to clear framing error flag, otherwise the RX does not work. */
+ while (base->S1 & UART_S1_RDRF_MASK)
+ {
+ (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
+
+ handle->rxState = kUART_RxFramingError;
+ handle->rxDataSize = 0U;
+ /* Trigger callback. */
+ if (handle->callback)
+ {
+ handle->callback(base, handle, kStatus_UART_FramingError, handle->userData);
+ }
+ }
+
+ /* If RX parity error */
+ if (UART_S1_PF_MASK & base->S1)
+ {
+ /* Read base->D to clear parity error flag, otherwise the RX does not work. */
+ while (base->S1 & UART_S1_RDRF_MASK)
+ {
+ (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
+
+ handle->rxState = kUART_RxParityError;
+ handle->rxDataSize = 0U;
+ /* Trigger callback. */
+ if (handle->callback)
+ {
+ handle->callback(base, handle, kStatus_UART_ParityError, handle->userData);
+ }
+ }
+
+ /* If RX overrun. */
+ if (UART_S1_OR_MASK & base->S1)
+ {
+ /* Read base->D to clear overrun flag, otherwise the RX does not work. */
+ while (base->S1 & UART_S1_RDRF_MASK)
+ {
+ (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);
+ }
+ }
+
+ /* If IDLE line was detected. */
+ if ((UART_S1_IDLE_MASK & base->S1) && (UART_C2_ILIE_MASK & base->C2))
+ {
+#if defined(FSL_FEATURE_UART_HAS_FIFO) && FSL_FEATURE_UART_HAS_FIFO
+ /* If still some data in the FIFO, read out these data to user data buffer. */
+ count = base->RCFIFO;
+ /* If handle->rxDataSize is not 0, first save data to handle->rxData. */
+ while ((count) && (handle->rxDataSize))
+ {
+ tempCount = MIN(handle->rxDataSize, count);
+
+ /* 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;
+
+ /* Disable RX interrupt/overrun interrupt/fram error/idle line detected interrupt */
+ UART_DisableInterrupts(base, kUART_RxDataRegFullInterruptEnable | kUART_RxOverrunInterruptEnable |
+ kUART_FramingErrorInterruptEnable);
+
+ /* Disable parity error interrupt when parity mode is enable*/
+ if (UART_C1_PE_MASK & base->C1)
+ {
+ UART_DisableInterrupts(base, kUART_ParityErrorInterruptEnable);
+ }
+
+ if (handle->callback)
+ {
+ handle->callback(base, handle, kStatus_UART_RxIdle, handle->userData);
+ }
+ }
+ }
+#endif
+ /* To clear IDLE, read UART status S1 with IDLE set and then read D.*/
+ while (UART_S1_IDLE_MASK & 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 rxDataSize is 0, disable idle line interrupt.*/
+ if (!(handle->rxDataSize))
+ {
+ UART_DisableInterrupts(base, kUART_IdleLineInterruptEnable);
+ }
+ /* If callback is not NULL and rxDataSize is not 0. */
+ if ((handle->callback) && (handle->rxDataSize))
+ {
+ handle->callback(base, handle, kStatus_UART_IdleLineDetected, 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++;
+ }
+ }
+ }
+
+ else if (!handle->rxDataSize)
+ {
+ /* Disable RX interrupt/overrun interrupt/fram error/idle line detected interrupt */
+ UART_DisableInterrupts(base, kUART_RxDataRegFullInterruptEnable | kUART_RxOverrunInterruptEnable |
+ kUART_FramingErrorInterruptEnable);
+
+ /* Disable parity error interrupt when parity mode is enable*/
+ if (UART_C1_PE_MASK & base->C1)
+ {
+ UART_DisableInterrupts(base, kUART_ParityErrorInterruptEnable);
+ }
+ }
+ else
+ {
+ }
+ }
+
+ /* If framing error or parity error happened, stop the RX interrupt when ues no ring buffer */
+ if (((handle->rxState == kUART_RxFramingError) || (handle->rxState == kUART_RxParityError)) &&
+ (!handle->rxRingBuffer))
+ {
+ UART_DisableInterrupts(base, kUART_RxDataRegFullInterruptEnable | kUART_RxOverrunInterruptEnable |
+ kUART_FramingErrorInterruptEnable | kUART_IdleLineInterruptEnable);
+
+ /* Disable parity error interrupt when parity mode is enable*/
+ if (UART_C1_PE_MASK & base->C1)
+ {
+ UART_DisableInterrupts(base, kUART_ParityErrorInterruptEnable);
+ }
+ }
+
+ /* 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]);
+/* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void UART0_RX_TX_DriverIRQHandler(void)
+{
+ UART0_DriverIRQHandler();
+/* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+#endif
+#endif
+
+#if defined(UART1)
+void UART1_DriverIRQHandler(void)
+{
+ s_uartIsr(UART1, s_uartHandle[1]);
+/* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void UART1_RX_TX_DriverIRQHandler(void)
+{
+ UART1_DriverIRQHandler();
+/* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+#endif
+
+#if defined(UART2)
+void UART2_DriverIRQHandler(void)
+{
+ s_uartIsr(UART2, s_uartHandle[2]);
+/* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void UART2_RX_TX_DriverIRQHandler(void)
+{
+ UART2_DriverIRQHandler();
+/* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+#endif
+
+#if defined(UART3)
+void UART3_DriverIRQHandler(void)
+{
+ s_uartIsr(UART3, s_uartHandle[3]);
+/* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void UART3_RX_TX_DriverIRQHandler(void)
+{
+ UART3_DriverIRQHandler();
+/* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+#endif
+
+#if defined(UART4)
+void UART4_DriverIRQHandler(void)
+{
+ s_uartIsr(UART4, s_uartHandle[4]);
+/* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void UART4_RX_TX_DriverIRQHandler(void)
+{
+ UART4_DriverIRQHandler();
+/* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+#endif
+
+#if defined(UART5)
+void UART5_DriverIRQHandler(void)
+{
+ s_uartIsr(UART5, s_uartHandle[5]);
+/* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+
+void UART5_RX_TX_DriverIRQHandler(void)
+{
+ UART5_DriverIRQHandler();
+/* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
+ exception return operation might vector to incorrect interrupt */
+#if defined __CORTEX_M && (__CORTEX_M == 4U)
+ __DSB();
+#endif
+}
+#endif
diff --git a/drivers/fsl_uart.h b/drivers/fsl_uart.h
new file mode 100644
index 0000000..3abffbd
--- /dev/null
+++ b/drivers/fsl_uart.h
@@ -0,0 +1,808 @@
+/*
+ * The Clear BSD License
+ * Copyright (c) 2015-2016, Freescale Semiconductor, Inc.
+ * Copyright 2016-2017 NXP
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted (subject to the limitations in the disclaimer below) provided
+ * that the following conditions are met:
+ *
+ * o Redistributions of source code must retain the above copyright notice, this list
+ * of conditions and the following disclaimer.
+ *
+ * o Redistributions in binary form must reproduce the above copyright notice, this
+ * list of conditions and the following disclaimer in the documentation and/or
+ * other materials provided with the distribution.
+ *
+ * o Neither the name of the copyright holder nor the names of its
+ * contributors may be used to endorse or promote products derived from this
+ * software without specific prior written permission.
+ *
+ * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS LICENSE.
+ * 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.5. */
+#define FSL_UART_DRIVER_VERSION (MAKE_VERSION(2, 1, 5))
+/*@}*/
+
+/*! @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 */
+ kStatus_UART_IdleLineDetected = MAKE_STATUS(kStatusGroup_UART, 14), /*!< UART IDLE line detected. */
+};
+
+/*! @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 idle type select. */
+typedef enum _uart_idle_type_select
+{
+ kUART_IdleTypeStartBit = 0U, /*!< Start counting after a valid start bit. */
+ kUART_IdleTypeStopBit = 1U, /*!< Start conuting after a stop bit. */
+} uart_idle_type_select_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
+#if defined(FSL_FEATURE_UART_HAS_MODEM_SUPPORT) && FSL_FEATURE_UART_HAS_MODEM_SUPPORT
+ bool enableRxRTS; /*!< RX RTS enable */
+ bool enableTxCTS; /*!< TX CTS enable */
+#endif
+ uart_idle_type_select_t idleType; /*!< IDLE type select. */
+ 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 */
+
+/*!
+ * @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);
+
+/*!
+ * @name Initialization and deinitialization
+ * @{
+ */
+
+/*!
+ * @brief Initializes a UART instance with a 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.
+ * The 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 the 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 as follows.
+ * uartConfig->baudRate_Bps = 115200U;
+ * uartConfig->bitCountPerChar = kUART_8BitsPerChar;
+ * uartConfig->parityMode = kUART_ParityDisabled;
+ * uartConfig->stopBitCount = kUART_OneStopBit;
+ * uartConfig->txFifoWatermark = 0;
+ * uartConfig->rxFifoWatermark = 1;
+ * uartConfig->idleType = kUART_IdleTypeStartBit;
+ * 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 the current clock source.
+ * @retval kStatus_Success Set baudrate succeeded.
+ */
+status_t UART_SetBaudRate(UART_Type *base, uint32_t baudRate_Bps, uint32_t srcClock_Hz);
+
+/* @} */
+
+/*!
+ * @name Status
+ * @{
+ */
+
+/*!
+ * @brief Gets UART status flags.
+ *
+ * This function gets 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, do the following.
+ * @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. An automatically cleared flag
+ * can't be cleared by this function.
+ * These flags can only be cleared or set by hardware.
+ * kUART_TxDataRegEmptyFlag, kUART_TransmissionCompleteFlag, kUART_RxDataRegFullFlag,
+ * kUART_RxActiveFlag, kUART_NoiseErrorInRxDataRegFlag, kUART_ParityErrorInRxDataRegFlag,
+ * kUART_TxFifoEmptyFlag,kUART_RxFifoEmptyFlag
+ * Note that this API should be called when the Tx/Rx is idle. Otherwise it has no effect.
+ *
+ * @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 is 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, do the following.
+ * @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 do the following.
+ * @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, do the following.
+ * @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 addresses which are used both by the transmitter and the 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 RX 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 data is 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 reads 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 occurred while receiving data.
+ * @retval kStatus_UART_NoiseError A noise error occurred while receiving data.
+ * @retval kStatus_UART_FramingError A framing error occurred while receiving data.
+ * @retval kStatus_UART_ParityError A parity error occurred 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 data is already 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, 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 Get the length of received data in RX ring buffer.
+ *
+ * @param handle UART handle pointer.
+ * @return Length of received data in RX ring buffer.
+ */
+size_t UART_TransferGetRxRingBufferLength(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 is 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 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 Gets the number of bytes written to the UART TX register.
+ *
+ * This function gets the number of bytes written to the UART TX
+ * register by using the 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 The 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 are 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 Gets 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 handles 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_ */