LPC546XX: Update SDK driver to version 2.3

Signed-off-by: Mahesh Mahadevan <mahesh.mahadevan@nxp.com>
pull/6189/head
Mahesh Mahadevan 2018-02-22 13:34:34 -06:00
parent 107976773c
commit eff848abea
88 changed files with 2917 additions and 840 deletions

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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
@ -46,8 +50,8 @@
/*! @name Driver version */
/*@{*/
/*! @brief ADC driver version 2.0.0. */
#define LPC_ADC_DRIVER_VERSION (MAKE_VERSION(2, 0, 0))
/*! @brief ADC driver version 2.1.0. */
#define LPC_ADC_DRIVER_VERSION (MAKE_VERSION(2, 1, 0))
/*@}*/
/*!
@ -150,7 +154,7 @@ typedef enum _adc_trigger_polarity
typedef enum _adc_priority
{
kADC_PriorityLow = 0U, /*!< This sequence would be preempted when another sequence is started. */
kADC_PriorityHigh = 1U, /*!< This sequence would preempt other sequence even when is is started. */
kADC_PriorityHigh = 1U, /*!< This sequence would preempt other sequence even when it is started. */
} adc_priority_t;
/*!
@ -247,7 +251,7 @@ typedef struct _adc_conv_seq_config
*/
typedef struct _adc_result_info
{
uint32_t result; /*!< Keey the conversion data value. */
uint32_t result; /*!< Keep the conversion data value. */
adc_threshold_compare_status_t thresholdCompareStatus; /*!< Keep the threshold compare status. */
adc_threshold_crossing_status_t thresholdCorssingStatus; /*!< Keep the threshold crossing status. */
uint32_t channelNumber; /*!< Keep the channel number for this conversion. */
@ -307,6 +311,7 @@ void ADC_GetDefaultConfig(adc_config_t *config);
*/
bool ADC_DoSelfCalibration(ADC_Type *base);
#if !(defined(FSL_FEATURE_ADC_HAS_NO_INSEL) && FSL_FEATURE_ADC_HAS_NO_INSEL)
/*!
* @brief Enable the internal temperature sensor measurement.
*
@ -327,7 +332,7 @@ static inline void ADC_EnableTemperatureSensor(ADC_Type *base, bool enable)
base->INSEL = (base->INSEL & ~ADC_INSEL_SEL_MASK) | ADC_INSEL_SEL(0);
}
}
#endif /* FSL_FEATURE_ADC_HAS_NO_INSEL. */
/* @} */
/*!
@ -611,13 +616,24 @@ static inline void ADC_DisableInterrupts(ADC_Type *base, uint32_t mask)
}
/*!
* @brief Enable the interrupt of shreshold compare event for each channel.
* @brief Enable the interrupt of threshold compare event for each channel.
* @deprecated Do not use this function. It has been superceded by @ADC_EnableThresholdCompareInterrupt
*/
static inline void ADC_EnableShresholdCompareInterrupt(ADC_Type *base,
uint32_t channel,
adc_threshold_interrupt_mode_t mode)
{
base->INTEN = (base->INTEN & ~(0x3U << ((channel << 1U) + 3U))) | ((uint32_t)(mode) << ((channel << 1U) + 3U));
}
/*!
* @brief Enable the interrupt of threshold compare event for each channel.
*
* @param base ADC peripheral base address.
* @param channel Channel number.
* @param mode Interrupt mode for threshold compare event, see to #adc_threshold_interrupt_mode_t.
*/
static inline void ADC_EnableShresholdCompareInterrupt(ADC_Type *base,
static inline void ADC_EnableThresholdCompareInterrupt(ADC_Type *base,
uint32_t channel,
adc_threshold_interrupt_mode_t mode)
{

View File

@ -1,10 +1,13 @@
/*
* The Clear BSD License
* Copyright (c) 2016, 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 provided that the following conditions are met:
* 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.
@ -17,6 +20,7 @@
* 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
@ -150,6 +154,10 @@ static uint32_t findPllPreDiv(uint32_t ctrlReg, uint32_t nDecReg);
static uint32_t findPllPostDiv(uint32_t ctrlReg, uint32_t pDecReg);
/* Get multiplier (M) from PLL MDEC and BYPASS_FBDIV2 settings */
static uint32_t findPllMMult(uint32_t ctrlReg, uint32_t mDecReg);
/* Convert the binary to fractional part */
static double Binary2Fractional(uint32_t binaryPart);
/* Calculate the powerTimes' power of 2 */
static uint32_t power2Cal(uint32_t powerTimes);
/* Get the greatest common divisor */
static uint32_t FindGreatestCommonDivisor(uint32_t m, uint32_t n);
/* Set PLL output based on desired output rate */
@ -969,6 +977,25 @@ static uint32_t findPllMMult(uint32_t ctrlReg, uint32_t mDecReg)
return mMult;
}
/* Calculate the powerTimes' power of 2 */
static uint32_t power2Cal(uint32_t powerTimes)
{
if (powerTimes == 0)
return 1;
return 2 * power2Cal(powerTimes - 1);
}
/* Convert the binary to fractional part */
static double Binary2Fractional(uint32_t binaryPart)
{
double fractional = 0;
for (uint32_t i = 0; i <= 14; i++)
{
fractional += (double)((binaryPart >> i) & 0x1U) / (double)power2Cal(15 - i);
}
return fractional;
}
/* Find greatest common divisor between m and n */
static uint32_t FindGreatestCommonDivisor(uint32_t m, uint32_t n)
{
@ -1174,6 +1201,12 @@ static void CLOCK_GetAudioPLLOutFromSetupUpdate(pll_setup_t *pSetup)
s_Audio_Pll_Freq = CLOCK_GetAudioPLLOutFromSetup(pSetup);
}
/* Update AUDIO Fractional PLL rate variable */
static void CLOCK_GetAudioPLLOutFromAudioFracSetupUpdate(pll_setup_t *pSetup)
{
s_Audio_Pll_Freq = CLOCK_GetAudioPLLOutFromFractSetup(pSetup);
}
/* Update USB PLL rate variable */
static void CLOCK_GetUsbPLLOutFromSetupUpdate(const usb_pll_setup_t *pSetup)
{
@ -1366,6 +1399,58 @@ uint32_t CLOCK_GetAudioPLLOutFromSetup(pll_setup_t *pSetup)
return (uint32_t)workRate;
}
/* Return Audio PLL output clock rate from audio fractioanl setup structure */
uint32_t CLOCK_GetAudioPLLOutFromFractSetup(pll_setup_t *pSetup)
{
uint32_t prediv, postdiv, inPllRate;
double workRate, mMultFactional;
inPllRate = CLOCK_GetAudioPLLInClockRate();
if ((pSetup->pllctrl & (1UL << SYSCON_SYSPLLCTRL_BYPASS_SHIFT)) == 0U)
{
/* PLL is not in bypass mode, get pre-divider, and M divider, post-divider. */
/*
* 1. Pre-divider
* Pre-divider is only available when the DIRECTI is disabled.
*/
if (0U == (pSetup->pllctrl & SYSCON_AUDPLLCTRL_DIRECTI_MASK))
{
prediv = findPllPreDiv(pSetup->pllctrl, pSetup->pllndec);
}
else
{
prediv = 1U; /* The pre-divider is bypassed. */
}
/*
* 2. Post-divider
* Post-divider is only available when the DIRECTO is disabled.
*/
if (0U == (pSetup->pllctrl & SYSCON_AUDPLLCTRL_DIRECTO_MASK))
{
postdiv = findPllPostDiv(pSetup->pllctrl, pSetup->pllpdec);
}
else
{
postdiv = 1U; /* The post-divider is bypassed. */
}
/* Adjust input clock */
inPllRate = inPllRate / prediv;
mMultFactional = (double)(pSetup->audpllfrac >> 15) + (double)Binary2Fractional(pSetup->audpllfrac & 0x7FFFU);
workRate = (double)inPllRate * (double)mMultFactional;
workRate = workRate / ((double)postdiv);
workRate = workRate * 2U; /* SYS PLL hardware cco is divide by 2 before to M-DIVIDER*/
}
else
{
/* In bypass mode */
workRate = (uint64_t)inPllRate;
}
return (uint32_t)workRate;
}
/* Set the current PLL Rate */
void CLOCK_SetStoredPLLClockRate(uint32_t rate)
{
@ -1609,6 +1694,48 @@ pll_error_t CLOCK_SetupAudioPLLPrec(pll_setup_t *pSetup, uint32_t flagcfg)
return kStatus_PLL_Success;
}
/* Set AUDIO PLL output from AUDIO PLL fractional setup structure */
pll_error_t CLOCK_SetupAudioPLLPrecFract(pll_setup_t *pSetup, uint32_t flagcfg)
{
if ((SYSCON->AUDPLLCLKSEL & SYSCON_AUDPLLCLKSEL_SEL_MASK) == 0x01U)
{
/* Turn on the ext clock if system pll input select clk_in */
CLOCK_Enable_SysOsc(true);
}
/* Enable power VD3 for PLLs */
POWER_SetPLL();
/* Power off PLL during setup changes */
POWER_EnablePD(kPDRUNCFG_PD_AUDIO_PLL);
pSetup->flags = flagcfg;
/* Write PLL setup data */
SYSCON->AUDPLLCTRL = pSetup->pllctrl;
SYSCON->AUDPLLNDEC = pSetup->pllndec;
SYSCON->AUDPLLNDEC = pSetup->pllndec | (1U << SYSCON_SYSPLLNDEC_NREQ_SHIFT); /* latch */
SYSCON->AUDPLLPDEC = pSetup->pllpdec;
SYSCON->AUDPLLPDEC = pSetup->pllpdec | (1U << SYSCON_SYSPLLPDEC_PREQ_SHIFT); /* latch */
SYSCON->AUDPLLMDEC = pSetup->pllmdec;
SYSCON->AUDPLLFRAC = SYSCON_AUDPLLFRAC_SEL_EXT(0); /* enable fractional function */
SYSCON->AUDPLLFRAC = pSetup->audpllfrac;
SYSCON->AUDPLLFRAC = pSetup->audpllfrac | (1U << SYSCON_AUDPLLFRAC_REQ_SHIFT);
/* Enable peripheral states by setting low */
POWER_DisablePD(kPDRUNCFG_PD_AUDIO_PLL);
if ((pSetup->flags & PLL_SETUPFLAG_WAITLOCK) != 0U)
{
while (CLOCK_IsAudioPLLLocked() == false)
{
}
}
/* Update current programmed PLL rate var */
CLOCK_GetAudioPLLOutFromAudioFracSetupUpdate(pSetup);
return kStatus_PLL_Success;
}
/* Set Audio PLL output based on the passed Audio PLL setup data */
pll_error_t CLOCK_SetupAudioPLLData(pll_config_t *pControl, pll_setup_t *pSetup)
{
@ -1819,7 +1946,7 @@ pll_error_t CLOCK_SetUsbPLLFreq(const usb_pll_setup_t *pSetup)
}
/* If configure the USB HOST clock, VD5 power for USB PHY should be enable
before the the PLL is working */
before the PLL is working */
/* Turn on the ext clock for usb pll input */
CLOCK_Enable_SysOsc(true);

View File

@ -1,10 +1,13 @@
/*
* The Clear BSD License
* Copyright (c) 2016, 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 provided that the following conditions are met:
* 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.
@ -17,6 +20,7 @@
* 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
@ -46,6 +50,12 @@
* Definitions
*****************************************************************************/
/*! @name Driver version */
/*@{*/
/*! @brief CLOCK driver version 2.0.0. */
#define FSL_CLOCK_DRIVER_VERSION (MAKE_VERSION(2, 0, 0))
/*@}*/
/*! @brief Configure whether driver controls clock
*
* When set to 0, peripheral drivers will enable clock in initialize function
@ -119,7 +129,7 @@
/*! @brief Clock ip name array for GPIO. */
#define GPIO_CLOCKS \
{ \
kCLOCK_Gpio0, kCLOCK_Gpio1, kCLOCK_Gpio2, kCLOCK_Gpio3, kCLOCK_Gpio4, kCLOCK_Gpio5 \
kCLOCK_Gpio0,kCLOCK_Gpio1, kCLOCK_Gpio2, kCLOCK_Gpio3, kCLOCK_Gpio4, kCLOCK_Gpio5 \
}
/*! @brief Clock ip name array for PINT. */
#define PINT_CLOCKS \
@ -670,12 +680,12 @@ typedef enum _clock_attach_id
kFRO_HF_to_SDIO_CLK = MUX_A(CM_SDIOCLKSEL, 3),
kAUDIO_PLL_to_SDIO_CLK = MUX_A(CM_SDIOCLKSEL, 4),
kNONE_to_SDIO_CLK = MUX_A(CM_SDIOCLKSEL, 7),
kMCLK_to_LCD_CLK = MUX_A(CM_LCDCLKSEL, 0),
kLCDCLKIN_to_LCD_CLK = MUX_A(CM_LCDCLKSEL, 1),
kFRO_HF_to_LCD_CLK = MUX_A(CM_LCDCLKSEL, 2),
kNONE_to_LCD_CLK = MUX_A(CM_LCDCLKSEL, 3),
kMAIN_CLK_to_ASYNC_APB = MUX_A(CM_ASYNCAPB, 0),
kFRO12M_to_ASYNC_APB = MUX_A(CM_ASYNCAPB, 1),
kAUDIO_PLL_to_ASYNC_APB = MUX_A(CM_ASYNCAPB, 2),
@ -988,10 +998,10 @@ __STATIC_INLINE void CLOCK_Enable_SysOsc(bool enable)
SYSCON->PDRUNCFGCLR[0] |= SYSCON_PDRUNCFG_PDEN_VD2_ANA_MASK;
SYSCON->PDRUNCFGCLR[1] |= SYSCON_PDRUNCFG_PDEN_SYSOSC_MASK;
}
else
{
SYSCON->PDRUNCFGSET[0] = SYSCON_PDRUNCFG_PDEN_VD2_ANA_MASK;
SYSCON->PDRUNCFGSET[0] = SYSCON_PDRUNCFG_PDEN_VD2_ANA_MASK;
SYSCON->PDRUNCFGSET[1] = SYSCON_PDRUNCFG_PDEN_SYSOSC_MASK;
}
@ -1134,6 +1144,12 @@ uint32_t CLOCK_GetSystemPLLOutFromSetup(pll_setup_t *pSetup);
*/
uint32_t CLOCK_GetAudioPLLOutFromSetup(pll_setup_t *pSetup);
/*! @brief Return System AUDIO PLL output clock rate from audio fractioanl setup structure
* @param pSetup : Pointer to a PLL setup structure
* @return System PLL output clock rate the setup structure will generate
*/
uint32_t CLOCK_GetAudioPLLOutFromFractSetup(pll_setup_t *pSetup);
/*! @brief Return System USB PLL output clock rate from setup structure
* @param pSetup : Pointer to a PLL setup structure
* @return System PLL output clock rate the setup structure will generate
@ -1182,6 +1198,18 @@ pll_error_t CLOCK_SetupSystemPLLPrec(pll_setup_t *pSetup, uint32_t flagcfg);
*/
pll_error_t CLOCK_SetupAudioPLLPrec(pll_setup_t *pSetup, uint32_t flagcfg);
/*! @brief Set AUDIO PLL output from AUDIOPLL setup structure using the Audio Fractional divider register(precise frequency)
* @param pSetup : Pointer to populated PLL setup structure
* @param flagcfg : Flag configuration for PLL config structure
* @return PLL_ERROR_SUCCESS on success, or PLL setup error code
* @note This function will power off the PLL, setup the PLL with the
* new setup data, and then optionally powerup the AUDIO PLL, wait for PLL lock,
* and adjust system voltages to the new AUDIOPLL rate. The function will not
* alter any source clocks (ie, main systen clock) that may use the AUDIO PLL,
* so these should be setup prior to and after exiting the function.
*/
pll_error_t CLOCK_SetupAudioPLLPrecFract(pll_setup_t *pSetup, uint32_t flagcfg);
/**
* @brief Set PLL output from PLL setup structure (precise frequency)
* @param pSetup : Pointer to populated PLL setup structure

View File

@ -1,78 +1,46 @@
/*
* Copyright (c) 2015-2016, Freescale Semiconductor, Inc.
* Copyright 2016-2017 NXP
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
* 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"
/* This is not needed for mbed */
#if 0
#include "fsl_debug_console.h"
#ifndef NDEBUG
#if (defined(__CC_ARM)) || (defined(__ICCARM__))
void __aeabi_assert(const char *failedExpr, const char *file, int line)
{
PRINTF("ASSERT ERROR \" %s \": file \"%s\" Line \"%d\" \n", failedExpr, file, line);
for (;;)
{
__BKPT(0);
}
}
#elif(defined(__REDLIB__))
#if SDK_DEBUGCONSOLE
void __assertion_failed(char *_Expr)
{
PRINTF("%s\n", _Expr);
for (;;)
{
__asm("bkpt #0");
}
}
#endif
#elif(defined(__GNUC__))
void __assert_func(const char *file, int line, const char *func, const char *failedExpr)
{
PRINTF("ASSERT ERROR \" %s \": file \"%s\" Line \"%d\" function name \"%s\" \n", failedExpr, file, line, func);
for (;;)
{
__BKPT(0);
}
}
#endif /* (defined(__CC_ARM)) || (defined (__ICCARM__)) */
#endif /* NDEBUG */
#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) || (defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050))
#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[];
@ -112,11 +80,18 @@ uint32_t InstallIRQHandler(IRQn_Type irq, uint32_t irqHandler)
EnableGlobalIRQ(irqMaskValue);
return ret;
}
/* 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
#ifndef CPU_QN908X
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)
@ -147,32 +122,5 @@ void DisableDeepSleepIRQ(IRQn_Type interrupt)
SYSCON->STARTERCLR[index] = 1u << intNumber;
}
#endif /* FSL_FEATURE_SOC_SYSCON_COUNT */
#else
void EnableDeepSleepIRQ(IRQn_Type interrupt)
{
uint32_t index = 0;
uint32_t intNumber = (uint32_t)interrupt;
while (intNumber >= 32u)
{
index++;
intNumber -= 32u;
}
/* SYSCON->STARTERSET[index] = 1u << intNumber; */
EnableIRQ(interrupt); /* also enable interrupt at NVIC */
}
void DisableDeepSleepIRQ(IRQn_Type interrupt)
{
uint32_t index = 0;
uint32_t intNumber = (uint32_t)interrupt;
while (intNumber >= 32u)
{
index++;
intNumber -= 32u;
}
DisableIRQ(interrupt); /* also disable interrupt at NVIC */
/* SYSCON->STARTERCLR[index] = 1u << intNumber; */
}
#endif /*CPU_QN908X */
#endif /* QN908XC_SERIES */

View File

@ -1,9 +1,12 @@
/*
* 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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
@ -57,6 +61,12 @@
/*! @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. */
@ -65,6 +75,7 @@
#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. */
/*! @brief Status group numbers. */
enum _status_groups
@ -96,6 +107,8 @@ enum _status_groups
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. */
@ -120,11 +133,20 @@ enum _status_groups
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_NOTIFIER = 98, /*!< Group number for NOTIFIER status codes. */
kStatusGroup_DebugConsole = 99, /*!< Group number for debug console status codes. */
kStatusGroup_ApplicationRangeStart = 100, /*!< Starting number for application groups. */
kStatusGroup_SEMC = 100, /*!< Group number for SEMC status codes. */
kStatusGroup_ApplicationRangeStart = 101, /*!< Starting number for application groups. */
};
/*! @brief Generic status return codes. */
@ -168,7 +190,9 @@ typedef int32_t status_t;
/* @} */
/*! @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 */
/* @{ */
@ -316,77 +340,102 @@ _Pragma("diag_suppress=Pm120")
******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif
/*!
* @brief Enable specific interrupt.
*
* Enable the interrupt not routed from intmux.
*
* @param interrupt The IRQ number.
*/
static inline void EnableIRQ(IRQn_Type interrupt)
extern "C"
{
if (NotAvail_IRQn == interrupt)
{
return;
}
#if defined(FSL_FEATURE_SOC_INTMUX_COUNT) && (FSL_FEATURE_SOC_INTMUX_COUNT > 0)
if (interrupt < FSL_FEATURE_INTMUX_IRQ_START_INDEX)
#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 the interrupt not routed from intmux.
*
* @param interrupt The IRQ number.
*/
static inline void DisableIRQ(IRQn_Type interrupt)
{
if (NotAvail_IRQn == interrupt)
/*!
* @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)
{
return;
}
if (NotAvail_IRQn == interrupt)
{
return kStatus_Fail;
}
#if defined(FSL_FEATURE_SOC_INTMUX_COUNT) && (FSL_FEATURE_SOC_INTMUX_COUNT > 0)
if (interrupt < FSL_FEATURE_INTMUX_IRQ_START_INDEX)
#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);
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)
{
/*!
* @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;
uint32_t cpsr = __get_CPSR() & CPSR_I_Msk;
__disable_irq();
__disable_irq();
return cpsr;
return cpsr;
#else
uint32_t regPrimask = __get_PRIMASK();
@ -394,66 +443,68 @@ static inline uint32_t DisableGlobalIRQ(void)
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)
{
/*!
* @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);
__set_CPSR((__get_CPSR() & ~CPSR_I_Msk) | primask);
#else
__set_PRIMASK(primask);
#endif
}
}
/*!
* @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);
#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 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);
/*!
* @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 */
#if defined(__cplusplus)

View File

@ -1,9 +1,12 @@
/*
* 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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

View File

@ -1,9 +1,12 @@
/*
* 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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
@ -302,7 +306,11 @@ void CTIMER_GenericIRQHandler(uint32_t index)
}
else
{
#if defined(FSL_FEATURE_CTIMER_HAS_IR_CR3INT) && FSL_FEATURE_CTIMER_HAS_IR_CR3INT
for (i = 0; i <= CTIMER_IR_CR3INT_SHIFT; i++)
#else
for (i = 0; i <= CTIMER_IR_CR2INT_SHIFT; i++)
#endif /* FSL_FEATURE_CTIMER_HAS_IR_CR3INT */
{
mask = 0x01 << i;
/* For each status flag bit that was set call the callback function if it is valid */
@ -312,6 +320,11 @@ void CTIMER_GenericIRQHandler(uint32_t index)
}
}
}
/* 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
}
/* IRQ handler functions overloading weak symbols in the startup */
@ -319,6 +332,11 @@ void CTIMER_GenericIRQHandler(uint32_t index)
void CTIMER0_DriverIRQHandler(void)
{
CTIMER_GenericIRQHandler(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
}
#endif
@ -326,6 +344,11 @@ void CTIMER0_DriverIRQHandler(void)
void CTIMER1_DriverIRQHandler(void)
{
CTIMER_GenericIRQHandler(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
}
#endif
@ -333,6 +356,11 @@ void CTIMER1_DriverIRQHandler(void)
void CTIMER2_DriverIRQHandler(void)
{
CTIMER_GenericIRQHandler(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
}
#endif
@ -340,6 +368,11 @@ void CTIMER2_DriverIRQHandler(void)
void CTIMER3_DriverIRQHandler(void)
{
CTIMER_GenericIRQHandler(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
}
#endif
@ -347,6 +380,11 @@ void CTIMER3_DriverIRQHandler(void)
void CTIMER4_DriverIRQHandler(void)
{
CTIMER_GenericIRQHandler(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
}
#endif

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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
@ -54,7 +58,9 @@ typedef enum _ctimer_capture_channel
kCTIMER_Capture_0 = 0U, /*!< Timer capture channel 0 */
kCTIMER_Capture_1, /*!< Timer capture channel 1 */
kCTIMER_Capture_2, /*!< Timer capture channel 2 */
kCTIMER_Capture_3 /*!< Timer capture channel 3 */
#if defined(FSL_FEATURE_CTIMER_HAS_CCR_CAP3) && FSL_FEATURE_CTIMER_HAS_CCR_CAP3
kCTIMER_Capture_3 /*!< Timer capture channel 3 */
#endif /* FSL_FEATURE_CTIMER_HAS_IR_CR3INT */
} ctimer_capture_channel_t;
/*! @brief List of capture edge options */
@ -102,7 +108,9 @@ typedef enum _ctimer_interrupt_enable
kCTIMER_Capture0InterruptEnable = CTIMER_CCR_CAP0I_MASK, /*!< Capture 0 interrupt */
kCTIMER_Capture1InterruptEnable = CTIMER_CCR_CAP1I_MASK, /*!< Capture 1 interrupt */
kCTIMER_Capture2InterruptEnable = CTIMER_CCR_CAP2I_MASK, /*!< Capture 2 interrupt */
#if defined(FSL_FEATURE_CTIMER_HAS_CCR_CAP3) && FSL_FEATURE_CTIMER_HAS_CCR_CAP3
kCTIMER_Capture3InterruptEnable = CTIMER_CCR_CAP3I_MASK, /*!< Capture 3 interrupt */
#endif /* FSL_FEATURE_CTIMER_HAS_CCR_CAP3 */
} ctimer_interrupt_enable_t;
/*! @brief List of Timer flags */
@ -115,7 +123,9 @@ typedef enum _ctimer_status_flags
kCTIMER_Capture0Flag = CTIMER_IR_CR0INT_MASK, /*!< Capture 0 interrupt flag */
kCTIMER_Capture1Flag = CTIMER_IR_CR1INT_MASK, /*!< Capture 1 interrupt flag */
kCTIMER_Capture2Flag = CTIMER_IR_CR2INT_MASK, /*!< Capture 2 interrupt flag */
#if defined(FSL_FEATURE_CTIMER_HAS_IR_CR3INT) && FSL_FEATURE_CTIMER_HAS_IR_CR3INT
kCTIMER_Capture3Flag = CTIMER_IR_CR3INT_MASK, /*!< Capture 3 interrupt flag */
#endif /* FSL_FEATURE_CTIMER_HAS_IR_CR3INT */
} ctimer_status_flags_t;
typedef void (*ctimer_callback_t)(uint32_t flags);
@ -126,9 +136,9 @@ typedef void (*ctimer_callback_t)(uint32_t flags);
*/
typedef enum
{
kCTIMER_SingleCallback, /*!< Single Callback type where there is only one callback for the timer.
kCTIMER_SingleCallback, /*!< Single Callback type where there is only one callback for the timer.
based on the status flags different channels needs to be handled differently */
kCTIMER_MultipleCallback /*!< Multiple Callback type where there can be 8 valid callbacks, one per channel.
kCTIMER_MultipleCallback /*!< Multiple Callback type where there can be 8 valid callbacks, one per channel.
for both match/capture */
} ctimer_callback_type_t;
@ -306,10 +316,14 @@ void CTIMER_RegisterCallBack(CTIMER_Type *base, ctimer_callback_t *cb_func, ctim
static inline void CTIMER_EnableInterrupts(CTIMER_Type *base, uint32_t mask)
{
/* Enable match interrupts */
base->MCR |= mask;
base->MCR |= mask & (CTIMER_MCR_MR0I_MASK | CTIMER_MCR_MR1I_MASK | CTIMER_MCR_MR2I_MASK | CTIMER_MCR_MR3I_MASK);
/* Enable capture interrupts */
base->CCR |= mask;
base->CCR |= mask & (CTIMER_CCR_CAP0I_MASK | CTIMER_CCR_CAP1I_MASK | CTIMER_CCR_CAP2I_MASK
#if defined(FSL_FEATURE_CTIMER_HAS_CCR_CAP3) && FSL_FEATURE_CTIMER_HAS_CCR_CAP3
| CTIMER_CCR_CAP3I_MASK
#endif /* FSL_FEATURE_CTIMER_HAS_CCR_CAP3 */
);
}
/*!
@ -322,10 +336,14 @@ static inline void CTIMER_EnableInterrupts(CTIMER_Type *base, uint32_t mask)
static inline void CTIMER_DisableInterrupts(CTIMER_Type *base, uint32_t mask)
{
/* Disable match interrupts */
base->MCR &= ~mask;
base->MCR &= ~(mask & (CTIMER_MCR_MR0I_MASK | CTIMER_MCR_MR1I_MASK | CTIMER_MCR_MR2I_MASK | CTIMER_MCR_MR3I_MASK));
/* Disable capture interrupts */
base->CCR &= ~mask;
base->CCR &= ~(mask & (CTIMER_CCR_CAP0I_MASK | CTIMER_CCR_CAP1I_MASK | CTIMER_CCR_CAP2I_MASK
#if defined(FSL_FEATURE_CTIMER_HAS_CCR_CAP3) && FSL_FEATURE_CTIMER_HAS_CCR_CAP3
| CTIMER_CCR_CAP3I_MASK
#endif /* FSL_FEATURE_CTIMER_HAS_CCR_CAP3 */
));
}
/*!
@ -342,11 +360,14 @@ static inline uint32_t CTIMER_GetEnabledInterrupts(CTIMER_Type *base)
/* Get all the match interrupts enabled */
enabledIntrs =
base->MCR & (CTIMER_MCR_MR0I_SHIFT | CTIMER_MCR_MR1I_SHIFT | CTIMER_MCR_MR2I_SHIFT | CTIMER_MCR_MR3I_SHIFT);
base->MCR & (CTIMER_MCR_MR0I_MASK | CTIMER_MCR_MR1I_MASK | CTIMER_MCR_MR2I_MASK | CTIMER_MCR_MR3I_MASK);
/* Get all the capture interrupts enabled */
enabledIntrs |=
base->CCR & (CTIMER_CCR_CAP0I_SHIFT | CTIMER_CCR_CAP1I_SHIFT | CTIMER_CCR_CAP2I_SHIFT | CTIMER_CCR_CAP3I_SHIFT);
enabledIntrs |= base->CCR & (CTIMER_CCR_CAP0I_MASK | CTIMER_CCR_CAP1I_MASK | CTIMER_CCR_CAP2I_MASK
#if defined(FSL_FEATURE_CTIMER_HAS_CCR_CAP3) && FSL_FEATURE_CTIMER_HAS_CCR_CAP3
| CTIMER_CCR_CAP3I_MASK
#endif /* FSL_FEATURE_CTIMER_HAS_CCR_CAP3 */
);
return enabledIntrs;
}

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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
@ -111,11 +115,9 @@ void DMA_ConfigureChannelTrigger(DMA_Type *base, uint32_t channel, dma_channel_t
{
assert((channel < FSL_FEATURE_DMA_NUMBER_OF_CHANNELS) && (NULL != trigger));
uint32_t tmp = (
DMA_CHANNEL_CFG_HWTRIGEN_MASK | DMA_CHANNEL_CFG_TRIGPOL_MASK | DMA_CHANNEL_CFG_TRIGTYPE_MASK |
DMA_CHANNEL_CFG_TRIGBURST_MASK | DMA_CHANNEL_CFG_BURSTPOWER_MASK | DMA_CHANNEL_CFG_SRCBURSTWRAP_MASK |
DMA_CHANNEL_CFG_DSTBURSTWRAP_MASK
);
uint32_t tmp = (DMA_CHANNEL_CFG_HWTRIGEN_MASK | DMA_CHANNEL_CFG_TRIGPOL_MASK | DMA_CHANNEL_CFG_TRIGTYPE_MASK |
DMA_CHANNEL_CFG_TRIGBURST_MASK | DMA_CHANNEL_CFG_BURSTPOWER_MASK |
DMA_CHANNEL_CFG_SRCBURSTWRAP_MASK | DMA_CHANNEL_CFG_DSTBURSTWRAP_MASK);
tmp = base->CHANNEL[channel].CFG & (~tmp);
tmp |= (uint32_t)(trigger->type) | (uint32_t)(trigger->burst) | (uint32_t)(trigger->wrap);
base->CHANNEL[channel].CFG = tmp;
@ -132,7 +134,7 @@ uint32_t DMA_GetRemainingBytes(DMA_Type *base, uint32_t channel)
{
assert(channel < FSL_FEATURE_DMA_NUMBER_OF_CHANNELS);
/* NOTE: when descriptors are chained, ACTIVE bit is set for whole chain. It makes
/* NOTE: when descriptors are chained, ACTIVE bit is set for whole chain. It makes
* impossible to distinguish between:
* - transfer finishes (represented by value '0x3FF')
* - and remaining 1024 bytes to transfer (value 0x3FF)
@ -140,10 +142,9 @@ uint32_t DMA_GetRemainingBytes(DMA_Type *base, uint32_t channel)
* If you decide to use this function, please use 1023 transfers as maximal value */
/* Channel not active (transfer finished) and value is 0x3FF - nothing to transfer */
if (
(!(base->COMMON[DMA_CHANNEL_GROUP(channel)].ACTIVE & (1U << (DMA_CHANNEL_INDEX(channel))))) &&
(0x3FF == ((base->CHANNEL[channel].XFERCFG & DMA_CHANNEL_XFERCFG_XFERCOUNT_MASK) >> DMA_CHANNEL_XFERCFG_XFERCOUNT_SHIFT))
)
if ((!(base->COMMON[DMA_CHANNEL_GROUP(channel)].ACTIVE & (1U << (DMA_CHANNEL_INDEX(channel))))) &&
(0x3FF == ((base->CHANNEL[channel].XFERCFG & DMA_CHANNEL_XFERCFG_XFERCOUNT_MASK) >>
DMA_CHANNEL_XFERCFG_XFERCOUNT_SHIFT)))
{
return 0;
}
@ -152,12 +153,7 @@ uint32_t DMA_GetRemainingBytes(DMA_Type *base, uint32_t channel)
}
static void DMA_SetupDescriptor(
dma_descriptor_t *desc,
uint32_t xfercfg,
void *srcEndAddr,
void *dstEndAddr,
void *nextDesc
)
dma_descriptor_t *desc, uint32_t xfercfg, void *srcEndAddr, void *dstEndAddr, void *nextDesc)
{
desc->xfercfg = xfercfg;
desc->srcEndAddr = srcEndAddr;
@ -166,10 +162,7 @@ static void DMA_SetupDescriptor(
}
/* Verify and convert dma_xfercfg_t to XFERCFG register */
static void DMA_SetupXferCFG(
dma_xfercfg_t *xfercfg,
uint32_t *xfercfg_addr
)
static void DMA_SetupXferCFG(dma_xfercfg_t *xfercfg, uint32_t *xfercfg_addr)
{
assert(xfercfg != NULL);
/* check source increment */
@ -187,9 +180,9 @@ static void DMA_SetupXferCFG(
/* set reload - allow link to next descriptor */
xfer |= DMA_CHANNEL_XFERCFG_RELOAD(xfercfg->reload ? 1 : 0);
/* set swtrig flag - start transfer */
xfer |= DMA_CHANNEL_XFERCFG_SWTRIG(xfercfg->swtrig? 1 : 0);
xfer |= DMA_CHANNEL_XFERCFG_SWTRIG(xfercfg->swtrig ? 1 : 0);
/* set transfer count */
xfer |= DMA_CHANNEL_XFERCFG_CLRTRIG(xfercfg->clrtrig? 1 : 0);
xfer |= DMA_CHANNEL_XFERCFG_CLRTRIG(xfercfg->clrtrig ? 1 : 0);
/* set INTA */
xfer |= DMA_CHANNEL_XFERCFG_SETINTA(xfercfg->intA ? 1 : 0);
/* set INTB */
@ -210,13 +203,7 @@ static void DMA_SetupXferCFG(
*xfercfg_addr = xfer;
}
void DMA_CreateDescriptor(
dma_descriptor_t *desc,
dma_xfercfg_t *xfercfg,
void *srcAddr,
void *dstAddr,
void *nextDesc
)
void DMA_CreateDescriptor(dma_descriptor_t *desc, dma_xfercfg_t *xfercfg, void *srcAddr, void *dstAddr, void *nextDesc)
{
uint32_t xfercfg_reg = 0;
@ -229,11 +216,9 @@ void DMA_CreateDescriptor(
DMA_SetupXferCFG(xfercfg, &xfercfg_reg);
/* Set descriptor structure */
DMA_SetupDescriptor(desc, xfercfg_reg,
(uint8_t*)srcAddr + (xfercfg->srcInc * xfercfg->byteWidth * (xfercfg->transferCount - 1)),
(uint8_t*)dstAddr + (xfercfg->dstInc * xfercfg->byteWidth * (xfercfg->transferCount - 1)),
nextDesc
);
DMA_SetupDescriptor(
desc, xfercfg_reg, (uint8_t *)srcAddr + (xfercfg->srcInc * xfercfg->byteWidth * (xfercfg->transferCount - 1)),
(uint8_t *)dstAddr + (xfercfg->dstInc * xfercfg->byteWidth * (xfercfg->transferCount - 1)), nextDesc);
}
void DMA_AbortTransfer(dma_handle_t *handle)
@ -242,7 +227,8 @@ void DMA_AbortTransfer(dma_handle_t *handle)
DMA_DisableChannel(handle->base, handle->channel);
while (handle->base->COMMON[DMA_CHANNEL_GROUP(handle->channel)].BUSY & (1U << DMA_CHANNEL_INDEX(handle->channel)))
{ }
{
}
handle->base->COMMON[DMA_CHANNEL_GROUP(handle->channel)].ABORT |= 1U << DMA_CHANNEL_INDEX(handle->channel);
DMA_EnableChannel(handle->base, handle->channel);
}
@ -272,12 +258,12 @@ void DMA_SetCallback(dma_handle_t *handle, dma_callback callback, void *userData
}
void DMA_PrepareTransfer(dma_transfer_config_t *config,
void *srcAddr,
void *dstAddr,
uint32_t byteWidth,
uint32_t transferBytes,
dma_transfer_type_t type,
void *nextDesc)
void *srcAddr,
void *dstAddr,
uint32_t byteWidth,
uint32_t transferBytes,
dma_transfer_type_t type,
void *nextDesc)
{
uint32_t xfer_count;
assert((NULL != config) && (NULL != srcAddr) && (NULL != dstAddr));
@ -290,35 +276,35 @@ void DMA_PrepareTransfer(dma_transfer_config_t *config,
memset(config, 0, sizeof(*config));
switch (type)
{
case kDMA_MemoryToMemory:
config->xfercfg.srcInc = 1;
config->xfercfg.dstInc = 1;
config->isPeriph = false;
break;
case kDMA_PeripheralToMemory:
/* Peripheral register - source doesn't increment */
config->xfercfg.srcInc = 0;
config->xfercfg.dstInc = 1;
config->isPeriph = true;
break;
case kDMA_MemoryToPeripheral:
/* Peripheral register - destination doesn't increment */
config->xfercfg.srcInc = 1;
config->xfercfg.dstInc = 0;
config->isPeriph = true;
break;
case kDMA_StaticToStatic:
config->xfercfg.srcInc = 0;
config->xfercfg.dstInc = 0;
config->isPeriph = true;
break;
default:
return;
case kDMA_MemoryToMemory:
config->xfercfg.srcInc = 1;
config->xfercfg.dstInc = 1;
config->isPeriph = false;
break;
case kDMA_PeripheralToMemory:
/* Peripheral register - source doesn't increment */
config->xfercfg.srcInc = 0;
config->xfercfg.dstInc = 1;
config->isPeriph = true;
break;
case kDMA_MemoryToPeripheral:
/* Peripheral register - destination doesn't increment */
config->xfercfg.srcInc = 1;
config->xfercfg.dstInc = 0;
config->isPeriph = true;
break;
case kDMA_StaticToStatic:
config->xfercfg.srcInc = 0;
config->xfercfg.dstInc = 0;
config->isPeriph = true;
break;
default:
return;
}
config->dstAddr = (uint8_t*)dstAddr;
config->srcAddr = (uint8_t*)srcAddr;
config->nextDesc = (uint8_t*)nextDesc;
config->dstAddr = (uint8_t *)dstAddr;
config->srcAddr = (uint8_t *)srcAddr;
config->nextDesc = (uint8_t *)nextDesc;
config->xfercfg.transferCount = xfer_count;
config->xfercfg.byteWidth = byteWidth;
config->xfercfg.intA = true;
@ -333,7 +319,7 @@ status_t DMA_SubmitTransfer(dma_handle_t *handle, dma_transfer_config_t *config)
/* Previous transfer has not finished */
if (DMA_ChannelIsActive(handle->base, handle->channel))
{
return kStatus_DMA_Busy;
return kStatus_DMA_Busy;
}
/* enable/disable peripheral request */
@ -346,10 +332,8 @@ status_t DMA_SubmitTransfer(dma_handle_t *handle, dma_transfer_config_t *config)
DMA_DisableChannelPeriphRq(handle->base, handle->channel);
}
DMA_CreateDescriptor(
&s_dma_descriptor_table[ handle->channel ], &config->xfercfg,
config->srcAddr, config->dstAddr, config->nextDesc
);
DMA_CreateDescriptor(&s_dma_descriptor_table[handle->channel], &config->xfercfg, config->srcAddr, config->dstAddr,
config->nextDesc);
return kStatus_Success;
}
@ -364,18 +348,18 @@ void DMA_StartTransfer(dma_handle_t *handle)
/* If HW trigger is enabled - disable SW trigger */
if (handle->base->CHANNEL[handle->channel].CFG & DMA_CHANNEL_CFG_HWTRIGEN_MASK)
{
s_dma_descriptor_table[ handle->channel ].xfercfg &= ~(DMA_CHANNEL_XFERCFG_SWTRIG_MASK);
s_dma_descriptor_table[handle->channel].xfercfg &= ~(DMA_CHANNEL_XFERCFG_SWTRIG_MASK);
}
/* Otherwise enable SW trigger */
else
{
s_dma_descriptor_table[ handle->channel ].xfercfg |= DMA_CHANNEL_XFERCFG_SWTRIG_MASK;
s_dma_descriptor_table[handle->channel].xfercfg |= DMA_CHANNEL_XFERCFG_SWTRIG_MASK;
}
/* Set channel XFERCFG register according first channel descriptor. */
handle->base->CHANNEL[handle->channel].XFERCFG = s_dma_descriptor_table[ handle->channel ].xfercfg;
/* At this moment, the channel ACTIVE bit is set and application cannot modify
* or start another transfer using this channel. Channel ACTIVE bit is cleared by
handle->base->CHANNEL[handle->channel].XFERCFG = s_dma_descriptor_table[handle->channel].xfercfg;
/* At this moment, the channel ACTIVE bit is set and application cannot modify
* or start another transfer using this channel. Channel ACTIVE bit is cleared by
* 'AbortTransfer' function or when the transfer finishes */
}
@ -416,6 +400,20 @@ void DMA0_DriverIRQHandler(void)
(handle->callback)(handle, handle->userData, true, kDMA_IntB);
}
}
/* Error flag */
if (handle->base->COMMON[channel_group].ERRINT & (1U << channel_index))
{
/* Clear error flag */
handle->base->COMMON[channel_group].ERRINT = 1U << channel_index;
if (handle->callback)
{
(handle->callback)(handle, handle->userData, false, kDMA_IntError);
}
}
}
/* 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
}

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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
@ -56,17 +60,18 @@
/* Channel index in channel group. channel_index = (channel % 32) */
#define DMA_CHANNEL_INDEX(channel) (((uint8_t)channel) & 0x1F)
/*! @brief DMA descriptor structure */
typedef struct _dma_descriptor {
uint32_t xfercfg; /*!< Transfer configuration */
void *srcEndAddr; /*!< Last source address of DMA transfer */
void *dstEndAddr; /*!< Last destination address of DMA transfer */
void *linkToNextDesc; /*!< Address of next DMA descriptor in chain */
typedef struct _dma_descriptor
{
uint32_t xfercfg; /*!< Transfer configuration */
void *srcEndAddr; /*!< Last source address of DMA transfer */
void *dstEndAddr; /*!< Last destination address of DMA transfer */
void *linkToNextDesc; /*!< Address of next DMA descriptor in chain */
} dma_descriptor_t;
/*! @brief DMA transfer configuration */
typedef struct _dma_xfercfg {
typedef struct _dma_xfercfg
{
bool valid; /*!< Descriptor is ready to transfer */
bool reload; /*!< Reload channel configuration register after
current descriptor is exhausted */
@ -82,55 +87,74 @@ typedef struct _dma_xfercfg {
} dma_xfercfg_t;
/*! @brief DMA channel priority */
typedef enum _dma_priority {
kDMA_ChannelPriority0 = 0, /*!< Highest channel priority - priority 0 */
kDMA_ChannelPriority1, /*!< Channel priority 1 */
kDMA_ChannelPriority2, /*!< Channel priority 2 */
kDMA_ChannelPriority3, /*!< Channel priority 3 */
kDMA_ChannelPriority4, /*!< Channel priority 4 */
kDMA_ChannelPriority5, /*!< Channel priority 5 */
kDMA_ChannelPriority6, /*!< Channel priority 6 */
kDMA_ChannelPriority7, /*!< Lowest channel priority - priority 7 */
typedef enum _dma_priority
{
kDMA_ChannelPriority0 = 0, /*!< Highest channel priority - priority 0 */
kDMA_ChannelPriority1, /*!< Channel priority 1 */
kDMA_ChannelPriority2, /*!< Channel priority 2 */
kDMA_ChannelPriority3, /*!< Channel priority 3 */
kDMA_ChannelPriority4, /*!< Channel priority 4 */
kDMA_ChannelPriority5, /*!< Channel priority 5 */
kDMA_ChannelPriority6, /*!< Channel priority 6 */
kDMA_ChannelPriority7, /*!< Lowest channel priority - priority 7 */
} dma_priority_t;
/*! @brief DMA interrupt flags */
typedef enum _dma_int {
kDMA_IntA, /*!< DMA interrupt flag A */
kDMA_IntB, /*!< DMA interrupt flag B */
typedef enum _dma_int
{
kDMA_IntA, /*!< DMA interrupt flag A */
kDMA_IntB, /*!< DMA interrupt flag B */
kDMA_IntError, /*!< DMA interrupt flag error */
} dma_irq_t;
/*! @brief DMA trigger type*/
typedef enum _dma_trigger_type {
kDMA_NoTrigger = 0, /*!< Trigger is disabled */
typedef enum _dma_trigger_type
{
kDMA_NoTrigger = 0, /*!< Trigger is disabled */
kDMA_LowLevelTrigger = DMA_CHANNEL_CFG_HWTRIGEN(1) | DMA_CHANNEL_CFG_TRIGTYPE(1), /*!< Low level active trigger */
kDMA_HighLevelTrigger = DMA_CHANNEL_CFG_HWTRIGEN(1) | DMA_CHANNEL_CFG_TRIGTYPE(1) | DMA_CHANNEL_CFG_TRIGPOL(1), /*!< High level active trigger */
kDMA_HighLevelTrigger = DMA_CHANNEL_CFG_HWTRIGEN(1) | DMA_CHANNEL_CFG_TRIGTYPE(1) |
DMA_CHANNEL_CFG_TRIGPOL(1), /*!< High level active trigger */
kDMA_FallingEdgeTrigger = DMA_CHANNEL_CFG_HWTRIGEN(1), /*!< Falling edge active trigger */
kDMA_RisingEdgeTrigger = DMA_CHANNEL_CFG_HWTRIGEN(1) | DMA_CHANNEL_CFG_TRIGPOL(1), /*!< Rising edge active trigger */
kDMA_RisingEdgeTrigger =
DMA_CHANNEL_CFG_HWTRIGEN(1) | DMA_CHANNEL_CFG_TRIGPOL(1), /*!< Rising edge active trigger */
} dma_trigger_type_t;
/*! @brief DMA trigger burst */
typedef enum _dma_trigger_burst {
kDMA_SingleTransfer = 0, /*!< Single transfer */
kDMA_LevelBurstTransfer = DMA_CHANNEL_CFG_TRIGBURST(1), /*!< Burst transfer driven by level trigger */
kDMA_EdgeBurstTransfer1 = DMA_CHANNEL_CFG_TRIGBURST(1), /*!< Perform 1 transfer by edge trigger */
kDMA_EdgeBurstTransfer2 = DMA_CHANNEL_CFG_TRIGBURST(1) | DMA_CHANNEL_CFG_BURSTPOWER(1), /*!< Perform 2 transfers by edge trigger */
kDMA_EdgeBurstTransfer4 = DMA_CHANNEL_CFG_TRIGBURST(1) | DMA_CHANNEL_CFG_BURSTPOWER(2), /*!< Perform 4 transfers by edge trigger */
kDMA_EdgeBurstTransfer8 = DMA_CHANNEL_CFG_TRIGBURST(1) | DMA_CHANNEL_CFG_BURSTPOWER(3), /*!< Perform 8 transfers by edge trigger */
kDMA_EdgeBurstTransfer16 = DMA_CHANNEL_CFG_TRIGBURST(1) | DMA_CHANNEL_CFG_BURSTPOWER(4), /*!< Perform 16 transfers by edge trigger */
kDMA_EdgeBurstTransfer32 = DMA_CHANNEL_CFG_TRIGBURST(1) | DMA_CHANNEL_CFG_BURSTPOWER(5), /*!< Perform 32 transfers by edge trigger */
kDMA_EdgeBurstTransfer64 = DMA_CHANNEL_CFG_TRIGBURST(1) | DMA_CHANNEL_CFG_BURSTPOWER(6), /*!< Perform 64 transfers by edge trigger */
kDMA_EdgeBurstTransfer128 = DMA_CHANNEL_CFG_TRIGBURST(1) | DMA_CHANNEL_CFG_BURSTPOWER(7), /*!< Perform 128 transfers by edge trigger */
kDMA_EdgeBurstTransfer256 = DMA_CHANNEL_CFG_TRIGBURST(1) | DMA_CHANNEL_CFG_BURSTPOWER(8), /*!< Perform 256 transfers by edge trigger */
kDMA_EdgeBurstTransfer512 = DMA_CHANNEL_CFG_TRIGBURST(1) | DMA_CHANNEL_CFG_BURSTPOWER(9), /*!< Perform 512 transfers by edge trigger */
kDMA_EdgeBurstTransfer1024 = DMA_CHANNEL_CFG_TRIGBURST(1) | DMA_CHANNEL_CFG_BURSTPOWER(10), /*!< Perform 1024 transfers by edge trigger */
} dma_trigger_burst_t;
typedef enum _dma_trigger_burst
{
kDMA_SingleTransfer = 0, /*!< Single transfer */
kDMA_LevelBurstTransfer = DMA_CHANNEL_CFG_TRIGBURST(1), /*!< Burst transfer driven by level trigger */
kDMA_EdgeBurstTransfer1 = DMA_CHANNEL_CFG_TRIGBURST(1), /*!< Perform 1 transfer by edge trigger */
kDMA_EdgeBurstTransfer2 =
DMA_CHANNEL_CFG_TRIGBURST(1) | DMA_CHANNEL_CFG_BURSTPOWER(1), /*!< Perform 2 transfers by edge trigger */
kDMA_EdgeBurstTransfer4 =
DMA_CHANNEL_CFG_TRIGBURST(1) | DMA_CHANNEL_CFG_BURSTPOWER(2), /*!< Perform 4 transfers by edge trigger */
kDMA_EdgeBurstTransfer8 =
DMA_CHANNEL_CFG_TRIGBURST(1) | DMA_CHANNEL_CFG_BURSTPOWER(3), /*!< Perform 8 transfers by edge trigger */
kDMA_EdgeBurstTransfer16 =
DMA_CHANNEL_CFG_TRIGBURST(1) | DMA_CHANNEL_CFG_BURSTPOWER(4), /*!< Perform 16 transfers by edge trigger */
kDMA_EdgeBurstTransfer32 =
DMA_CHANNEL_CFG_TRIGBURST(1) | DMA_CHANNEL_CFG_BURSTPOWER(5), /*!< Perform 32 transfers by edge trigger */
kDMA_EdgeBurstTransfer64 =
DMA_CHANNEL_CFG_TRIGBURST(1) | DMA_CHANNEL_CFG_BURSTPOWER(6), /*!< Perform 64 transfers by edge trigger */
kDMA_EdgeBurstTransfer128 =
DMA_CHANNEL_CFG_TRIGBURST(1) | DMA_CHANNEL_CFG_BURSTPOWER(7), /*!< Perform 128 transfers by edge trigger */
kDMA_EdgeBurstTransfer256 =
DMA_CHANNEL_CFG_TRIGBURST(1) | DMA_CHANNEL_CFG_BURSTPOWER(8), /*!< Perform 256 transfers by edge trigger */
kDMA_EdgeBurstTransfer512 =
DMA_CHANNEL_CFG_TRIGBURST(1) | DMA_CHANNEL_CFG_BURSTPOWER(9), /*!< Perform 512 transfers by edge trigger */
kDMA_EdgeBurstTransfer1024 =
DMA_CHANNEL_CFG_TRIGBURST(1) | DMA_CHANNEL_CFG_BURSTPOWER(10), /*!< Perform 1024 transfers by edge trigger */
} dma_trigger_burst_t;
/*! @brief DMA burst wrapping */
typedef enum _dma_burst_wrap {
kDMA_NoWrap = 0, /*!< Wrapping is disabled */
kDMA_SrcWrap = DMA_CHANNEL_CFG_SRCBURSTWRAP(1), /*!< Wrapping is enabled for source */
kDMA_DstWrap = DMA_CHANNEL_CFG_DSTBURSTWRAP(1), /*!< Wrapping is enabled for destination */
kDMA_SrcAndDstWrap = DMA_CHANNEL_CFG_SRCBURSTWRAP(1) | DMA_CHANNEL_CFG_DSTBURSTWRAP(1), /*!< Wrapping is enabled for source and destination */
typedef enum _dma_burst_wrap
{
kDMA_NoWrap = 0, /*!< Wrapping is disabled */
kDMA_SrcWrap = DMA_CHANNEL_CFG_SRCBURSTWRAP(1), /*!< Wrapping is enabled for source */
kDMA_DstWrap = DMA_CHANNEL_CFG_DSTBURSTWRAP(1), /*!< Wrapping is enabled for destination */
kDMA_SrcAndDstWrap = DMA_CHANNEL_CFG_SRCBURSTWRAP(1) |
DMA_CHANNEL_CFG_DSTBURSTWRAP(1), /*!< Wrapping is enabled for source and destination */
} dma_burst_wrap_t;
/*! @brief DMA transfer type */
@ -143,27 +167,28 @@ typedef enum _dma_transfer_type
} dma_transfer_type_t;
/*! @brief DMA channel trigger */
typedef struct _dma_channel_trigger {
dma_trigger_type_t type;
dma_trigger_burst_t burst;
dma_burst_wrap_t wrap;
typedef struct _dma_channel_trigger
{
dma_trigger_type_t type; /*!< Select hardware trigger as edge triggered or level triggered. */
dma_trigger_burst_t burst; /*!< Select whether hardware triggers cause a single or burst transfer. */
dma_burst_wrap_t wrap; /*!< Select wrap type, source wrap or dest wrap, or both. */
} dma_channel_trigger_t;
/*! @brief DMA transfer status */
enum _dma_transfer_status
{
kStatus_DMA_Busy = MAKE_STATUS(kStatusGroup_DMA, 0), /*!< Channel is busy and can't handle the
transfer request. */
kStatus_DMA_Busy = MAKE_STATUS(kStatusGroup_DMA, 0), /*!< Channel is busy and can't handle the
transfer request. */
};
/*! @brief DMA transfer configuration */
typedef struct _dma_transfer_config
{
uint8_t *srcAddr; /*!< Source data address */
uint8_t *dstAddr; /*!< Destination data address */
uint8_t *nextDesc; /*!< Chain custom descriptor */
dma_xfercfg_t xfercfg; /*!< Transfer options */
bool isPeriph; /*!< DMA transfer is driven by peripheral */
uint8_t *srcAddr; /*!< Source data address */
uint8_t *dstAddr; /*!< Destination data address */
uint8_t *nextDesc; /*!< Chain custom descriptor */
dma_xfercfg_t xfercfg; /*!< Transfer options */
bool isPeriph; /*!< DMA transfer is driven by peripheral */
} dma_transfer_config_t;
/*! @brief Callback for DMA */
@ -175,11 +200,11 @@ typedef void (*dma_callback)(struct _dma_handle *handle, void *userData, bool tr
/*! @brief DMA transfer handle structure */
typedef struct _dma_handle
{
dma_callback callback; /*!< Callback function. Invoked when transfer
of descriptor with interrupt flag finishes */
void *userData; /*!< Callback function parameter */
DMA_Type *base; /*!< DMA peripheral base address */
uint8_t channel; /*!< DMA channel number */
dma_callback callback; /*!< Callback function. Invoked when transfer
of descriptor with interrupt flag finishes */
void *userData; /*!< Callback function parameter */
DMA_Type *base; /*!< DMA peripheral base address */
uint8_t channel; /*!< DMA channel number */
} dma_handle_t;
/*******************************************************************************
@ -219,13 +244,13 @@ void DMA_Deinit(DMA_Type *base);
* @{
*/
/*!
* @brief Return whether DMA channel is processing transfer
*
* @param base DMA peripheral base address.
* @param channel DMA channel number.
* @return True for active state, false otherwise.
*/
/*!
* @brief Return whether DMA channel is processing transfer
*
* @param base DMA peripheral base address.
* @param channel DMA channel number.
* @return True for active state, false otherwise.
*/
static inline bool DMA_ChannelIsActive(DMA_Type *base, uint32_t channel)
{
assert(channel < FSL_FEATURE_DMA_NUMBER_OF_CHANNELS);
@ -333,7 +358,8 @@ uint32_t DMA_GetRemainingBytes(DMA_Type *base, uint32_t channel);
static inline void DMA_SetChannelPriority(DMA_Type *base, uint32_t channel, dma_priority_t priority)
{
assert(channel < FSL_FEATURE_DMA_NUMBER_OF_CHANNELS);
base->CHANNEL[channel].CFG = (base->CHANNEL[channel].CFG & (~(DMA_CHANNEL_CFG_CHPRIORITY_MASK))) | DMA_CHANNEL_CFG_CHPRIORITY(priority);
base->CHANNEL[channel].CFG =
(base->CHANNEL[channel].CFG & (~(DMA_CHANNEL_CFG_CHPRIORITY_MASK))) | DMA_CHANNEL_CFG_CHPRIORITY(priority);
}
/*!
@ -346,11 +372,12 @@ static inline void DMA_SetChannelPriority(DMA_Type *base, uint32_t channel, dma_
static inline dma_priority_t DMA_GetChannelPriority(DMA_Type *base, uint32_t channel)
{
assert(channel < FSL_FEATURE_DMA_NUMBER_OF_CHANNELS);
return (dma_priority_t)((base->CHANNEL[channel].CFG & DMA_CHANNEL_CFG_CHPRIORITY_MASK) >> DMA_CHANNEL_CFG_CHPRIORITY_SHIFT);
return (dma_priority_t)((base->CHANNEL[channel].CFG & DMA_CHANNEL_CFG_CHPRIORITY_MASK) >>
DMA_CHANNEL_CFG_CHPRIORITY_SHIFT);
}
/*!
* @brief Create application specific DMA descriptor
* @brief Create application specific DMA descriptor
* to be used in a chain in transfer
*
* @param desc DMA descriptor address.
@ -359,13 +386,7 @@ static inline dma_priority_t DMA_GetChannelPriority(DMA_Type *base, uint32_t cha
* @param dstAddr Address of last item to receive.
* @param nextDesc Address of next descriptor in chain.
*/
void DMA_CreateDescriptor(
dma_descriptor_t *desc,
dma_xfercfg_t *xfercfg,
void *srcAddr,
void *dstAddr,
void *nextDesc
);
void DMA_CreateDescriptor(dma_descriptor_t *desc, dma_xfercfg_t *xfercfg, void *srcAddr, void *dstAddr, void *nextDesc);
/* @} */
@ -379,7 +400,7 @@ void DMA_CreateDescriptor(
*
* This function aborts DMA transfer specified by handle.
*
* @param handle DMA handle pointer.
* @param handle DMA handle pointer.
*/
void DMA_AbortTransfer(dma_handle_t *handle);
@ -425,12 +446,12 @@ void DMA_SetCallback(dma_handle_t *handle, dma_callback callback, void *userData
* source address error(SAE).
*/
void DMA_PrepareTransfer(dma_transfer_config_t *config,
void *srcAddr,
void *dstAddr,
uint32_t byteWidth,
uint32_t transferBytes,
dma_transfer_type_t type,
void *nextDesc);
void *srcAddr,
void *dstAddr,
uint32_t byteWidth,
uint32_t transferBytes,
dma_transfer_type_t type,
void *nextDesc);
/*!
* @brief Submits the DMA transfer request.

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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
@ -223,13 +227,23 @@ void DMIC0_DriverIRQHandler(void)
{
s_dmicCallback[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
}
/*DMIC0 HWVAD IRQ handler */
void HWVAD0_IRQHandler(void)
void HWVAD0_DriverIRQHandler(void)
{
if (s_dmicHwvadCallback[0] != NULL)
{
s_dmicHwvadCallback[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
}
#endif

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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
@ -120,6 +124,7 @@ status_t DMIC_TransferCreateHandleDMA(DMIC_Type *base,
handle->userData = userData;
handle->rxDmaHandle = rxDmaHandle;
handle->dataWidth = 2U;
/* Set DMIC state to idle */
handle->state = kDMIC_Idle;
@ -157,7 +162,7 @@ status_t DMIC_TransferReceiveDMA(DMIC_Type *base,
handle->transferSize = xfer->dataSize;
/* Prepare transfer. */
DMA_PrepareTransfer(&xferConfig, (void *)&base->CHANNEL[dmic_channel].FIFO_DATA, xfer->data, sizeof(uint16_t),
DMA_PrepareTransfer(&xferConfig, (void *)&base->CHANNEL[dmic_channel].FIFO_DATA, xfer->data, handle->dataWidth,
xfer->dataSize, kDMA_PeripheralToMemory, NULL);
/* Submit transfer. */

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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
@ -51,6 +55,13 @@ typedef struct _dmic_transfer
size_t dataSize; /*!< The byte count to be transfer. */
} dmic_transfer_t;
/*! @brief DMIC transfer structure. */
typedef enum dmic_bitwidth
{
kDMICBitWidth16Bits = 2U, /*!< 16 bits mode.*/
kDMICBitWidth32Bits = 4U, /*!< 32 bits mode. */
} dmic_bitwidth_t;
/* Forward declaration of the handle typedef. */
typedef struct _dmic_dma_handle dmic_dma_handle_t;
@ -68,6 +79,7 @@ struct _dmic_dma_handle
DMIC_Type *base; /*!< DMIC peripheral base address. */
dma_handle_t *rxDmaHandle; /*!< The DMA RX channel used. */
dmic_dma_transfer_callback_t callback; /*!< Callback function. */
uint8_t dataWidth; /*!< Data bit width */
void *userData; /*!< DMIC callback function parameter.*/
size_t transferSize; /*!< Size of the data to receive. */
volatile uint8_t state; /*!< Internal state of DMIC DMA transfer */
@ -100,16 +112,33 @@ status_t DMIC_TransferCreateHandleDMA(DMIC_Type *base,
void *userData,
dma_handle_t *rxDmaHandle);
/*!
* @brief Configure the transfer data width.
*
* This function is optional to users, the default data width is set to 16 bits if not call this fuction.
* DMIC only support 16 bits and 32 bits setting. As DMA cannot support 24 bits directly, please set to 32 bits
* while need a 24 bits data. In 32 bit mode, the MSB 8 bits always 0, as the register can only have 24 bits valid bits.
*
* @param base DMIC peripheral base address.
* @param handle Pointer to usart_dma_handle_t structure.
* @param width DMIC width. See #dmic_bitwidth_t.
* @retval kStatus_Success
*/
static inline void DMIC_TransferSetBitWidthDMA(DMIC_Type *base, dmic_dma_handle_t *handle, dmic_bitwidth_t width)
{
handle->dataWidth = width;
}
/*!
* @brief Receives data using DMA.
*
* This function receives data using DMA. This is a non-blocking function, which returns
* right away. When all data is received, the receive callback function is called.
*
* @param base USART peripheral base address.
* @param base DMIC peripheral base address.
* @param handle Pointer to usart_dma_handle_t structure.
* @param xfer DMIC DMA transfer structure. See #dmic_transfer_t.
* @param dmic_channel DMIC channel
* @param dmic_channel DMIC channel
* @retval kStatus_Success
*/
status_t DMIC_TransferReceiveDMA(DMIC_Type *base,

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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
@ -919,8 +923,8 @@ status_t ENET_DescriptorInit(ENET_Type *base, enet_config_t *config, enet_buffer
assert(config);
assert(bufferConfig);
bool intTxEnable;
bool intRxEnable;
bool intTxEnable = false;
bool intRxEnable = false;
bool doubleBuffEnable = (config->specialControl & kENET_DescDoubleBuffer) ? true : false;
uint8_t ringNum = config->multiqueueCfg == NULL ? 1 : 2;
uint8_t channel;
@ -928,12 +932,12 @@ status_t ENET_DescriptorInit(ENET_Type *base, enet_config_t *config, enet_buffer
for (channel = 0; channel < ringNum; channel++)
{
intRxEnable = (base->DMA_CH[channel].DMA_CHX_INT_EN & ENET_DMA_CH_DMA_CHX_INT_EN_RIE_MASK) ? true : false;
intTxEnable = (base->DMA_CH[channel].DMA_CHX_INT_EN & ENET_DMA_CH_DMA_CHX_INT_EN_TIE_MASK) ? true : false;
if (ENET_TxDescriptorsInit(base, bufferConfig, intTxEnable, channel) != kStatus_Success)
{
return kStatus_Fail;
}
intTxEnable = (base->DMA_CH[channel].DMA_CHX_INT_EN & ENET_DMA_CH_DMA_CHX_INT_EN_TIE_MASK) ? true : false;
if (ENET_RxDescriptorsInit(base, bufferConfig, intRxEnable, channel, doubleBuffEnable) != kStatus_Success)
{
@ -1244,7 +1248,7 @@ status_t ENET_GetRxFrameSize(ENET_Type *base, enet_handle_t *handle, uint32_t *l
enet_rx_bd_ring_t *rxBdRing = (enet_rx_bd_ring_t *)&handle->rxBdRing[channel];
enet_rx_bd_struct_t *rxDesc = rxBdRing->rxBdBase + rxBdRing->rxGenIdx;
uint16_t index;
uint16_t index = rxBdRing->rxGenIdx;
/* Reset the length to zero. */
*length = 0;
@ -1802,9 +1806,19 @@ void ENET_IRQHandler(ENET_Type *base, enet_handle_t *handle)
}
}
#endif /* ENET_PTP1588FEATURE_REQUIRED */
/* 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 ETHERNET_DriverIRQHandler(void)
{
s_enetIsr(ENET, s_ENETHandle[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
}

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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
@ -155,6 +159,11 @@ void FLEXCOMM_SetIRQHandler(void *base, flexcomm_irq_handler_t handler, void *ha
s_flexcommIrqHandler[instance] = NULL;
s_flexcommHandle[instance] = handle;
s_flexcommIrqHandler[instance] = handler;
/* 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
}
/* IRQ handler functions overloading weak symbols in the startup */
@ -163,6 +172,11 @@ void FLEXCOMM0_DriverIRQHandler(void)
{
assert(s_flexcommIrqHandler[0]);
s_flexcommIrqHandler[0]((void *)s_flexcommBaseAddrs[0], s_flexcommHandle[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
}
#endif
@ -171,6 +185,11 @@ void FLEXCOMM1_DriverIRQHandler(void)
{
assert(s_flexcommIrqHandler[1]);
s_flexcommIrqHandler[1]((void *)s_flexcommBaseAddrs[1], s_flexcommHandle[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
}
#endif
@ -179,6 +198,11 @@ void FLEXCOMM2_DriverIRQHandler(void)
{
assert(s_flexcommIrqHandler[2]);
s_flexcommIrqHandler[2]((void *)s_flexcommBaseAddrs[2], s_flexcommHandle[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
}
#endif
@ -187,6 +211,11 @@ void FLEXCOMM3_DriverIRQHandler(void)
{
assert(s_flexcommIrqHandler[3]);
s_flexcommIrqHandler[3]((void *)s_flexcommBaseAddrs[3], s_flexcommHandle[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
}
#endif
@ -195,6 +224,11 @@ void FLEXCOMM4_DriverIRQHandler(void)
{
assert(s_flexcommIrqHandler[4]);
s_flexcommIrqHandler[4]((void *)s_flexcommBaseAddrs[4], s_flexcommHandle[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
}
#endif
@ -204,6 +238,11 @@ void FLEXCOMM5_DriverIRQHandler(void)
{
assert(s_flexcommIrqHandler[5]);
s_flexcommIrqHandler[5]((void *)s_flexcommBaseAddrs[5], s_flexcommHandle[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
}
#endif
@ -212,6 +251,11 @@ void FLEXCOMM6_DriverIRQHandler(void)
{
assert(s_flexcommIrqHandler[6]);
s_flexcommIrqHandler[6]((void *)s_flexcommBaseAddrs[6], s_flexcommHandle[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
}
#endif
@ -220,6 +264,11 @@ void FLEXCOMM7_DriverIRQHandler(void)
{
assert(s_flexcommIrqHandler[7]);
s_flexcommIrqHandler[7]((void *)s_flexcommBaseAddrs[7], s_flexcommHandle[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
@ -228,6 +277,11 @@ void FLEXCOMM8_DriverIRQHandler(void)
{
assert(s_flexcommIrqHandler[8]);
s_flexcommIrqHandler[8]((void *)s_flexcommBaseAddrs[8], s_flexcommHandle[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
}
#endif
@ -236,5 +290,10 @@ void FLEXCOMM9_DriverIRQHandler(void)
{
assert(s_flexcommIrqHandler[9]);
s_flexcommIrqHandler[9]((void *)s_flexcommBaseAddrs[9], s_flexcommHandle[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
}
#endif

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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
@ -37,6 +41,12 @@
* @{
*/
/*! @name Driver version */
/*@{*/
/*! @brief FlexCOMM driver version 2.0.0. */
#define FSL_FLEXCOMM_DRIVER_VERSION (MAKE_VERSION(2, 0, 0))
/*@}*/
/*! @brief FLEXCOMM peripheral modes. */
typedef enum
{

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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
@ -176,6 +180,11 @@ void GINT0_DriverIRQHandler(void)
{
s_gintCallback[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
}
#endif
@ -189,6 +198,11 @@ void GINT1_DriverIRQHandler(void)
{
s_gintCallback[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
}
#endif
@ -202,6 +216,11 @@ void GINT2_DriverIRQHandler(void)
{
s_gintCallback[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
}
#endif
@ -215,6 +234,11 @@ void GINT3_DriverIRQHandler(void)
{
s_gintCallback[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
}
#endif
@ -228,6 +252,11 @@ void GINT4_DriverIRQHandler(void)
{
s_gintCallback[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
}
#endif
@ -241,6 +270,11 @@ void GINT5_DriverIRQHandler(void)
{
s_gintCallback[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
}
#endif
@ -254,6 +288,11 @@ void GINT6_DriverIRQHandler(void)
{
s_gintCallback[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
}
#endif
@ -267,5 +306,10 @@ void GINT7_DriverIRQHandler(void)
{
s_gintCallback[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

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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
@ -33,7 +37,10 @@
/*******************************************************************************
* Variables
******************************************************************************/
#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_gpioClockName[] = GPIO_CLOCKS;
#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
/*******************************************************************************
* Prototypes
************ ******************************************************************/
@ -41,6 +48,15 @@
/*******************************************************************************
* Code
******************************************************************************/
void GPIO_PortInit(GPIO_Type *base, uint32_t port)
{
#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
assert(port < ARRAY_SIZE(s_gpioClockName));
/* Upgate the GPIO clock */
CLOCK_EnableClock(s_gpioClockName[port]);
#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
}
void GPIO_PinInit(GPIO_Type *base, uint32_t port, uint32_t pin, const gpio_pin_config_t *config)
{

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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
@ -46,8 +50,8 @@
/*! @name Driver version */
/*@{*/
/*! @brief LPC GPIO driver version 2.0.0. */
#define FSL_GPIO_DRIVER_VERSION (MAKE_VERSION(2, 0, 0))
/*! @brief LPC GPIO driver version 2.1.1. */
#define FSL_GPIO_DRIVER_VERSION (MAKE_VERSION(2, 1, 1))
/*@}*/
/*! @brief LPC GPIO direction definition */
@ -80,6 +84,25 @@ extern "C" {
/*! @name GPIO Configuration */
/*@{*/
/*!
* @brief Initializes the GPIO peripheral.
*
* This function ungates the GPIO clock.
*
* @param base GPIO peripheral base pointer.
* @param port GPIO port number.
*/
void GPIO_PortInit(GPIO_Type *base, uint32_t port);
/*!
* @brief Initializes the GPIO peripheral.
* @deprecated Do not use this function. It has been superceded by @ref GPIO_PortInit.
*/
static inline void GPIO_Init(GPIO_Type *base, uint32_t port)
{
GPIO_PortInit(base, port);
}
/*!
* @brief Initializes a GPIO pin used by the board.
*
@ -124,6 +147,15 @@ void GPIO_PinInit(GPIO_Type *base, uint32_t port, uint32_t pin, const gpio_pin_c
* - 0: corresponding pin output low-logic level.
* - 1: corresponding pin output high-logic level.
*/
static inline void GPIO_PinWrite(GPIO_Type *base, uint32_t port, uint32_t pin, uint8_t output)
{
base->B[port][pin] = output;
}
/*!
* @brief Sets the output level of the one GPIO pin 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 port, uint32_t pin, uint8_t output)
{
base->B[port][pin] = output;
@ -142,10 +174,19 @@ static inline void GPIO_WritePinOutput(GPIO_Type *base, uint32_t port, uint32_t
* - 0: corresponding pin input low-logic level.
* - 1: corresponding pin input high-logic level.
*/
static inline uint32_t GPIO_ReadPinInput(GPIO_Type *base, uint32_t port, uint32_t pin)
static inline uint32_t GPIO_PinRead(GPIO_Type *base, uint32_t port, uint32_t pin)
{
return (uint32_t)base->B[port][pin];
}
/*!
* @brief Reads the current input value of the GPIO PIN.
* @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 port, uint32_t pin)
{
return GPIO_PinRead(base, port, pin);
}
/*@}*/
/*!
@ -155,11 +196,20 @@ static inline uint32_t GPIO_ReadPinInput(GPIO_Type *base, uint32_t port, uint32_
* @param port GPIO port number
* @param mask GPIO pin number macro
*/
static inline void GPIO_SetPinsOutput(GPIO_Type *base, uint32_t port, uint32_t mask)
static inline void GPIO_PortSet(GPIO_Type *base, uint32_t port, uint32_t mask)
{
base->SET[port] = 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 port, uint32_t mask)
{
GPIO_PortSet(base, port, mask);
}
/*!
* @brief Sets the output level of the multiple GPIO pins to the logic 0.
*
@ -167,11 +217,20 @@ static inline void GPIO_SetPinsOutput(GPIO_Type *base, uint32_t port, uint32_t m
* @param port GPIO port number
* @param mask GPIO pin number macro
*/
static inline void GPIO_ClearPinsOutput(GPIO_Type *base, uint32_t port, uint32_t mask)
static inline void GPIO_PortClear(GPIO_Type *base, uint32_t port, uint32_t mask)
{
base->CLR[port] = 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.
*/
static inline void GPIO_ClearPinsOutput(GPIO_Type *base, uint32_t port, uint32_t mask)
{
GPIO_PortClear(base, port, mask);
}
/*!
* @brief Reverses current output logic of the multiple GPIO pins.
*
@ -179,10 +238,19 @@ static inline void GPIO_ClearPinsOutput(GPIO_Type *base, uint32_t port, uint32_t
* @param port GPIO port number
* @param mask GPIO pin number macro
*/
static inline void GPIO_TogglePinsOutput(GPIO_Type *base, uint32_t port, uint32_t mask)
static inline void GPIO_PortToggle(GPIO_Type *base, uint32_t port, uint32_t mask)
{
base->NOT[port] = mask;
}
/*!
* @brief Reverses 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 port, uint32_t mask)
{
GPIO_PortToggle(base, port, mask);
}
/*@}*/
/*!
@ -191,11 +259,20 @@ static inline void GPIO_TogglePinsOutput(GPIO_Type *base, uint32_t port, uint32_
* @param base GPIO peripheral base pointer(Typically GPIO)
* @param port GPIO port number
*/
static inline uint32_t GPIO_ReadPinsInput(GPIO_Type *base, uint32_t port)
static inline uint32_t GPIO_PortRead(GPIO_Type *base, uint32_t port)
{
return (uint32_t)base->PIN[port];
}
/*!
* @brief Reads the current input value of the whole GPIO port.
* @deprecated Do not use this function. It has been superceded by @ref GPIO_PortRead
*/
static inline uint32_t GPIO_ReadPinsInput(GPIO_Type *base, uint32_t port)
{
return GPIO_PortRead(base, port);
}
/*@}*/
/*! @name GPIO Mask Operations */
/*@{*/
@ -207,11 +284,20 @@ static inline uint32_t GPIO_ReadPinsInput(GPIO_Type *base, uint32_t port)
* @param port GPIO port number
* @param mask GPIO pin number macro
*/
static inline void GPIO_SetPortMask(GPIO_Type *base, uint32_t port, uint32_t mask)
static inline void GPIO_PortMaskedSet(GPIO_Type *base, uint32_t port, uint32_t mask)
{
base->MASK[port] = mask;
}
/*!
* @brief Sets port mask, 0 - enable pin, 1 - disable pin.
* @deprecated Do not use this function. It has been superceded by @ref GPIO_PortMaskedSet.
*/
static inline void GPIO_SetPortMask(GPIO_Type *base, uint32_t port, uint32_t mask)
{
GPIO_PortMaskedSet(base, port, mask);
}
/*!
* @brief Sets the output level of the masked GPIO port. Only pins enabled by GPIO_SetPortMask() will be affected.
*
@ -219,11 +305,20 @@ static inline void GPIO_SetPortMask(GPIO_Type *base, uint32_t port, uint32_t mas
* @param port GPIO port number
* @param output GPIO port output value.
*/
static inline void GPIO_WriteMPort(GPIO_Type *base, uint32_t port, uint32_t output)
static inline void GPIO_PortMaskedWrite(GPIO_Type *base, uint32_t port, uint32_t output)
{
base->MPIN[port] = output;
}
/*!
* @brief Sets the output level of the masked GPIO port. Only pins enabled by GPIO_SetPortMask() will be affected.
* @deprecated Do not use this function. It has been superceded by @ref GPIO_PortMaskedWrite.
*/
static inline void GPIO_WriteMPort(GPIO_Type *base, uint32_t port, uint32_t output)
{
GPIO_PortMaskedWrite(base, port, output);
}
/*!
* @brief Reads the current input value of the masked GPIO port. Only pins enabled by GPIO_SetPortMask() will be
* affected.
@ -232,11 +327,21 @@ static inline void GPIO_WriteMPort(GPIO_Type *base, uint32_t port, uint32_t outp
* @param port GPIO port number
* @retval masked GPIO port value
*/
static inline uint32_t GPIO_ReadMPort(GPIO_Type *base, uint32_t port)
static inline uint32_t GPIO_PortMaskedRead(GPIO_Type *base, uint32_t port)
{
return (uint32_t)base->MPIN[port];
}
/*!
* @brief Reads the current input value of the masked GPIO port. Only pins enabled by GPIO_SetPortMask() will be
* affected.
* @deprecated Do not use this function. It has been superceded by @ref GPIO_PortMaskedRead.
*/
static inline uint32_t GPIO_ReadMPort(GPIO_Type *base, uint32_t port)
{
return GPIO_PortMaskedRead(base, port);
}
/*@}*/
#if defined(__cplusplus)

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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
@ -159,10 +163,23 @@ static uint32_t I2C_PendingStatusWait(I2C_Type *base)
{
uint32_t status;
#if I2C_WAIT_TIMEOUT
uint32_t waitTimes = I2C_WAIT_TIMEOUT;
#endif
do
{
status = I2C_GetStatusFlags(base);
#if I2C_WAIT_TIMEOUT
} while (((status & I2C_STAT_MSTPENDING_MASK) == 0) && (--waitTimes));
if (waitTimes == 0)
{
return kStatus_I2C_Timeout;
}
#else
} while ((status & I2C_STAT_MSTPENDING_MASK) == 0);
#endif
/* Clear controller state. */
I2C_MasterClearStatusFlags(base, I2C_STAT_MSTARBLOSS_MASK | I2C_STAT_MSTSTSTPERR_MASK);
@ -172,7 +189,12 @@ static uint32_t I2C_PendingStatusWait(I2C_Type *base)
status_t I2C_MasterStart(I2C_Type *base, uint8_t address, i2c_direction_t direction)
{
I2C_PendingStatusWait(base);
status_t result;
result = I2C_PendingStatusWait(base);
if (result == kStatus_I2C_Timeout)
{
return kStatus_I2C_Timeout;
}
/* Write Address and RW bit to data register */
base->MSTDAT = ((uint32_t)address << 1) | ((uint32_t)direction & 1u);
@ -184,7 +206,12 @@ status_t I2C_MasterStart(I2C_Type *base, uint8_t address, i2c_direction_t direct
status_t I2C_MasterStop(I2C_Type *base)
{
I2C_PendingStatusWait(base);
status_t result;
result = I2C_PendingStatusWait(base);
if (result == kStatus_I2C_Timeout)
{
return kStatus_I2C_Timeout;
}
base->MSTCTL = I2C_MSTCTL_MSTSTOP_MASK;
return kStatus_Success;
@ -204,6 +231,10 @@ status_t I2C_MasterWriteBlocking(I2C_Type *base, const void *txBuff, size_t txSi
while (txSize)
{
status = I2C_PendingStatusWait(base);
if (status == kStatus_I2C_Timeout)
{
return kStatus_I2C_Timeout;
}
if (status & I2C_STAT_MSTARBLOSS_MASK)
{
@ -245,6 +276,11 @@ status_t I2C_MasterWriteBlocking(I2C_Type *base, const void *txBuff, size_t txSi
status = I2C_PendingStatusWait(base);
if (status == kStatus_I2C_Timeout)
{
return kStatus_I2C_Timeout;
}
if ((status & (I2C_STAT_MSTARBLOSS_MASK | I2C_STAT_MSTSTSTPERR_MASK)) == 0)
{
if (!(flags & kI2C_TransferNoStopFlag))
@ -252,6 +288,10 @@ status_t I2C_MasterWriteBlocking(I2C_Type *base, const void *txBuff, size_t txSi
/* Initiate stop */
base->MSTCTL = I2C_MSTCTL_MSTSTOP_MASK;
status = I2C_PendingStatusWait(base);
if (status == kStatus_I2C_Timeout)
{
return kStatus_I2C_Timeout;
}
}
}
@ -282,6 +322,10 @@ status_t I2C_MasterReadBlocking(I2C_Type *base, void *rxBuff, size_t rxSize, uin
while (rxSize)
{
status = I2C_PendingStatusWait(base);
if (status == kStatus_I2C_Timeout)
{
return kStatus_I2C_Timeout;
}
if (status & (I2C_STAT_MSTARBLOSS_MASK | I2C_STAT_MSTSTSTPERR_MASK))
{
@ -305,6 +349,10 @@ status_t I2C_MasterReadBlocking(I2C_Type *base, void *rxBuff, size_t rxSize, uin
/* initiate NAK and stop */
base->MSTCTL = I2C_MSTCTL_MSTSTOP_MASK;
status = I2C_PendingStatusWait(base);
if (status == kStatus_I2C_Timeout)
{
return kStatus_I2C_Timeout;
}
}
}
break;
@ -483,7 +531,7 @@ status_t I2C_MasterTransferGetCount(I2C_Type *base, i2c_master_handle_t *handle,
return kStatus_Success;
}
void I2C_MasterTransferAbort(I2C_Type *base, i2c_master_handle_t *handle)
status_t I2C_MasterTransferAbort(I2C_Type *base, i2c_master_handle_t *handle)
{
uint32_t status;
uint32_t master_state;
@ -495,6 +543,10 @@ void I2C_MasterTransferAbort(I2C_Type *base, i2c_master_handle_t *handle)
/* Wait until module is ready */
status = I2C_PendingStatusWait(base);
if (status == kStatus_I2C_Timeout)
{
return kStatus_I2C_Timeout;
}
/* Get the state of the I2C module */
master_state = (status & I2C_STAT_MSTSTATE_MASK) >> I2C_STAT_MSTSTATE_SHIFT;
@ -505,12 +557,17 @@ void I2C_MasterTransferAbort(I2C_Type *base, i2c_master_handle_t *handle)
base->MSTCTL = I2C_MSTCTL_MSTSTOP_MASK;
/* Wait until the STOP is completed */
I2C_PendingStatusWait(base);
status = I2C_PendingStatusWait(base);
if (status == kStatus_I2C_Timeout)
{
return kStatus_I2C_Timeout;
}
}
/* Reset handle. */
handle->state = kIdleState;
}
return kStatus_Success;
}
/*!
@ -842,10 +899,22 @@ static uint32_t I2C_SlavePollPending(I2C_Type *base)
{
uint32_t stat;
#if I2C_WAIT_TIMEOUT
uint32_t waitTimes = I2C_WAIT_TIMEOUT;
#endif
do
{
stat = base->STAT;
#if I2C_WAIT_TIMEOUT
} while ((0u == (stat & I2C_STAT_SLVPENDING_MASK)) && (--waitTimes));
if (waitTimes == 0u)
{
return kStatus_I2C_Timeout;
}
#else
} while (0u == (stat & I2C_STAT_SLVPENDING_MASK));
#endif
return stat;
}
@ -1099,6 +1168,10 @@ status_t I2C_SlaveWriteBlocking(I2C_Type *base, const uint8_t *txBuff, size_t tx
/* wait for SLVPENDING */
stat = I2C_SlavePollPending(base);
if (stat == kStatus_I2C_Timeout)
{
return kStatus_I2C_Timeout;
}
/* Get slave machine state */
slaveAddress = (((stat & I2C_STAT_SLVSTATE_MASK) >> I2C_STAT_SLVSTATE_SHIFT) == I2C_STAT_SLVST_ADDR);
@ -1118,6 +1191,10 @@ status_t I2C_SlaveWriteBlocking(I2C_Type *base, const uint8_t *txBuff, size_t tx
/* wait for SLVPENDING */
stat = I2C_SlavePollPending(base);
if (stat == kStatus_I2C_Timeout)
{
return kStatus_I2C_Timeout;
}
}
/* send bytes up to txSize */
@ -1145,6 +1222,10 @@ status_t I2C_SlaveWriteBlocking(I2C_Type *base, const uint8_t *txBuff, size_t tx
{
/* wait for SLVPENDING */
stat = I2C_SlavePollPending(base);
if (stat == kStatus_I2C_Timeout)
{
return kStatus_I2C_Timeout;
}
}
}
@ -1163,6 +1244,10 @@ status_t I2C_SlaveReadBlocking(I2C_Type *base, uint8_t *rxBuff, size_t rxSize)
/* wait for SLVPENDING */
stat = I2C_SlavePollPending(base);
if (stat == kStatus_I2C_Timeout)
{
return kStatus_I2C_Timeout;
}
/* Get slave machine state */
slaveAddress = (((stat & I2C_STAT_SLVSTATE_MASK) >> I2C_STAT_SLVSTATE_SHIFT) == I2C_STAT_SLVST_ADDR);
@ -1182,6 +1267,10 @@ status_t I2C_SlaveReadBlocking(I2C_Type *base, uint8_t *rxBuff, size_t rxSize)
/* wait for SLVPENDING */
stat = I2C_SlavePollPending(base);
if (stat == kStatus_I2C_Timeout)
{
return kStatus_I2C_Timeout;
}
}
/* receive bytes up to rxSize */
@ -1209,6 +1298,10 @@ status_t I2C_SlaveReadBlocking(I2C_Type *base, uint8_t *rxBuff, size_t rxSize)
{
/* wait for SLVPENDING */
stat = I2C_SlavePollPending(base);
if (stat == kStatus_I2C_Timeout)
{
return kStatus_I2C_Timeout;
}
}
}

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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
@ -49,10 +53,15 @@
/*! @name Driver version */
/*@{*/
/*! @brief I2C driver version 1.0.0. */
#define NXP_I2C_DRIVER_VERSION (MAKE_VERSION(1, 0, 0))
/*! @brief I2C driver version 2.0.1. */
#define FSL_I2C_DRIVER_VERSION (MAKE_VERSION(2, 0, 1))
/*@}*/
/*! @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
/* definitions for MSTCODE bits in I2C Status register STAT */
#define I2C_STAT_MSTCODE_IDLE (0) /*!< Master Idle State Code */
#define I2C_STAT_MSTCODE_RXREADY (1) /*!< Master Receive Ready State Code */
@ -77,10 +86,11 @@ enum _i2c_status
kStatus_I2C_BitError = MAKE_STATUS(kStatusGroup_FLEXCOMM_I2C, 4), /*!< Transferred bit was not seen on the bus. */
kStatus_I2C_ArbitrationLost = MAKE_STATUS(kStatusGroup_FLEXCOMM_I2C, 5), /*!< Arbitration lost error. */
kStatus_I2C_NoTransferInProgress =
MAKE_STATUS(kStatusGroup_FLEXCOMM_I2C, 7), /*!< Attempt to abort a transfer when one is not in progress. */
MAKE_STATUS(kStatusGroup_FLEXCOMM_I2C, 6), /*!< Attempt to abort a transfer when one is not in progress. */
kStatus_I2C_DmaRequestFail = MAKE_STATUS(kStatusGroup_FLEXCOMM_I2C, 7), /*!< DMA request failed. */
kStatus_I2C_StartStopError = MAKE_STATUS(kStatusGroup_FLEXCOMM_I2C, 8),
kStatus_I2C_UnexpectedState = MAKE_STATUS(kStatusGroup_FLEXCOMM_I2C, 9),
kStatus_I2C_Timeout = MAKE_STATUS(kStatusGroup_FLEXCOMM_I2C, 10), /*!< Timeout poling status flags. */
};
/*! @} */
@ -98,8 +108,10 @@ enum _i2c_status
enum _i2c_master_flags
{
kI2C_MasterPendingFlag = I2C_STAT_MSTPENDING_MASK, /*!< The I2C module is waiting for software interaction. */
kI2C_MasterArbitrationLostFlag = I2C_STAT_MSTARBLOSS_MASK, /*!< The arbitration of the bus was lost. There was collision on the bus */
kI2C_MasterStartStopErrorFlag = I2C_STAT_MSTSTSTPERR_MASK /*!< There was an error during start or stop phase of the transaction. */
kI2C_MasterArbitrationLostFlag =
I2C_STAT_MSTARBLOSS_MASK, /*!< The arbitration of the bus was lost. There was collision on the bus */
kI2C_MasterStartStopErrorFlag =
I2C_STAT_MSTSTSTPERR_MASK /*!< There was an error during start or stop phase of the transaction. */
};
/*! @brief Direction of master and slave transfers. */
@ -215,19 +227,21 @@ struct _i2c_master_handle
* @{
*/
/*!
* @brief I2C slave peripheral flags.
*
* @note These enums are meant to be OR'd together to form a bit mask.
*/
/*!
* @brief I2C slave peripheral flags.
*
* @note These enums are meant to be OR'd together to form a bit mask.
*/
enum _i2c_slave_flags
{
kI2C_SlavePendingFlag = I2C_STAT_SLVPENDING_MASK, /*!< The I2C module is waiting for software interaction. */
kI2C_SlaveNotStretching = I2C_STAT_SLVNOTSTR_MASK, /*!< Indicates whether the slave is currently stretching clock (0 = yes, 1 = no). */
kI2C_SlaveNotStretching =
I2C_STAT_SLVNOTSTR_MASK, /*!< Indicates whether the slave is currently stretching clock (0 = yes, 1 = no). */
kI2C_SlaveSelected = I2C_STAT_SLVSEL_MASK, /*!< Indicates whether the slave is selected by an address match. */
kI2C_SaveDeselected = I2C_STAT_SLVDESEL_MASK /*!< Indicates that slave was previously deselected (deselect event took place, w1c). */
kI2C_SaveDeselected =
I2C_STAT_SLVDESEL_MASK /*!< Indicates that slave was previously deselected (deselect event took place, w1c). */
};
/*! @brief I2C slave address register. */
typedef enum _i2c_slave_address_register
{
@ -621,7 +635,8 @@ static inline status_t I2C_MasterRepeatedStart(I2C_Type *base, uint8_t address,
* @param base The I2C peripheral base address.
* @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 control special behavior like suppressing start or stop, for normal transfers use kI2C_TransferDefaultFlag
* @param flags Transfer control flag to control special behavior like suppressing start or stop, for normal transfers
* use kI2C_TransferDefaultFlag
* @retval kStatus_Success Data was sent successfully.
* @retval #kStatus_I2C_Busy Another master is currently utilizing the bus.
* @retval #kStatus_I2C_Nak The slave device sent a NAK in response to a byte.
@ -635,7 +650,8 @@ status_t I2C_MasterWriteBlocking(I2C_Type *base, const void *txBuff, size_t txSi
* @param base The I2C peripheral base address.
* @param rxBuff The pointer to the data to be transferred.
* @param rxSize The length in bytes of the data to be transferred.
* @param flags Transfer control flag to control special behavior like suppressing start or stop, for normal transfers use kI2C_TransferDefaultFlag
* @param flags Transfer control flag to control special behavior like suppressing start or stop, for normal transfers
* use kI2C_TransferDefaultFlag
* @retval kStatus_Success Data was received successfully.
* @retval #kStatus_I2C_Busy Another master is currently utilizing the bus.
* @retval #kStatus_I2C_Nak The slave device sent a NAK in response to a byte.
@ -712,9 +728,9 @@ status_t I2C_MasterTransferGetCount(I2C_Type *base, i2c_master_handle_t *handle,
* @param base The I2C peripheral base address.
* @param handle Pointer to the I2C master driver handle.
* @retval kStatus_Success A transaction was successfully aborted.
* @retval #kStatus_I2C_Idle There is not a non-blocking transaction currently in progress.
* @retval #kStatus_I2C_Timeout Timeout during polling for flags.
*/
void I2C_MasterTransferAbort(I2C_Type *base, i2c_master_handle_t *handle);
status_t I2C_MasterTransferAbort(I2C_Type *base, i2c_master_handle_t *handle);
/*@}*/
@ -786,7 +802,8 @@ status_t I2C_SlaveInit(I2C_Type *base, const i2c_slave_config_t *slaveConfig, ui
* This function writes new value to Slave Address register.
*
* @param base The I2C peripheral base address.
* @param addressRegister The module supports multiple address registers. The parameter determines which one shall be changed.
* @param addressRegister The module supports multiple address registers. The parameter determines which one shall be
* changed.
* @param address The slave address to be stored to the address register for matching.
* @param addressDisable Disable matching of the specified address register.
*/

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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
@ -316,7 +320,7 @@ static status_t I2C_RunTransferStateMachineDMA(I2C_Type *base, i2c_master_dma_ha
DMA_PrepareTransfer(&xferConfig, handle->subaddrBuf, (void *)&base->MSTDAT, sizeof(uint8_t),
handle->remainingSubaddr, kDMA_MemoryToPeripheral, NULL);
DMA_SubmitTransfer(handle->dmaHandle, &xferConfig);
DMA_StartTransfer(handle->dmaHandle);
handle->remainingSubaddr = 0;
if (transfer->dataSize)
{

View File

@ -1,9 +1,12 @@
/*
* 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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
@ -46,21 +50,6 @@
* @{
*/
/*! @file */
/*! @name Driver version */
/*@{*/
/*! @brief I2S DMA driver version 2.0.0.
*
* Current version: 2.0.0
*
* Change log:
* - Version 2.0.0
* - initial version
*/
#define FSL_I2S_DMA_DRIVER_VERSION (MAKE_VERSION(2, 0, 0))
/*@}*/
/*! @brief Members not to be accessed / modified outside of the driver. */
typedef struct _i2s_dma_handle i2s_dma_handle_t;

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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

View File

@ -1,9 +1,13 @@
/*
* Copyright (c) 2013-2016, NXP Semiconductors.
* The Clear BSD License
* Copyright (c) 2016, Freescale Semiconductor, Inc.
* Copyright (c) 2017, NXP
* All rights reserved.
*
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 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.
@ -16,6 +20,7 @@
* 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
@ -90,8 +95,8 @@ typedef enum _inputmux_connection_t
kINPUTMUX_WdtOscToFreqmeas = 3U + (FREQMEAS_PMUX_ID << PMUX_SHIFT),
kINPUTMUX_32KhzOscToFreqmeas = 4U + (FREQMEAS_PMUX_ID << PMUX_SHIFT),
kINPUTMUX_MainClkToFreqmeas = 5U + (FREQMEAS_PMUX_ID << PMUX_SHIFT),
kINPUTMUX_FreqmeGpioClk_a = 5U + (FREQMEAS_PMUX_ID << PMUX_SHIFT),
kINPUTMUX_FreqmeGpioClk_b = 6U + (FREQMEAS_PMUX_ID << PMUX_SHIFT),
kINPUTMUX_FreqmeGpioClk_a = 6U + (FREQMEAS_PMUX_ID << PMUX_SHIFT),
kINPUTMUX_FreqmeGpioClk_b = 7U + (FREQMEAS_PMUX_ID << PMUX_SHIFT),
/*!< Pin Interrupt. */
kINPUTMUX_GpioPort0Pin0ToPintsel = 0U + (PINTSEL_PMUX_ID << PMUX_SHIFT),
@ -163,18 +168,18 @@ typedef enum _inputmux_connection_t
kINPUTMUX_Adc0SeqbIrqToDma = 1U + (DMA_TRIG0_PMUX_ID << PMUX_SHIFT),
kINPUTMUX_Sct0DmaReq0ToDma = 2U + (DMA_TRIG0_PMUX_ID << PMUX_SHIFT),
kINPUTMUX_Sct0DmaReq1ToDma = 3U + (DMA_TRIG0_PMUX_ID << PMUX_SHIFT),
kINPUTMUX_Ctimer0M0ToDma = 4U + (DMA_TRIG0_PMUX_ID << PMUX_SHIFT),
kINPUTMUX_Ctimer0M1ToDma = 5U + (DMA_TRIG0_PMUX_ID << PMUX_SHIFT),
kINPUTMUX_Ctimer1M0ToDma = 6U + (DMA_TRIG0_PMUX_ID << PMUX_SHIFT),
kINPUTMUX_Ctimer2M0ToDma = 7U + (DMA_TRIG0_PMUX_ID << PMUX_SHIFT),
kINPUTMUX_Ctimer2M1ToDma = 8U + (DMA_TRIG0_PMUX_ID << PMUX_SHIFT),
kINPUTMUX_Ctimer3M0ToDma = 9U + (DMA_TRIG0_PMUX_ID << PMUX_SHIFT),
kINPUTMUX_Ctimer4M0ToDma = 10U + (DMA_TRIG0_PMUX_ID << PMUX_SHIFT),
kINPUTMUX_Ctimer4M1ToDma = 11U + (DMA_TRIG0_PMUX_ID << PMUX_SHIFT),
kINPUTMUX_PinInt0ToDma = 12U + (DMA_TRIG0_PMUX_ID << PMUX_SHIFT),
kINPUTMUX_PinInt1ToDma = 13U + (DMA_TRIG0_PMUX_ID << PMUX_SHIFT),
kINPUTMUX_PinInt2ToDma = 14U + (DMA_TRIG0_PMUX_ID << PMUX_SHIFT),
kINPUTMUX_PinInt3ToDma = 15U + (DMA_TRIG0_PMUX_ID << PMUX_SHIFT),
kINPUTMUX_PinInt0ToDma = 4U + (DMA_TRIG0_PMUX_ID << PMUX_SHIFT),
kINPUTMUX_PinInt1ToDma = 5U + (DMA_TRIG0_PMUX_ID << PMUX_SHIFT),
kINPUTMUX_PinInt2ToDma = 6U + (DMA_TRIG0_PMUX_ID << PMUX_SHIFT),
kINPUTMUX_PinInt3ToDma = 7U + (DMA_TRIG0_PMUX_ID << PMUX_SHIFT),
kINPUTMUX_Ctimer0M0ToDma = 8U + (DMA_TRIG0_PMUX_ID << PMUX_SHIFT),
kINPUTMUX_Ctimer0M1ToDma = 9U + (DMA_TRIG0_PMUX_ID << PMUX_SHIFT),
kINPUTMUX_Ctimer1M0ToDma = 10U + (DMA_TRIG0_PMUX_ID << PMUX_SHIFT),
kINPUTMUX_Ctimer2M0ToDma = 11U + (DMA_TRIG0_PMUX_ID << PMUX_SHIFT),
kINPUTMUX_Ctimer2M1ToDma = 12U + (DMA_TRIG0_PMUX_ID << PMUX_SHIFT),
kINPUTMUX_Ctimer3M0ToDma = 13U + (DMA_TRIG0_PMUX_ID << PMUX_SHIFT),
kINPUTMUX_Ctimer4M0ToDma = 14U + (DMA_TRIG0_PMUX_ID << PMUX_SHIFT),
kINPUTMUX_Ctimer4M1ToDma = 15U + (DMA_TRIG0_PMUX_ID << PMUX_SHIFT),
kINPUTMUX_Otrig0ToDma = 16U + (DMA_TRIG0_PMUX_ID << PMUX_SHIFT),
kINPUTMUX_Otrig1ToDma = 17U + (DMA_TRIG0_PMUX_ID << PMUX_SHIFT),
kINPUTMUX_Otrig2ToDma = 18U + (DMA_TRIG0_PMUX_ID << PMUX_SHIFT),

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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
@ -64,75 +68,76 @@ typedef struct _iocon_group
* @brief IOCON function and mode selection definitions
* @note See the User Manual for specific modes and functions supported by the various pins.
*/
#if defined(FSL_FEATURE_IOCON_FUNC_FIELD_WIDTH) && (FSL_FEATURE_IOCON_FUNC_FIELD_WIDTH== 4)
#define IOCON_FUNC0 0x0 /*!< Selects pin function 0 */
#define IOCON_FUNC1 0x1 /*!< Selects pin function 1 */
#define IOCON_FUNC2 0x2 /*!< Selects pin function 2 */
#define IOCON_FUNC3 0x3 /*!< Selects pin function 3 */
#define IOCON_FUNC4 0x4 /*!< Selects pin function 4 */
#define IOCON_FUNC5 0x5 /*!< Selects pin function 5 */
#define IOCON_FUNC6 0x6 /*!< Selects pin function 6 */
#define IOCON_FUNC7 0x7 /*!< Selects pin function 7 */
#define IOCON_FUNC8 0x8 /*!< Selects pin function 8 */
#define IOCON_FUNC9 0x9 /*!< Selects pin function 9 */
#define IOCON_FUNC10 0xA /*!< Selects pin function 10 */
#define IOCON_FUNC11 0xB /*!< Selects pin function 11 */
#define IOCON_FUNC12 0xC /*!< Selects pin function 12 */
#define IOCON_FUNC13 0xD /*!< Selects pin function 13 */
#define IOCON_FUNC14 0xE /*!< Selects pin function 14 */
#define IOCON_FUNC15 0xF /*!< Selects pin function 15 */
#define IOCON_MODE_INACT (0x0 << 4) /*!< No addition pin function */
#define IOCON_MODE_PULLDOWN (0x1 << 4) /*!< Selects pull-down function */
#define IOCON_MODE_PULLUP (0x2 << 4) /*!< Selects pull-up function */
#define IOCON_MODE_REPEATER (0x3 << 4) /*!< Selects pin repeater function */
#define IOCON_HYS_EN (0x1 << 6) /*!< Enables hysteresis */
#define IOCON_GPIO_MODE (0x1 << 6) /*!< GPIO Mode */
#define IOCON_I2C_SLEW (0x1 << 6) /*!< I2C Slew Rate Control */
#define IOCON_INV_EN (0x1 << 7) /*!< Enables invert function on input */
#define IOCON_ANALOG_EN (0x0 << 8) /*!< Enables analog function by setting 0 to bit 7 */
#define IOCON_DIGITAL_EN (0x1 << 8) /*!< Enables digital function by setting 1 to bit 7(default) */
#define IOCON_STDI2C_EN (0x1 << 9) /*!< I2C standard mode/fast-mode */
#define IOCON_FASTI2C_EN (0x3 << 9) /*!< I2C Fast-mode Plus and high-speed slave */
#define IOCON_INPFILT_OFF (0x1 << 9) /*!< Input filter Off for GPIO pins */
#define IOCON_INPFILT_ON (0x0 << 9) /*!< Input filter On for GPIO pins */
#define IOCON_OPENDRAIN_EN (0x1 << 11) /*!< Enables open-drain function */
#define IOCON_S_MODE_0CLK (0x0 << 12) /*!< Bypass input filter */
#define IOCON_S_MODE_1CLK (0x1 << 12) /*!< Input pulses shorter than 1 filter clock are rejected */
#define IOCON_S_MODE_2CLK (0x2 << 12) /*!< Input pulses shorter than 2 filter clock2 are rejected */
#define IOCON_S_MODE_3CLK (0x3 << 12) /*!< Input pulses shorter than 3 filter clock2 are rejected */
#define IOCON_S_MODE(clks) ((clks) << 12) /*!< Select clocks for digital input filter mode */
#define IOCON_CLKDIV(div) ((div) << 14) /*!< Select peripheral clock divider for input filter sampling clock, 2^n, n=0-6 */
#if defined(FSL_FEATURE_IOCON_FUNC_FIELD_WIDTH) && (FSL_FEATURE_IOCON_FUNC_FIELD_WIDTH == 4)
#define IOCON_FUNC0 0x0 /*!< Selects pin function 0 */
#define IOCON_FUNC1 0x1 /*!< Selects pin function 1 */
#define IOCON_FUNC2 0x2 /*!< Selects pin function 2 */
#define IOCON_FUNC3 0x3 /*!< Selects pin function 3 */
#define IOCON_FUNC4 0x4 /*!< Selects pin function 4 */
#define IOCON_FUNC5 0x5 /*!< Selects pin function 5 */
#define IOCON_FUNC6 0x6 /*!< Selects pin function 6 */
#define IOCON_FUNC7 0x7 /*!< Selects pin function 7 */
#define IOCON_FUNC8 0x8 /*!< Selects pin function 8 */
#define IOCON_FUNC9 0x9 /*!< Selects pin function 9 */
#define IOCON_FUNC10 0xA /*!< Selects pin function 10 */
#define IOCON_FUNC11 0xB /*!< Selects pin function 11 */
#define IOCON_FUNC12 0xC /*!< Selects pin function 12 */
#define IOCON_FUNC13 0xD /*!< Selects pin function 13 */
#define IOCON_FUNC14 0xE /*!< Selects pin function 14 */
#define IOCON_FUNC15 0xF /*!< Selects pin function 15 */
#define IOCON_MODE_INACT (0x0 << 4) /*!< No addition pin function */
#define IOCON_MODE_PULLDOWN (0x1 << 4) /*!< Selects pull-down function */
#define IOCON_MODE_PULLUP (0x2 << 4) /*!< Selects pull-up function */
#define IOCON_MODE_REPEATER (0x3 << 4) /*!< Selects pin repeater function */
#define IOCON_HYS_EN (0x1 << 6) /*!< Enables hysteresis */
#define IOCON_GPIO_MODE (0x1 << 6) /*!< GPIO Mode */
#define IOCON_I2C_SLEW (0x0 << 6) /*!< I2C Slew Rate Control */
#define IOCON_INV_EN (0x1 << 7) /*!< Enables invert function on input */
#define IOCON_ANALOG_EN (0x0 << 8) /*!< Enables analog function by setting 0 to bit 7 */
#define IOCON_DIGITAL_EN (0x1 << 8) /*!< Enables digital function by setting 1 to bit 7(default) */
#define IOCON_STDI2C_EN (0x1 << 9) /*!< I2C standard mode/fast-mode */
#define IOCON_FASTI2C_EN (0x3 << 9) /*!< I2C Fast-mode Plus and high-speed slave */
#define IOCON_INPFILT_OFF (0x1 << 9) /*!< Input filter Off for GPIO pins */
#define IOCON_INPFILT_ON (0x0 << 9) /*!< Input filter On for GPIO pins */
#define IOCON_OPENDRAIN_EN (0x1 << 11) /*!< Enables open-drain function */
#define IOCON_S_MODE_0CLK (0x0 << 12) /*!< Bypass input filter */
#define IOCON_S_MODE_1CLK (0x1 << 12) /*!< Input pulses shorter than 1 filter clock are rejected */
#define IOCON_S_MODE_2CLK (0x2 << 12) /*!< Input pulses shorter than 2 filter clock2 are rejected */
#define IOCON_S_MODE_3CLK (0x3 << 12) /*!< Input pulses shorter than 3 filter clock2 are rejected */
#define IOCON_S_MODE(clks) ((clks) << 12) /*!< Select clocks for digital input filter mode */
#define IOCON_CLKDIV(div) \
((div) << 14) /*!< Select peripheral clock divider for input filter sampling clock, 2^n, n=0-6 */
#else
#define IOCON_FUNC0 0x0 /*!< Selects pin function 0 */
#define IOCON_FUNC1 0x1 /*!< Selects pin function 1 */
#define IOCON_FUNC2 0x2 /*!< Selects pin function 2 */
#define IOCON_FUNC3 0x3 /*!< Selects pin function 3 */
#define IOCON_FUNC4 0x4 /*!< Selects pin function 4 */
#define IOCON_FUNC5 0x5 /*!< Selects pin function 5 */
#define IOCON_FUNC6 0x6 /*!< Selects pin function 6 */
#define IOCON_FUNC7 0x7 /*!< Selects pin function 7 */
#define IOCON_MODE_INACT (0x0 << 3) /*!< No addition pin function */
#define IOCON_MODE_PULLDOWN (0x1 << 3) /*!< Selects pull-down function */
#define IOCON_MODE_PULLUP (0x2 << 3) /*!< Selects pull-up function */
#define IOCON_MODE_REPEATER (0x3 << 3) /*!< Selects pin repeater function */
#define IOCON_HYS_EN (0x1 << 5) /*!< Enables hysteresis */
#define IOCON_GPIO_MODE (0x1 << 5) /*!< GPIO Mode */
#define IOCON_I2C_SLEW (0x1 << 5) /*!< I2C Slew Rate Control */
#define IOCON_INV_EN (0x1 << 6) /*!< Enables invert function on input */
#define IOCON_ANALOG_EN (0x0 << 7) /*!< Enables analog function by setting 0 to bit 7 */
#define IOCON_DIGITAL_EN (0x1 << 7) /*!< Enables digital function by setting 1 to bit 7(default) */
#define IOCON_STDI2C_EN (0x1 << 8) /*!< I2C standard mode/fast-mode */
#define IOCON_FASTI2C_EN (0x3 << 8) /*!< I2C Fast-mode Plus and high-speed slave */
#define IOCON_INPFILT_OFF (0x1 << 8) /*!< Input filter Off for GPIO pins */
#define IOCON_INPFILT_ON (0x0 << 8) /*!< Input filter On for GPIO pins */
#define IOCON_OPENDRAIN_EN (0x1 << 10) /*!< Enables open-drain function */
#define IOCON_S_MODE_0CLK (0x0 << 11) /*!< Bypass input filter */
#define IOCON_S_MODE_1CLK (0x1 << 11) /*!< Input pulses shorter than 1 filter clock are rejected */
#define IOCON_S_MODE_2CLK (0x2 << 11) /*!< Input pulses shorter than 2 filter clock2 are rejected */
#define IOCON_S_MODE_3CLK (0x3 << 11) /*!< Input pulses shorter than 3 filter clock2 are rejected */
#define IOCON_S_MODE(clks) ((clks) << 11) /*!< Select clocks for digital input filter mode */
#define IOCON_CLKDIV(div) \
((div) << 13) /*!< Select peripheral clock divider for input filter sampling clock, 2^n, n=0-6 */
#define IOCON_FUNC0 0x0 /*!< Selects pin function 0 */
#define IOCON_FUNC1 0x1 /*!< Selects pin function 1 */
#define IOCON_FUNC2 0x2 /*!< Selects pin function 2 */
#define IOCON_FUNC3 0x3 /*!< Selects pin function 3 */
#define IOCON_FUNC4 0x4 /*!< Selects pin function 4 */
#define IOCON_FUNC5 0x5 /*!< Selects pin function 5 */
#define IOCON_FUNC6 0x6 /*!< Selects pin function 6 */
#define IOCON_FUNC7 0x7 /*!< Selects pin function 7 */
#define IOCON_MODE_INACT (0x0 << 3) /*!< No addition pin function */
#define IOCON_MODE_PULLDOWN (0x1 << 3) /*!< Selects pull-down function */
#define IOCON_MODE_PULLUP (0x2 << 3) /*!< Selects pull-up function */
#define IOCON_MODE_REPEATER (0x3 << 3) /*!< Selects pin repeater function */
#define IOCON_HYS_EN (0x1 << 5) /*!< Enables hysteresis */
#define IOCON_GPIO_MODE (0x1 << 5) /*!< GPIO Mode */
#define IOCON_I2C_SLEW (0x0 << 5) /*!< I2C Slew Rate Control */
#define IOCON_INV_EN (0x1 << 6) /*!< Enables invert function on input */
#define IOCON_ANALOG_EN (0x0 << 7) /*!< Enables analog function by setting 0 to bit 7 */
#define IOCON_DIGITAL_EN (0x1 << 7) /*!< Enables digital function by setting 1 to bit 7(default) */
#define IOCON_STDI2C_EN (0x1 << 8) /*!< I2C standard mode/fast-mode */
#define IOCON_FASTI2C_EN (0x3 << 8) /*!< I2C Fast-mode Plus and high-speed slave */
#define IOCON_INPFILT_OFF (0x1 << 8) /*!< Input filter Off for GPIO pins */
#define IOCON_INPFILT_ON (0x0 << 8) /*!< Input filter On for GPIO pins */
#define IOCON_OPENDRAIN_EN (0x1 << 10) /*!< Enables open-drain function */
#define IOCON_S_MODE_0CLK (0x0 << 11) /*!< Bypass input filter */
#define IOCON_S_MODE_1CLK (0x1 << 11) /*!< Input pulses shorter than 1 filter clock are rejected */
#define IOCON_S_MODE_2CLK (0x2 << 11) /*!< Input pulses shorter than 2 filter clock2 are rejected */
#define IOCON_S_MODE_3CLK (0x3 << 11) /*!< Input pulses shorter than 3 filter clock2 are rejected */
#define IOCON_S_MODE(clks) ((clks) << 11) /*!< Select clocks for digital input filter mode */
#define IOCON_CLKDIV(div) \
((div) << 13) /*!< Select peripheral clock divider for input filter sampling clock, 2^n, n=0-6 */
#endif
#if defined(__cplusplus)
extern "C" {

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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
@ -149,8 +153,8 @@ static bool LCDC_GetClockDivider(const lcdc_config_t *config, uint32_t srcClock_
if (((kLCDC_DisplaySingleColorSTN8Bit == config->display) && (pcd < 1U)) ||
((kLCDC_DisplayDualColorSTN8Bit == config->display) && (pcd < 4U)) ||
((kLCDC_DisplaySingleMonoSTN4Bit == config->display) && (pcd < 2U)) ||
((kLCDC_DisplaySingleMonoSTN8Bit == config->display) && (pcd < 8U)) ||
((kLCDC_DisplayDualMonoSTN4Bit == config->display) && (pcd < 8U)) ||
((kLCDC_DisplaySingleMonoSTN8Bit == config->display) && (pcd < 6U)) ||
((kLCDC_DisplayDualMonoSTN4Bit == config->display) && (pcd < 6U)) ||
((kLCDC_DisplayDualMonoSTN8Bit == config->display) && (pcd < 14U)))
{
return false;

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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
@ -102,7 +106,7 @@ typedef enum _lcdc_display
kLCDC_DisplayDualMonoSTN4Bit =
LCD_CTRL_LCDBW_MASK | LCD_CTRL_LCDDUAL_MASK, /*!< Dual-panel monochrome STN (4-bit bus interface). */
kLCDC_DisplayDualMonoSTN8Bit = LCD_CTRL_LCDBW_MASK | LCD_CTRL_LCDMONO8_MASK |
LCD_CTRL_LCDDUAL_MASK, /*!< Dual-panel monochrome STN (8-bit bus interface). */
LCD_CTRL_LCDDUAL_MASK, /*!< Dual-panel monochrome STN (8-bit bus interface). */
kLCDC_DisplaySingleColorSTN8Bit = 0U, /*!< Single-panel color STN (8-bit bus interface). */
kLCDC_DisplayDualColorSTN8Bit = LCD_CTRL_LCDDUAL_MASK, /*!< Dual-panel coor STN (8-bit bus interface). */
} lcdc_display_t;
@ -137,9 +141,9 @@ typedef struct _lcdc_config
uint8_t lineEndDelay; /*!< The panel clocks between the last pixel of line and the start of line end. */
uint32_t upperPanelAddr; /*!< LCD upper panel base address, must be double-word(64-bit) align. */
uint32_t lowerPanelAddr; /*!< LCD lower panel base address, must be double-word(64-bit) align. */
lcdc_bpp_t bpp; /*!< LCD bits per pixel. */
lcdc_bpp_t bpp; /*!< LCD bits per pixel. */
lcdc_data_format_t dataFormat; /*!< Data format. */
bool swapRedBlue; /*!< Set true to use BGR format, set false to choose RGB format. */
bool swapRedBlue; /*!< Set true to use BGR format, set false to choose RGB format. */
lcdc_display_t display; /*!< The display type. */
} lcdc_config_t;

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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
@ -835,6 +839,11 @@ void CAN0_IRQ0_DriverIRQHandler(void)
assert(s_mcanHandle[0]);
s_mcanIsr(CAN0, s_mcanHandle[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 CAN0_IRQ1_DriverIRQHandler(void)
@ -842,6 +851,11 @@ void CAN0_IRQ1_DriverIRQHandler(void)
assert(s_mcanHandle[0]);
s_mcanIsr(CAN0, s_mcanHandle[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
}
#endif
@ -851,6 +865,11 @@ void CAN1_IRQ0_DriverIRQHandler(void)
assert(s_mcanHandle[1]);
s_mcanIsr(CAN1, s_mcanHandle[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 CAN1_IRQ1_DriverIRQHandler(void)
@ -858,5 +877,10 @@ void CAN1_IRQ1_DriverIRQHandler(void)
assert(s_mcanHandle[1]);
s_mcanIsr(CAN1, s_mcanHandle[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
}
#endif

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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
@ -43,8 +47,8 @@
/*! @name Driver version */
/*@{*/
/*! @brief MCAN driver version 2.0.0. */
#define MCAN_DRIVER_VERSION (MAKE_VERSION(2, 0, 0))
/*! @brief MCAN driver version 2.0.1. */
#define MCAN_DRIVER_VERSION (MAKE_VERSION(2, 0, 1))
/*@}*/
/*! @brief MCAN transfer status. */

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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
@ -88,7 +92,7 @@ status_t PHY_Init(ENET_Type *base, uint32_t phyAddr, uint32_t srcClock_Hz)
while ((idReg != PHY_CONTROL_ID1) && (delay != 0))
{
PHY_Read(base, phyAddr, PHY_ID1_REG, &idReg);
delay --;
delay--;
}
if (!delay)
@ -118,7 +122,7 @@ status_t PHY_Init(ENET_Type *base, uint32_t phyAddr, uint32_t srcClock_Hz)
do
{
PHY_Read(base, phyAddr, PHY_SEPCIAL_CONTROL_REG, &reg);
delay --;
delay--;
} while (delay && ((reg & PHY_SPECIALCTL_AUTONEGDONE_MASK) == 0));
if (!delay)
@ -180,7 +184,7 @@ status_t PHY_Write(ENET_Type *base, uint32_t phyAddr, uint32_t phyReg, uint32_t
status_t PHY_Read(ENET_Type *base, uint32_t phyAddr, uint32_t phyReg, uint32_t *dataPtr)
{
#if defined(FSL_FEATURE_SOC_ENET_COUNT) && (FSL_FEATURE_SOC_ENET_COUNT > 0)
assert(dataPtr);
assert(dataPtr);
uint32_t counter;
@ -216,7 +220,7 @@ status_t PHY_Read(ENET_Type *base, uint32_t phyAddr, uint32_t phyReg, uint32_t *
;
*dataPtr = ENET_ReadSMIData(base);
#endif
return kStatus_Success;
return kStatus_Success;
}
status_t PHY_GetLinkStatus(ENET_Type *base, uint32_t phyAddr, bool *status)
@ -236,7 +240,7 @@ status_t PHY_GetLinkStatus(ENET_Type *base, uint32_t phyAddr, bool *status)
else
{
*status = false;
}
}
}
return result;
}
@ -272,7 +276,7 @@ status_t PHY_GetLinkSpeedDuplex(ENET_Type *base, uint32_t phyAddr, phy_speed_t *
else
{ /* 10M speed. */
*speed = kPHY_Speed10M;
}
}
}
return result;
}

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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
@ -111,7 +115,7 @@ extern "C" {
*
* This function initialize the SMI interface and initialize PHY.
* The SMI is the MII management interface between PHY and MAC, which should be
* firstly initialized before any other operation for PHY.
* firstly initialized before any other operation for PHY. The PHY initialize with auto-negotiation.
*
* @param base ENET peripheral base address.
* @param phyAddr The PHY address.

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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
@ -303,6 +307,13 @@ void PIN_INT0_DriverIRQHandler(void)
{
s_pintCallback[kPINT_PinInt0](kPINT_PinInt0, pmstatus);
}
/* Clear Pin interrupt after callback */
PINT_PinInterruptClrStatus(PINT, kPINT_PinInt0);
/* 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 (FSL_FEATURE_PINT_NUMBER_OF_CONNECTED_OUTPUTS > 1U)
@ -317,6 +328,13 @@ void PIN_INT1_DriverIRQHandler(void)
{
s_pintCallback[kPINT_PinInt1](kPINT_PinInt1, pmstatus);
}
/* Clear Pin interrupt after callback */
PINT_PinInterruptClrStatus(PINT, kPINT_PinInt1);
/* 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
@ -332,6 +350,13 @@ void PIN_INT2_DriverIRQHandler(void)
{
s_pintCallback[kPINT_PinInt2](kPINT_PinInt2, pmstatus);
}
/* Clear Pin interrupt after callback */
PINT_PinInterruptClrStatus(PINT, kPINT_PinInt2);
/* 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
@ -347,6 +372,13 @@ void PIN_INT3_DriverIRQHandler(void)
{
s_pintCallback[kPINT_PinInt3](kPINT_PinInt3, pmstatus);
}
/* Clear Pin interrupt after callback */
PINT_PinInterruptClrStatus(PINT, kPINT_PinInt3);
/* 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
@ -362,6 +394,13 @@ void PIN_INT4_DriverIRQHandler(void)
{
s_pintCallback[kPINT_PinInt4](kPINT_PinInt4, pmstatus);
}
/* Clear Pin interrupt after callback */
PINT_PinInterruptClrStatus(PINT, kPINT_PinInt4);
/* 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
@ -377,6 +416,13 @@ void PIN_INT5_DriverIRQHandler(void)
{
s_pintCallback[kPINT_PinInt5](kPINT_PinInt5, pmstatus);
}
/* Clear Pin interrupt after callback */
PINT_PinInterruptClrStatus(PINT, kPINT_PinInt5);
/* 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
@ -392,6 +438,13 @@ void PIN_INT6_DriverIRQHandler(void)
{
s_pintCallback[kPINT_PinInt6](kPINT_PinInt6, pmstatus);
}
/* Clear Pin interrupt after callback */
PINT_PinInterruptClrStatus(PINT, kPINT_PinInt6);
/* 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
@ -407,5 +460,12 @@ void PIN_INT7_DriverIRQHandler(void)
{
s_pintCallback[kPINT_PinInt7](kPINT_PinInt7, pmstatus);
}
/* Clear Pin interrupt after callback */
PINT_PinInterruptClrStatus(PINT, kPINT_PinInt7);
/* 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

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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

View File

@ -1,10 +1,13 @@
/*
* The Clear BSD License
* Copyright (c) 2016, Freescale Semiconductor, Inc.
* Copyright (c) 2016, NXP
* All rights reserved.
*
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 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.
@ -17,6 +20,7 @@
* 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

View File

@ -1,10 +1,13 @@
/*
* The Clear BSD License
* Copyright (c) 2016, Freescale Semiconductor, Inc.
* Copyright (c) 2016, NXP
* All rights reserved.
*
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 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.
@ -17,6 +20,7 @@
* 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
@ -37,6 +41,12 @@
* Definitions
******************************************************************************/
/*! @name Driver version */
/*@{*/
/*! @brief power driver version 2.0.0. */
#define FSL_POWER_DRIVER_VERSION (MAKE_VERSION(2, 0, 0))
/*@}*/
#define MAKE_PD_BITS(reg, slot) ((reg << 8) | slot)
#define PDRCFG0 0x0U
#define PDRCFG1 0x1U

View File

@ -1,10 +1,13 @@
/*
* The Clear BSD License
* Copyright (c) 2016, Freescale Semiconductor, Inc.
* Copyright (c) 2016, NXP
* All rights reserved.
*
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 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.
@ -17,6 +20,7 @@
* 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

View File

@ -1,10 +1,13 @@
/*
* The Clear BSD License
* Copyright (c) 2016, Freescale Semiconductor, Inc.
* Copyright (c) 2016, NXP
* All rights reserved.
*
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 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.
@ -17,6 +20,7 @@
* 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
@ -47,6 +51,12 @@
* Definitions
******************************************************************************/
/*! @name Driver version */
/*@{*/
/*! @brief reset driver version 2.0.0. */
#define FSL_RESET_DRIVER_VERSION (MAKE_VERSION(2, 0, 0))
/*@}*/
/*!
* @brief Enumeration for peripheral reset control bits
*

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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
@ -215,8 +219,10 @@ void RTC_Init(RTC_Type *base)
/* Make sure the reset bit is cleared */
base->CTRL &= ~RTC_CTRL_SWRESET_MASK;
#if !(defined(FSL_FEATURE_RTC_HAS_NO_OSC_PD) && FSL_FEATURE_RTC_HAS_NO_OSC_PD)
/* Make sure the RTC OSC is powered up */
base->CTRL &= ~RTC_CTRL_RTC_OSC_PD_MASK;
#endif
}
status_t RTC_SetDatetime(RTC_Type *base, const rtc_datetime_t *datetime)

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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
@ -532,4 +536,9 @@ void SCTIMER_EventHandleIRQ(SCT_Type *base)
void SCT0_IRQHandler(void)
{
s_sctimerIsr(SCT0);
/* 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
}

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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
@ -37,6 +41,25 @@
/* Typedef for interrupt handler. */
typedef void (*sdif_isr_t)(SDIF_Type *base, sdif_handle_t *handle);
/*! @brief convert the name here, due to RM use SDIO */
#define SDIF_DriverIRQHandler SDIO_DriverIRQHandler
/*! @brief define the controller support sd/sdio card version 2.0 */
#define SDIF_SUPPORT_SD_VERSION (0x20)
/*! @brief define the controller support mmc card version 4.4 */
#define SDIF_SUPPORT_MMC_VERSION (0x44)
/*! @brief define the timeout counter */
#define SDIF_TIMEOUT_VALUE (65535U)
/*! @brief this value can be any value */
#define SDIF_POLL_DEMAND_VALUE (0xFFU)
/*! @brief DMA descriptor buffer1 size */
#define SDIF_DMA_DESCRIPTOR_BUFFER1_SIZE(x) (x & 0x1FFFU)
/*! @brief DMA descriptor buffer2 size */
#define SDIF_DMA_DESCRIPTOR_BUFFER2_SIZE(x) ((x & 0x1FFFU) << 13U)
/*! @brief RX water mark value */
#define SDIF_RX_WATERMARK (15U)
/*! @brief TX water mark value */
#define SDIF_TX_WATERMARK (16U)
/*******************************************************************************
* Prototypes
******************************************************************************/
@ -141,9 +164,18 @@ static status_t SDIF_WriteDataPortBlocking(SDIF_Type *base, sdif_data_t *data);
/*
* @brief handle sdio interrupt
* This function will call the SDIO interrupt callback
* @param SDIF base address
* @param SDIF handle
*/
static void SDIF_TransferHandleSDIOInterrupt(sdif_handle_t *handle);
static void SDIF_TransferHandleSDIOInterrupt(SDIF_Type *base, sdif_handle_t *handle);
/*
* @brief handle card detect
* This function will call the cardInserted callback
* @param SDIF base addres
* @param SDIF handle
*/
static void SDIF_TransferHandleCardDetect(SDIF_Type *base, sdif_handle_t *handle);
/*******************************************************************************
* Variables
@ -288,19 +320,18 @@ static status_t SDIF_WaitCommandDone(SDIF_Type *base, sdif_command_t *command)
do
{
status = SDIF_GetInterruptStatus(base);
if ((status &
(kSDIF_ResponseError | kSDIF_ResponseCRCError | kSDIF_ResponseTimeout | kSDIF_HardwareLockError)) != 0u)
{
SDIF_ClearInterruptStatus(base, status & (kSDIF_ResponseError | kSDIF_ResponseCRCError |
kSDIF_ResponseTimeout | kSDIF_HardwareLockError));
return kStatus_SDIF_SendCmdFail;
}
} while ((status & kSDIF_CommandDone) != kSDIF_CommandDone);
/* clear the command done bit */
SDIF_ClearInterruptStatus(base, status & kSDIF_CommandDone);
return SDIF_ReadCommandResponse(base, command);
/* clear interrupt status flag first */
SDIF_ClearInterruptStatus(base, status);
if ((status & (kSDIF_ResponseError | kSDIF_ResponseCRCError | kSDIF_ResponseTimeout | kSDIF_HardwareLockError)) !=
0u)
{
return kStatus_SDIF_SendCmdFail;
}
else
{
return SDIF_ReadCommandResponse(base, command);
}
}
status_t SDIF_ReleaseDMADescriptor(SDIF_Type *base, sdif_dma_config_t *dmaConfig)
@ -675,68 +706,35 @@ bool SDIF_SendCardActive(SDIF_Type *base, uint32_t timeout)
void SDIF_ConfigClockDelay(uint32_t target_HZ, uint32_t divider)
{
/*config the clock delay and pharse shift
*should config the clk_in_drv,
*clk_in_sample to meet the min hold and
*setup time
*/
if (target_HZ <= kSDIF_Freq400KHZ)
uint32_t sdioClkCtrl = SYSCON->SDIOCLKCTRL;
if (target_HZ >= SDIF_CLOCK_RANGE_NEED_DELAY)
{
/*min hold time:5ns
* min setup time: 5ns
* delay = (x+1)*250ps
*/
SYSCON->SDIOCLKCTRL = SYSCON_SDIOCLKCTRL_CCLK_SAMPLE_DELAY_ACTIVE_MASK |
SYSCON_SDIOCLKCTRL_CCLK_SAMPLE_DELAY(SDIF_INDENTIFICATION_MODE_SAMPLE_DELAY) |
SYSCON_SDIOCLKCTRL_CCLK_DRV_DELAY_ACTIVE_MASK |
SYSCON_SDIOCLKCTRL_CCLK_DRV_DELAY(SDIF_INDENTIFICATION_MODE_DRV_DELAY);
}
else if (target_HZ >= kSDIF_Freq50MHZ)
{
/*
* user need to pay attention to this parameter
* can be change the setting for you card and board
* min hold time:2ns
* min setup time: 6ns
* delay = (x+1)*250ps
*/
SYSCON->SDIOCLKCTRL = SYSCON_SDIOCLKCTRL_CCLK_SAMPLE_DELAY_ACTIVE_MASK |
SYSCON_SDIOCLKCTRL_CCLK_SAMPLE_DELAY(SDIF_HIGHSPEED_50MHZ_SAMPLE_DELAY) |
SYSCON_SDIOCLKCTRL_CCLK_DRV_DELAY_ACTIVE_MASK |
SYSCON_SDIOCLKCTRL_CCLK_DRV_DELAY(SDIF_HIGHSPEED_50MHZ_DRV_DELAY);
/* means the input clock = 2 * card clock,
* can use clock pharse shift tech
*/
if (divider == 1U)
{
SYSCON->SDIOCLKCTRL |= SYSCON_SDIOCLKCTRL_PHASE_ACTIVE_MASK |
SYSCON_SDIOCLKCTRL_CCLK_SAMPLE_PHASE(kSDIF_ClcokPharseShift90) |
SYSCON_SDIOCLKCTRL_CCLK_DRV_PHASE(kSDIF_ClcokPharseShift180);
#if defined(SDIF_HIGHSPEED_SAMPLE_PHASE_SHIFT) && (SDIF_HIGHSPEED_SAMPLE_PHASE_SHIFT != 0U)
sdioClkCtrl |= SYSCON_SDIOCLKCTRL_PHASE_ACTIVE_MASK |
SYSCON_SDIOCLKCTRL_CCLK_SAMPLE_PHASE(SDIF_HIGHSPEED_SAMPLE_PHASE_SHIFT);
#endif
#if defined(SDIF_HIGHSPEED_DRV_PHASE_SHIFT) && (SDIF_HIGHSPEED_DRV_PHASE_SHIFT != 0U)
sdioClkCtrl |= SYSCON_SDIOCLKCTRL_PHASE_ACTIVE_MASK |
SYSCON_SDIOCLKCTRL_CCLK_DRV_PHASE(SDIF_HIGHSPEED_DRV_PHASE_SHIFT);
#endif
}
}
else
{
/*
* user need to pay attention to this parameter
* can be change the setting for you card and board
* min hold time:5ns
* min setup time: 5ns
* delay = (x+1)*250ps
*/
SYSCON->SDIOCLKCTRL = SYSCON_SDIOCLKCTRL_CCLK_SAMPLE_DELAY_ACTIVE_MASK |
SYSCON_SDIOCLKCTRL_CCLK_SAMPLE_DELAY(SDIF_HIGHSPEED_25MHZ_SAMPLE_DELAY) |
SYSCON_SDIOCLKCTRL_CCLK_DRV_DELAY_ACTIVE_MASK |
SYSCON_SDIOCLKCTRL_CCLK_DRV_DELAY(SDIF_HIGHSPEED_25MHZ_DRV_DELAY);
/* means the input clock = 2 * card clock,
* can use clock pharse shift tech
*/
if (divider == 1U)
else
{
SYSCON->SDIOCLKCTRL |= SYSCON_SDIOCLKCTRL_PHASE_ACTIVE_MASK |
SYSCON_SDIOCLKCTRL_CCLK_SAMPLE_PHASE(kSDIF_ClcokPharseShift90) |
SYSCON_SDIOCLKCTRL_CCLK_DRV_PHASE(kSDIF_ClcokPharseShift90);
#ifdef SDIF_HIGHSPEED_SAMPLE_DELAY
sdioClkCtrl |= SYSCON_SDIOCLKCTRL_CCLK_SAMPLE_DELAY_ACTIVE_MASK |
SYSCON_SDIOCLKCTRL_CCLK_SAMPLE_DELAY(SDIF_HIGHSPEED_SAMPLE_DELAY);
#endif
#ifdef SDIF_HIGHSPEED_DRV_DELAY
sdioClkCtrl |= SYSCON_SDIOCLKCTRL_CCLK_DRV_DELAY_ACTIVE_MASK |
SYSCON_SDIOCLKCTRL_CCLK_DRV_DELAY(SDIF_HIGHSPEED_DRV_DELAY);
#endif
}
}
SYSCON->SDIOCLKCTRL = sdioClkCtrl;
}
uint32_t SDIF_SetCardClock(SDIF_Type *base, uint32_t srcClock_Hz, uint32_t target_HZ)
@ -1098,7 +1096,7 @@ void SDIF_TransferCreateHandle(SDIF_Type *base,
handle->callback.DMADesUnavailable = callback->DMADesUnavailable;
handle->callback.CommandReload = callback->CommandReload;
handle->callback.TransferComplete = callback->TransferComplete;
handle->callback.cardInserted = callback->cardInserted;
handle->userData = userData;
/* Save the handle in global variables to support the double weak mechanism. */
@ -1130,26 +1128,32 @@ static void SDIF_TransferHandleCommand(SDIF_Type *base, sdif_handle_t *handle, u
{
assert(handle->command);
/* transfer error */
if (interruptFlags & (kSDIF_ResponseError | kSDIF_ResponseCRCError | kSDIF_ResponseTimeout))
{
handle->callback.TransferComplete(base, handle, kStatus_SDIF_SendCmdFail, handle->userData);
}
/* cmd buffer full, in this condition user need re-send the command */
else if (interruptFlags & kSDIF_HardwareLockError)
if (interruptFlags & kSDIF_HardwareLockError)
{
if (handle->callback.CommandReload)
{
handle->callback.CommandReload();
handle->callback.CommandReload(base, handle->userData);
}
}
/* transfer command success */
/* transfer command done */
else
{
SDIF_ReadCommandResponse(base, handle->command);
if (((handle->data) == NULL) && (handle->callback.TransferComplete))
if ((kSDIF_CommandDone & interruptFlags) != 0U)
{
handle->callback.TransferComplete(base, handle, kStatus_Success, handle->userData);
/* transfer error */
if (interruptFlags & (kSDIF_ResponseError | kSDIF_ResponseCRCError | kSDIF_ResponseTimeout))
{
handle->callback.TransferComplete(base, handle, kStatus_SDIF_SendCmdFail, handle->userData);
}
else
{
SDIF_ReadCommandResponse(base, handle->command);
if (((handle->data) == NULL) && (handle->callback.TransferComplete))
{
handle->callback.TransferComplete(base, handle, kStatus_Success, handle->userData);
}
}
}
}
}
@ -1217,7 +1221,7 @@ static void SDIF_TransferHandleDMA(SDIF_Type *base, sdif_handle_t *handle, uint3
{
if (handle->callback.DMADesUnavailable)
{
handle->callback.DMADesUnavailable();
handle->callback.DMADesUnavailable(base, handle->userData);
}
}
else if ((interruptFlags & (kSDIF_AbnormalInterruptSummary | kSDIF_DMACardErrorSummary)) &&
@ -1232,11 +1236,29 @@ static void SDIF_TransferHandleDMA(SDIF_Type *base, sdif_handle_t *handle, uint3
}
}
static void SDIF_TransferHandleSDIOInterrupt(sdif_handle_t *handle)
static void SDIF_TransferHandleSDIOInterrupt(SDIF_Type *base, sdif_handle_t *handle)
{
if (handle->callback.SDIOInterrupt != NULL)
{
handle->callback.SDIOInterrupt();
handle->callback.SDIOInterrupt(base, handle->userData);
}
}
static void SDIF_TransferHandleCardDetect(SDIF_Type *base, sdif_handle_t *handle)
{
if (SDIF_DetectCardInsert(base, false))
{
if ((handle->callback.cardInserted) != NULL)
{
handle->callback.cardInserted(base, handle->userData);
}
}
else
{
if ((handle->callback.cardRemoved) != NULL)
{
handle->callback.cardRemoved(base, handle->userData);
}
}
}
@ -1262,12 +1284,16 @@ static void SDIF_TransferHandleIRQ(SDIF_Type *base, sdif_handle_t *handle)
}
if (interruptFlags & kSDIF_SDIOInterrupt)
{
SDIF_TransferHandleSDIOInterrupt(handle);
SDIF_TransferHandleSDIOInterrupt(base, handle);
}
if (dmaInterruptFlags & kSDIF_DMAAllStatus)
{
SDIF_TransferHandleDMA(base, handle, dmaInterruptFlags);
}
if (interruptFlags & kSDIF_CardDetect)
{
SDIF_TransferHandleCardDetect(base, handle);
}
SDIF_ClearInterruptStatus(base, interruptFlags);
SDIF_ClearInternalDMAStatus(base, dmaInterruptFlags);
@ -1289,5 +1315,10 @@ void SDIF_DriverIRQHandler(void)
assert(s_sdifHandle[0]);
s_sdifIsr(SDIF, s_sdifHandle[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
}
#endif

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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
@ -37,40 +41,56 @@
* @{
*/
/******************************************************************************
/**********************************
* Definitions.
*****************************************************************************/
/*! @name Driver version */
/*@{*/
/*! @brief Driver version 2.0.1. */
#define FSL_SDIF_DRIVER_VERSION (MAKE_VERSION(2U, 0U, 1U))
/*! @brief Driver version 2.0.4. */
#define FSL_SDIF_DRIVER_VERSION (MAKE_VERSION(2U, 0U, 4U))
/*@}*/
#define SDIF_DriverIRQHandler SDIO_DriverIRQHandler /*!< convert the name here, due to RM use SDIO */
#define SDIF_SUPPORT_SD_VERSION (0x20) /*!< define the controller support sd/sdio card version 2.0 */
#define SDIF_SUPPORT_MMC_VERSION (0x44) /*!< define the controller support mmc card version 4.4 */
#define SDIF_TIMEOUT_VALUE (65535U) /*!< define the timeout counter */
#define SDIF_POLL_DEMAND_VALUE (0xFFU) /*!< this value can be any value */
#define SDIF_DMA_DESCRIPTOR_BUFFER1_SIZE(x) (x & 0x1FFFU) /*!< DMA descriptor buffer1 size */
#define SDIF_DMA_DESCRIPTOR_BUFFER2_SIZE(x) ((x & 0x1FFFU) << 13U) /*!<DMA descriptor buffer2 size */
#define SDIF_RX_WATERMARK (15U) /*!<RX water mark value */
#define SDIF_TX_WATERMARK (16U) /*!<TX water mark value */
/*! @brief SDIOCLKCTRL setting
* below clock delay setting should meet you board layout
* user can change it when you meet timing mismatch issue
* such as: response error/CRC error and so on
* Below clock delay setting should depend on specific platform, so
* it can be redefined when timing mismatch issue occur.
* Such as: response error/CRC error and so on
*/
#define SDIF_INDENTIFICATION_MODE_SAMPLE_DELAY (0X17U)
#define SDIF_INDENTIFICATION_MODE_DRV_DELAY (0X17U)
#define SDIF_HIGHSPEED_25MHZ_SAMPLE_DELAY (0x10U)
#define SDIF_HIGHSPEED_25MHZ_DRV_DELAY (0x10U)
#define SDIF_HIGHSPEED_50MHZ_SAMPLE_DELAY (0x1FU)
#define SDIF_HIGHSPEED_50MHZ_DRV_DELAY (0x1FU)
/*! @brief clock range value which need to add delay to avoid timing issue */
#ifndef SDIF_CLOCK_RANGE_NEED_DELAY
#define SDIF_CLOCK_RANGE_NEED_DELAY (50000000U)
#endif
/*
* Fixed delay configuration
* min hold time:2ns
* min setup time: 6ns
* delay = (x+1)*250ps
*/
/*! @brief High speed mode clk_sample fixed delay*/
#ifndef SDIF_HIGHSPEED_SAMPLE_DELAY
#define SDIF_HIGHSPEED_SAMPLE_DELAY (0U)
#endif
/*! @brief High speed mode clk_drv fixed delay */
#ifndef SDIF_HIGHSPEED_DRV_DELAY
#define SDIF_HIGHSPEED_DRV_DELAY (0x1FU)
#endif
/*
* Pharse shift delay configuration
* 0 degree: no delay
* 90 degree: 0.25/source clk value
* 180 degree: 0.50/source clk value
* 270 degree: 0.75/source clk value
*/
/*! @brief High speed mode clk_sample pharse shift */
#ifndef SDIF_HIGHSPEED_SAMPLE_PHASE_SHIFT
#define SDIF_HIGHSPEED_SAMPLE_PHASE_SHIFT (0U)
#endif
/*! @brief High speed mode clk_drv pharse shift */
#ifndef SDIF_HIGHSPEED_DRV_PHASE_SHIFT
#define SDIF_HIGHSPEED_DRV_PHASE_SHIFT (1U) /* 90 degrees clk_drv pharse delay */
#endif
/*! @brief SDIF status */
enum _sdif_status
@ -257,22 +277,6 @@ typedef enum _sdif_dma_mode
kSDIF_DualDMAMode = 0x02U, /* dual mode is one descriptor with two buffer */
} sdif_dma_mode_t;
/*! @brief define the card work freq mode */
enum _sdif_card_freq
{
kSDIF_Freq50MHZ = 50000000U, /*!< 50MHZ mode*/
kSDIF_Freq400KHZ = 400000U, /*!< identificatioin mode*/
};
/*! @brief define the clock pharse shift */
enum _sdif_clock_pharse_shift
{
kSDIF_ClcokPharseShift0, /*!< clock pharse shift 0*/
kSDIF_ClcokPharseShift90, /*!< clock pharse shift 90*/
kSDIF_ClcokPharseShift180, /*!< clock pharse shift 180*/
kSDIF_ClcokPharseShift270, /*!< clock pharse shift 270*/
};
/*! @brief define the internal DMA descriptor */
typedef struct _sdif_dma_descriptor
{
@ -368,9 +372,11 @@ typedef struct _sdif_capability
/*! @brief sdif callback functions. */
typedef struct _sdif_transfer_callback
{
void (*SDIOInterrupt)(void); /*!< SDIO card interrupt occurs */
void (*DMADesUnavailable)(void); /*!< DMA descriptor unavailable */
void (*CommandReload)(void); /*!< command buffer full,need re-load */
void (*cardInserted)(SDIF_Type *base, void *userData); /*!< card insert call back */
void (*cardRemoved)(SDIF_Type *base, void *userData); /*!< card remove call back */
void (*SDIOInterrupt)(SDIF_Type *base, void *userData); /*!< SDIO card interrupt occurs */
void (*DMADesUnavailable)(SDIF_Type *base, void *userData); /*!< DMA descriptor unavailable */
void (*CommandReload)(SDIF_Type *base, void *userData); /*!< command buffer full,need re-load */
void (*TransferComplete)(SDIF_Type *base,
void *handle,
status_t status,
@ -448,17 +454,18 @@ bool SDIF_SendCardActive(SDIF_Type *base, uint32_t timeout);
* @brief SDIF module detect card insert status function.
* @param base SDIF peripheral base address.
* @param data3 indicate use data3 as card insert detect pin
* will return the data3 PIN status in this condition
* @retval 1 card is inserted
* 0 card is removed
*/
static inline uint32_t SDIF_DetectCardInsert(SDIF_Type *base, bool data3)
{
if (data3)
{
return base->STATUS & SDIF_STATUS_DATA_3_STATUS_MASK;
return (base->STATUS & SDIF_STATUS_DATA_3_STATUS_MASK) == SDIF_STATUS_DATA_3_STATUS_MASK ? 1U : 0U;
}
else
{
return base->CDETECT & SDIF_CDETECT_CARD_DETECT_MASK;
return (base->CDETECT & SDIF_CDETECT_CARD_DETECT_MASK) == 0U ? 1U : 0U;
}
}

View File

@ -0,0 +1,489 @@
/*
* The Clear BSD License
* Copyright (c) 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_sha.h"
/*******************************************************************************
* Definitions
*******************************************************************************/
/*!< SHA-1 and SHA-256 block size */
#define SHA_BLOCK_SIZE 64
/*!< Use standard C library memcpy */
#define sha_memcpy memcpy
/*! Internal states of the HASH creation process */
typedef enum _sha_algo_state
{
kSHA_HashInit = 1u, /*!< Init state, the NEW bit in SHA Control register has not been written yet. */
kSHA_HashUpdate, /*!< Update state, DIGEST registers contain running hash, NEW bit in SHA control register has been
written. */
} sha_algo_state_t;
/*! 64-byte block represented as byte array of 16 32-bit words */
typedef union _sha_hash_block
{
uint32_t w[SHA_BLOCK_SIZE / 4]; /*!< array of 32-bit words */
uint8_t b[SHA_BLOCK_SIZE]; /*!< byte array */
} sha_block_t;
/*! internal sha context structure */
typedef struct _sha_ctx_internal
{
sha_block_t blk; /*!< memory buffer. only full 64-byte blocks are written to SHA during hash updates */
size_t blksz; /*!< number of valid bytes in memory buffer */
sha_algo_t algo; /*!< selected algorithm from the set of supported algorithms */
sha_algo_state_t state; /*!< finite machine state of the hash software process */
size_t fullMessageSize; /*!< track message size during SHA_Update(). The value is used for padding. */
} sha_ctx_internal_t;
/*!< SHA-1 and SHA-256 digest length in bytes */
enum _sha_digest_len
{
kSHA_OutLenSha1 = 20u,
kSHA_OutLenSha256 = 32u,
};
/*!< macro for checking build time condition. It is used to assure the sha_ctx_internal_t can fit into sha_ctx_t */
#define BUILD_ASSERT(condition, msg) extern int msg[1 - 2 * (!(condition))] __attribute__((unused))
/*******************************************************************************
* Code
******************************************************************************/
/*!
* @brief LDM to SHA engine INDATA and ALIAS registers.
*
* This function writes 16 words starting from the src address (must be word aligned)
* to the dst address. Dst address does not increment (destination is peripheral module register INDATA).
* Src address increments to load 16 consecutive words.
*
* @param dst peripheral register address (word aligned)
* @param src address of the input 512-bit block (16 words) (word aligned)
*
*/
__STATIC_INLINE void sha_ldm_stm_16_words(volatile uint32_t *dst, const uint32_t *src)
{
for (int i = 0; i < 8; i++)
{
dst[i] = src[i];
}
src += 8u;
for (int i = 0; i < 8; i++)
{
dst[i] = src[i];
}
}
/*!
* @brief Swap bytes withing 32-bit word.
*
* This function changes endianess of a 32-bit word.
*
* @param in 32-bit unsigned integer
* @return 32-bit unsigned integer with different endianess (big endian to little endian and vice versa).
*/
static uint32_t swap_bytes(uint32_t in)
{
return (((in & 0x000000ffu) << 24) | ((in & 0x0000ff00u) << 8) | ((in & 0x00ff0000u) >> 8) |
((in & 0xff000000u) >> 24));
}
/*!
* @brief Check validity of algoritm.
*
* This function checks the validity of input argument.
*
* @param algo Tested algorithm value.
* @return kStatus_Success if valid, kStatus_InvalidArgument otherwise.
*/
static status_t sha_check_input_alg(sha_algo_t algo)
{
if ((algo != kSHA_Sha1) && (algo != kSHA_Sha256))
{
return kStatus_InvalidArgument;
}
return kStatus_Success;
}
/*!
* @brief Check validity of input arguments.
*
* This function checks the validity of input arguments.
*
* @param base SHA peripheral base address.
* @param ctx Memory buffer given by user application where the SHA_Init/SHA_Update/SHA_Finish store context.
* @param algo Tested algorithm value.
* @return kStatus_Success if valid, kStatus_InvalidArgument otherwise.
*/
static status_t sha_check_input_args(SHA_Type *base, sha_ctx_t *ctx, sha_algo_t algo)
{
/* Check validity of input algorithm */
if (kStatus_Success != sha_check_input_alg(algo))
{
return kStatus_InvalidArgument;
}
if ((NULL == ctx) || (NULL == base))
{
return kStatus_InvalidArgument;
}
return kStatus_Success;
}
/*!
* @brief Check validity of internal software context.
*
* This function checks if the internal context structure looks correct.
*
* @param ctxInternal Internal context.
* @param message Input message address.
* @return kStatus_Success if valid, kStatus_InvalidArgument otherwise.
*/
static status_t sha_check_context(sha_ctx_internal_t *ctxInternal, const uint8_t *message)
{
if ((NULL == message) || (NULL == ctxInternal) || (kStatus_Success != sha_check_input_alg(ctxInternal->algo)))
{
return kStatus_InvalidArgument;
}
return kStatus_Success;
}
/*!
* @brief Initialize the SHA engine for new hash.
*
* This function sets NEW and MODE fields in SHA Control register to start new hash.
*
* @param base SHA peripheral base address.
* @param ctxInternal Internal context.
*/
static void sha_engine_init(SHA_Type *base, sha_ctx_internal_t *ctxInternal)
{
uint32_t shaCtrl;
if (kSHA_Sha1 == ctxInternal->algo)
{
shaCtrl = SHA_CTRL_MODE(1) | SHA_CTRL_NEW(1);
}
else
{
shaCtrl = SHA_CTRL_MODE(2) | SHA_CTRL_NEW(1);
}
base->CTRL = shaCtrl;
}
/*!
* @brief Load 512-bit block (16 words) into SHA engine.
*
* This function aligns the input block and moves it into SHA engine INDATA.
* CPU polls the WAITING bit and then moves data by using LDM and STM instructions.
*
* @param base SHA peripheral base address.
* @param blk 512-bit block
*/
static void sha_one_block(SHA_Type *base, const uint8_t *blk)
{
uint32_t temp[SHA_BLOCK_SIZE / sizeof(uint32_t)];
const uint32_t *actBlk;
/* make sure the 512-bit block is word aligned */
if ((uintptr_t)blk & 0x3u)
{
sha_memcpy(temp, blk, SHA_BLOCK_SIZE);
actBlk = (const uint32_t *)(uintptr_t)temp;
}
else
{
actBlk = (const uint32_t *)(uintptr_t)blk;
}
/* poll waiting. */
while (0 == (base->STATUS & SHA_STATUS_WAITING_MASK))
{
}
/* feed INDATA (and ALIASes). use STM instruction. */
sha_ldm_stm_16_words(&base->INDATA, actBlk);
}
/*!
* @brief Adds message to current hash.
*
* This function merges the message to fill the internal buffer, empties the internal buffer if
* it becomes full, then process all remaining message data.
*
*
* @param base SHA peripheral base address.
* @param ctxInternal Internal context.
* @param message Input message.
* @param messageSize Size of input message in bytes.
* @return kStatus_Success.
*/
static status_t sha_process_message_data(SHA_Type *base,
sha_ctx_internal_t *ctxInternal,
const uint8_t *message,
size_t messageSize)
{
/* first fill the internal buffer to full block */
size_t toCopy = SHA_BLOCK_SIZE - ctxInternal->blksz;
sha_memcpy(&ctxInternal->blk.b[ctxInternal->blksz], message, toCopy);
message += toCopy;
messageSize -= toCopy;
/* process full internal block */
sha_one_block(base, &ctxInternal->blk.b[0]);
/* process all full blocks in message[] */
while (messageSize >= SHA_BLOCK_SIZE)
{
sha_one_block(base, message);
message += SHA_BLOCK_SIZE;
messageSize -= SHA_BLOCK_SIZE;
}
/* copy last incomplete message bytes into internal block */
sha_memcpy(&ctxInternal->blk.b[0], message, messageSize);
ctxInternal->blksz = messageSize;
return kStatus_Success;
}
/*!
* @brief Finalize the running hash to make digest.
*
* This function empties the internal buffer, adds padding bits, and generates final digest.
*
* @param base SHA peripheral base address.
* @param ctxInternal Internal context.
* @return kStatus_Success.
*/
static status_t sha_finalize(SHA_Type *base, sha_ctx_internal_t *ctxInternal)
{
sha_block_t lastBlock;
memset(&lastBlock, 0, sizeof(sha_block_t));
/* this is last call, so need to flush buffered message bytes along with padding */
if (ctxInternal->blksz <= 55u)
{
/* last data is 440 bits or less. */
sha_memcpy(&lastBlock.b[0], &ctxInternal->blk.b[0], ctxInternal->blksz);
lastBlock.b[ctxInternal->blksz] = (uint8_t)0x80U;
lastBlock.w[SHA_BLOCK_SIZE / 4 - 1] = swap_bytes(8u * ctxInternal->fullMessageSize);
sha_one_block(base, &lastBlock.b[0]);
}
else
{
if (ctxInternal->blksz < SHA_BLOCK_SIZE)
{
ctxInternal->blk.b[ctxInternal->blksz] = (uint8_t)0x80U;
for (uint32_t i = ctxInternal->blksz + 1u; i < SHA_BLOCK_SIZE; i++)
{
ctxInternal->blk.b[i] = 0;
}
}
else
{
lastBlock.b[0] = (uint8_t)0x80U;
}
sha_one_block(base, &ctxInternal->blk.b[0]);
lastBlock.w[SHA_BLOCK_SIZE / 4 - 1] = swap_bytes(8u * ctxInternal->fullMessageSize);
sha_one_block(base, &lastBlock.b[0]);
}
/* poll wait for final digest */
while (0 == (base->STATUS & SHA_STATUS_DIGEST_MASK))
{
}
return kStatus_Success;
}
/*!
* @brief Read DIGEST registers.
*
* This function copies DIGEST to output buffer.
*
* @param base SHA peripheral base address.
* @param[out] output Output buffer.
* @param Number of bytes to copy.
* @return kStatus_Success.
*/
static void sha_get_digest(SHA_Type *base, uint8_t *output, size_t outputSize)
{
uint32_t digest[8];
for (int i = 0; i < 8; i++)
{
digest[i] = swap_bytes(base->DIGEST[i]);
}
if (outputSize > sizeof(digest))
{
outputSize = sizeof(digest);
}
sha_memcpy(output, digest, outputSize);
}
status_t SHA_Init(SHA_Type *base, sha_ctx_t *ctx, sha_algo_t algo)
{
status_t status;
sha_ctx_internal_t *ctxInternal;
/* compile time check for the correct structure size */
BUILD_ASSERT(sizeof(sha_ctx_t) >= sizeof(sha_ctx_internal_t), sha_ctx_t_size);
uint32_t i;
status = sha_check_input_args(base, ctx, algo);
if (status != kStatus_Success)
{
return status;
}
/* set algorithm in context struct for later use */
ctxInternal = (sha_ctx_internal_t *)ctx;
ctxInternal->algo = algo;
ctxInternal->blksz = 0u;
for (i = 0; i < sizeof(ctxInternal->blk.w) / sizeof(ctxInternal->blk.w[0]); i++)
{
ctxInternal->blk.w[0] = 0u;
}
ctxInternal->state = kSHA_HashInit;
ctxInternal->fullMessageSize = 0;
return status;
}
status_t SHA_Update(SHA_Type *base, sha_ctx_t *ctx, const uint8_t *message, size_t messageSize)
{
bool isUpdateState;
status_t status;
sha_ctx_internal_t *ctxInternal;
size_t blockSize;
if (messageSize == 0)
{
return kStatus_Success;
}
ctxInternal = (sha_ctx_internal_t *)ctx;
status = sha_check_context(ctxInternal, message);
if (kStatus_Success != status)
{
return status;
}
ctxInternal->fullMessageSize += messageSize;
blockSize = SHA_BLOCK_SIZE;
/* if we are still less than 64 bytes, keep only in context */
if ((ctxInternal->blksz + messageSize) <= blockSize)
{
sha_memcpy((&ctxInternal->blk.b[0]) + ctxInternal->blksz, message, messageSize);
ctxInternal->blksz += messageSize;
return status;
}
else
{
isUpdateState = ctxInternal->state == kSHA_HashUpdate;
if (!isUpdateState)
{
/* start NEW hash */
sha_engine_init(base, ctxInternal);
ctxInternal->state = kSHA_HashUpdate;
}
}
/* process message data */
status = sha_process_message_data(base, ctxInternal, message, messageSize);
return status;
}
status_t SHA_Finish(SHA_Type *base, sha_ctx_t *ctx, uint8_t *output, size_t *outputSize)
{
size_t algOutSize = 0;
status_t status;
sha_ctx_internal_t *ctxInternal;
uint32_t *ctxW;
uint32_t i;
ctxInternal = (sha_ctx_internal_t *)ctx;
status = sha_check_context(ctxInternal, output);
if (kStatus_Success != status)
{
return status;
}
if (ctxInternal->state == kSHA_HashInit)
{
sha_engine_init(base, ctxInternal);
}
size_t outSize = 0u;
/* compute algorithm output length */
switch (ctxInternal->algo)
{
case kSHA_Sha1:
outSize = kSHA_OutLenSha1;
break;
case kSHA_Sha256:
outSize = kSHA_OutLenSha256;
break;
default:
break;
}
algOutSize = outSize;
/* flush message last incomplete block, if there is any, and add padding bits */
status = sha_finalize(base, ctxInternal);
if (outputSize)
{
if (algOutSize < *outputSize)
{
*outputSize = algOutSize;
}
else
{
algOutSize = *outputSize;
}
}
sha_get_digest(base, &output[0], algOutSize);
ctxW = (uint32_t *)ctx;
for (i = 0; i < SHA_CTX_SIZE; i++)
{
ctxW[i] = 0u;
}
return status;
}

View File

@ -0,0 +1,145 @@
/*
* The Clear BSD License
* Copyright (c) 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_SHA_H_
#define _FSL_SHA_H_
#include "fsl_common.h"
/*!
* @addtogroup sha
* @{
*/
/*! @file */
/*******************************************************************************
* Definitions
*******************************************************************************/
/*! @name Driver version */
/*@{*/
/*! @brief Defines LPC SHA driver version 2.0.0.
*
* Change log:
* - Version 2.0.0
* - initial version
*/
#define FSL_SHA_DRIVER_VERSION (MAKE_VERSION(2, 0, 0))
/*@}*/
/*! Supported cryptographic block cipher functions for HASH creation */
typedef enum _sha_algo_t
{
kSHA_Sha1, /*!< SHA_1 */
kSHA_Sha256, /*!< SHA_256 */
} sha_algo_t;
/*! @brief SHA Context size. */
#define SHA_CTX_SIZE 20
/*! @brief Storage type used to save hash context. */
typedef struct _sha_ctx_t
{
uint32_t x[SHA_CTX_SIZE];
} sha_ctx_t;
/*******************************************************************************
* API
*******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif /* __cplusplus */
/*!
* @name SHA Functional Operation
* @{
*/
/*!
* @addtogroup sha_algorithm_level_api
* @{
*/
/*!
* @brief Initialize HASH context
*
* This function initializes new hash context.
*
* @param base SHA peripheral base address
* @param[out] ctx Output hash context
* @param algo Underlaying algorithm to use for hash computation. Either SHA-1 or SHA-256.
* @return Status of initialization
*/
status_t SHA_Init(SHA_Type *base, sha_ctx_t *ctx, sha_algo_t algo);
/*!
* @brief Add data to current HASH
*
* Add data to current HASH. This can be called repeatedly with an arbitrary amount of data to be
* hashed.
*
* @param base SHA peripheral base address
* @param[in,out] ctx HASH context
* @param message Input message
* @param messageSize Size of input message in bytes
* @return Status of the hash update operation
*/
status_t SHA_Update(SHA_Type *base, sha_ctx_t *ctx, const uint8_t *message, size_t messageSize);
/*!
* @brief Finalize hashing
*
* Outputs the final hash and erases the context. SHA-1 or SHA-256 padding bits are automatically added by this
* function.
*
* @param base SHA peripheral base address
* @param[in,out] ctx HASH context
* @param[out] output Output hash data
* @param[in,out] outputSize On input, determines the size of bytes of the output array. On output, tells how many bytes
* have been written to output.
* @return Status of the hash finish operation
*/
status_t SHA_Finish(SHA_Type *base, sha_ctx_t *ctx, uint8_t *output, size_t *outputSize);
/*!
*@}
*/ /* sha_algorithm_level_api */
#if defined(__cplusplus)
}
#endif /* __cplusplus */
/*! @}*/
/*! @}*/ /* end of group sha */
#endif /* _FSL_SHA_H_ */

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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
@ -41,6 +45,7 @@
* range <0,15>. Range <8,15> represents 2B transfer */
#define SPI_COUNT_TO_BYTES(dataWidth, count) ((count) << ((dataWidth) >> 3U))
#define SPI_BYTES_TO_COUNT(dataWidth, bytes) ((bytes) >> ((dataWidth) >> 3U))
#define SPI_SSELPOL_MASK ((SPI_CFG_SPOL0_MASK) | (SPI_CFG_SPOL1_MASK) | (SPI_CFG_SPOL2_MASK) | (SPI_CFG_SPOL3_MASK))
/*******************************************************************************
* Variables
@ -54,6 +59,8 @@ static const uint32_t s_spiBaseAddrs[FSL_FEATURE_SOC_SPI_COUNT] = SPI_BASE_ADDRS
/*! @brief IRQ name array */
static const IRQn_Type s_spiIRQ[] = SPI_IRQS;
/* @brief Dummy data for each instance. This data is used when user's tx buffer is NULL*/
volatile uint8_t s_dummyData[FSL_FEATURE_SOC_SPI_COUNT] = {0};
/*******************************************************************************
* Code
******************************************************************************/
@ -75,6 +82,12 @@ uint32_t SPI_GetInstance(SPI_Type *base)
return 0;
}
void SPI_SetDummyData(SPI_Type *base, uint8_t dummyData)
{
uint32_t instance = SPI_GetInstance(base);
s_dummyData[instance] = dummyData;
}
void *SPI_GetConfig(SPI_Type *base)
{
int32_t instance;
@ -100,6 +113,11 @@ void SPI_MasterGetDefaultConfig(spi_master_config_t *config)
config->sselNum = kSPI_Ssel0;
config->txWatermark = kSPI_TxFifo0;
config->rxWatermark = kSPI_RxFifo1;
config->sselPol = kSPI_SpolActiveAllLow;
config->delayConfig.preDelay = 0U;
config->delayConfig.postDelay = 0U;
config->delayConfig.frameDelay = 0U;
config->delayConfig.transferDelay = 0U;
}
status_t SPI_MasterInit(SPI_Type *base, const spi_master_config_t *config, uint32_t srcClock_Hz)
@ -134,7 +152,8 @@ status_t SPI_MasterInit(SPI_Type *base, const spi_master_config_t *config, uint3
/* configure SPI mode */
tmp = base->CFG;
tmp &= ~(SPI_CFG_MASTER_MASK | SPI_CFG_LSBF_MASK | SPI_CFG_CPHA_MASK | SPI_CFG_CPOL_MASK | SPI_CFG_LOOP_MASK | SPI_CFG_ENABLE_MASK);
tmp &= ~(SPI_CFG_MASTER_MASK | SPI_CFG_LSBF_MASK | SPI_CFG_CPHA_MASK | SPI_CFG_CPOL_MASK | SPI_CFG_LOOP_MASK |
SPI_CFG_ENABLE_MASK | SPI_SSELPOL_MASK);
/* phase */
tmp |= SPI_CFG_CPHA(config->phase);
/* polarity */
@ -145,6 +164,8 @@ status_t SPI_MasterInit(SPI_Type *base, const spi_master_config_t *config, uint3
tmp |= SPI_CFG_MASTER(1);
/* loopback */
tmp |= SPI_CFG_LOOP(config->enableLoopback);
/* configure active level for all CS */
tmp |= ((uint32_t)config->sselPol & (SPI_SSELPOL_MASK));
base->CFG = tmp;
/* store configuration */
@ -161,6 +182,11 @@ status_t SPI_MasterInit(SPI_Type *base, const spi_master_config_t *config, uint3
/* set FIFOTRIG */
base->FIFOTRIG = tmp;
/* Set the delay configuration. */
SPI_SetTransferDelay(base, &config->delayConfig);
/* Set the dummy data. */
SPI_SetDummyData(base, (uint8_t)SPI_DUMMYDATA);
SPI_Enable(base, config->enableMaster);
return kStatus_Success;
}
@ -176,6 +202,7 @@ void SPI_SlaveGetDefaultConfig(spi_slave_config_t *config)
config->dataWidth = kSPI_Data8Bits;
config->txWatermark = kSPI_TxFifo0;
config->rxWatermark = kSPI_RxFifo1;
config->sselPol = kSPI_SpolActiveAllLow;
}
status_t SPI_SlaveInit(SPI_Type *base, const spi_slave_config_t *config)
@ -201,13 +228,16 @@ status_t SPI_SlaveInit(SPI_Type *base, const spi_slave_config_t *config)
/* configure SPI mode */
tmp = base->CFG;
tmp &= ~(SPI_CFG_MASTER_MASK | SPI_CFG_LSBF_MASK | SPI_CFG_CPHA_MASK | SPI_CFG_CPOL_MASK | SPI_CFG_ENABLE_MASK);
tmp &= ~(SPI_CFG_MASTER_MASK | SPI_CFG_LSBF_MASK | SPI_CFG_CPHA_MASK | SPI_CFG_CPOL_MASK | SPI_CFG_ENABLE_MASK |
SPI_SSELPOL_MASK);
/* phase */
tmp |= SPI_CFG_CPHA(config->phase);
/* polarity */
tmp |= SPI_CFG_CPOL(config->polarity);
/* direction */
tmp |= SPI_CFG_LSBF(config->direction);
/* configure active level for all CS */
tmp |= ((uint32_t)config->sselPol & (SPI_SSELPOL_MASK));
base->CFG = tmp;
/* store configuration */
@ -223,6 +253,8 @@ status_t SPI_SlaveInit(SPI_Type *base, const spi_slave_config_t *config)
/* set FIFOTRIG */
base->FIFOTRIG = tmp;
SPI_SetDummyData(base, (uint8_t)SPI_DUMMYDATA);
SPI_Enable(base, config->enableSlave);
return kStatus_Success;
}
@ -402,10 +434,10 @@ status_t SPI_MasterTransferBlocking(SPI_Type *base, spi_transfer_t *xfer)
tx_ctrl |= (SPI_DEASSERT_ALL & (~SPI_DEASSERTNUM_SSEL(g_configs[instance].sselNum)));
/* set width of data - range asserted at entry */
tx_ctrl |= SPI_FIFOWR_LEN(dataWidth);
/* delay for frames */
tx_ctrl |= (xfer->configFlags & (uint32_t)kSPI_FrameDelay) ? (uint32_t)kSPI_FrameDelay : 0;
/* end of transfer */
last_ctrl |= (xfer->configFlags & (uint32_t)kSPI_FrameAssert) ? (uint32_t)kSPI_FrameAssert : 0;
/* delay end of transfer */
last_ctrl |= (xfer->configFlags & (uint32_t)kSPI_FrameDelay) ? (uint32_t)kSPI_FrameDelay : 0;
/* last index of loop */
while (txRemainingBytes || rxRemainingBytes || toReceiveCount)
{
@ -450,7 +482,7 @@ status_t SPI_MasterTransferBlocking(SPI_Type *base, spi_transfer_t *xfer)
}
else
{
tmp32 = SPI_DUMMYDATA;
tmp32 = ((uint32_t)s_dummyData[instance] << 8U | (s_dummyData[instance]));
/* last transfer */
if (rxRemainingBytes == SPI_COUNT_TO_BYTES(dataWidth, toReceiveCount + 1))
{
@ -513,6 +545,118 @@ status_t SPI_MasterTransferNonBlocking(SPI_Type *base, spi_master_handle_t *hand
return kStatus_Success;
}
status_t SPI_MasterHalfDuplexTransferBlocking(SPI_Type *base, spi_half_duplex_transfer_t *xfer)
{
assert(xfer);
spi_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) & (uint32_t)(~kSPI_FrameAssert);
}
else
{
tempXfer.configFlags = (xfer->configFlags) | kSPI_FrameAssert;
}
status = SPI_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;
/* SPI transfer blocking. */
status = SPI_MasterTransferBlocking(base, &tempXfer);
return status;
}
status_t SPI_MasterHalfDuplexTransferNonBlocking(SPI_Type *base,
spi_master_handle_t *handle,
spi_half_duplex_transfer_t *xfer)
{
assert(xfer);
assert(handle);
spi_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) & (uint32_t)(~kSPI_FrameAssert);
}
else
{
tempXfer.configFlags = (xfer->configFlags) | kSPI_FrameAssert;
}
status = SPI_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 = SPI_MasterTransferNonBlocking(base, handle, &tempXfer);
return status;
}
status_t SPI_MasterTransferGetCount(SPI_Type *base, spi_master_handle_t *handle, size_t *count)
{
assert(NULL != handle);
@ -552,6 +696,8 @@ static void SPI_TransferHandleIRQInternal(SPI_Type *base, spi_master_handle_t *h
uint32_t tx_ctrl = 0, last_ctrl = 0, tmp32;
bool loopContinue;
uint32_t fifoDepth;
/* Get flexcomm instance by 'base' param */
uint32_t instance = SPI_GetInstance(base);
/* check params */
assert((NULL != base) && (NULL != handle) && ((NULL != handle->txData) || (NULL != handle->rxData)));
@ -561,10 +707,10 @@ static void SPI_TransferHandleIRQInternal(SPI_Type *base, spi_master_handle_t *h
tx_ctrl |= (SPI_DEASSERT_ALL & SPI_ASSERTNUM_SSEL(handle->sselNum));
/* set width of data */
tx_ctrl |= SPI_FIFOWR_LEN(handle->dataWidth);
/* delay for frames */
tx_ctrl |= (handle->configFlags & (uint32_t)kSPI_FrameDelay) ? (uint32_t)kSPI_FrameDelay : 0;
/* end of transfer */
last_ctrl |= (handle->configFlags & (uint32_t)kSPI_FrameAssert) ? (uint32_t)kSPI_FrameAssert : 0;
/* delay end of transfer */
last_ctrl |= (handle->configFlags & (uint32_t)kSPI_FrameDelay) ? (uint32_t)kSPI_FrameDelay : 0;
do
{
loopContinue = false;
@ -619,7 +765,7 @@ static void SPI_TransferHandleIRQInternal(SPI_Type *base, spi_master_handle_t *h
}
else
{
tmp32 = SPI_DUMMYDATA;
tmp32 = ((uint32_t)s_dummyData[instance] << 8U | (s_dummyData[instance]));
/* last transfer */
if (handle->rxRemainingBytes == SPI_COUNT_TO_BYTES(handle->dataWidth, handle->toReceiveCount + 1))
{

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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
@ -46,11 +50,15 @@
/*! @name Driver version */
/*@{*/
/*! @brief USART driver version 2.0.0. */
#define FSL_SPI_DRIVER_VERSION (MAKE_VERSION(2, 0, 0))
/*! @brief SPI driver version 2.0.1. */
#define FSL_SPI_DRIVER_VERSION (MAKE_VERSION(2, 0, 1))
/*@}*/
#define SPI_DUMMYDATA (0xFFFF)
#ifndef SPI_DUMMYDATA
/*! @brief SPI dummy transfer data, the data is sent while txBuff is NULL. */
#define SPI_DUMMYDATA (0xFFU)
#endif
#define SPI_DATA(n) (((uint32_t)(n)) & 0xFFFF)
#define SPI_CTRLMASK (0xFFFF0000)
@ -64,25 +72,29 @@
#define SPI_FIFOTRIG_RXLVL_GET(base) (((base)->FIFOTRIG & SPI_FIFOTRIG_RXLVL_MASK) >> SPI_FIFOTRIG_RXLVL_SHIFT)
/*! @brief SPI transfer option.*/
typedef enum _spi_xfer_option {
typedef enum _spi_xfer_option
{
kSPI_FrameDelay = (SPI_FIFOWR_EOF_MASK), /*!< Delay chip select */
kSPI_FrameAssert = (SPI_FIFOWR_EOT_MASK), /*!< When transfer ends, assert chip select */
} spi_xfer_option_t;
/*! @brief SPI data shifter direction options.*/
typedef enum _spi_shift_direction {
typedef enum _spi_shift_direction
{
kSPI_MsbFirst = 0U, /*!< Data transfers start with most significant bit. */
kSPI_LsbFirst = 1U /*!< Data transfers start with least significant bit. */
} spi_shift_direction_t;
/*! @brief SPI clock polarity configuration.*/
typedef enum _spi_clock_polarity {
typedef enum _spi_clock_polarity
{
kSPI_ClockPolarityActiveHigh = 0x0U, /*!< Active-high SPI clock (idles low). */
kSPI_ClockPolarityActiveLow /*!< Active-low SPI clock (idles high). */
} spi_clock_polarity_t;
/*! @brief SPI clock phase configuration.*/
typedef enum _spi_clock_phase {
typedef enum _spi_clock_phase
{
kSPI_ClockPhaseFirstEdge = 0x0U, /*!< First edge on SCK occurs at the middle of the first
* cycle of a data transfer. */
kSPI_ClockPhaseSecondEdge /*!< First edge on SCK occurs at the start of the
@ -90,7 +102,8 @@ typedef enum _spi_clock_phase {
} spi_clock_phase_t;
/*! @brief txFIFO watermark values */
typedef enum _spi_txfifo_watermark {
typedef enum _spi_txfifo_watermark
{
kSPI_TxFifo0 = 0, /*!< SPI tx watermark is empty */
kSPI_TxFifo1 = 1, /*!< SPI tx watermark at 1 item */
kSPI_TxFifo2 = 2, /*!< SPI tx watermark at 2 items */
@ -102,7 +115,8 @@ typedef enum _spi_txfifo_watermark {
} spi_txfifo_watermark_t;
/*! @brief rxFIFO watermark values */
typedef enum _spi_rxfifo_watermark {
typedef enum _spi_rxfifo_watermark
{
kSPI_RxFifo1 = 0, /*!< SPI rx watermark at 1 item */
kSPI_RxFifo2 = 1, /*!< SPI rx watermark at 2 items */
kSPI_RxFifo3 = 2, /*!< SPI rx watermark at 3 items */
@ -114,7 +128,8 @@ typedef enum _spi_rxfifo_watermark {
} spi_rxfifo_watermark_t;
/*! @brief Transfer data width */
typedef enum _spi_data_width {
typedef enum _spi_data_width
{
kSPI_Data4Bits = 3, /*!< 4 bits data width */
kSPI_Data5Bits = 4, /*!< 5 bits data width */
kSPI_Data6Bits = 5, /*!< 6 bits data width */
@ -131,13 +146,41 @@ typedef enum _spi_data_width {
} spi_data_width_t;
/*! @brief Slave select */
typedef enum _spi_ssel {
typedef enum _spi_ssel
{
kSPI_Ssel0 = 0, /*!< Slave select 0 */
kSPI_Ssel1 = 1, /*!< Slave select 1 */
kSPI_Ssel2 = 2, /*!< Slave select 2 */
kSPI_Ssel3 = 3, /*!< Slave select 3 */
} spi_ssel_t;
/*! @brief ssel polarity */
typedef enum _spi_spol
{
kSPI_Spol0ActiveHigh = SPI_CFG_SPOL0(1),
kSPI_Spol1ActiveHigh = SPI_CFG_SPOL1(1),
kSPI_Spol2ActiveHigh = SPI_CFG_SPOL2(1),
kSPI_Spol3ActiveHigh = SPI_CFG_SPOL3(1),
kSPI_SpolActiveAllHigh =
(kSPI_Spol0ActiveHigh | kSPI_Spol1ActiveHigh | kSPI_Spol2ActiveHigh | kSPI_Spol3ActiveHigh),
kSPI_SpolActiveAllLow = 0,
} spi_spol_t;
/*!
* @brief SPI delay time configure structure.
* Note:
* The DLY register controls several programmable delays related to SPI signalling,
* it stands for how many SPI clock time will be inserted.
* The maxinun value of these delay time is 15.
*/
typedef struct _spi_delay_config
{
uint8_t preDelay; /*!< Delay between SSEL assertion and the beginning of transfer. */
uint8_t postDelay; /*!< Delay between the end of transfer and SSEL deassertion. */
uint8_t frameDelay; /*!< Delay between frame to frame. */
uint8_t transferDelay; /*!< Delay between transfer to transfer. */
} spi_delay_config_t;
/*! @brief SPI master user configure structure.*/
typedef struct _spi_master_config
{
@ -149,8 +192,10 @@ typedef struct _spi_master_config
uint32_t baudRate_Bps; /*!< Baud Rate for SPI in Hz */
spi_data_width_t dataWidth; /*!< Width of the data */
spi_ssel_t sselNum; /*!< Slave select number */
spi_spol_t sselPol; /*!< Configure active CS polarity */
spi_txfifo_watermark_t txWatermark; /*!< txFIFO watermark */
spi_rxfifo_watermark_t rxWatermark; /*!< rxFIFO watermark */
spi_delay_config_t delayConfig; /*!< Delay configuration. */
} spi_master_config_t;
/*! @brief SPI slave user configure structure.*/
@ -161,6 +206,7 @@ typedef struct _spi_slave_config
spi_clock_phase_t phase; /*!< Clock phase */
spi_shift_direction_t direction; /*!< MSB or LSB */
spi_data_width_t dataWidth; /*!< Width of the data */
spi_spol_t sselPol; /*!< Configure active CS polarity */
spi_txfifo_watermark_t txWatermark; /*!< txFIFO watermark */
spi_rxfifo_watermark_t rxWatermark; /*!< rxFIFO watermark */
} spi_slave_config_t;
@ -200,6 +246,19 @@ typedef struct _spi_transfer
size_t dataSize; /*!< Transfer bytes */
} spi_transfer_t;
/*! @brief SPI half-duplex(master only) transfer structure */
typedef struct _spi_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. */
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. */
} spi_half_duplex_transfer_t;
/*! @brief Internal configuration structure used in 'spi' and 'spi_dma' driver */
typedef struct _spi_config
{
@ -468,6 +527,28 @@ static inline uint32_t SPI_ReadData(SPI_Type *base)
return base->FIFORD;
}
/*!
* @brief Set delay time for transfer.
* the delay uint is SPI clock time, maximum value is 0xF.
* @param base SPI base pointer
* @param config configuration for delay option @ref spi_delay_config_t.
*/
static inline void SPI_SetTransferDelay(SPI_Type *base, const spi_delay_config_t *config)
{
assert(NULL != base);
assert(NULL != config);
base->DLY = (SPI_DLY_PRE_DELAY(config->preDelay) | SPI_DLY_POST_DELAY(config->postDelay) |
SPI_DLY_FRAME_DELAY(config->frameDelay) | SPI_DLY_TRANSFER_DELAY(config->transferDelay));
}
/*!
* @brief Set up the dummy data.
*
* @param base SPI peripheral address.
* @param dummyData Data to be transferred when tx buffer is NULL.
*/
void SPI_SetDummyData(SPI_Type *base, uint8_t dummyData);
/*! @} */
/*!
@ -513,6 +594,36 @@ status_t SPI_MasterTransferBlocking(SPI_Type *base, spi_transfer_t *xfer);
*/
status_t SPI_MasterTransferNonBlocking(SPI_Type *base, spi_master_handle_t *handle, spi_transfer_t *xfer);
/*!
* @brief Transfers a block of data using a polling method.
*
* This function will do a half-duplex transfer for SPI master, This is a blocking function,
* which does not retuen until all transfer have been completed. And data transfer mechanism is half-duplex,
* users can set transmit first or receive first.
*
* @param base SPI base pointer
* @param xfer pointer to spi_half_duplex_transfer_t structure
* @return status of status_t.
*/
status_t SPI_MasterHalfDuplexTransferBlocking(SPI_Type *base, spi_half_duplex_transfer_t *xfer);
/*!
* @brief Performs a non-blocking SPI interrupt transfer.
*
* This function using polling way to do the first half transimission and using interrupts to
* do the second half transimission, the transfer mechanism is half-duplex.
* When do the second half transimission, code will return right away. When all data is transferred,
* the callback function is called.
*
* @param base SPI peripheral base address.
* @param handle pointer to spi_master_handle_t structure which stores the transfer state
* @param xfer pointer to spi_half_duplex_transfer_t structure
* @return status of status_t.
*/
status_t SPI_MasterHalfDuplexTransferNonBlocking(SPI_Type *base,
spi_master_handle_t *handle,
spi_half_duplex_transfer_t *xfer);
/*!
* @brief Gets the master transfer count.
*
@ -591,7 +702,7 @@ static inline status_t SPI_SlaveTransferNonBlocking(SPI_Type *base, spi_slave_ha
*/
static inline status_t SPI_SlaveTransferGetCount(SPI_Type *base, spi_slave_handle_t *handle, size_t *count)
{
return SPI_MasterTransferGetCount(base, (spi_master_handle_t*)handle, count);
return SPI_MasterTransferGetCount(base, (spi_master_handle_t *)handle, count);
}
/*!
@ -604,7 +715,7 @@ static inline status_t SPI_SlaveTransferGetCount(SPI_Type *base, spi_slave_handl
*/
static inline void SPI_SlaveTransferAbort(SPI_Type *base, spi_slave_handle_t *handle)
{
SPI_MasterTransferAbort(base, (spi_master_handle_t*)handle);
SPI_MasterTransferAbort(base, (spi_master_handle_t *)handle);
}
/*!

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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
@ -97,10 +101,13 @@ __attribute__((aligned(4))) static spi_dma_txdummy_t s_txDummy[FSL_FEATURE_SOC_S
#if defined(__ICCARM__)
#pragma data_alignment = 4
static uint16_t s_rxDummy;
static uint32_t s_txLastWord[FSL_FEATURE_SOC_SPI_COUNT];
#elif defined(__CC_ARM)
__attribute__((aligned(4))) static uint16_t s_rxDummy;
__attribute__((aligned(4))) static uint32_t s_txLastWord[FSL_FEATURE_SOC_SPI_COUNT];
#elif defined(__GNUC__)
__attribute__((aligned(4))) static uint16_t s_rxDummy;
__attribute__((aligned(4))) static uint32_t s_txLastWord[FSL_FEATURE_SOC_SPI_COUNT];
#endif
#if defined(__ICCARM__)
@ -112,6 +119,8 @@ __attribute__((aligned(16))) static dma_descriptor_t s_spi_descriptor_table[FSL_
__attribute__((aligned(16))) static dma_descriptor_t s_spi_descriptor_table[FSL_FEATURE_SOC_SPI_COUNT] = {0};
#endif
/*! @brief Global variable for dummy data value setting. */
extern volatile uint8_t s_dummyData[];
/*******************************************************************************
* Code
******************************************************************************/
@ -129,31 +138,31 @@ static void SpiConfigToFifoWR(spi_config_t *config, uint32_t *fifowr)
*fifowr |= SPI_FIFOWR_LEN(config->dataWidth);
}
static void PrepareTxFIFO(uint32_t *fifo, uint32_t count, uint32_t ctrl)
static void PrepareTxLastWord(spi_transfer_t *xfer, uint32_t *txLastWord, spi_config_t *config)
{
assert(!(fifo == NULL));
if (fifo == NULL)
if (config->dataWidth > kSPI_Data8Bits)
{
return;
*txLastWord = (((uint32_t)xfer->txData[xfer->dataSize - 1] << 8U) | (xfer->txData[xfer->dataSize - 2]));
}
/* CS deassert and CS delay are relevant only for last word */
uint32_t tx_ctrl = ctrl & (~(SPI_FIFOWR_EOT_MASK | SPI_FIFOWR_EOF_MASK));
uint32_t i = 0;
for (; i + 1 < count; i++)
else
{
fifo[i] = (fifo[i] & 0xFFFFU) | (tx_ctrl & 0xFFFF0000U);
}
if (i < count)
{
fifo[i] = (fifo[i] & 0xFFFFU) | (ctrl & 0xFFFF0000U);
*txLastWord = xfer->txData[xfer->dataSize - 1];
}
XferToFifoWR(xfer, txLastWord);
SpiConfigToFifoWR(config, txLastWord);
}
static void SPI_SetupDummy(uint32_t *dummy, spi_transfer_t *xfer, spi_config_t *spi_config_p)
static void SPI_SetupDummy(SPI_Type *base, spi_dma_txdummy_t *dummy, spi_transfer_t *xfer, spi_config_t *spi_config_p)
{
*dummy = SPI_DUMMYDATA;
XferToFifoWR(xfer, dummy);
SpiConfigToFifoWR(spi_config_p, dummy);
uint32_t instance = SPI_GetInstance(base);
dummy->word = ((uint32_t)s_dummyData[instance] << 8U | s_dummyData[instance]);
dummy->lastWord = ((uint32_t)s_dummyData[instance] << 8U | s_dummyData[instance]);
XferToFifoWR(xfer, &dummy->word);
XferToFifoWR(xfer, &dummy->lastWord);
SpiConfigToFifoWR(spi_config_p, &dummy->word);
SpiConfigToFifoWR(spi_config_p, &dummy->lastWord);
/* Clear the end of transfer bit for continue word transfer. */
dummy->word &= (uint32_t)(~kSPI_FrameAssert);
}
status_t SPI_MasterTransferCreateHandleDMA(SPI_Type *base,
@ -212,21 +221,10 @@ status_t SPI_MasterTransferDMA(SPI_Type *base, spi_dma_handle_t *handle, spi_tra
{
return kStatus_InvalidArgument;
}
/* txData set and not aligned to sizeof(uint32_t) */
assert(!((NULL != xfer->txData) && ((uint32_t)xfer->txData % sizeof(uint32_t))));
if ((NULL != xfer->txData) && ((uint32_t)xfer->txData % sizeof(uint32_t)))
{
return kStatus_InvalidArgument;
}
/* rxData set and not aligned to sizeof(uint32_t) */
assert(!((NULL != xfer->rxData) && ((uint32_t)xfer->rxData % sizeof(uint32_t))));
if ((NULL != xfer->rxData) && ((uint32_t)xfer->rxData % sizeof(uint32_t)))
{
return kStatus_InvalidArgument;
}
/* byte size is zero or not aligned to sizeof(uint32_t) */
assert(!((xfer->dataSize == 0) || (xfer->dataSize % sizeof(uint32_t))));
if ((xfer->dataSize == 0) || (xfer->dataSize % sizeof(uint32_t)))
/* Byte size is zero. */
assert(!(xfer->dataSize == 0));
if (xfer->dataSize == 0)
{
return kStatus_InvalidArgument;
}
@ -256,13 +254,15 @@ status_t SPI_MasterTransferDMA(SPI_Type *base, spi_dma_handle_t *handle, spi_tra
SPI_EnableRxDMA(base, true);
if (xfer->rxData)
{
DMA_PrepareTransfer(&xferConfig, (void *)&base->FIFORD, xfer->rxData, sizeof(uint32_t), xfer->dataSize,
kDMA_PeripheralToMemory, NULL);
DMA_PrepareTransfer(&xferConfig, (void *)&base->FIFORD, xfer->rxData,
((spi_config_p->dataWidth > kSPI_Data8Bits) ? (sizeof(uint16_t)) : (sizeof(uint8_t))),
xfer->dataSize, kDMA_PeripheralToMemory, NULL);
}
else
{
DMA_PrepareTransfer(&xferConfig, (void *)&base->FIFORD, &s_rxDummy, sizeof(uint32_t), xfer->dataSize,
kDMA_StaticToStatic, NULL);
DMA_PrepareTransfer(&xferConfig, (void *)&base->FIFORD, &s_rxDummy,
((spi_config_p->dataWidth > kSPI_Data8Bits) ? (sizeof(uint16_t)) : (sizeof(uint8_t))),
xfer->dataSize, kDMA_StaticToStatic, NULL);
}
DMA_SubmitTransfer(handle->rxHandle, &xferConfig);
handle->rxInProgress = true;
@ -270,21 +270,21 @@ status_t SPI_MasterTransferDMA(SPI_Type *base, spi_dma_handle_t *handle, spi_tra
/* transmit */
SPI_EnableTxDMA(base, true);
if (xfer->configFlags & kSPI_FrameAssert)
{
PrepareTxLastWord(xfer, &s_txLastWord[instance], spi_config_p);
}
if (xfer->txData)
{
tmp = 0;
XferToFifoWR(xfer, &tmp);
SpiConfigToFifoWR(spi_config_p, &tmp);
PrepareTxFIFO((uint32_t *)xfer->txData, xfer->dataSize / sizeof(uint32_t), tmp);
DMA_PrepareTransfer(&xferConfig, xfer->txData, (void *)&base->FIFOWR, sizeof(uint32_t), xfer->dataSize,
kDMA_MemoryToPeripheral, NULL);
DMA_SubmitTransfer(handle->txHandle, &xferConfig);
}
else
{
if ((xfer->configFlags & kSPI_FrameAssert) && (xfer->dataSize > sizeof(uint32_t)))
/* If end of tranfer function is enabled and data transfer frame is bigger then 1, use dma
* descriptor to send the last data.
*/
if ((xfer->configFlags & kSPI_FrameAssert) &&
((spi_config_p->dataWidth > kSPI_Data8Bits) ? (xfer->dataSize > 2) : (xfer->dataSize > 1)))
{
dma_xfercfg_t tmp_xfercfg = { 0 };
dma_xfercfg_t tmp_xfercfg = {0};
tmp_xfercfg.valid = true;
tmp_xfercfg.swtrig = true;
tmp_xfercfg.intA = true;
@ -292,17 +292,16 @@ status_t SPI_MasterTransferDMA(SPI_Type *base, spi_dma_handle_t *handle, spi_tra
tmp_xfercfg.srcInc = 0;
tmp_xfercfg.dstInc = 0;
tmp_xfercfg.transferCount = 1;
/* create chained descriptor to transmit last word */
SPI_SetupDummy(&s_txDummy[instance].lastWord, xfer, spi_config_p);
DMA_CreateDescriptor(&s_spi_descriptor_table[instance], &tmp_xfercfg, &s_txDummy[instance].lastWord,
(uint32_t *)&base->FIFOWR, NULL);
/* use common API to setup first descriptor */
SPI_SetupDummy(&s_txDummy[instance].word, NULL, spi_config_p);
DMA_PrepareTransfer(&xferConfig, &s_txDummy[instance].word, (void *)&base->FIFOWR, sizeof(uint32_t),
xfer->dataSize - sizeof(uint32_t), kDMA_StaticToStatic,
&s_spi_descriptor_table[instance]);
/* disable interrupts for first descriptor
* to avoid calling callback twice */
/* Create chained descriptor to transmit last word */
DMA_CreateDescriptor(&s_spi_descriptor_table[instance], &tmp_xfercfg, &s_txLastWord[instance],
(void *)&base->FIFOWR, NULL);
DMA_PrepareTransfer(
&xferConfig, xfer->txData, (void *)&base->FIFOWR,
((spi_config_p->dataWidth > kSPI_Data8Bits) ? (sizeof(uint16_t)) : (sizeof(uint8_t))),
((spi_config_p->dataWidth > kSPI_Data8Bits) ? (xfer->dataSize - 2) : (xfer->dataSize - 1)),
kDMA_MemoryToPeripheral, &s_spi_descriptor_table[instance]);
/* Disable interrupts for first descriptor to avoid calling callback twice. */
xferConfig.xfercfg.intA = false;
xferConfig.xfercfg.intB = false;
result = DMA_SubmitTransfer(handle->txHandle, &xferConfig);
@ -313,9 +312,52 @@ status_t SPI_MasterTransferDMA(SPI_Type *base, spi_dma_handle_t *handle, spi_tra
}
else
{
SPI_SetupDummy(&s_txDummy[instance].word, xfer, spi_config_p);
DMA_PrepareTransfer(&xferConfig, &s_txDummy[instance].word, (void *)&base->FIFOWR, sizeof(uint32_t),
xfer->dataSize, kDMA_StaticToStatic, NULL);
DMA_PrepareTransfer(
&xferConfig, xfer->txData, (void *)&base->FIFOWR,
((spi_config_p->dataWidth > kSPI_Data8Bits) ? (sizeof(uint16_t)) : (sizeof(uint8_t))),
xfer->dataSize, kDMA_MemoryToPeripheral, NULL);
DMA_SubmitTransfer(handle->txHandle, &xferConfig);
}
}
else
{
/* Setup tx dummy data. */
SPI_SetupDummy(base, &s_txDummy[instance], xfer, spi_config_p);
if ((xfer->configFlags & kSPI_FrameAssert) &&
((spi_config_p->dataWidth > kSPI_Data8Bits) ? (xfer->dataSize > 2) : (xfer->dataSize > 1)))
{
dma_xfercfg_t tmp_xfercfg = {0};
tmp_xfercfg.valid = true;
tmp_xfercfg.swtrig = true;
tmp_xfercfg.intA = true;
tmp_xfercfg.byteWidth = sizeof(uint32_t);
tmp_xfercfg.srcInc = 0;
tmp_xfercfg.dstInc = 0;
tmp_xfercfg.transferCount = 1;
/* Create chained descriptor to transmit last word */
DMA_CreateDescriptor(&s_spi_descriptor_table[instance], &tmp_xfercfg, &s_txDummy[instance].lastWord,
(uint32_t *)&base->FIFOWR, NULL);
/* Use common API to setup first descriptor */
DMA_PrepareTransfer(
&xferConfig, &s_txDummy[instance].word, (void *)&base->FIFOWR,
((spi_config_p->dataWidth > kSPI_Data8Bits) ? (sizeof(uint16_t)) : (sizeof(uint8_t))),
((spi_config_p->dataWidth > kSPI_Data8Bits) ? (xfer->dataSize - 2) : (xfer->dataSize - 1)),
kDMA_StaticToStatic, &s_spi_descriptor_table[instance]);
/* Disable interrupts for first descriptor to avoid calling callback twice */
xferConfig.xfercfg.intA = false;
xferConfig.xfercfg.intB = false;
result = DMA_SubmitTransfer(handle->txHandle, &xferConfig);
if (result != kStatus_Success)
{
return result;
}
}
else
{
DMA_PrepareTransfer(
&xferConfig, &s_txDummy[instance].word, (void *)&base->FIFOWR,
((spi_config_p->dataWidth > kSPI_Data8Bits) ? (sizeof(uint16_t)) : (sizeof(uint8_t))),
xfer->dataSize, kDMA_StaticToStatic, NULL);
result = DMA_SubmitTransfer(handle->txHandle, &xferConfig);
if (result != kStatus_Success)
{
@ -323,13 +365,89 @@ status_t SPI_MasterTransferDMA(SPI_Type *base, spi_dma_handle_t *handle, spi_tra
}
}
}
handle->txInProgress = true;
tmp = 0;
XferToFifoWR(xfer, &tmp);
SpiConfigToFifoWR(spi_config_p, &tmp);
/* Setup the control info.
* Halfword writes to just the control bits (offset 0xE22) doesn't push anything into the FIFO.
* And the data access type of control bits must be uint16_t, byte writes or halfword writes to FIFOWR
* will push the data and the current control bits into the FIFO.
*/
if ((xfer->configFlags & kSPI_FrameAssert) &&
((spi_config_p->dataWidth > kSPI_Data8Bits) ? (xfer->dataSize == 2U) : (xfer->dataSize == 1U)))
{
*(((uint16_t *)&(base->FIFOWR)) + 1) = (uint16_t)(tmp >> 16U);
}
else
{
/* Clear the SPI_FIFOWR_EOT_MASK bit when data is not the last. */
tmp &= (uint32_t)(~kSPI_FrameAssert);
*(((uint16_t *)&(base->FIFOWR)) + 1) = (uint16_t)(tmp >> 16U);
}
DMA_StartTransfer(handle->txHandle);
}
return result;
}
status_t SPI_MasterHalfDuplexTransferDMA(SPI_Type *base, spi_dma_handle_t *handle, spi_half_duplex_transfer_t *xfer)
{
assert(xfer);
assert(handle);
spi_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) & (uint32_t)(~kSPI_FrameAssert);
}
else
{
tempXfer.configFlags = (xfer->configFlags) | kSPI_FrameAssert;
}
status = SPI_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 = SPI_MasterTransferDMA(base, handle, &tempXfer);
return status;
}
static void SPI_RxDMACallback(dma_handle_t *handle, void *userData, bool transferDone, uint32_t intmode)
{
spi_dma_private_handle_t *privHandle = (spi_dma_private_handle_t *)userData;

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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
@ -111,6 +115,21 @@ status_t SPI_MasterTransferCreateHandleDMA(SPI_Type *base,
*/
status_t SPI_MasterTransferDMA(SPI_Type *base, spi_dma_handle_t *handle, spi_transfer_t *xfer);
/*!
* @brief Transfers a block of data using a DMA method.
*
* This function using polling way to do the first half transimission and using DMA way to
* do the srcond half transimission, the transfer mechanism is half-duplex.
* When do the second half transimission, code will return right away. When all data is transferred,
* the callback function is called.
*
* @param base SPI base pointer
* @param handle A pointer to the spi_master_dma_handle_t structure which stores the transfer state.
* @param transfer A pointer to the spi_half_duplex_transfer_t structure.
* @return status of status_t.
*/
status_t SPI_MasterHalfDuplexTransferDMA(SPI_Type *base, spi_dma_handle_t *handle, spi_half_duplex_transfer_t *xfer);
/*!
* @brief Initialize the SPI slave DMA handle.
*

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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
@ -87,7 +91,7 @@ void SPIFI_GetDefaultConfig(spifi_config_t *config)
config->disableCachePrefech = false;
config->isFeedbackClock = true;
config->spiMode = kSPIFI_SPISckLow;
config->isReadFullClockCycle = false;
config->isReadFullClockCycle = true;
config->dualMode = kSPIFI_QuadMode;
}

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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
@ -71,7 +75,7 @@ uint32_t USART_GetInstance(USART_Type *base)
return 0;
}
static size_t USART_TransferGetRxRingBufferLength(usart_handle_t *handle)
size_t USART_TransferGetRxRingBufferLength(usart_handle_t *handle)
{
size_t size;

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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
@ -366,7 +370,19 @@ static inline void USART_EnableInterrupts(USART_Type *base, uint32_t mask)
*/
static inline void USART_DisableInterrupts(USART_Type *base, uint32_t mask)
{
base->FIFOINTENSET = ~(mask & 0xF);
base->FIFOINTENCLR = mask & 0xF;
}
/*!
* @brief Returns enabled USART interrupts.
*
* This function returns the enabled USART interrupts.
*
* @param base USART peripheral base address.
*/
static inline uint32_t USART_GetEnabledInterrupts(USART_Type *base)
{
return base->FIFOINTENSET;
}
/*!
@ -540,6 +556,14 @@ void USART_TransferStartRingBuffer(USART_Type *base,
*/
void USART_TransferStopRingBuffer(USART_Type *base, usart_handle_t *handle);
/*!
* @brief Get the length of received data in RX ring buffer.
*
* @param handle USART handle pointer.
* @return Length of received data in RX ring buffer.
*/
size_t USART_TransferGetRxRingBufferLength(usart_handle_t *handle);
/*!
* @brief Aborts the interrupt-driven data transmit.
*

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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
@ -139,17 +143,32 @@ void UTICK_HandleIRQ(UTICK_Type *base, utick_callback_t cb)
void UTICK0_DriverIRQHandler(void)
{
s_utickIsr(UTICK0, s_utickHandle[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
}
#endif
#if defined(UTICK1)
void UTICK1_DriverIRQHandler(void)
{
s_utickIsr(UTICK1, s_utickHandle[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
}
#endif
#if defined(UTICK2)
void UTICK2_DriverIRQHandler(void)
{
s_utickIsr(UTICK2, s_utickHandle[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
}
#endif

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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

View File

@ -1,9 +1,12 @@
/*
* The Clear BSD License
* Copyright (c) 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 provided that the following conditions are met:
* 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.
@ -16,6 +19,7 @@
* 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