Add support for FRDM-KW41

Signed-off-by: Mahadevan Mahesh <Mahesh.Mahadevan@nxp.com>
pull/3241/head
Mahadevan Mahesh 2016-11-03 07:06:29 -05:00
parent 9d8ec61df5
commit 15d64c9aec
95 changed files with 59243 additions and 0 deletions

View File

@ -0,0 +1,78 @@
/* mbed Microcontroller Library
* Copyright (c) 2006-2013 ARM Limited
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#ifndef MBED_PERIPHERALNAMES_H
#define MBED_PERIPHERALNAMES_H
#include "cmsis.h"
#ifdef __cplusplus
extern "C" {
#endif
typedef enum {
OSC32KCLK = 0
} RTCName;
typedef enum {
LPUART_0 = 0
} UARTName;
#define STDIO_UART_TX USBTX
#define STDIO_UART_RX USBRX
#define STDIO_UART LPUART_0
typedef enum {
I2C_0 = 0,
I2C_1 = 1,
} I2CName;
#define TPM_SHIFT 8
typedef enum {
PWM_1 = (0 << TPM_SHIFT) | (0), // TPM0 CH0
PWM_2 = (0 << TPM_SHIFT) | (1), // TPM0 CH1
PWM_3 = (0 << TPM_SHIFT) | (2), // TPM0 CH2
PWM_4 = (0 << TPM_SHIFT) | (3), // TPM0 CH3
PWM_5 = (1 << TPM_SHIFT) | (0), // TPM1 CH0
PWM_6 = (1 << TPM_SHIFT) | (1), // TPM1 CH1
PWM_7 = (2 << TPM_SHIFT) | (0), // TPM2 CH0
PWM_8 = (2 << TPM_SHIFT) | (1), // TPM2 CH1
} PWMName;
#define ADC_INSTANCE_SHIFT 8
#define ADC_B_CHANNEL_SHIFT 5
typedef enum {
ADC0_SE1 = (0 << ADC_INSTANCE_SHIFT) | 1,
ADC0_SE2 = (0 << ADC_INSTANCE_SHIFT) | 2,
ADC0_SE3 = (0 << ADC_INSTANCE_SHIFT) | 3,
ADC0_SE4 = (0 << ADC_INSTANCE_SHIFT) | 4,
ADC0_SE5 = (0 << ADC_INSTANCE_SHIFT) | 5,
} ADCName;
typedef enum {
DAC_0 = 0
} DACName;
typedef enum {
SPI_0 = 0,
SPI_1 = 1,
} SPIName;
#ifdef __cplusplus
}
#endif
#endif

View File

@ -0,0 +1,143 @@
/* mbed Microcontroller Library
* Copyright (c) 2006-2013 ARM Limited
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#include "PeripheralPins.h"
/************RTC***************/
const PinMap PinMap_RTC[] = {
{NC, OSC32KCLK, 0},
};
/************ADC***************/
const PinMap PinMap_ADC[] = {
{PTB1, ADC0_SE1, 0},
{PTB3, ADC0_SE2, 0},
{PTB2, ADC0_SE3, 0},
{PTB18, ADC0_SE4, 0},
{PTA19, ADC0_SE5, 0},
{NC , NC , 0}
};
/************DAC***************/
const PinMap PinMap_DAC[] = {
{DAC0_OUT, DAC_0, 0},
{NC, NC, 0}
};
/************I2C***************/
const PinMap PinMap_I2C_SDA[] = {
{PTB1, I2C_0, 3},
{PTB17, I2C_1, 3},
{PTC1, I2C_0, 3},
{PTC3, I2C_1, 3},
{PTC7, I2C_1, 3},
{PTC16, I2C_0, 3},
{PTC18, I2C_1, 3},
{NC , NC , 0}
};
const PinMap PinMap_I2C_SCL[] = {
{PTB0, I2C_0, 3},
{PTB16, I2C_1, 3},
{PTB18, I2C_1, 3},
{PTC2, I2C_1, 3},
{PTC6, I2C_1, 3},
{PTC17, I2C_1, 3},
{PTC19, I2C_0, 3},
{NC , NC , 0}
};
/************UART***************/
const PinMap PinMap_UART_TX[] = {
{PTC3, LPUART_0, 4},
{PTC7, LPUART_0, 4},
{PTC18, LPUART_0, 4},
{NC , NC , 0}
};
const PinMap PinMap_UART_RX[] = {
{PTC2, LPUART_0, 4},
{PTC6, LPUART_0, 4},
{PTC17, LPUART_0, 4},
{NC , NC , 0}
};
const PinMap PinMap_UART_CTS[] = {
{PTC4, LPUART_0, 4},
{PTC19, LPUART_0, 4},
{NC , NC , 0}
};
const PinMap PinMap_UART_RTS[] = {
{PTC1, LPUART_0, 4},
{PTC5, LPUART_0, 4},
{PTC16, LPUART_0, 4},
{NC , NC , 0}
};
/************SPI***************/
const PinMap PinMap_SPI_SCLK[] = {
{PTA18, SPI_1, 2},
{PTC16, SPI_0, 2},
{NC , NC , 0}
};
const PinMap PinMap_SPI_MOSI[] = {
{PTA16, SPI_1, 2},
{PTC17, SPI_0, 2},
{NC , NC , 0}
};
const PinMap PinMap_SPI_MISO[] = {
{PTA17, SPI_1, 2},
{PTC18, SPI_0, 2},
{NC , NC , 0}
};
const PinMap PinMap_SPI_SSEL[] = {
{PTA1, SPI_1, 2},
{PTA19, SPI_1, 2},
{PTC19, SPI_0, 2},
{NC , NC , 0}
};
/************PWM***************/
const PinMap PinMap_PWM[] = {
/* TPM 0 */
{PTA16, PWM_1, 5},
{PTB0, PWM_2, 5},
{PTB1, PWM_3, 5},
{PTA2, PWM_4, 5},
{PTB18, PWM_1, 5},
{PTC3, PWM_2, 5},
{PTC1, PWM_3, 5},
{PTC16, PWM_4, 5},
/* TPM 1 */
{PTA0, PWM_5, 5},
{PTA1, PWM_6, 5},
{PTB2, PWM_5, 5},
{PTB3, PWM_6, 5},
{PTC4, PWM_5, 5},
{PTC5, PWM_6, 5},
/* TPM 2 */
{PTA18, PWM_7, 5},
{PTA19, PWM_8, 5},
{PTB16, PWM_7, 5},
{PTB17, PWM_8, 5},
{PTC6, PWM_7, 5},
{PTC7, PWM_8, 5},
{NC , NC , 0}
};

View File

@ -0,0 +1,122 @@
/* mbed Microcontroller Library
* Copyright (c) 2006-2013 ARM Limited
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#ifndef MBED_PINNAMES_H
#define MBED_PINNAMES_H
#include "cmsis.h"
#ifdef __cplusplus
extern "C" {
#endif
typedef enum {
PIN_INPUT,
PIN_OUTPUT
} PinDirection;
#define GPIO_PORT_SHIFT 12
typedef enum {
PTA0 = (0 << GPIO_PORT_SHIFT | 0),
PTA1 = (0 << GPIO_PORT_SHIFT | 1),
PTA2 = (0 << GPIO_PORT_SHIFT | 2),
PTA16 = (0 << GPIO_PORT_SHIFT | 16),
PTA17 = (0 << GPIO_PORT_SHIFT | 17),
PTA18 = (0 << GPIO_PORT_SHIFT | 18),
PTA19 = (0 << GPIO_PORT_SHIFT | 19),
PTB0 = (1 << GPIO_PORT_SHIFT | 0),
PTB1 = (1 << GPIO_PORT_SHIFT | 1),
PTB2 = (1 << GPIO_PORT_SHIFT | 2),
PTB3 = (1 << GPIO_PORT_SHIFT | 3),
PTB16 = (1 << GPIO_PORT_SHIFT | 16),
PTB17 = (1 << GPIO_PORT_SHIFT | 17),
PTB18 = (1 << GPIO_PORT_SHIFT | 18),
PTC1 = (2 << GPIO_PORT_SHIFT | 1),
PTC2 = (2 << GPIO_PORT_SHIFT | 2),
PTC3 = (2 << GPIO_PORT_SHIFT | 3),
PTC4 = (2 << GPIO_PORT_SHIFT | 4),
PTC5 = (2 << GPIO_PORT_SHIFT | 5),
PTC6 = (2 << GPIO_PORT_SHIFT | 6),
PTC7 = (2 << GPIO_PORT_SHIFT | 7),
PTC16 = (2 << GPIO_PORT_SHIFT | 16),
PTC17 = (2 << GPIO_PORT_SHIFT | 17),
PTC18 = (2 << GPIO_PORT_SHIFT | 18),
PTC19 = (2 << GPIO_PORT_SHIFT | 19),
LED_RED = PTC1,
LED_GREEN = PTA19,
LED_BLUE = PTA18,
// mbed original LED naming
LED1 = LED_RED,
LED2 = LED_GREEN,
LED3 = LED_BLUE,
LED4 = LED_RED,
//Push buttons
SW3 = PTC4,
SW4 = PTC5,
// USB Pins
USBTX = PTC7,
USBRX = PTC6,
// Arduino Headers
D0 = PTC6,
D1 = PTC7,
D2 = PTC19,
D3 = PTC16,
D4 = PTC4,
D5 = PTC17,
D6 = PTC18,
D7 = PTA1,
D8 = PTA0,
D9 = PTC1,
D10 = PTA19,
D11 = PTA16,
D12 = PTA17,
D13 = PTA18,
D14 = PTC3,
D15 = PTC2,
I2C_SCL = D15,
I2C_SDA = D14,
DAC0_OUT = PTB18,
A1 = DAC0_OUT,
A2 = PTB2,
A3 = PTB3,
A4 = PTB1,
A5 = PTB0,
// Not connected
NC = (int)0xFFFFFFFF
} PinName;
typedef enum {
PullNone = 0,
PullDown = 1,
PullUp = 2,
PullDefault = PullUp
} PinMode;
#ifdef __cplusplus
}
#endif
#endif

View File

@ -0,0 +1,39 @@
// The 'features' section in 'target.json' is now used to create the device's hardware preprocessor switches.
// Check the 'features' section of the target description in 'targets.json' for more details.
/* mbed Microcontroller Library
* Copyright (c) 2006-2013 ARM Limited
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#ifndef MBED_DEVICE_H
#define MBED_DEVICE_H
#define DEVICE_ID_LENGTH 24
#include "objects.h"
#endif

View File

@ -0,0 +1,221 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include "fsl_common.h"
#include "fsl_smc.h"
#include "fsl_clock_config.h"
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @brief Clock configuration structure. */
typedef struct _clock_config
{
mcg_config_t mcgConfig; /*!< MCG configuration. */
sim_clock_config_t simConfig; /*!< SIM configuration. */
osc_config_t oscConfig; /*!< OSC configuration. */
uint32_t coreClock; /*!< core clock frequency. */
} clock_config_t;
/*******************************************************************************
* Variables
******************************************************************************/
/* System clock frequency. */
extern uint32_t SystemCoreClock;
/* Configuration for enter VLPR mode. Core clock = 4MHz. */
const clock_config_t g_defaultClockConfigVlpr = {
.mcgConfig =
{
.mcgMode = kMCG_ModeBLPI, /* Work in BLPI mode. */
.irclkEnableMode = kMCG_IrclkEnable, /* MCGIRCLK enable. */
.ircs = kMCG_IrcFast, /* Select IRC4M. */
.fcrdiv = 0U, /* FCRDIV is 0. */
.frdiv = 5U,
.drs = kMCG_DrsLow, /* Low frequency range */
.dmx32 = kMCG_Dmx32Default, /* DCO has a default range of 25% */
.oscsel = kMCG_OscselOsc, /* Select OSC */
},
.simConfig =
{
.er32kSrc = 0U, /* ERCLK32K selection, use OSC. */
.clkdiv1 = 0x00040000U, /* SIM_CLKDIV1. */
},
.oscConfig =
{
.freq = BOARD_XTAL0_CLK_HZ, /* Feed by RF XTAL_32M */
.workMode = kOSC_ModeExt, /* Must work in external source mode. */
},
.coreClock = 4000000U, /* Core clock frequency */
};
/* Configuration for enter RUN mode. Core clock = 40MHz. */
const clock_config_t g_defaultClockConfigRun = {
.mcgConfig =
{
.mcgMode = kMCG_ModeFEE, /* Work in FEE mode. */
.irclkEnableMode = kMCG_IrclkEnable, /* MCGIRCLK enable. */
.ircs = kMCG_IrcFast, /* Select IRC4M. */
.fcrdiv = 0U, /* FCRDIV is 0. */
.frdiv = 5U,
.drs = kMCG_DrsMid, /* Middle frequency range */
.dmx32 = kMCG_Dmx32Default, /* DCO has a default range of 25% */
.oscsel = kMCG_OscselOsc, /* Select OSC */
},
.simConfig =
{
.er32kSrc = 0U, /* ERCLK32K selection, use OSC. */
.clkdiv1 = 0x00010000U, /* SIM_CLKDIV1. */
},
.oscConfig =
{
.freq = BOARD_XTAL0_CLK_HZ, /* Feed by RF XTAL_32M */
.workMode = kOSC_ModeExt, /* Must work in external source mode. */
},
.coreClock = 40000000U, /* Core clock frequency */
};
/*******************************************************************************
* Code
******************************************************************************/
/*
* How to setup clock using clock driver functions:
*
* 1. CLOCK_SetSimSafeDivs, to make sure core clock, bus clock, flexbus clock
* and flash clock are in allowed range during clock mode switch.
*
* 2. Call CLOCK_Osc0Init to setup OSC clock, if it is used in target mode.
*
* 3. Set MCG configuration, MCG includes three parts: FLL clock, PLL clock and
* internal reference clock(MCGIRCLK). Follow the steps to setup:
*
* 1). Call CLOCK_BootToXxxMode to set MCG to target mode.
*
* 2). If target mode is FBI/BLPI/PBI mode, the MCGIRCLK has been configured
* correctly. For other modes, need to call CLOCK_SetInternalRefClkConfig
* explicitly to setup MCGIRCLK.
*
* 3). Don't need to configure FLL explicitly, because if target mode is FLL
* mode, then FLL has been configured by the function CLOCK_BootToXxxMode,
* if the target mode is not FLL mode, the FLL is disabled.
*
* 4). If target mode is PEE/PBE/PEI/PBI mode, then the related PLL has been
* setup by CLOCK_BootToXxxMode. In FBE/FBI/FEE/FBE mode, the PLL could
* be enabled independently, call CLOCK_EnablePll0 explicitly in this case.
*
* 4. Call CLOCK_SetSimConfig to set the clock configuration in SIM.
*/
static void CLOCK_SYS_FllStableDelay(void)
{
uint32_t i = 30000U;
while (i--)
{
__NOP();
}
}
void BOARD_BootClockVLPR(void)
{
/* ERR010224 */
RSIM->RF_OSC_CTRL |= RSIM_RF_OSC_CTRL_RADIO_EXT_OSC_OVRD_EN_MASK; /* Prevent XTAL_OUT_EN from generating XTAL_OUT request */
CLOCK_SetSimSafeDivs();
CLOCK_BootToBlpiMode(g_defaultClockConfigVlpr.mcgConfig.fcrdiv, g_defaultClockConfigVlpr.mcgConfig.ircs,
g_defaultClockConfigVlpr.mcgConfig.irclkEnableMode);
CLOCK_SetSimConfig(&g_defaultClockConfigVlpr.simConfig);
SystemCoreClock = g_defaultClockConfigVlpr.coreClock;
SMC_SetPowerModeProtection(SMC, kSMC_AllowPowerModeAll);
SMC_SetPowerModeVlpr(SMC);
while (SMC_GetPowerModeState(SMC) != kSMC_PowerStateVlpr)
{
}
}
void BOARD_BootClockRUN(void)
{
BOARD_RfOscInit();
CLOCK_SetSimSafeDivs();
CLOCK_InitOsc0(&g_defaultClockConfigRun.oscConfig);
CLOCK_SetXtal0Freq(BOARD_XTAL0_CLK_HZ);
CLOCK_BootToFeeMode(kMCG_OscselOsc, g_defaultClockConfigRun.mcgConfig.frdiv,
g_defaultClockConfigRun.mcgConfig.dmx32, g_defaultClockConfigRun.mcgConfig.drs,
CLOCK_SYS_FllStableDelay);
CLOCK_SetInternalRefClkConfig(g_defaultClockConfigRun.mcgConfig.irclkEnableMode,
g_defaultClockConfigRun.mcgConfig.ircs, g_defaultClockConfigRun.mcgConfig.fcrdiv);
CLOCK_SetSimConfig(&g_defaultClockConfigRun.simConfig);
SystemCoreClock = g_defaultClockConfigRun.coreClock;
}
void BOARD_RfOscInit(void)
{
uint32_t temp, tempTrim;
uint8_t revId;
/* Obtain REV ID from SIM */
temp = SIM->SDID;
revId = (uint8_t)((temp & SIM_SDID_REVID_MASK) >> SIM_SDID_REVID_SHIFT);
if(0 == revId)
{
tempTrim = RSIM->ANA_TRIM;
RSIM->ANA_TRIM |= RSIM_ANA_TRIM_BB_LDO_XO_TRIM_MASK; /* Set max trim for BB LDO for XO */
}/* Workaround for Rev 1.0 XTAL startup and ADC analog diagnostics circuitry */
/* Turn on clocks for the XCVR */
/* Enable RF OSC in RSIM and wait for ready */
temp = RSIM->CONTROL;
temp &= ~RSIM_CONTROL_RF_OSC_EN_MASK;
RSIM->CONTROL = temp | RSIM_CONTROL_RF_OSC_EN(1);
/* ERR010224 */
RSIM->RF_OSC_CTRL |= RSIM_RF_OSC_CTRL_RADIO_EXT_OSC_OVRD_EN_MASK; /* Prevent XTAL_OUT_EN from generating XTAL_OUT request */
while((RSIM->CONTROL & RSIM_CONTROL_RF_OSC_READY_MASK) == 0); /* Wait for RF_OSC_READY */
if(0 == revId)
{
SIM->SCGC5 |= SIM_SCGC5_PHYDIG_MASK;
XCVR_TSM->OVRD0 |= XCVR_TSM_OVRD0_BB_LDO_ADCDAC_EN_OVRD_EN_MASK | XCVR_TSM_OVRD0_BB_LDO_ADCDAC_EN_OVRD_MASK; /* Force ADC DAC LDO on to prevent BGAP failure */
RSIM->ANA_TRIM = tempTrim; /* Reset LDO trim settings */
}/* Workaround for Rev 1.0 XTAL startup and ADC analog diagnostics circuitry */
}

View File

@ -0,0 +1,55 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _CLOCK_CONFIG_H_
#define _CLOCK_CONFIG_H_
/*******************************************************************************
* DEFINITION
******************************************************************************/
#define BOARD_XTAL0_CLK_HZ 32000000U
#define BOARD_XTAL32K_CLK_HZ 32768U
/*******************************************************************************
* API
******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif /* __cplusplus*/
void BOARD_BootClockVLPR(void);
void BOARD_BootClockRUN(void);
void BOARD_RfOscInit(void);
#if defined(__cplusplus)
}
#endif /* __cplusplus*/
#endif /* _CLOCK_CONFIG_H_ */

View File

@ -0,0 +1,40 @@
/* mbed Microcontroller Library
* Copyright (c) 2006-2013 ARM Limited
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#include "gpio_api.h"
#include "fsl_clock_config.h"
// called before main - implement here if board needs it otherwise, let
// the application override this if necessary
void mbed_sdk_init()
{
BOARD_BootClockRUN();
}
// Enable the RTC oscillator if available on the board
void rtc_setup_oscillator(RTC_Type *base)
{
/* Enable the RTC oscillator */
RTC->CR |= RTC_CR_OSCE_MASK;
}
// Change the NMI pin to an input. This allows NMI pin to
// be used as a low power mode wakeup. The application will
// need to change the pin back to NMI_b or wakeup only occurs once!
void NMI_Handler(void)
{
gpio_t gpio;
gpio_init_in(&gpio, PTB18);
}

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,111 @@
#! armcc -E
/*
** ###################################################################
** Processor: MKW41Z512VHT4
** Compiler: Keil ARM C/C++ Compiler
** Reference manual: MKW41Z512RM Rev. 0.1, 04/2016
** Version: rev. 1.0, 2015-09-23
** Build: b160720
**
** Abstract:
** Linker file for the Keil ARM C/C++ Compiler
**
** Copyright (c) 2016 Freescale Semiconductor, Inc.
** All rights reserved.
**
** Redistribution and use in source and binary forms, with or without modification,
** are permitted provided that the following conditions are met:
**
** o Redistributions of source code must retain the above copyright notice, this list
** of conditions and the following disclaimer.
**
** o Redistributions in binary form must reproduce the above copyright notice, this
** list of conditions and the following disclaimer in the documentation and/or
** other materials provided with the distribution.
**
** o Neither the name of Freescale Semiconductor, Inc. nor the names of its
** contributors may be used to endorse or promote products derived from this
** software without specific prior written permission.
**
** THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
** ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
** WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
** DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
** ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
** (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
** LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
** ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
** (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
** SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
**
** http: www.freescale.com
** mail: support@freescale.com
**
** ###################################################################
*/
#define __ram_vector_table__ 1
/* Heap 1/4 of ram and stack 1/8 */
#define __stack_size__ 0x4000
#define __heap_size__ 0x8000
#if (defined(__ram_vector_table__))
#define __ram_vector_table_size__ 0x00000200
#else
#define __ram_vector_table_size__ 0x00000000
#endif
#define m_interrupts_start 0x00000000
#define m_interrupts_size 0x00000200
#define m_flash_config_start 0x00000400
#define m_flash_config_size 0x00000010
#define m_text_start 0x00000410
#define m_text_size 0x0007FBF0
#define m_interrupts_ram_start 0x1FFF8000
#define m_interrupts_ram_size __ram_vector_table_size__
#define m_data_start (m_interrupts_ram_start + m_interrupts_ram_size)
#define m_data_size (0x00020000 - m_interrupts_ram_size)
/* Sizes */
#if (defined(__stack_size__))
#define Stack_Size __stack_size__
#else
#define Stack_Size 0x0400
#endif
#if (defined(__heap_size__))
#define Heap_Size __heap_size__
#else
#define Heap_Size 0x0400
#endif
LR_m_text m_interrupts_start m_text_start+m_text_size-m_interrupts_start { ; load region size_region
VECTOR_ROM m_interrupts_start m_interrupts_size { ; load address = execution address
* (RESET,+FIRST)
}
ER_m_flash_config m_flash_config_start FIXED m_flash_config_size { ; load address = execution address
* (FlashConfig)
}
ER_m_text m_text_start m_text_size { ; load address = execution address
* (InRoot$$Sections)
.ANY (+RO)
}
#if (defined(__ram_vector_table__))
VECTOR_RAM m_interrupts_ram_start EMPTY m_interrupts_ram_size {
}
#else
VECTOR_RAM m_interrupts_start EMPTY 0 {
}
#endif
RW_m_data m_data_start m_data_size-Stack_Size-Heap_Size { ; RW data
.ANY (+RW +ZI)
}
RW_IRAM1 +0 { ; Heap region growing up
}
}

View File

@ -0,0 +1,426 @@
; * ---------------------------------------------------------------------------------------
; * @file: startup_MKW41Z4.s
; * @purpose: CMSIS Cortex-M0P Core Device Startup File
; * MKW41Z4
; * @version: 1.0
; * @date: 2015-9-23
; * @build: b160720
; * ---------------------------------------------------------------------------------------
; *
; * Copyright (c) 1997 - 2016 , Freescale Semiconductor, Inc.
; * All rights reserved.
; *
; * Redistribution and use in source and binary forms, with or without modification,
; * are permitted provided that the following conditions are met:
; *
; * o Redistributions of source code must retain the above copyright notice, this list
; * of conditions and the following disclaimer.
; *
; * o Redistributions in binary form must reproduce the above copyright notice, this
; * list of conditions and the following disclaimer in the documentation and/or
; * other materials provided with the distribution.
; *
; * o Neither the name of Freescale Semiconductor, Inc. nor the names of its
; * contributors may be used to endorse or promote products derived from this
; * software without specific prior written permission.
; *
; * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
; * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
; * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
; * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
; * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
; * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
; * ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
; * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
; * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
; *
; *------- <<< Use Configuration Wizard in Context Menu >>> ------------------
; *
; *****************************************************************************/
__initial_sp EQU 0x20018000 ; Top of RAM
PRESERVE8
THUMB
; Vector Table Mapped to Address 0 at Reset
AREA RESET, DATA, READONLY
EXPORT __Vectors
EXPORT __Vectors_End
EXPORT __Vectors_Size
__Vectors DCD __initial_sp ; Top of Stack
DCD Reset_Handler ; Reset Handler
DCD NMI_Handler ;NMI Handler
DCD HardFault_Handler ;Hard Fault Handler
DCD 0 ;Reserved
DCD 0 ;Reserved
DCD 0 ;Reserved
DCD 0 ;Reserved
DCD 0 ;Reserved
DCD 0 ;Reserved
DCD 0 ;Reserved
DCD SVC_Handler ;SVCall Handler
DCD 0 ;Reserved
DCD 0 ;Reserved
DCD PendSV_Handler ;PendSV Handler
DCD SysTick_Handler ;SysTick Handler
;External Interrupts
DCD DMA0_IRQHandler ;DMA channel 0 transfer complete
DCD DMA1_IRQHandler ;DMA channel 1 transfer complete
DCD DMA2_IRQHandler ;DMA channel 2 transfer complete
DCD DMA3_IRQHandler ;DMA channel 3 transfer complete
DCD Reserved20_IRQHandler ;Reserved interrupt
DCD FTFA_IRQHandler ;Command complete and read collision
DCD LVD_LVW_DCDC_IRQHandler ;Low-voltage detect, low-voltage warning, DCDC
DCD LLWU_IRQHandler ;Low leakage wakeup Unit
DCD I2C0_IRQHandler ;I2C0 interrupt
DCD I2C1_IRQHandler ;I2C1 interrupt
DCD SPI0_IRQHandler ;SPI0 single interrupt vector for all sources
DCD TSI0_IRQHandler ;TSI0 single interrupt vector for all sources
DCD LPUART0_IRQHandler ;LPUART0 status and error
DCD TRNG0_IRQHandler ;TRNG0 interrupt
DCD CMT_IRQHandler ;CMT interrupt
DCD ADC0_IRQHandler ;ADC0 interrupt
DCD CMP0_IRQHandler ;CMP0 interrupt
DCD TPM0_IRQHandler ;TPM0 single interrupt vector for all sources
DCD TPM1_IRQHandler ;TPM1 single interrupt vector for all sources
DCD TPM2_IRQHandler ;TPM2 single interrupt vector for all sources
DCD RTC_IRQHandler ;RTC alarm
DCD RTC_Seconds_IRQHandler ;RTC seconds
DCD PIT_IRQHandler ;PIT interrupt
DCD LTC0_IRQHandler ;LTC0 interrupt
DCD Radio_0_IRQHandler ;BTLE, ZIGBEE, ANT, GENFSK interrupt 0
DCD DAC0_IRQHandler ;DAC0 interrupt
DCD Radio_1_IRQHandler ;BTLE, ZIGBEE, ANT, GENFSK interrupt 1
DCD MCG_IRQHandler ;MCG interrupt
DCD LPTMR0_IRQHandler ;LPTMR0 interrupt
DCD SPI1_IRQHandler ;SPI1 single interrupt vector for all sources
DCD PORTA_IRQHandler ;PORTA Pin detect
DCD PORTB_PORTC_IRQHandler ;PORTB and PORTC Pin detect
__Vectors_End
__Vectors_Size EQU __Vectors_End - __Vectors
; <h> Flash Configuration
; <i> 16-byte flash configuration field that stores default protection settings (loaded on reset)
; <i> and security information that allows the MCU to restrict access to the FTFL module.
; <h> Backdoor Comparison Key
; <o0> Backdoor Comparison Key 0. <0x0-0xFF:2>
; <o1> Backdoor Comparison Key 1. <0x0-0xFF:2>
; <o2> Backdoor Comparison Key 2. <0x0-0xFF:2>
; <o3> Backdoor Comparison Key 3. <0x0-0xFF:2>
; <o4> Backdoor Comparison Key 4. <0x0-0xFF:2>
; <o5> Backdoor Comparison Key 5. <0x0-0xFF:2>
; <o6> Backdoor Comparison Key 6. <0x0-0xFF:2>
; <o7> Backdoor Comparison Key 7. <0x0-0xFF:2>
BackDoorK0 EQU 0xFF
BackDoorK1 EQU 0xFF
BackDoorK2 EQU 0xFF
BackDoorK3 EQU 0xFF
BackDoorK4 EQU 0xFF
BackDoorK5 EQU 0xFF
BackDoorK6 EQU 0xFF
BackDoorK7 EQU 0xFF
; </h>
; <h> Program flash protection bytes (FPROT)
; <i> Each program flash region can be protected from program and erase operation by setting the associated PROT bit.
; <i> Each bit protects a 1/32 region of the program flash memory.
; <h> FPROT0
; <i> Program Flash Region Protect Register 0
; <i> 1/32 - 8/32 region
; <o.0> FPROT0.0
; <o.1> FPROT0.1
; <o.2> FPROT0.2
; <o.3> FPROT0.3
; <o.4> FPROT0.4
; <o.5> FPROT0.5
; <o.6> FPROT0.6
; <o.7> FPROT0.7
nFPROT0 EQU 0x00
FPROT0 EQU nFPROT0:EOR:0xFF
; </h>
; <h> FPROT1
; <i> Program Flash Region Protect Register 1
; <i> 9/32 - 16/32 region
; <o.0> FPROT1.0
; <o.1> FPROT1.1
; <o.2> FPROT1.2
; <o.3> FPROT1.3
; <o.4> FPROT1.4
; <o.5> FPROT1.5
; <o.6> FPROT1.6
; <o.7> FPROT1.7
nFPROT1 EQU 0x00
FPROT1 EQU nFPROT1:EOR:0xFF
; </h>
; <h> FPROT2
; <i> Program Flash Region Protect Register 2
; <i> 17/32 - 24/32 region
; <o.0> FPROT2.0
; <o.1> FPROT2.1
; <o.2> FPROT2.2
; <o.3> FPROT2.3
; <o.4> FPROT2.4
; <o.5> FPROT2.5
; <o.6> FPROT2.6
; <o.7> FPROT2.7
nFPROT2 EQU 0x00
FPROT2 EQU nFPROT2:EOR:0xFF
; </h>
; <h> FPROT3
; <i> Program Flash Region Protect Register 3
; <i> 25/32 - 32/32 region
; <o.0> FPROT3.0
; <o.1> FPROT3.1
; <o.2> FPROT3.2
; <o.3> FPROT3.3
; <o.4> FPROT3.4
; <o.5> FPROT3.5
; <o.6> FPROT3.6
; <o.7> FPROT3.7
nFPROT3 EQU 0x00
FPROT3 EQU nFPROT3:EOR:0xFF
; </h>
; </h>
; <h> Flash nonvolatile option byte (FOPT)
; <i> Allows the user to customize the operation of the MCU at boot time.
; <o.0> LPBOOT0
; <0=> Core and system clock divider (OUTDIV1) is 0x7 (divide by 8) when LPBOOT1=0 or 0x1 (divide by 2) when LPBOOT1=1.
; <1=> Core and system clock divider (OUTDIV1) is 0x3 (divide by 4) when LPBOOT1=0 or 0x0 (divide by 1) when LPBOOT1=1.
; <o.2> NMI_DIS
; <0=> NMI interrupts are always blocked
; <1=> NMI_b pin/interrupts reset default to enabled
; <o.3> RESET_PIN_CFG
; <0=> RESET pin is disabled following a POR and cannot be enabled as reset function
; <1=> RESET_b pin is dedicated
; <o.4> LPBOOT1
; <0=> Core and system clock divider (OUTDIV1) is 0x7 (divide by 8) when LPBOOT0=0 or 0x3 (divide by 4) when LPBOOT0=1.
; <1=> Core and system clock divider (OUTDIV1) is 0x1 (divide by 2) when LPBOOT0=0 or 0x0 (divide by 1) when LPBOOT0=1.
; <o.5> FAST_INIT
; <0=> Slower initialization
; <1=> Fast Initialization
FOPT EQU 0xFF
; </h>
; <h> Flash security byte (FSEC)
; <i> WARNING: If SEC field is configured as "MCU security status is secure" and MEEN field is configured as "Mass erase is disabled",
; <i> MCU's security status cannot be set back to unsecure state since Mass erase via the debugger is blocked !!!
; <o.0..1> SEC
; <2=> MCU security status is unsecure
; <3=> MCU security status is secure
; <i> Flash Security
; <o.2..3> FSLACC
; <2=> Freescale factory access denied
; <3=> Freescale factory access granted
; <i> Freescale Failure Analysis Access Code
; <o.4..5> MEEN
; <2=> Mass erase is disabled
; <3=> Mass erase is enabled
; <o.6..7> KEYEN
; <2=> Backdoor key access enabled
; <3=> Backdoor key access disabled
; <i> Backdoor Key Security Enable
FSEC EQU 0xFE
; </h>
; </h>
IF :LNOT::DEF:RAM_TARGET
AREA FlashConfig, DATA, READONLY
__FlashConfig
DCB BackDoorK0, BackDoorK1, BackDoorK2, BackDoorK3
DCB BackDoorK4, BackDoorK5, BackDoorK6, BackDoorK7
DCB FPROT0 , FPROT1 , FPROT2 , FPROT3
DCB FSEC , FOPT , 0xFF , 0xFF
ENDIF
AREA |.text|, CODE, READONLY
; Reset Handler
Reset_Handler PROC
EXPORT Reset_Handler [WEAK]
IMPORT SystemInit
IMPORT __main
IF :LNOT::DEF:RAM_TARGET
REQUIRE FlashConfig
ENDIF
CPSID I ; Mask interrupts
LDR R0, =0xE000ED08
LDR R1, =__Vectors
STR R1, [R0]
LDR R0, =SystemInit
BLX R0
CPSIE i ; Unmask interrupts
LDR R0, =__main
BX R0
ENDP
; Dummy Exception Handlers (infinite loops which can be modified)
NMI_Handler\
PROC
EXPORT NMI_Handler [WEAK]
B .
ENDP
HardFault_Handler\
PROC
EXPORT HardFault_Handler [WEAK]
B .
ENDP
SVC_Handler\
PROC
EXPORT SVC_Handler [WEAK]
B .
ENDP
PendSV_Handler\
PROC
EXPORT PendSV_Handler [WEAK]
B .
ENDP
SysTick_Handler\
PROC
EXPORT SysTick_Handler [WEAK]
B .
ENDP
DMA0_IRQHandler\
PROC
EXPORT DMA0_IRQHandler [WEAK]
LDR R0, =DMA0_DriverIRQHandler
BX R0
ENDP
DMA1_IRQHandler\
PROC
EXPORT DMA1_IRQHandler [WEAK]
LDR R0, =DMA1_DriverIRQHandler
BX R0
ENDP
DMA2_IRQHandler\
PROC
EXPORT DMA2_IRQHandler [WEAK]
LDR R0, =DMA2_DriverIRQHandler
BX R0
ENDP
DMA3_IRQHandler\
PROC
EXPORT DMA3_IRQHandler [WEAK]
LDR R0, =DMA3_DriverIRQHandler
BX R0
ENDP
I2C0_IRQHandler\
PROC
EXPORT I2C0_IRQHandler [WEAK]
LDR R0, =I2C0_DriverIRQHandler
BX R0
ENDP
I2C1_IRQHandler\
PROC
EXPORT I2C1_IRQHandler [WEAK]
LDR R0, =I2C1_DriverIRQHandler
BX R0
ENDP
SPI0_IRQHandler\
PROC
EXPORT SPI0_IRQHandler [WEAK]
LDR R0, =SPI0_DriverIRQHandler
BX R0
ENDP
LPUART0_IRQHandler\
PROC
EXPORT LPUART0_IRQHandler [WEAK]
LDR R0, =LPUART0_DriverIRQHandler
BX R0
ENDP
SPI1_IRQHandler\
PROC
EXPORT SPI1_IRQHandler [WEAK]
LDR R0, =SPI1_DriverIRQHandler
BX R0
ENDP
Default_Handler\
PROC
EXPORT DMA0_DriverIRQHandler [WEAK]
EXPORT DMA1_DriverIRQHandler [WEAK]
EXPORT DMA2_DriverIRQHandler [WEAK]
EXPORT DMA3_DriverIRQHandler [WEAK]
EXPORT Reserved20_IRQHandler [WEAK]
EXPORT FTFA_IRQHandler [WEAK]
EXPORT LVD_LVW_DCDC_IRQHandler [WEAK]
EXPORT LLWU_IRQHandler [WEAK]
EXPORT I2C0_DriverIRQHandler [WEAK]
EXPORT I2C1_DriverIRQHandler [WEAK]
EXPORT SPI0_DriverIRQHandler [WEAK]
EXPORT TSI0_IRQHandler [WEAK]
EXPORT LPUART0_DriverIRQHandler [WEAK]
EXPORT TRNG0_IRQHandler [WEAK]
EXPORT CMT_IRQHandler [WEAK]
EXPORT ADC0_IRQHandler [WEAK]
EXPORT CMP0_IRQHandler [WEAK]
EXPORT TPM0_IRQHandler [WEAK]
EXPORT TPM1_IRQHandler [WEAK]
EXPORT TPM2_IRQHandler [WEAK]
EXPORT RTC_IRQHandler [WEAK]
EXPORT RTC_Seconds_IRQHandler [WEAK]
EXPORT PIT_IRQHandler [WEAK]
EXPORT LTC0_IRQHandler [WEAK]
EXPORT Radio_0_IRQHandler [WEAK]
EXPORT DAC0_IRQHandler [WEAK]
EXPORT Radio_1_IRQHandler [WEAK]
EXPORT MCG_IRQHandler [WEAK]
EXPORT LPTMR0_IRQHandler [WEAK]
EXPORT SPI1_DriverIRQHandler [WEAK]
EXPORT PORTA_IRQHandler [WEAK]
EXPORT PORTB_PORTC_IRQHandler [WEAK]
EXPORT DefaultISR [WEAK]
DMA0_DriverIRQHandler
DMA1_DriverIRQHandler
DMA2_DriverIRQHandler
DMA3_DriverIRQHandler
Reserved20_IRQHandler
FTFA_IRQHandler
LVD_LVW_DCDC_IRQHandler
LLWU_IRQHandler
I2C0_DriverIRQHandler
I2C1_DriverIRQHandler
SPI0_DriverIRQHandler
TSI0_IRQHandler
LPUART0_DriverIRQHandler
TRNG0_IRQHandler
CMT_IRQHandler
ADC0_IRQHandler
CMP0_IRQHandler
TPM0_IRQHandler
TPM1_IRQHandler
TPM2_IRQHandler
RTC_IRQHandler
RTC_Seconds_IRQHandler
PIT_IRQHandler
LTC0_IRQHandler
Radio_0_IRQHandler
DAC0_IRQHandler
Radio_1_IRQHandler
MCG_IRQHandler
LPTMR0_IRQHandler
SPI1_DriverIRQHandler
PORTA_IRQHandler
PORTB_PORTC_IRQHandler
DefaultISR
LDR R0, =DefaultISR
BX R0
ENDP
ALIGN
END

View File

@ -0,0 +1,32 @@
/* mbed Microcontroller Library - stackheap
* Copyright (C) 2009-2011 ARM Limited. All rights reserved.
*
* Setup a fixed single stack/heap memory model,
* between the top of the RW/ZI region and the stackpointer
*/
#ifdef __cplusplus
extern "C" {
#endif
#include <rt_misc.h>
#include <stdint.h>
extern char Image$$RW_IRAM1$$ZI$$Limit[];
extern __value_in_regs struct __initial_stackheap __user_setup_stackheap(uint32_t R0, uint32_t R1, uint32_t R2, uint32_t R3)
{
uint32_t zi_limit = (uint32_t)Image$$RW_IRAM1$$ZI$$Limit;
uint32_t sp_limit = __current_sp();
zi_limit = (zi_limit + 7) & ~0x7; // ensure zi_limit is 8-byte aligned
struct __initial_stackheap r;
r.heap_base = zi_limit;
r.heap_limit = sp_limit;
return r;
}
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,258 @@
/*
** ###################################################################
** Processor: MKW41Z512VHT4
** Compiler: GNU C Compiler
** Reference manual: MKW41Z512RM Rev. 0.1, 04/2016
** Version: rev. 1.0, 2015-09-23
** Build: b160720
**
** Abstract:
** Linker file for the GNU C Compiler
**
** Copyright (c) 2016 Freescale Semiconductor, Inc.
** All rights reserved.
**
** Redistribution and use in source and binary forms, with or without modification,
** are permitted provided that the following conditions are met:
**
** o Redistributions of source code must retain the above copyright notice, this list
** of conditions and the following disclaimer.
**
** o Redistributions in binary form must reproduce the above copyright notice, this
** list of conditions and the following disclaimer in the documentation and/or
** other materials provided with the distribution.
**
** o Neither the name of Freescale Semiconductor, Inc. nor the names of its
** contributors may be used to endorse or promote products derived from this
** software without specific prior written permission.
**
** THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
** ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
** WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
** DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
** ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
** (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
** LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
** ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
** (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
** SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
**
** http: www.freescale.com
** mail: support@freescale.com
**
** ###################################################################
*/
/* Entry Point */
ENTRY(Reset_Handler)
__ram_vector_table__ = 1;
/* Heap 1/4 of ram and stack 1/8 */
__stack_size__ = 0x4000;
__heap_size__ = 0x8000;
HEAP_SIZE = DEFINED(__heap_size__) ? __heap_size__ : 0x0400;
STACK_SIZE = DEFINED(__stack_size__) ? __stack_size__ : 0x0400;
M_VECTOR_RAM_SIZE = DEFINED(__ram_vector_table__) ? 0x0200 : 0x0;
/* Specify the memory areas */
MEMORY
{
m_interrupts (RX) : ORIGIN = 0x00000000, LENGTH = 0x00000200
m_flash_config (RX) : ORIGIN = 0x00000400, LENGTH = 0x00000010
m_text (RX) : ORIGIN = 0x00000410, LENGTH = 0x0007FBF0
m_data (RW) : ORIGIN = 0x1FFF8000, LENGTH = 0x00020000
}
/* Define output sections */
SECTIONS
{
/* The startup code goes first into internal flash */
.interrupts :
{
__VECTOR_TABLE = .;
. = ALIGN(4);
KEEP(*(.isr_vector)) /* Startup code */
. = ALIGN(4);
} > m_interrupts
.flash_config :
{
. = ALIGN(4);
KEEP(*(.FlashConfig)) /* Flash Configuration Field (FCF) */
. = ALIGN(4);
} > m_flash_config
/* The program code and other data goes into internal flash */
.text :
{
. = ALIGN(4);
*(.text) /* .text sections (code) */
*(.text*) /* .text* sections (code) */
*(.rodata) /* .rodata sections (constants, strings, etc.) */
*(.rodata*) /* .rodata* sections (constants, strings, etc.) */
*(.glue_7) /* glue arm to thumb code */
*(.glue_7t) /* glue thumb to arm code */
*(.eh_frame)
KEEP (*(.init))
KEEP (*(.fini))
. = ALIGN(4);
} > m_text
.ARM.extab :
{
*(.ARM.extab* .gnu.linkonce.armextab.*)
} > m_text
.ARM :
{
__exidx_start = .;
*(.ARM.exidx*)
__exidx_end = .;
} > m_text
.ctors :
{
__CTOR_LIST__ = .;
/* gcc uses crtbegin.o to find the start of
the constructors, so we make sure it is
first. Because this is a wildcard, it
doesn't matter if the user does not
actually link against crtbegin.o; the
linker won't look for a file to match a
wildcard. The wildcard also means that it
doesn't matter which directory crtbegin.o
is in. */
KEEP (*crtbegin.o(.ctors))
KEEP (*crtbegin?.o(.ctors))
/* We don't want to include the .ctor section from
from the crtend.o file until after the sorted ctors.
The .ctor section from the crtend file contains the
end of ctors marker and it must be last */
KEEP (*(EXCLUDE_FILE(*crtend?.o *crtend.o) .ctors))
KEEP (*(SORT(.ctors.*)))
KEEP (*(.ctors))
__CTOR_END__ = .;
} > m_text
.dtors :
{
__DTOR_LIST__ = .;
KEEP (*crtbegin.o(.dtors))
KEEP (*crtbegin?.o(.dtors))
KEEP (*(EXCLUDE_FILE(*crtend?.o *crtend.o) .dtors))
KEEP (*(SORT(.dtors.*)))
KEEP (*(.dtors))
__DTOR_END__ = .;
} > m_text
.preinit_array :
{
PROVIDE_HIDDEN (__preinit_array_start = .);
KEEP (*(.preinit_array*))
PROVIDE_HIDDEN (__preinit_array_end = .);
} > m_text
.init_array :
{
PROVIDE_HIDDEN (__init_array_start = .);
KEEP (*(SORT(.init_array.*)))
KEEP (*(.init_array*))
PROVIDE_HIDDEN (__init_array_end = .);
} > m_text
.fini_array :
{
PROVIDE_HIDDEN (__fini_array_start = .);
KEEP (*(SORT(.fini_array.*)))
KEEP (*(.fini_array*))
PROVIDE_HIDDEN (__fini_array_end = .);
} > m_text
__etext = .; /* define a global symbol at end of code */
__DATA_ROM = .; /* Symbol is used by startup for data initialization */
/* reserve MTB memory at the beginning of m_data */
.mtb : /* MTB buffer address as defined by the hardware */
{
. = ALIGN(8);
_mtb_start = .;
KEEP(*(.mtb_buf)) /* need to KEEP Micro Trace Buffer as not referenced by application */
. = ALIGN(8);
_mtb_end = .;
} > m_data
.interrupts_ram :
{
. = ALIGN(4);
__VECTOR_RAM__ = .;
__interrupts_ram_start__ = .; /* Create a global symbol at data start */
*(.m_interrupts_ram) /* This is a user defined section */
. += M_VECTOR_RAM_SIZE;
. = ALIGN(4);
__interrupts_ram_end__ = .; /* Define a global symbol at data end */
} > m_data
__VECTOR_RAM = DEFINED(__ram_vector_table__) ? __VECTOR_RAM__ : ORIGIN(m_interrupts);
__RAM_VECTOR_TABLE_SIZE_BYTES = DEFINED(__ram_vector_table__) ? (__interrupts_ram_end__ - __interrupts_ram_start__) : 0x0;
.data : AT(__DATA_ROM)
{
. = ALIGN(4);
__DATA_RAM = .;
__data_start__ = .; /* create a global symbol at data start */
*(.data) /* .data sections */
*(.data*) /* .data* sections */
KEEP(*(.jcr*))
. = ALIGN(4);
__data_end__ = .; /* define a global symbol at data end */
} > m_data
__DATA_END = __DATA_ROM + (__data_end__ - __data_start__);
text_end = ORIGIN(m_text) + LENGTH(m_text);
ASSERT(__DATA_END <= text_end, "region m_text overflowed with text and data")
/* Uninitialized data section */
.bss :
{
/* This is used by the startup in order to initialize the .bss section */
. = ALIGN(4);
__START_BSS = .;
__bss_start__ = .;
*(.bss)
*(.bss*)
*(COMMON)
. = ALIGN(4);
__bss_end__ = .;
__END_BSS = .;
} > m_data
.heap :
{
. = ALIGN(8);
__end__ = .;
PROVIDE(end = .);
__HeapBase = .;
. += HEAP_SIZE;
__HeapLimit = .;
__heap_limit = .; /* Add for _sbrk */
} > m_data
.stack :
{
. = ALIGN(8);
. += STACK_SIZE;
} > m_data
/* Initializes stack on the end of block */
__StackTop = ORIGIN(m_data) + LENGTH(m_data);
__StackLimit = __StackTop - STACK_SIZE;
PROVIDE(__stack = __StackTop);
.ARM.attributes 0 : { *(.ARM.attributes) }
ASSERT(__StackLimit >= __HeapLimit, "region m_data overflowed with stack and heap")
}

View File

@ -0,0 +1,364 @@
/* ---------------------------------------------------------------------------------------*/
/* @file: startup_MKW41Z4.s */
/* @purpose: CMSIS Cortex-M0P Core Device Startup File */
/* MKW41Z4 */
/* @version: 1.0 */
/* @date: 2015-9-23 */
/* @build: b160720 */
/* ---------------------------------------------------------------------------------------*/
/* */
/* Copyright (c) 1997 - 2016 , Freescale Semiconductor, Inc. */
/* All rights reserved. */
/* */
/* Redistribution and use in source and binary forms, with or without modification, */
/* are permitted provided that the following conditions are met: */
/* */
/* o Redistributions of source code must retain the above copyright notice, this list */
/* of conditions and the following disclaimer. */
/* */
/* o Redistributions in binary form must reproduce the above copyright notice, this */
/* list of conditions and the following disclaimer in the documentation and/or */
/* other materials provided with the distribution. */
/* */
/* o Neither the name of Freescale Semiconductor, Inc. nor the names of its */
/* contributors may be used to endorse or promote products derived from this */
/* software without specific prior written permission. */
/* */
/* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND */
/* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED */
/* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE */
/* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR */
/* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES */
/* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; */
/* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON */
/* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT */
/* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS */
/* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. */
/*****************************************************************************/
/* Version: GCC for ARM Embedded Processors */
/*****************************************************************************/
.syntax unified
.arch armv6-m
.section .isr_vector, "a"
.align 2
.globl __isr_vector
__isr_vector:
.long __StackTop /* Top of Stack */
.long Reset_Handler /* Reset Handler */
.long NMI_Handler /* NMI Handler*/
.long HardFault_Handler /* Hard Fault Handler*/
.long 0 /* Reserved*/
.long 0 /* Reserved*/
.long 0 /* Reserved*/
.long 0 /* Reserved*/
.long 0 /* Reserved*/
.long 0 /* Reserved*/
.long 0 /* Reserved*/
.long SVC_Handler /* SVCall Handler*/
.long 0 /* Reserved*/
.long 0 /* Reserved*/
.long PendSV_Handler /* PendSV Handler*/
.long SysTick_Handler /* SysTick Handler*/
/* External Interrupts*/
.long DMA0_IRQHandler /* DMA channel 0 transfer complete*/
.long DMA1_IRQHandler /* DMA channel 1 transfer complete*/
.long DMA2_IRQHandler /* DMA channel 2 transfer complete*/
.long DMA3_IRQHandler /* DMA channel 3 transfer complete*/
.long Reserved20_IRQHandler /* Reserved interrupt*/
.long FTFA_IRQHandler /* Command complete and read collision*/
.long LVD_LVW_DCDC_IRQHandler /* Low-voltage detect, low-voltage warning, DCDC*/
.long LLWU_IRQHandler /* Low leakage wakeup Unit*/
.long I2C0_IRQHandler /* I2C0 interrupt*/
.long I2C1_IRQHandler /* I2C1 interrupt*/
.long SPI0_IRQHandler /* SPI0 single interrupt vector for all sources*/
.long TSI0_IRQHandler /* TSI0 single interrupt vector for all sources*/
.long LPUART0_IRQHandler /* LPUART0 status and error*/
.long TRNG0_IRQHandler /* TRNG0 interrupt*/
.long CMT_IRQHandler /* CMT interrupt*/
.long ADC0_IRQHandler /* ADC0 interrupt*/
.long CMP0_IRQHandler /* CMP0 interrupt*/
.long TPM0_IRQHandler /* TPM0 single interrupt vector for all sources*/
.long TPM1_IRQHandler /* TPM1 single interrupt vector for all sources*/
.long TPM2_IRQHandler /* TPM2 single interrupt vector for all sources*/
.long RTC_IRQHandler /* RTC alarm*/
.long RTC_Seconds_IRQHandler /* RTC seconds*/
.long PIT_IRQHandler /* PIT interrupt*/
.long LTC0_IRQHandler /* LTC0 interrupt*/
.long Radio_0_IRQHandler /* BTLE, ZIGBEE, ANT, GENFSK interrupt 0*/
.long DAC0_IRQHandler /* DAC0 interrupt*/
.long Radio_1_IRQHandler /* BTLE, ZIGBEE, ANT, GENFSK interrupt 1*/
.long MCG_IRQHandler /* MCG interrupt*/
.long LPTMR0_IRQHandler /* LPTMR0 interrupt*/
.long SPI1_IRQHandler /* SPI1 single interrupt vector for all sources*/
.long PORTA_IRQHandler /* PORTA Pin detect*/
.long PORTB_PORTC_IRQHandler /* PORTB and PORTC Pin detect*/
.size __isr_vector, . - __isr_vector
/* Flash Configuration */
.section .FlashConfig, "a"
.long 0xFFFFFFFF
.long 0xFFFFFFFF
.long 0xFFFFFFFF
.long 0xFFFFFFFE
.text
.thumb
/* Reset Handler */
.thumb_func
.align 2
.globl Reset_Handler
.weak Reset_Handler
.type Reset_Handler, %function
Reset_Handler:
cpsid i /* Mask interrupts */
.equ VTOR, 0xE000ED08
ldr r0, =VTOR
ldr r1, =__isr_vector
str r1, [r0]
#ifndef __NO_SYSTEM_INIT
ldr r0,=SystemInit
blx r0
#endif
/* Loop to copy data from read only memory to RAM. The ranges
* of copy from/to are specified by following symbols evaluated in
* linker script.
* __etext: End of code section, i.e., begin of data sections to copy from.
* __data_start__/__data_end__: RAM address range that data should be
* copied to. Both must be aligned to 4 bytes boundary. */
ldr r1, =__etext
ldr r2, =__data_start__
ldr r3, =__data_end__
subs r3, r2
ble .LC0
.LC1:
subs r3, 4
ldr r0, [r1,r3]
str r0, [r2,r3]
bgt .LC1
.LC0:
#ifdef __STARTUP_CLEAR_BSS
/* This part of work usually is done in C library startup code. Otherwise,
* define this macro to enable it in this startup.
*
* Loop to zero out BSS section, which uses following symbols
* in linker script:
* __bss_start__: start of BSS section. Must align to 4
* __bss_end__: end of BSS section. Must align to 4
*/
ldr r1, =__bss_start__
ldr r2, =__bss_end__
subs r2, r1
ble .LC3
movs r0, 0
.LC2:
str r0, [r1, r2]
subs r2, 4
bge .LC2
.LC3:
#endif
cpsie i /* Unmask interrupts */
#ifndef __START
#define __START _start
#endif
#ifndef __ATOLLIC__
ldr r0,=__START
blx r0
#else
ldr r0,=__libc_init_array
blx r0
ldr r0,=main
bx r0
#endif
.pool
.size Reset_Handler, . - Reset_Handler
.align 1
.thumb_func
.weak DefaultISR
.type DefaultISR, %function
DefaultISR:
ldr r0, =DefaultISR
bx r0
.size DefaultISR, . - DefaultISR
.align 1
.thumb_func
.weak NMI_Handler
.type NMI_Handler, %function
NMI_Handler:
ldr r0,=NMI_Handler
bx r0
.size NMI_Handler, . - NMI_Handler
.align 1
.thumb_func
.weak HardFault_Handler
.type HardFault_Handler, %function
HardFault_Handler:
ldr r0,=HardFault_Handler
bx r0
.size HardFault_Handler, . - HardFault_Handler
.align 1
.thumb_func
.weak SVC_Handler
.type SVC_Handler, %function
SVC_Handler:
ldr r0,=SVC_Handler
bx r0
.size SVC_Handler, . - SVC_Handler
.align 1
.thumb_func
.weak PendSV_Handler
.type PendSV_Handler, %function
PendSV_Handler:
ldr r0,=PendSV_Handler
bx r0
.size PendSV_Handler, . - PendSV_Handler
.align 1
.thumb_func
.weak SysTick_Handler
.type SysTick_Handler, %function
SysTick_Handler:
ldr r0,=SysTick_Handler
bx r0
.size SysTick_Handler, . - SysTick_Handler
.align 1
.thumb_func
.weak DMA0_IRQHandler
.type DMA0_IRQHandler, %function
DMA0_IRQHandler:
ldr r0,=DMA0_DriverIRQHandler
bx r0
.size DMA0_IRQHandler, . - DMA0_IRQHandler
.align 1
.thumb_func
.weak DMA1_IRQHandler
.type DMA1_IRQHandler, %function
DMA1_IRQHandler:
ldr r0,=DMA1_DriverIRQHandler
bx r0
.size DMA1_IRQHandler, . - DMA1_IRQHandler
.align 1
.thumb_func
.weak DMA2_IRQHandler
.type DMA2_IRQHandler, %function
DMA2_IRQHandler:
ldr r0,=DMA2_DriverIRQHandler
bx r0
.size DMA2_IRQHandler, . - DMA2_IRQHandler
.align 1
.thumb_func
.weak DMA3_IRQHandler
.type DMA3_IRQHandler, %function
DMA3_IRQHandler:
ldr r0,=DMA3_DriverIRQHandler
bx r0
.size DMA3_IRQHandler, . - DMA3_IRQHandler
.align 1
.thumb_func
.weak I2C0_IRQHandler
.type I2C0_IRQHandler, %function
I2C0_IRQHandler:
ldr r0,=I2C0_DriverIRQHandler
bx r0
.size I2C0_IRQHandler, . - I2C0_IRQHandler
.align 1
.thumb_func
.weak I2C1_IRQHandler
.type I2C1_IRQHandler, %function
I2C1_IRQHandler:
ldr r0,=I2C1_DriverIRQHandler
bx r0
.size I2C1_IRQHandler, . - I2C1_IRQHandler
.align 1
.thumb_func
.weak SPI0_IRQHandler
.type SPI0_IRQHandler, %function
SPI0_IRQHandler:
ldr r0,=SPI0_DriverIRQHandler
bx r0
.size SPI0_IRQHandler, . - SPI0_IRQHandler
.align 1
.thumb_func
.weak LPUART0_IRQHandler
.type LPUART0_IRQHandler, %function
LPUART0_IRQHandler:
ldr r0,=LPUART0_DriverIRQHandler
bx r0
.size LPUART0_IRQHandler, . - LPUART0_IRQHandler
.align 1
.thumb_func
.weak SPI1_IRQHandler
.type SPI1_IRQHandler, %function
SPI1_IRQHandler:
ldr r0,=SPI1_DriverIRQHandler
bx r0
.size SPI1_IRQHandler, . - SPI1_IRQHandler
/* Macro to define default handlers. Default handler
* will be weak symbol and just dead loops. They can be
* overwritten by other handlers */
.macro def_irq_handler handler_name
.weak \handler_name
.set \handler_name, DefaultISR
.endm
/* Exception Handlers */
def_irq_handler DMA0_DriverIRQHandler
def_irq_handler DMA1_DriverIRQHandler
def_irq_handler DMA2_DriverIRQHandler
def_irq_handler DMA3_DriverIRQHandler
def_irq_handler Reserved20_IRQHandler
def_irq_handler FTFA_IRQHandler
def_irq_handler LVD_LVW_DCDC_IRQHandler
def_irq_handler LLWU_IRQHandler
def_irq_handler I2C0_DriverIRQHandler
def_irq_handler I2C1_DriverIRQHandler
def_irq_handler SPI0_DriverIRQHandler
def_irq_handler TSI0_IRQHandler
def_irq_handler LPUART0_DriverIRQHandler
def_irq_handler TRNG0_IRQHandler
def_irq_handler CMT_IRQHandler
def_irq_handler ADC0_IRQHandler
def_irq_handler CMP0_IRQHandler
def_irq_handler TPM0_IRQHandler
def_irq_handler TPM1_IRQHandler
def_irq_handler TPM2_IRQHandler
def_irq_handler RTC_IRQHandler
def_irq_handler RTC_Seconds_IRQHandler
def_irq_handler PIT_IRQHandler
def_irq_handler LTC0_IRQHandler
def_irq_handler Radio_0_IRQHandler
def_irq_handler DAC0_IRQHandler
def_irq_handler Radio_1_IRQHandler
def_irq_handler MCG_IRQHandler
def_irq_handler LPTMR0_IRQHandler
def_irq_handler SPI1_DriverIRQHandler
def_irq_handler PORTA_IRQHandler
def_irq_handler PORTB_PORTC_IRQHandler
.end

View File

@ -0,0 +1,110 @@
/*
** ###################################################################
** Processor: MKW41Z512VHT4
** Compiler: IAR ANSI C/C++ Compiler for ARM
** Reference manual: MKW41Z512RM Rev. 0.1, 04/2016
** Version: rev. 1.0, 2015-09-23
** Build: b160720
**
** Abstract:
** Linker file for the IAR ANSI C/C++ Compiler for ARM
**
** Copyright (c) 2016 Freescale Semiconductor, Inc.
** All rights reserved.
**
** Redistribution and use in source and binary forms, with or without modification,
** are permitted provided that the following conditions are met:
**
** o Redistributions of source code must retain the above copyright notice, this list
** of conditions and the following disclaimer.
**
** o Redistributions in binary form must reproduce the above copyright notice, this
** list of conditions and the following disclaimer in the documentation and/or
** other materials provided with the distribution.
**
** o Neither the name of Freescale Semiconductor, Inc. nor the names of its
** contributors may be used to endorse or promote products derived from this
** software without specific prior written permission.
**
** THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
** ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
** WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
** DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
** ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
** (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
** LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
** ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
** (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
** SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
**
** http: www.freescale.com
** mail: support@freescale.com
**
** ###################################################################
*/
define symbol __ram_vector_table__ = 1;
/* Heap 1/4 of ram and stack 1/8 */
define symbol __stack_size__=0x4000;
define symbol __heap_size__=0x8000;
define symbol __ram_vector_table_size__ = isdefinedsymbol(__ram_vector_table__) ? 0x00000200 : 0;
define symbol __ram_vector_table_offset__ = isdefinedsymbol(__ram_vector_table__) ? 0x000001FF : 0;
define symbol m_interrupts_start = 0x00000000;
define symbol m_interrupts_end = 0x000001FF;
define symbol m_flash_config_start = 0x00000400;
define symbol m_flash_config_end = 0x0000040F;
define symbol m_text_start = 0x00000410;
define symbol m_text_end = 0x0007FFFF;
define symbol m_interrupts_ram_start = 0x1FFF8000;
define symbol m_interrupts_ram_end = 0x1FFF8000 + __ram_vector_table_offset__;
define symbol m_data_start = m_interrupts_ram_start + __ram_vector_table_size__;
define symbol m_data_end = 0x20017FFF;
/* Sizes */
if (isdefinedsymbol(__stack_size__)) {
define symbol __size_cstack__ = __stack_size__;
} else {
define symbol __size_cstack__ = 0x0400;
}
if (isdefinedsymbol(__heap_size__)) {
define symbol __size_heap__ = __heap_size__;
} else {
define symbol __size_heap__ = 0x0400;
}
define exported symbol __VECTOR_TABLE = m_interrupts_start;
define exported symbol __VECTOR_RAM = isdefinedsymbol(__ram_vector_table__) ? m_interrupts_ram_start : m_interrupts_start;
define exported symbol __RAM_VECTOR_TABLE_SIZE = __ram_vector_table_size__;
define memory mem with size = 4G;
define region m_flash_config_region = mem:[from m_flash_config_start to m_flash_config_end];
define region TEXT_region = mem:[from m_interrupts_start to m_interrupts_end]
| mem:[from m_text_start to m_text_end];
define region DATA_region = mem:[from m_data_start to m_data_end-__size_cstack__];
define region CSTACK_region = mem:[from m_data_end-__size_cstack__+1 to m_data_end];
define region m_interrupts_ram_region = mem:[from m_interrupts_ram_start to m_interrupts_ram_end];
define block CSTACK with alignment = 8, size = __size_cstack__ { };
define block HEAP with alignment = 8, size = __size_heap__ { };
define block RW { readwrite };
define block ZI { zi };
initialize by copy { readwrite, section .textrw };
do not initialize { section .noinit };
place at address mem: m_interrupts_start { readonly section .intvec };
place in m_flash_config_region { section FlashConfig };
place in TEXT_region { readonly };
place in DATA_region { block RW };
place in DATA_region { block ZI };
place in DATA_region { last block HEAP };
place in CSTACK_region { block CSTACK };
place in m_interrupts_ram_region { section m_interrupts_ram };

View File

@ -0,0 +1,305 @@
; ---------------------------------------------------------------------------------------
; @file: startup_MKW41Z4.s
; @purpose: CMSIS Cortex-M0P Core Device Startup File
; MKW41Z4
; @version: 1.0
; @date: 2015-9-23
; @build: b160720
; ---------------------------------------------------------------------------------------
;
; Copyright (c) 1997 - 2016 , Freescale Semiconductor, Inc.
; All rights reserved.
;
; Redistribution and use in source and binary forms, with or without modification,
; are permitted provided that the following conditions are met:
;
; o Redistributions of source code must retain the above copyright notice, this list
; of conditions and the following disclaimer.
;
; o Redistributions in binary form must reproduce the above copyright notice, this
; list of conditions and the following disclaimer in the documentation and/or
; other materials provided with the distribution.
;
; o Neither the name of Freescale Semiconductor, Inc. nor the names of its
; contributors may be used to endorse or promote products derived from this
; software without specific prior written permission.
;
; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
; ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
; WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
; DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
; ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
; (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
; ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
; (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
; SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
;
; The modules in this file are included in the libraries, and may be replaced
; by any user-defined modules that define the PUBLIC symbol _program_start or
; a user defined start symbol.
; To override the cstartup defined in the library, simply add your modified
; version to the workbench project.
;
; The vector table is normally located at address 0.
; When debugging in RAM, it can be located in RAM, aligned to at least 2^6.
; The name "__vector_table" has special meaning for C-SPY:
; it is where the SP start value is found, and the NVIC vector
; table register (VTOR) is initialized to this address if != 0.
;
; Cortex-M version
;
MODULE ?cstartup
;; Forward declaration of sections.
SECTION CSTACK:DATA:NOROOT(3)
SECTION .intvec:CODE:NOROOT(2)
EXTERN __iar_program_start
EXTERN SystemInit
PUBLIC __vector_table
PUBLIC __vector_table_0x1c
PUBLIC __Vectors
PUBLIC __Vectors_End
PUBLIC __Vectors_Size
DATA
__vector_table
DCD sfe(CSTACK)
DCD Reset_Handler
DCD NMI_Handler ;NMI Handler
DCD HardFault_Handler ;Hard Fault Handler
DCD 0 ;Reserved
DCD 0 ;Reserved
DCD 0 ;Reserved
__vector_table_0x1c
DCD 0 ;Reserved
DCD 0 ;Reserved
DCD 0 ;Reserved
DCD 0 ;Reserved
DCD SVC_Handler ;SVCall Handler
DCD 0 ;Reserved
DCD 0 ;Reserved
DCD PendSV_Handler ;PendSV Handler
DCD SysTick_Handler ;SysTick Handler
;External Interrupts
DCD DMA0_IRQHandler ;DMA channel 0 transfer complete
DCD DMA1_IRQHandler ;DMA channel 1 transfer complete
DCD DMA2_IRQHandler ;DMA channel 2 transfer complete
DCD DMA3_IRQHandler ;DMA channel 3 transfer complete
DCD Reserved20_IRQHandler ;Reserved interrupt
DCD FTFA_IRQHandler ;Command complete and read collision
DCD LVD_LVW_DCDC_IRQHandler ;Low-voltage detect, low-voltage warning, DCDC
DCD LLWU_IRQHandler ;Low leakage wakeup Unit
DCD I2C0_IRQHandler ;I2C0 interrupt
DCD I2C1_IRQHandler ;I2C1 interrupt
DCD SPI0_IRQHandler ;SPI0 single interrupt vector for all sources
DCD TSI0_IRQHandler ;TSI0 single interrupt vector for all sources
DCD LPUART0_IRQHandler ;LPUART0 status and error
DCD TRNG0_IRQHandler ;TRNG0 interrupt
DCD CMT_IRQHandler ;CMT interrupt
DCD ADC0_IRQHandler ;ADC0 interrupt
DCD CMP0_IRQHandler ;CMP0 interrupt
DCD TPM0_IRQHandler ;TPM0 single interrupt vector for all sources
DCD TPM1_IRQHandler ;TPM1 single interrupt vector for all sources
DCD TPM2_IRQHandler ;TPM2 single interrupt vector for all sources
DCD RTC_IRQHandler ;RTC alarm
DCD RTC_Seconds_IRQHandler ;RTC seconds
DCD PIT_IRQHandler ;PIT interrupt
DCD LTC0_IRQHandler ;LTC0 interrupt
DCD Radio_0_IRQHandler ;BTLE, ZIGBEE, ANT, GENFSK interrupt 0
DCD DAC0_IRQHandler ;DAC0 interrupt
DCD Radio_1_IRQHandler ;BTLE, ZIGBEE, ANT, GENFSK interrupt 1
DCD MCG_IRQHandler ;MCG interrupt
DCD LPTMR0_IRQHandler ;LPTMR0 interrupt
DCD SPI1_IRQHandler ;SPI1 single interrupt vector for all sources
DCD PORTA_IRQHandler ;PORTA Pin detect
DCD PORTB_PORTC_IRQHandler ;PORTB and PORTC Pin detect
__Vectors_End
SECTION FlashConfig:CODE
__FlashConfig
DCD 0xFFFFFFFF
DCD 0xFFFFFFFF
DCD 0xFFFFFFFF
DCD 0xFFFFFFFE
__FlashConfig_End
__Vectors EQU __vector_table
__Vectors_Size EQU __Vectors_End - __Vectors
;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;
;;
;; Default interrupt handlers.
;;
THUMB
PUBWEAK Reset_Handler
SECTION .text:CODE:REORDER:NOROOT(2)
Reset_Handler
CPSID I ; Mask interrupts
LDR R0, =0xE000ED08
LDR R1, =__vector_table
STR R1, [R0]
LDR R0, =SystemInit
BLX R0
CPSIE I ; Unmask interrupts
LDR R0, =__iar_program_start
BX R0
PUBWEAK NMI_Handler
SECTION .text:CODE:REORDER:NOROOT(1)
NMI_Handler
B .
PUBWEAK HardFault_Handler
SECTION .text:CODE:REORDER:NOROOT(1)
HardFault_Handler
B .
PUBWEAK SVC_Handler
SECTION .text:CODE:REORDER:NOROOT(1)
SVC_Handler
B .
PUBWEAK PendSV_Handler
SECTION .text:CODE:REORDER:NOROOT(1)
PendSV_Handler
B .
PUBWEAK SysTick_Handler
SECTION .text:CODE:REORDER:NOROOT(1)
SysTick_Handler
B .
PUBWEAK DMA0_IRQHandler
PUBWEAK DMA0_DriverIRQHandler
SECTION .text:CODE:REORDER:NOROOT(2)
DMA0_IRQHandler
LDR R0, =DMA0_DriverIRQHandler
BX R0
PUBWEAK DMA1_IRQHandler
PUBWEAK DMA1_DriverIRQHandler
SECTION .text:CODE:REORDER:NOROOT(2)
DMA1_IRQHandler
LDR R0, =DMA1_DriverIRQHandler
BX R0
PUBWEAK DMA2_IRQHandler
PUBWEAK DMA2_DriverIRQHandler
SECTION .text:CODE:REORDER:NOROOT(2)
DMA2_IRQHandler
LDR R0, =DMA2_DriverIRQHandler
BX R0
PUBWEAK DMA3_IRQHandler
PUBWEAK DMA3_DriverIRQHandler
SECTION .text:CODE:REORDER:NOROOT(2)
DMA3_IRQHandler
LDR R0, =DMA3_DriverIRQHandler
BX R0
PUBWEAK Reserved20_IRQHandler
PUBWEAK FTFA_IRQHandler
PUBWEAK LVD_LVW_DCDC_IRQHandler
PUBWEAK LLWU_IRQHandler
PUBWEAK I2C0_IRQHandler
PUBWEAK I2C0_DriverIRQHandler
SECTION .text:CODE:REORDER:NOROOT(2)
I2C0_IRQHandler
LDR R0, =I2C0_DriverIRQHandler
BX R0
PUBWEAK I2C1_IRQHandler
PUBWEAK I2C1_DriverIRQHandler
SECTION .text:CODE:REORDER:NOROOT(2)
I2C1_IRQHandler
LDR R0, =I2C1_DriverIRQHandler
BX R0
PUBWEAK SPI0_IRQHandler
PUBWEAK SPI0_DriverIRQHandler
SECTION .text:CODE:REORDER:NOROOT(2)
SPI0_IRQHandler
LDR R0, =SPI0_DriverIRQHandler
BX R0
PUBWEAK TSI0_IRQHandler
PUBWEAK LPUART0_IRQHandler
PUBWEAK LPUART0_DriverIRQHandler
SECTION .text:CODE:REORDER:NOROOT(2)
LPUART0_IRQHandler
LDR R0, =LPUART0_DriverIRQHandler
BX R0
PUBWEAK TRNG0_IRQHandler
PUBWEAK CMT_IRQHandler
PUBWEAK ADC0_IRQHandler
PUBWEAK CMP0_IRQHandler
PUBWEAK TPM0_IRQHandler
PUBWEAK TPM1_IRQHandler
PUBWEAK TPM2_IRQHandler
PUBWEAK RTC_IRQHandler
PUBWEAK RTC_Seconds_IRQHandler
PUBWEAK PIT_IRQHandler
PUBWEAK LTC0_IRQHandler
PUBWEAK Radio_0_IRQHandler
PUBWEAK DAC0_IRQHandler
PUBWEAK Radio_1_IRQHandler
PUBWEAK MCG_IRQHandler
PUBWEAK LPTMR0_IRQHandler
PUBWEAK SPI1_IRQHandler
PUBWEAK SPI1_DriverIRQHandler
SECTION .text:CODE:REORDER:NOROOT(2)
SPI1_IRQHandler
LDR R0, =SPI1_DriverIRQHandler
BX R0
PUBWEAK PORTA_IRQHandler
PUBWEAK PORTB_PORTC_IRQHandler
PUBWEAK DefaultISR
SECTION .text:CODE:REORDER:NOROOT(2)
DMA0_DriverIRQHandler
DMA1_DriverIRQHandler
DMA2_DriverIRQHandler
DMA3_DriverIRQHandler
Reserved20_IRQHandler
FTFA_IRQHandler
LVD_LVW_DCDC_IRQHandler
LLWU_IRQHandler
I2C0_DriverIRQHandler
I2C1_DriverIRQHandler
SPI0_DriverIRQHandler
TSI0_IRQHandler
LPUART0_DriverIRQHandler
TRNG0_IRQHandler
CMT_IRQHandler
ADC0_IRQHandler
CMP0_IRQHandler
TPM0_IRQHandler
TPM1_IRQHandler
TPM2_IRQHandler
RTC_IRQHandler
RTC_Seconds_IRQHandler
PIT_IRQHandler
LTC0_IRQHandler
Radio_0_IRQHandler
DAC0_IRQHandler
Radio_1_IRQHandler
MCG_IRQHandler
LPTMR0_IRQHandler
SPI1_DriverIRQHandler
PORTA_IRQHandler
PORTB_PORTC_IRQHandler
DefaultISR
LDR R0, =DefaultISR
BX R0
END

View File

@ -0,0 +1,13 @@
/* mbed Microcontroller Library - CMSIS
* Copyright (C) 2009-2011 ARM Limited. All rights reserved.
*
* A generic CMSIS include header, pulling in LPC11U24 specifics
*/
#ifndef MBED_CMSIS_H
#define MBED_CMSIS_H
#include "fsl_device_registers.h"
#include "cmsis_nvic.h"
#endif

View File

@ -0,0 +1,44 @@
/* mbed Microcontroller Library
* CMSIS-style functionality to support dynamic vectors
*******************************************************************************
* Copyright (c) 2011 ARM Limited. All rights reserved.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of ARM Limited nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*******************************************************************************
*/
#include "cmsis_nvic.h"
extern void InstallIRQHandler(IRQn_Type irq, uint32_t irqHandler);
void NVIC_SetVector(IRQn_Type IRQn, uint32_t vector)
{
InstallIRQHandler(IRQn, vector);
}
uint32_t NVIC_GetVector(IRQn_Type IRQn)
{
uint32_t *vectors = (uint32_t*)SCB->VTOR;
return vectors[IRQn + 16];
}

View File

@ -0,0 +1,51 @@
/* mbed Microcontroller Library
* CMSIS-style functionality to support dynamic vectors
*******************************************************************************
* Copyright (c) 2011 ARM Limited. All rights reserved.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of ARM Limited nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*******************************************************************************
*/
#ifndef MBED_CMSIS_NVIC_H
#define MBED_CMSIS_NVIC_H
#define NVIC_NUM_VECTORS (16 + 32) // CORE + MCU Peripherals
#define NVIC_USER_IRQ_OFFSET 16
#include "cmsis.h"
#ifdef __cplusplus
extern "C" {
#endif
void NVIC_SetVector(IRQn_Type IRQn, uint32_t vector);
uint32_t NVIC_GetVector(IRQn_Type IRQn);
#ifdef __cplusplus
}
#endif
#endif

View File

@ -0,0 +1,56 @@
/*
* Copyright (c) 2014 - 2016, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef __FSL_DEVICE_REGISTERS_H__
#define __FSL_DEVICE_REGISTERS_H__
/*
* Include the cpu specific register header files.
*
* The CPU macro should be declared in the project or makefile.
*/
#if (defined(CPU_MKW41Z256VHT4) || defined(CPU_MKW41Z512VHT4))
#define KW41Z4_SERIES
/* CMSIS-style register definitions */
#include "MKW41Z4.h"
/* CPU specific feature definitions */
#include "MKW41Z4_features.h"
#else
#error "No valid CPU defined!"
#endif
#endif /* __FSL_DEVICE_REGISTERS_H__ */
/*******************************************************************************
* EOF
******************************************************************************/

View File

@ -0,0 +1,179 @@
/*
** ###################################################################
** Processors: MKW41Z256VHT4
** MKW41Z512VHT4
**
** Compilers: Keil ARM C/C++ Compiler
** GNU C Compiler
** IAR ANSI C/C++ Compiler for ARM
**
** Reference manual: MKW41Z512RM Rev. 0.1, 04/2016
** Version: rev. 1.0, 2015-09-23
** Build: b160720
**
** Abstract:
** Provides a system configuration function and a global variable that
** contains the system frequency. It configures the device and initializes
** the oscillator (PLL) that is part of the microcontroller device.
**
** Copyright (c) 2016 Freescale Semiconductor, Inc.
** All rights reserved.
**
** Redistribution and use in source and binary forms, with or without modification,
** are permitted provided that the following conditions are met:
**
** o Redistributions of source code must retain the above copyright notice, this list
** of conditions and the following disclaimer.
**
** o Redistributions in binary form must reproduce the above copyright notice, this
** list of conditions and the following disclaimer in the documentation and/or
** other materials provided with the distribution.
**
** o Neither the name of Freescale Semiconductor, Inc. nor the names of its
** contributors may be used to endorse or promote products derived from this
** software without specific prior written permission.
**
** THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
** ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
** WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
** DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
** ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
** (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
** LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
** ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
** (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
** SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
**
** http: www.freescale.com
** mail: support@freescale.com
**
** Revisions:
** - rev. 1.0 (2015-09-23)
** Initial version.
**
** ###################################################################
*/
/*!
* @file MKW41Z4
* @version 1.0
* @date 2015-09-23
* @brief Device specific configuration file for MKW41Z4 (implementation file)
*
* Provides a system configuration function and a global variable that contains
* the system frequency. It configures the device and initializes the oscillator
* (PLL) that is part of the microcontroller device.
*/
#include <stdint.h>
#include "fsl_device_registers.h"
/* ----------------------------------------------------------------------------
-- Core clock
---------------------------------------------------------------------------- */
uint32_t SystemCoreClock = DEFAULT_SYSTEM_CLOCK;
/* ----------------------------------------------------------------------------
-- SystemInit()
---------------------------------------------------------------------------- */
void SystemInit (void) {
#if (DISABLE_WDOG)
/* SIM_COPC: COPT=0,COPCLKS=0,COPW=0 */
SIM->COPC = (uint32_t)0x00u;
#endif /* (DISABLE_WDOG) */
}
/* ----------------------------------------------------------------------------
-- SystemCoreClockUpdate()
---------------------------------------------------------------------------- */
void SystemCoreClockUpdate (void) {
uint32_t MCGOUTClock; /* Variable to store output clock frequency of the MCG module */
uint16_t Divider;
if ((MCG->C1 & MCG_C1_CLKS_MASK) == 0x00U) {
/* FLL is selected */
if ((MCG->C1 & MCG_C1_IREFS_MASK) == 0x00U) {
/* External reference clock is selected */
if((MCG->C7 & MCG_C7_OSCSEL_MASK) == 0x00U) {
MCGOUTClock = CPU_XTAL_CLK_HZ; /* System oscillator drives MCG clock */
} else {
MCGOUTClock = CPU_XTAL32k_CLK_HZ; /* RTC 32 kHz oscillator drives MCG clock */
}
if (((MCG->C2 & MCG_C2_RANGE_MASK) != 0x00U) && ((MCG->C7 & MCG_C7_OSCSEL_MASK) != 0x01U)) {
switch (MCG->C1 & MCG_C1_FRDIV_MASK) {
case 0x38U:
Divider = 1536U;
break;
case 0x30U:
Divider = 1280U;
break;
default:
Divider = (uint16_t)(32LU << ((MCG->C1 & MCG_C1_FRDIV_MASK) >> MCG_C1_FRDIV_SHIFT));
break;
}
} else {/* ((MCG->C2 & MCG_C2_RANGE_MASK) != 0x00U) */
Divider = (uint16_t)(1LU << ((MCG->C1 & MCG_C1_FRDIV_MASK) >> MCG_C1_FRDIV_SHIFT));
}
MCGOUTClock = (MCGOUTClock / Divider); /* Calculate the divided FLL reference clock */
} else { /* (!((MCG->C1 & MCG_C1_IREFS_MASK) == 0x00U)) */
MCGOUTClock = CPU_INT_SLOW_CLK_HZ; /* The slow internal reference clock is selected */
} /* (!((MCG->C1 & MCG_C1_IREFS_MASK) == 0x00U)) */
/* Select correct multiplier to calculate the MCG output clock */
switch (MCG->C4 & (MCG_C4_DMX32_MASK | MCG_C4_DRST_DRS_MASK)) {
case 0x00U:
MCGOUTClock *= 640U;
break;
case 0x20U:
MCGOUTClock *= 1280U;
break;
case 0x40U:
MCGOUTClock *= 1920U;
break;
case 0x60U:
MCGOUTClock *= 2560U;
break;
case 0x80U:
MCGOUTClock *= 732U;
break;
case 0xA0U:
MCGOUTClock *= 1464U;
break;
case 0xC0U:
MCGOUTClock *= 2197U;
break;
case 0xE0U:
MCGOUTClock *= 2929U;
break;
default:
break;
}
} else if ((MCG->C1 & MCG_C1_CLKS_MASK) == 0x40U) {
/* Internal reference clock is selected */
if ((MCG->C2 & MCG_C2_IRCS_MASK) == 0x00U) {
MCGOUTClock = CPU_INT_SLOW_CLK_HZ; /* Slow internal reference clock selected */
} else { /* (!((MCG->C2 & MCG_C2_IRCS_MASK) == 0x00U)) */
Divider = (uint16_t)(0x01LU << ((MCG->SC & MCG_SC_FCRDIV_MASK) >> MCG_SC_FCRDIV_SHIFT));
MCGOUTClock = (uint32_t) (CPU_INT_FAST_CLK_HZ / Divider); /* Fast internal reference clock selected */
} /* (!((MCG->C2 & MCG_C2_IRCS_MASK) == 0x00U)) */
} else if ((MCG->C1 & MCG_C1_CLKS_MASK) == 0x80U) {
/* External reference clock is selected */
if((MCG->C7 & MCG_C7_OSCSEL_MASK) == 0x00U) {
MCGOUTClock = CPU_XTAL_CLK_HZ; /* System oscillator drives MCG clock */
} else {
MCGOUTClock = CPU_XTAL32k_CLK_HZ; /* RTC 32 kHz oscillator drives MCG clock */
}
} else { /* (!((MCG->C1 & MCG_C1_CLKS_MASK) == 0x80U)) */
/* Reserved value */
return;
} /* (!((MCG->C1 & MCG_C1_CLKS_MASK) == 0x80U)) */
SystemCoreClock = (MCGOUTClock / (0x01U + ((SIM->CLKDIV1 & SIM_CLKDIV1_OUTDIV1_MASK) >> SIM_CLKDIV1_OUTDIV1_SHIFT)));
}

View File

@ -0,0 +1,133 @@
/*
** ###################################################################
** Processors: MKW41Z256VHT4
** MKW41Z512VHT4
**
** Compilers: Keil ARM C/C++ Compiler
** GNU C Compiler
** IAR ANSI C/C++ Compiler for ARM
**
** Reference manual: MKW41Z512RM Rev. 0.1, 04/2016
** Version: rev. 1.0, 2015-09-23
** Build: b160720
**
** Abstract:
** Provides a system configuration function and a global variable that
** contains the system frequency. It configures the device and initializes
** the oscillator (PLL) that is part of the microcontroller device.
**
** Copyright (c) 2016 Freescale Semiconductor, Inc.
** All rights reserved.
**
** Redistribution and use in source and binary forms, with or without modification,
** are permitted provided that the following conditions are met:
**
** o Redistributions of source code must retain the above copyright notice, this list
** of conditions and the following disclaimer.
**
** o Redistributions in binary form must reproduce the above copyright notice, this
** list of conditions and the following disclaimer in the documentation and/or
** other materials provided with the distribution.
**
** o Neither the name of Freescale Semiconductor, Inc. nor the names of its
** contributors may be used to endorse or promote products derived from this
** software without specific prior written permission.
**
** THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
** ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
** WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
** DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
** ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
** (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
** LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
** ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
** (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
** SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
**
** http: www.freescale.com
** mail: support@freescale.com
**
** Revisions:
** - rev. 1.0 (2015-09-23)
** Initial version.
**
** ###################################################################
*/
/*!
* @file MKW41Z4
* @version 1.0
* @date 2015-09-23
* @brief Device specific configuration file for MKW41Z4 (header file)
*
* Provides a system configuration function and a global variable that contains
* the system frequency. It configures the device and initializes the oscillator
* (PLL) that is part of the microcontroller device.
*/
#ifndef _SYSTEM_MKW41Z4_H_
#define _SYSTEM_MKW41Z4_H_ /**< Symbol preventing repeated inclusion */
#ifdef __cplusplus
extern "C" {
#endif
#include <stdint.h>
#ifndef DISABLE_WDOG
#define DISABLE_WDOG 1
#endif
/* Define clock source values */
#define CPU_XTAL_CLK_HZ 32000000u /* Value of the external crystal or oscillator clock frequency in Hz */
#define CPU_XTAL32k_CLK_HZ 32768u /* Value of the external 32k crystal or oscillator clock frequency in Hz */
#define CPU_INT_SLOW_CLK_HZ 32768u /* Value of the slow internal oscillator clock frequency in Hz */
#define CPU_INT_FAST_CLK_HZ 4000000u /* Value of the fast internal oscillator clock frequency in Hz */
/* RF oscillator setting */
#define SYSTEM_RSIM_CONTROL_VALUE 0xC00100U /* Enable RF oscillator in Run/Wait mode */
/* Low power mode enable */
/* SMC_PMPROT: ?=0,?=0,AVLP=1,?=0,?=0,?=0,AVLLS=1,?=0 */
#define SYSTEM_SMC_PMPROT_VALUE (SMC_PMPROT_AVLP_MASK | SMC_PMPROT_ALLS_MASK | SMC_PMPROT_AVLLS_MASK) /* Mask of allowed low power modes used to initialize power modes protection register */
#define DEFAULT_SYSTEM_CLOCK 20971520U /* Default System clock value */
/**
* @brief System clock frequency (core clock)
*
* The system clock frequency supplied to the SysTick timer and the processor
* core clock. This variable can be used by the user application to setup the
* SysTick timer or configure other parameters. It may also be used by debugger to
* query the frequency of the debug timer or configure the trace clock speed
* SystemCoreClock is initialized with a correct predefined value.
*/
extern uint32_t SystemCoreClock;
/**
* @brief Setup the microcontroller system.
*
* Typically this function configures the oscillator (PLL) that is part of the
* microcontroller device. For systems with variable clock speed it also updates
* the variable SystemCoreClock. SystemInit is called from startup_device file.
*/
void SystemInit (void);
/**
* @brief Updates the SystemCoreClock variable.
*
* It must be called whenever the core clock is changed during program
* execution. SystemCoreClockUpdate() evaluates the clock register settings and calculates
* the current core clock.
*/
void SystemCoreClockUpdate (void);
#ifdef __cplusplus
}
#endif
#endif /* _SYSTEM_MKW41Z4_H_ */

View File

@ -0,0 +1,364 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include "fsl_adc16.h"
/*******************************************************************************
* Prototypes
******************************************************************************/
/*!
* @brief Get instance number for ADC16 module.
*
* @param base ADC16 peripheral base address
*/
static uint32_t ADC16_GetInstance(ADC_Type *base);
/*******************************************************************************
* Variables
******************************************************************************/
/*! @brief Pointers to ADC16 bases for each instance. */
static ADC_Type *const s_adc16Bases[] = ADC_BASE_PTRS;
/*! @brief Pointers to ADC16 clocks for each instance. */
static const clock_ip_name_t s_adc16Clocks[] = ADC16_CLOCKS;
/*******************************************************************************
* Code
******************************************************************************/
static uint32_t ADC16_GetInstance(ADC_Type *base)
{
uint32_t instance;
/* Find the instance index from base address mappings. */
for (instance = 0; instance < FSL_FEATURE_SOC_ADC16_COUNT; instance++)
{
if (s_adc16Bases[instance] == base)
{
break;
}
}
assert(instance < FSL_FEATURE_SOC_ADC16_COUNT);
return instance;
}
void ADC16_Init(ADC_Type *base, const adc16_config_t *config)
{
assert(NULL != config);
uint32_t tmp32;
/* Enable the clock. */
CLOCK_EnableClock(s_adc16Clocks[ADC16_GetInstance(base)]);
/* ADCx_CFG1. */
tmp32 = ADC_CFG1_ADICLK(config->clockSource) | ADC_CFG1_MODE(config->resolution);
if (kADC16_LongSampleDisabled != config->longSampleMode)
{
tmp32 |= ADC_CFG1_ADLSMP_MASK;
}
tmp32 |= ADC_CFG1_ADIV(config->clockDivider);
if (config->enableLowPower)
{
tmp32 |= ADC_CFG1_ADLPC_MASK;
}
base->CFG1 = tmp32;
/* ADCx_CFG2. */
tmp32 = base->CFG2 & ~(ADC_CFG2_ADACKEN_MASK | ADC_CFG2_ADHSC_MASK | ADC_CFG2_ADLSTS_MASK);
if (kADC16_LongSampleDisabled != config->longSampleMode)
{
tmp32 |= ADC_CFG2_ADLSTS(config->longSampleMode);
}
if (config->enableHighSpeed)
{
tmp32 |= ADC_CFG2_ADHSC_MASK;
}
if (config->enableAsynchronousClock)
{
tmp32 |= ADC_CFG2_ADACKEN_MASK;
}
base->CFG2 = tmp32;
/* ADCx_SC2. */
tmp32 = base->SC2 & ~(ADC_SC2_REFSEL_MASK);
tmp32 |= ADC_SC2_REFSEL(config->referenceVoltageSource);
base->SC2 = tmp32;
/* ADCx_SC3. */
if (config->enableContinuousConversion)
{
base->SC3 |= ADC_SC3_ADCO_MASK;
}
else
{
base->SC3 &= ~ADC_SC3_ADCO_MASK;
}
}
void ADC16_Deinit(ADC_Type *base)
{
/* Disable the clock. */
CLOCK_DisableClock(s_adc16Clocks[ADC16_GetInstance(base)]);
}
void ADC16_GetDefaultConfig(adc16_config_t *config)
{
assert(NULL != config);
config->referenceVoltageSource = kADC16_ReferenceVoltageSourceVref;
config->clockSource = kADC16_ClockSourceAsynchronousClock;
config->enableAsynchronousClock = true;
config->clockDivider = kADC16_ClockDivider8;
config->resolution = kADC16_ResolutionSE12Bit;
config->longSampleMode = kADC16_LongSampleDisabled;
config->enableHighSpeed = false;
config->enableLowPower = false;
config->enableContinuousConversion = false;
}
#if defined(FSL_FEATURE_ADC16_HAS_CALIBRATION) && FSL_FEATURE_ADC16_HAS_CALIBRATION
status_t ADC16_DoAutoCalibration(ADC_Type *base)
{
bool bHWTrigger = false;
volatile uint32_t tmp32; /* 'volatile' here is for the dummy read of ADCx_R[0] register. */
status_t status = kStatus_Success;
/* The calibration would be failed when in hardwar mode.
* Remember the hardware trigger state here and restore it later if the hardware trigger is enabled.*/
if (0U != (ADC_SC2_ADTRG_MASK & base->SC2))
{
bHWTrigger = true;
base->SC2 &= ~ADC_SC2_ADTRG_MASK;
}
/* Clear the CALF and launch the calibration. */
base->SC3 |= ADC_SC3_CAL_MASK | ADC_SC3_CALF_MASK;
while (0U == (kADC16_ChannelConversionDoneFlag & ADC16_GetChannelStatusFlags(base, 0U)))
{
/* Check the CALF when the calibration is active. */
if (0U != (kADC16_CalibrationFailedFlag & ADC16_GetStatusFlags(base)))
{
status = kStatus_Fail;
break;
}
}
tmp32 = base->R[0]; /* Dummy read to clear COCO caused by calibration. */
/* Restore the hardware trigger setting if it was enabled before. */
if (bHWTrigger)
{
base->SC2 |= ADC_SC2_ADTRG_MASK;
}
/* Check the CALF at the end of calibration. */
if (0U != (kADC16_CalibrationFailedFlag & ADC16_GetStatusFlags(base)))
{
status = kStatus_Fail;
}
if (kStatus_Success != status) /* Check if the calibration process is succeed. */
{
return status;
}
/* Calculate the calibration values. */
tmp32 = base->CLP0 + base->CLP1 + base->CLP2 + base->CLP3 + base->CLP4 + base->CLPS;
tmp32 = 0x8000U | (tmp32 >> 1U);
base->PG = tmp32;
#if defined(FSL_FEATURE_ADC16_HAS_DIFF_MODE) && FSL_FEATURE_ADC16_HAS_DIFF_MODE
tmp32 = base->CLM0 + base->CLM1 + base->CLM2 + base->CLM3 + base->CLM4 + base->CLMS;
tmp32 = 0x8000U | (tmp32 >> 1U);
base->MG = tmp32;
#endif /* FSL_FEATURE_ADC16_HAS_DIFF_MODE */
return kStatus_Success;
}
#endif /* FSL_FEATURE_ADC16_HAS_CALIBRATION */
#if defined(FSL_FEATURE_ADC16_HAS_MUX_SELECT) && FSL_FEATURE_ADC16_HAS_MUX_SELECT
void ADC16_SetChannelMuxMode(ADC_Type *base, adc16_channel_mux_mode_t mode)
{
if (kADC16_ChannelMuxA == mode)
{
base->CFG2 &= ~ADC_CFG2_MUXSEL_MASK;
}
else /* kADC16_ChannelMuxB. */
{
base->CFG2 |= ADC_CFG2_MUXSEL_MASK;
}
}
#endif /* FSL_FEATURE_ADC16_HAS_MUX_SELECT */
void ADC16_SetHardwareCompareConfig(ADC_Type *base, const adc16_hardware_compare_config_t *config)
{
uint32_t tmp32 = base->SC2 & ~(ADC_SC2_ACFE_MASK | ADC_SC2_ACFGT_MASK | ADC_SC2_ACREN_MASK);
if (!config) /* Pass "NULL" to disable the feature. */
{
base->SC2 = tmp32;
return;
}
/* Enable the feature. */
tmp32 |= ADC_SC2_ACFE_MASK;
/* Select the hardware compare working mode. */
switch (config->hardwareCompareMode)
{
case kADC16_HardwareCompareMode0:
break;
case kADC16_HardwareCompareMode1:
tmp32 |= ADC_SC2_ACFGT_MASK;
break;
case kADC16_HardwareCompareMode2:
tmp32 |= ADC_SC2_ACREN_MASK;
break;
case kADC16_HardwareCompareMode3:
tmp32 |= ADC_SC2_ACFGT_MASK | ADC_SC2_ACREN_MASK;
break;
default:
break;
}
base->SC2 = tmp32;
/* Load the compare values. */
base->CV1 = ADC_CV1_CV(config->value1);
base->CV2 = ADC_CV2_CV(config->value2);
}
#if defined(FSL_FEATURE_ADC16_HAS_HW_AVERAGE) && FSL_FEATURE_ADC16_HAS_HW_AVERAGE
void ADC16_SetHardwareAverage(ADC_Type *base, adc16_hardware_average_mode_t mode)
{
uint32_t tmp32 = base->SC3 & ~(ADC_SC3_AVGE_MASK | ADC_SC3_AVGS_MASK);
if (kADC16_HardwareAverageDisabled != mode)
{
tmp32 |= ADC_SC3_AVGE_MASK | ADC_SC3_AVGS(mode);
}
base->SC3 = tmp32;
}
#endif /* FSL_FEATURE_ADC16_HAS_HW_AVERAGE */
#if defined(FSL_FEATURE_ADC16_HAS_PGA) && FSL_FEATURE_ADC16_HAS_PGA
void ADC16_SetPGAConfig(ADC_Type *base, const adc16_pga_config_t *config)
{
uint32_t tmp32;
if (!config) /* Passing "NULL" is to disable the feature. */
{
base->PGA = 0U;
return;
}
/* Enable the PGA and set the gain value. */
tmp32 = ADC_PGA_PGAEN_MASK | ADC_PGA_PGAG(config->pgaGain);
/* Configure the misc features for PGA. */
if (config->enableRunInNormalMode)
{
tmp32 |= ADC_PGA_PGALPb_MASK;
}
#if defined(FSL_FEATURE_ADC16_HAS_PGA_CHOPPING) && FSL_FEATURE_ADC16_HAS_PGA_CHOPPING
if (config->disablePgaChopping)
{
tmp32 |= ADC_PGA_PGACHPb_MASK;
}
#endif /* FSL_FEATURE_ADC16_HAS_PGA_CHOPPING */
#if defined(FSL_FEATURE_ADC16_HAS_PGA_OFFSET_MEASUREMENT) && FSL_FEATURE_ADC16_HAS_PGA_OFFSET_MEASUREMENT
if (config->enableRunInOffsetMeasurement)
{
tmp32 |= ADC_PGA_PGAOFSM_MASK;
}
#endif /* FSL_FEATURE_ADC16_HAS_PGA_OFFSET_MEASUREMENT */
base->PGA = tmp32;
}
#endif /* FSL_FEATURE_ADC16_HAS_PGA */
uint32_t ADC16_GetStatusFlags(ADC_Type *base)
{
uint32_t ret = 0;
if (0U != (base->SC2 & ADC_SC2_ADACT_MASK))
{
ret |= kADC16_ActiveFlag;
}
#if defined(FSL_FEATURE_ADC16_HAS_CALIBRATION) && FSL_FEATURE_ADC16_HAS_CALIBRATION
if (0U != (base->SC3 & ADC_SC3_CALF_MASK))
{
ret |= kADC16_CalibrationFailedFlag;
}
#endif /* FSL_FEATURE_ADC16_HAS_CALIBRATION */
return ret;
}
void ADC16_ClearStatusFlags(ADC_Type *base, uint32_t mask)
{
#if defined(FSL_FEATURE_ADC16_HAS_CALIBRATION) && FSL_FEATURE_ADC16_HAS_CALIBRATION
if (0U != (mask & kADC16_CalibrationFailedFlag))
{
base->SC3 |= ADC_SC3_CALF_MASK;
}
#endif /* FSL_FEATURE_ADC16_HAS_CALIBRATION */
}
void ADC16_SetChannelConfig(ADC_Type *base, uint32_t channelGroup, const adc16_channel_config_t *config)
{
assert(channelGroup < ADC_SC1_COUNT);
assert(NULL != config);
uint32_t sc1 = ADC_SC1_ADCH(config->channelNumber); /* Set the channel number. */
#if defined(FSL_FEATURE_ADC16_HAS_DIFF_MODE) && FSL_FEATURE_ADC16_HAS_DIFF_MODE
/* Enable the differential conversion. */
if (config->enableDifferentialConversion)
{
sc1 |= ADC_SC1_DIFF_MASK;
}
#endif /* FSL_FEATURE_ADC16_HAS_DIFF_MODE */
/* Enable the interrupt when the conversion is done. */
if (config->enableInterruptOnConversionCompleted)
{
sc1 |= ADC_SC1_AIEN_MASK;
}
base->SC1[channelGroup] = sc1;
}
uint32_t ADC16_GetChannelStatusFlags(ADC_Type *base, uint32_t channelGroup)
{
assert(channelGroup < ADC_SC1_COUNT);
uint32_t ret = 0U;
if (0U != (base->SC1[channelGroup] & ADC_SC1_COCO_MASK))
{
ret |= kADC16_ChannelConversionDoneFlag;
}
return ret;
}

View File

@ -0,0 +1,526 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _FSL_ADC16_H_
#define _FSL_ADC16_H_
#include "fsl_common.h"
/*!
* @addtogroup adc16
* @{
*/
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @name Driver version */
/*@{*/
/*! @brief ADC16 driver version 2.0.0. */
#define FSL_ADC16_DRIVER_VERSION (MAKE_VERSION(2, 0, 0))
/*@}*/
/*!
* @brief Channel status flags.
*/
enum _adc16_channel_status_flags
{
kADC16_ChannelConversionDoneFlag = ADC_SC1_COCO_MASK, /*!< Conversion done. */
};
/*!
* @brief Converter status flags.
*/
enum _adc16_status_flags
{
kADC16_ActiveFlag = ADC_SC2_ADACT_MASK, /*!< Converter is active. */
#if defined(FSL_FEATURE_ADC16_HAS_CALIBRATION) && FSL_FEATURE_ADC16_HAS_CALIBRATION
kADC16_CalibrationFailedFlag = ADC_SC3_CALF_MASK, /*!< Calibration is failed. */
#endif /* FSL_FEATURE_ADC16_HAS_CALIBRATION */
};
#if defined(FSL_FEATURE_ADC16_HAS_MUX_SELECT) && FSL_FEATURE_ADC16_HAS_MUX_SELECT
/*!
* @brief Channel multiplexer mode for each channel.
*
* For some ADC16 channels, there are two pin selections in channel multiplexer. For example, ADC0_SE4a and ADC0_SE4b
* are the different channels but share the same channel number.
*/
typedef enum _adc_channel_mux_mode
{
kADC16_ChannelMuxA = 0U, /*!< For channel with channel mux a. */
kADC16_ChannelMuxB = 1U, /*!< For channel with channel mux b. */
} adc16_channel_mux_mode_t;
#endif /* FSL_FEATURE_ADC16_HAS_MUX_SELECT */
/*!
* @brief Clock divider for the converter.
*/
typedef enum _adc16_clock_divider
{
kADC16_ClockDivider1 = 0U, /*!< For divider 1 from the input clock to the module. */
kADC16_ClockDivider2 = 1U, /*!< For divider 2 from the input clock to the module. */
kADC16_ClockDivider4 = 2U, /*!< For divider 4 from the input clock to the module. */
kADC16_ClockDivider8 = 3U, /*!< For divider 8 from the input clock to the module. */
} adc16_clock_divider_t;
/*!
*@brief Converter's resolution.
*/
typedef enum _adc16_resolution
{
/* This group of enumeration is for internal use which is related to register setting. */
kADC16_Resolution8or9Bit = 0U, /*!< Single End 8-bit or Differential Sample 9-bit. */
kADC16_Resolution12or13Bit = 1U, /*!< Single End 12-bit or Differential Sample 13-bit. */
kADC16_Resolution10or11Bit = 2U, /*!< Single End 10-bit or Differential Sample 11-bit. */
/* This group of enumeration is for public user. */
kADC16_ResolutionSE8Bit = kADC16_Resolution8or9Bit, /*!< Single End 8-bit. */
kADC16_ResolutionSE12Bit = kADC16_Resolution12or13Bit, /*!< Single End 12-bit. */
kADC16_ResolutionSE10Bit = kADC16_Resolution10or11Bit, /*!< Single End 10-bit. */
#if defined(FSL_FEATURE_ADC16_HAS_DIFF_MODE) && FSL_FEATURE_ADC16_HAS_DIFF_MODE
kADC16_ResolutionDF9Bit = kADC16_Resolution8or9Bit, /*!< Differential Sample 9-bit. */
kADC16_ResolutionDF13Bit = kADC16_Resolution12or13Bit, /*!< Differential Sample 13-bit. */
kADC16_ResolutionDF11Bit = kADC16_Resolution10or11Bit, /*!< Differential Sample 11-bit. */
#endif /* FSL_FEATURE_ADC16_HAS_DIFF_MODE */
#if defined(FSL_FEATURE_ADC16_MAX_RESOLUTION) && (FSL_FEATURE_ADC16_MAX_RESOLUTION >= 16U)
/* 16-bit is supported by default. */
kADC16_Resolution16Bit = 3U, /*!< Single End 16-bit or Differential Sample 16-bit. */
kADC16_ResolutionSE16Bit = kADC16_Resolution16Bit, /*!< Single End 16-bit. */
#if defined(FSL_FEATURE_ADC16_HAS_DIFF_MODE) && FSL_FEATURE_ADC16_HAS_DIFF_MODE
kADC16_ResolutionDF16Bit = kADC16_Resolution16Bit, /*!< Differential Sample 16-bit. */
#endif /* FSL_FEATURE_ADC16_HAS_DIFF_MODE */
#endif /* FSL_FEATURE_ADC16_MAX_RESOLUTION >= 16U */
} adc16_resolution_t;
/*!
* @brief Clock source.
*/
typedef enum _adc16_clock_source
{
kADC16_ClockSourceAlt0 = 0U, /*!< Selection 0 of the clock source. */
kADC16_ClockSourceAlt1 = 1U, /*!< Selection 1 of the clock source. */
kADC16_ClockSourceAlt2 = 2U, /*!< Selection 2 of the clock source. */
kADC16_ClockSourceAlt3 = 3U, /*!< Selection 3 of the clock source. */
/* Chip defined clock source */
kADC16_ClockSourceAsynchronousClock = kADC16_ClockSourceAlt3, /*!< Using internal asynchronous clock. */
} adc16_clock_source_t;
/*!
* @brief Long sample mode.
*/
typedef enum _adc16_long_sample_mode
{
kADC16_LongSampleCycle24 = 0U, /*!< 20 extra ADCK cycles, 24 ADCK cycles total. */
kADC16_LongSampleCycle16 = 1U, /*!< 12 extra ADCK cycles, 16 ADCK cycles total. */
kADC16_LongSampleCycle10 = 2U, /*!< 6 extra ADCK cycles, 10 ADCK cycles total. */
kADC16_LongSampleCycle6 = 3U, /*!< 2 extra ADCK cycles, 6 ADCK cycles total. */
kADC16_LongSampleDisabled = 4U, /*!< Disable the long sample feature. */
} adc16_long_sample_mode_t;
/*!
* @brief Reference voltage source.
*/
typedef enum _adc16_reference_voltage_source
{
kADC16_ReferenceVoltageSourceVref = 0U, /*!< For external pins pair of VrefH and VrefL. */
kADC16_ReferenceVoltageSourceValt = 1U, /*!< For alternate reference pair of ValtH and ValtL. */
} adc16_reference_voltage_source_t;
#if defined(FSL_FEATURE_ADC16_HAS_HW_AVERAGE) && FSL_FEATURE_ADC16_HAS_HW_AVERAGE
/*!
* @brief Hardware average mode.
*/
typedef enum _adc16_hardware_average_mode
{
kADC16_HardwareAverageCount4 = 0U, /*!< For hardware average with 4 samples. */
kADC16_HardwareAverageCount8 = 1U, /*!< For hardware average with 8 samples. */
kADC16_HardwareAverageCount16 = 2U, /*!< For hardware average with 16 samples. */
kADC16_HardwareAverageCount32 = 3U, /*!< For hardware average with 32 samples. */
kADC16_HardwareAverageDisabled = 4U, /*!< Disable the hardware average feature.*/
} adc16_hardware_average_mode_t;
#endif /* FSL_FEATURE_ADC16_HAS_HW_AVERAGE */
/*!
* @brief Hardware compare mode.
*/
typedef enum _adc16_hardware_compare_mode
{
kADC16_HardwareCompareMode0 = 0U, /*!< x < value1. */
kADC16_HardwareCompareMode1 = 1U, /*!< x > value1. */
kADC16_HardwareCompareMode2 = 2U, /*!< if value1 <= value2, then x < value1 || x > value2;
else, value1 > x > value2. */
kADC16_HardwareCompareMode3 = 3U, /*!< if value1 <= value2, then value1 <= x <= value2;
else x >= value1 || x <= value2. */
} adc16_hardware_compare_mode_t;
#if defined(FSL_FEATURE_ADC16_HAS_PGA) && FSL_FEATURE_ADC16_HAS_PGA
/*!
* @brief PGA's Gain mode.
*/
typedef enum _adc16_pga_gain
{
kADC16_PGAGainValueOf1 = 0U, /*!< For amplifier gain of 1. */
kADC16_PGAGainValueOf2 = 1U, /*!< For amplifier gain of 2. */
kADC16_PGAGainValueOf4 = 2U, /*!< For amplifier gain of 4. */
kADC16_PGAGainValueOf8 = 3U, /*!< For amplifier gain of 8. */
kADC16_PGAGainValueOf16 = 4U, /*!< For amplifier gain of 16. */
kADC16_PGAGainValueOf32 = 5U, /*!< For amplifier gain of 32. */
kADC16_PGAGainValueOf64 = 6U, /*!< For amplifier gain of 64. */
} adc16_pga_gain_t;
#endif /* FSL_FEATURE_ADC16_HAS_PGA */
/*!
* @brief ADC16 converter configuration .
*/
typedef struct _adc16_config
{
adc16_reference_voltage_source_t referenceVoltageSource; /*!< Select the reference voltage source. */
adc16_clock_source_t clockSource; /*!< Select the input clock source to converter. */
bool enableAsynchronousClock; /*!< Enable the asynchronous clock output. */
adc16_clock_divider_t clockDivider; /*!< Select the divider of input clock source. */
adc16_resolution_t resolution; /*!< Select the sample resolution mode. */
adc16_long_sample_mode_t longSampleMode; /*!< Select the long sample mode. */
bool enableHighSpeed; /*!< Enable the high-speed mode. */
bool enableLowPower; /*!< Enable low power. */
bool enableContinuousConversion; /*!< Enable continuous conversion mode. */
} adc16_config_t;
/*!
* @brief ADC16 Hardware compare configuration.
*/
typedef struct _adc16_hardware_compare_config
{
adc16_hardware_compare_mode_t hardwareCompareMode; /*!< Select the hardware compare mode.
See "adc16_hardware_compare_mode_t". */
int16_t value1; /*!< Setting value1 for hardware compare mode. */
int16_t value2; /*!< Setting value2 for hardware compare mode. */
} adc16_hardware_compare_config_t;
/*!
* @brief ADC16 channel conversion configuration.
*/
typedef struct _adc16_channel_config
{
uint32_t channelNumber; /*!< Setting the conversion channel number. The available range is 0-31.
See channel connection information for each chip in Reference
Manual document. */
bool enableInterruptOnConversionCompleted; /*!< Generate an interrupt request once the conversion is completed. */
#if defined(FSL_FEATURE_ADC16_HAS_DIFF_MODE) && FSL_FEATURE_ADC16_HAS_DIFF_MODE
bool enableDifferentialConversion; /*!< Using Differential sample mode. */
#endif /* FSL_FEATURE_ADC16_HAS_DIFF_MODE */
} adc16_channel_config_t;
#if defined(FSL_FEATURE_ADC16_HAS_PGA) && FSL_FEATURE_ADC16_HAS_PGA
/*!
* @brief ADC16 programmable gain amplifier configuration.
*/
typedef struct _adc16_pga_config
{
adc16_pga_gain_t pgaGain; /*!< Setting PGA gain. */
bool enableRunInNormalMode; /*!< Enable PGA working in normal mode, or low power mode by default. */
#if defined(FSL_FEATURE_ADC16_HAS_PGA_CHOPPING) && FSL_FEATURE_ADC16_HAS_PGA_CHOPPING
bool disablePgaChopping; /*!< Disable the PGA chopping function.
The PGA employs chopping to remove/reduce offset and 1/f noise and offers
an offset measurement configuration that aids the offset calibration. */
#endif /* FSL_FEATURE_ADC16_HAS_PGA_CHOPPING */
#if defined(FSL_FEATURE_ADC16_HAS_PGA_OFFSET_MEASUREMENT) && FSL_FEATURE_ADC16_HAS_PGA_OFFSET_MEASUREMENT
bool enableRunInOffsetMeasurement; /*!< Enable the PGA working in offset measurement mode.
When this feature is enabled, the PGA disconnects itself from the external
inputs and auto-configures into offset measurement mode. With this field
set, run the ADC in the recommended settings and enable the maximum hardware
averaging to get the PGA offset number. The output is the
(PGA offset * (64+1)) for the given PGA setting. */
#endif /* FSL_FEATURE_ADC16_HAS_PGA_OFFSET_MEASUREMENT */
} adc16_pga_config_t;
#endif /* FSL_FEATURE_ADC16_HAS_PGA */
#if defined(__cplusplus)
extern "C" {
#endif
/*******************************************************************************
* API
******************************************************************************/
/*!
* @name Initialization
* @{
*/
/*!
* @brief Initializes the ADC16 module.
*
* @param base ADC16 peripheral base address.
* @param config Pointer to configuration structure. See "adc16_config_t".
*/
void ADC16_Init(ADC_Type *base, const adc16_config_t *config);
/*!
* @brief De-initializes the ADC16 module.
*
* @param base ADC16 peripheral base address.
*/
void ADC16_Deinit(ADC_Type *base);
/*!
* @brief Gets an available pre-defined settings for converter's configuration.
*
* This function initializes the converter configuration structure with an available settings. The default values are:
* @code
* config->referenceVoltageSource = kADC16_ReferenceVoltageSourceVref;
* config->clockSource = kADC16_ClockSourceAsynchronousClock;
* config->enableAsynchronousClock = true;
* config->clockDivider = kADC16_ClockDivider8;
* config->resolution = kADC16_ResolutionSE12Bit;
* config->longSampleMode = kADC16_LongSampleDisabled;
* config->enableHighSpeed = false;
* config->enableLowPower = false;
* config->enableContinuousConversion = false;
* @endcode
* @param config Pointer to configuration structure.
*/
void ADC16_GetDefaultConfig(adc16_config_t *config);
#if defined(FSL_FEATURE_ADC16_HAS_CALIBRATION) && FSL_FEATURE_ADC16_HAS_CALIBRATION
/*!
* @brief Automates the hardware calibration.
*
* This auto calibration helps to adjust the plus/minus side gain automatically on the converter's working situation.
* Execute the calibration before using the converter. Note that the hardware trigger should be used
* during calibration.
*
* @param base ADC16 peripheral base address.
*
* @return Execution status.
* @retval kStatus_Success Calibration is done successfully.
* @retval kStatus_Fail Calibration is failed.
*/
status_t ADC16_DoAutoCalibration(ADC_Type *base);
#endif /* FSL_FEATURE_ADC16_HAS_CALIBRATION */
#if defined(FSL_FEATURE_ADC16_HAS_OFFSET_CORRECTION) && FSL_FEATURE_ADC16_HAS_OFFSET_CORRECTION
/*!
* @brief Sets the offset value for the conversion result.
*
* This offset value takes effect on the conversion result. If the offset value is not zero, the reading result
* is subtracted by it. Note, the hardware calibration fills the offset value automatically.
*
* @param base ADC16 peripheral base address.
* @param value Setting offset value.
*/
static inline void ADC16_SetOffsetValue(ADC_Type *base, int16_t value)
{
base->OFS = (uint32_t)(value);
}
#endif /* FSL_FEATURE_ADC16_HAS_OFFSET_CORRECTION */
/* @} */
/*!
* @name Advanced Feature
* @{
*/
#if defined(FSL_FEATURE_ADC16_HAS_DMA) && FSL_FEATURE_ADC16_HAS_DMA
/*!
* @brief Enables generating the DMA trigger when conversion is completed.
*
* @param base ADC16 peripheral base address.
* @param enable Switcher of DMA feature. "true" means to enable, "false" means not.
*/
static inline void ADC16_EnableDMA(ADC_Type *base, bool enable)
{
if (enable)
{
base->SC2 |= ADC_SC2_DMAEN_MASK;
}
else
{
base->SC2 &= ~ADC_SC2_DMAEN_MASK;
}
}
#endif /* FSL_FEATURE_ADC16_HAS_DMA */
/*!
* @brief Enables the hardware trigger mode.
*
* @param base ADC16 peripheral base address.
* @param enable Switcher of hardware trigger feature. "true" means to enable, "false" means not.
*/
static inline void ADC16_EnableHardwareTrigger(ADC_Type *base, bool enable)
{
if (enable)
{
base->SC2 |= ADC_SC2_ADTRG_MASK;
}
else
{
base->SC2 &= ~ADC_SC2_ADTRG_MASK;
}
}
#if defined(FSL_FEATURE_ADC16_HAS_MUX_SELECT) && FSL_FEATURE_ADC16_HAS_MUX_SELECT
/*!
* @brief Sets the channel mux mode.
*
* Some sample pins share the same channel index. The channel mux mode decides which pin is used for an
* indicated channel.
*
* @param base ADC16 peripheral base address.
* @param mode Setting channel mux mode. See "adc16_channel_mux_mode_t".
*/
void ADC16_SetChannelMuxMode(ADC_Type *base, adc16_channel_mux_mode_t mode);
#endif /* FSL_FEATURE_ADC16_HAS_MUX_SELECT */
/*!
* @brief Configures the hardware compare mode.
*
* The hardware compare mode provides a way to process the conversion result automatically by hardware. Only the result
* in
* compare range is available. To compare the range, see "adc16_hardware_compare_mode_t", or the reference
* manual document for more detailed information.
*
* @param base ADC16 peripheral base address.
* @param config Pointer to "adc16_hardware_compare_config_t" structure. Passing "NULL" is to disable the feature.
*/
void ADC16_SetHardwareCompareConfig(ADC_Type *base, const adc16_hardware_compare_config_t *config);
#if defined(FSL_FEATURE_ADC16_HAS_HW_AVERAGE) && FSL_FEATURE_ADC16_HAS_HW_AVERAGE
/*!
* @brief Sets the hardware average mode.
*
* Hardware average mode provides a way to process the conversion result automatically by hardware. The multiple
* conversion results are accumulated and averaged internally. This aids reading results.
*
* @param base ADC16 peripheral base address.
* @param mode Setting hardware average mode. See "adc16_hardware_average_mode_t".
*/
void ADC16_SetHardwareAverage(ADC_Type *base, adc16_hardware_average_mode_t mode);
#endif /* FSL_FEATURE_ADC16_HAS_HW_AVERAGE */
#if defined(FSL_FEATURE_ADC16_HAS_PGA) && FSL_FEATURE_ADC16_HAS_PGA
/*!
* @brief Configures the PGA for converter's front end.
*
* @param base ADC16 peripheral base address.
* @param config Pointer to "adc16_pga_config_t" structure. Passing "NULL" is to disable the feature.
*/
void ADC16_SetPGAConfig(ADC_Type *base, const adc16_pga_config_t *config);
#endif /* FSL_FEATURE_ADC16_HAS_PGA */
/*!
* @brief Gets the status flags of the converter.
*
* @param base ADC16 peripheral base address.
*
* @return Flags' mask if indicated flags are asserted. See "_adc16_status_flags".
*/
uint32_t ADC16_GetStatusFlags(ADC_Type *base);
/*!
* @brief Clears the status flags of the converter.
*
* @param base ADC16 peripheral base address.
* @param mask Mask value for the cleared flags. See "_adc16_status_flags".
*/
void ADC16_ClearStatusFlags(ADC_Type *base, uint32_t mask);
/* @} */
/*!
* @name Conversion Channel
* @{
*/
/*!
* @brief Configures the conversion channel.
*
* This operation triggers the conversion if in software trigger mode. When in hardware trigger mode, this API
* configures the channel while the external trigger source helps to trigger the conversion.
*
* Note that the "Channel Group" has a detailed description.
* To allow sequential conversions of the ADC to be triggered by internal peripherals, the ADC can have more than one
* group of status and control register, one for each conversion. The channel group parameter indicates which group of
* registers are used channel group 0 is for Group A registers and channel group 1 is for Group B registers. The
* channel groups are used in a "ping-pong" approach to control the ADC operation. At any point, only one of
* the channel groups is actively controlling ADC conversions. Channel group 0 is used for both software and hardware
* trigger modes of operation. Channel groups 1 and greater indicate potentially multiple channel group registers for
* use only in hardware trigger mode. See the chip configuration information in the MCU reference manual about the
* number of SC1n registers (channel groups) specific to this device. None of the channel groups 1 or greater are used
* for software trigger operation and therefore writes to these channel groups do not initiate a new conversion.
* Updating channel group 0 while a different channel group is actively controlling a conversion is allowed and
* vice versa. Writing any of the channel group registers while that specific channel group is actively controlling a
* conversion aborts the current conversion.
*
* @param base ADC16 peripheral base address.
* @param channelGroup Channel group index.
* @param config Pointer to "adc16_channel_config_t" structure for conversion channel.
*/
void ADC16_SetChannelConfig(ADC_Type *base, uint32_t channelGroup, const adc16_channel_config_t *config);
/*!
* @brief Gets the conversion value.
*
* @param base ADC16 peripheral base address.
* @param channelGroup Channel group index.
*
* @return Conversion value.
*/
static inline uint32_t ADC16_GetChannelConversionValue(ADC_Type *base, uint32_t channelGroup)
{
assert(channelGroup < ADC_R_COUNT);
return base->R[channelGroup];
}
/*!
* @brief Gets the status flags of channel.
*
* @param base ADC16 peripheral base address.
* @param channelGroup Channel group index.
*
* @return Flags' mask if indicated flags are asserted. See "_adc16_channel_status_flags".
*/
uint32_t ADC16_GetChannelStatusFlags(ADC_Type *base, uint32_t channelGroup);
/* @} */
#if defined(__cplusplus)
}
#endif
/*!
* @}
*/
#endif /* _FSL_ADC16_H_ */

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,279 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include "fsl_cmp.h"
/*******************************************************************************
* Prototypes
******************************************************************************/
/*!
* @brief Get instance number for CMP module.
*
* @param base CMP peripheral base address
*/
static uint32_t CMP_GetInstance(CMP_Type *base);
/*******************************************************************************
* Variables
******************************************************************************/
/*! @brief Pointers to CMP bases for each instance. */
static CMP_Type *const s_cmpBases[] = CMP_BASE_PTRS;
/*! @brief Pointers to CMP clocks for each instance. */
static const clock_ip_name_t s_cmpClocks[] = CMP_CLOCKS;
/*******************************************************************************
* Codes
******************************************************************************/
static uint32_t CMP_GetInstance(CMP_Type *base)
{
uint32_t instance;
/* Find the instance index from base address mappings. */
for (instance = 0; instance < FSL_FEATURE_SOC_CMP_COUNT; instance++)
{
if (s_cmpBases[instance] == base)
{
break;
}
}
assert(instance < FSL_FEATURE_SOC_CMP_COUNT);
return instance;
}
void CMP_Init(CMP_Type *base, const cmp_config_t *config)
{
assert(NULL != config);
uint8_t tmp8;
/* Enable the clock. */
CLOCK_EnableClock(s_cmpClocks[CMP_GetInstance(base)]);
/* Configure. */
CMP_Enable(base, false); /* Disable the CMP module during configuring. */
/* CMPx_CR1. */
tmp8 = base->CR1 & ~(CMP_CR1_PMODE_MASK | CMP_CR1_INV_MASK | CMP_CR1_COS_MASK | CMP_CR1_OPE_MASK);
if (config->enableHighSpeed)
{
tmp8 |= CMP_CR1_PMODE_MASK;
}
if (config->enableInvertOutput)
{
tmp8 |= CMP_CR1_INV_MASK;
}
if (config->useUnfilteredOutput)
{
tmp8 |= CMP_CR1_COS_MASK;
}
if (config->enablePinOut)
{
tmp8 |= CMP_CR1_OPE_MASK;
}
#if defined(FSL_FEATURE_CMP_HAS_TRIGGER_MODE) && FSL_FEATURE_CMP_HAS_TRIGGER_MODE
if (config->enableTriggerMode)
{
tmp8 |= CMP_CR1_TRIGM_MASK;
}
else
{
tmp8 &= ~CMP_CR1_TRIGM_MASK;
}
#endif /* FSL_FEATURE_CMP_HAS_TRIGGER_MODE */
base->CR1 = tmp8;
/* CMPx_CR0. */
tmp8 = base->CR0 & ~CMP_CR0_HYSTCTR_MASK;
tmp8 |= CMP_CR0_HYSTCTR(config->hysteresisMode);
base->CR0 = tmp8;
CMP_Enable(base, config->enableCmp); /* Enable the CMP module after configured or not. */
}
void CMP_Deinit(CMP_Type *base)
{
/* Disable the CMP module. */
CMP_Enable(base, false);
/* Disable the clock. */
CLOCK_DisableClock(s_cmpClocks[CMP_GetInstance(base)]);
}
void CMP_GetDefaultConfig(cmp_config_t *config)
{
assert(NULL != config);
config->enableCmp = true; /* Enable the CMP module after initialization. */
config->hysteresisMode = kCMP_HysteresisLevel0;
config->enableHighSpeed = false;
config->enableInvertOutput = false;
config->useUnfilteredOutput = false;
config->enablePinOut = false;
#if defined(FSL_FEATURE_CMP_HAS_TRIGGER_MODE) && FSL_FEATURE_CMP_HAS_TRIGGER_MODE
config->enableTriggerMode = false;
#endif /* FSL_FEATURE_CMP_HAS_TRIGGER_MODE */
}
void CMP_SetInputChannels(CMP_Type *base, uint8_t positiveChannel, uint8_t negativeChannel)
{
uint8_t tmp8 = base->MUXCR;
tmp8 &= ~(CMP_MUXCR_PSEL_MASK | CMP_MUXCR_MSEL_MASK);
tmp8 |= CMP_MUXCR_PSEL(positiveChannel) | CMP_MUXCR_MSEL(negativeChannel);
base->MUXCR = tmp8;
}
#if defined(FSL_FEATURE_CMP_HAS_DMA) && FSL_FEATURE_CMP_HAS_DMA
void CMP_EnableDMA(CMP_Type *base, bool enable)
{
uint8_t tmp8 = base->SCR & ~(CMP_SCR_CFR_MASK | CMP_SCR_CFF_MASK); /* To avoid change the w1c bits. */
if (enable)
{
tmp8 |= CMP_SCR_DMAEN_MASK;
}
else
{
tmp8 &= ~CMP_SCR_DMAEN_MASK;
}
base->SCR = tmp8;
}
#endif /* FSL_FEATURE_CMP_HAS_DMA */
void CMP_SetFilterConfig(CMP_Type *base, const cmp_filter_config_t *config)
{
assert(NULL != config);
uint8_t tmp8;
#if defined(FSL_FEATURE_CMP_HAS_EXTERNAL_SAMPLE_SUPPORT) && FSL_FEATURE_CMP_HAS_EXTERNAL_SAMPLE_SUPPORT
/* Choose the clock source for sampling. */
if (config->enableSample)
{
base->CR1 |= CMP_CR1_SE_MASK; /* Choose the external SAMPLE clock. */
}
else
{
base->CR1 &= ~CMP_CR1_SE_MASK; /* Choose the internal divided bus clock. */
}
#endif /* FSL_FEATURE_CMP_HAS_EXTERNAL_SAMPLE_SUPPORT */
/* Set the filter count. */
tmp8 = base->CR0 & ~CMP_CR0_FILTER_CNT_MASK;
tmp8 |= CMP_CR0_FILTER_CNT(config->filterCount);
base->CR0 = tmp8;
/* Set the filter period. It is used as the divider to bus clock. */
base->FPR = CMP_FPR_FILT_PER(config->filterPeriod);
}
void CMP_SetDACConfig(CMP_Type *base, const cmp_dac_config_t *config)
{
uint8_t tmp8 = 0U;
if (NULL == config)
{
/* Passing "NULL" as input parameter means no available configuration. So the DAC feature is disabled.*/
base->DACCR = 0U;
return;
}
/* CMPx_DACCR. */
tmp8 |= CMP_DACCR_DACEN_MASK; /* Enable the internal DAC. */
if (kCMP_VrefSourceVin2 == config->referenceVoltageSource)
{
tmp8 |= CMP_DACCR_VRSEL_MASK;
}
tmp8 |= CMP_DACCR_VOSEL(config->DACValue);
base->DACCR = tmp8;
}
void CMP_EnableInterrupts(CMP_Type *base, uint32_t mask)
{
uint8_t tmp8 = base->SCR & ~(CMP_SCR_CFR_MASK | CMP_SCR_CFF_MASK); /* To avoid change the w1c bits. */
if (0U != (kCMP_OutputRisingInterruptEnable & mask))
{
tmp8 |= CMP_SCR_IER_MASK;
}
if (0U != (kCMP_OutputFallingInterruptEnable & mask))
{
tmp8 |= CMP_SCR_IEF_MASK;
}
base->SCR = tmp8;
}
void CMP_DisableInterrupts(CMP_Type *base, uint32_t mask)
{
uint8_t tmp8 = base->SCR & ~(CMP_SCR_CFR_MASK | CMP_SCR_CFF_MASK); /* To avoid change the w1c bits. */
if (0U != (kCMP_OutputRisingInterruptEnable & mask))
{
tmp8 &= ~CMP_SCR_IER_MASK;
}
if (0U != (kCMP_OutputFallingInterruptEnable & mask))
{
tmp8 &= ~CMP_SCR_IEF_MASK;
}
base->SCR = tmp8;
}
uint32_t CMP_GetStatusFlags(CMP_Type *base)
{
uint32_t ret32 = 0U;
if (0U != (CMP_SCR_CFR_MASK & base->SCR))
{
ret32 |= kCMP_OutputRisingEventFlag;
}
if (0U != (CMP_SCR_CFF_MASK & base->SCR))
{
ret32 |= kCMP_OutputFallingEventFlag;
}
if (0U != (CMP_SCR_COUT_MASK & base->SCR))
{
ret32 |= kCMP_OutputAssertEventFlag;
}
return ret32;
}
void CMP_ClearStatusFlags(CMP_Type *base, uint32_t mask)
{
uint8_t tmp8 = base->SCR & ~(CMP_SCR_CFR_MASK | CMP_SCR_CFF_MASK); /* To avoid change the w1c bits. */
if (0U != (kCMP_OutputRisingEventFlag & mask))
{
tmp8 |= CMP_SCR_CFR_MASK;
}
if (0U != (kCMP_OutputFallingEventFlag & mask))
{
tmp8 |= CMP_SCR_CFF_MASK;
}
base->SCR = tmp8;
}

View File

@ -0,0 +1,345 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _FSL_CMP_H_
#define _FSL_CMP_H_
#include "fsl_common.h"
/*!
* @addtogroup cmp
* @{
*/
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @name Driver version */
/*@{*/
/*! @brief CMP driver version 2.0.0. */
#define FSL_CMP_DRIVER_VERSION (MAKE_VERSION(2, 0, 0))
/*@}*/
/*!
* @brief Interrupt enable/disable mask.
*/
enum _cmp_interrupt_enable
{
kCMP_OutputRisingInterruptEnable = CMP_SCR_IER_MASK, /*!< Comparator interrupt enable rising. */
kCMP_OutputFallingInterruptEnable = CMP_SCR_IEF_MASK, /*!< Comparator interrupt enable falling. */
};
/*!
* @brief Status flags' mask.
*/
enum _cmp_status_flags
{
kCMP_OutputRisingEventFlag = CMP_SCR_CFR_MASK, /*!< Rising-edge on compare output has occurred. */
kCMP_OutputFallingEventFlag = CMP_SCR_CFF_MASK, /*!< Falling-edge on compare output has occurred. */
kCMP_OutputAssertEventFlag = CMP_SCR_COUT_MASK, /*!< Return the current value of the analog comparator output. */
};
/*!
* @brief CMP Hysteresis mode.
*/
typedef enum _cmp_hysteresis_mode
{
kCMP_HysteresisLevel0 = 0U, /*!< Hysteresis level 0. */
kCMP_HysteresisLevel1 = 1U, /*!< Hysteresis level 1. */
kCMP_HysteresisLevel2 = 2U, /*!< Hysteresis level 2. */
kCMP_HysteresisLevel3 = 3U, /*!< Hysteresis level 3. */
} cmp_hysteresis_mode_t;
/*!
* @brief CMP Voltage Reference source.
*/
typedef enum _cmp_reference_voltage_source
{
kCMP_VrefSourceVin1 = 0U, /*!< Vin1 is selected as resistor ladder network supply reference Vin. */
kCMP_VrefSourceVin2 = 1U, /*!< Vin2 is selected as resistor ladder network supply reference Vin. */
} cmp_reference_voltage_source_t;
/*!
* @brief Configuration for the comparator.
*/
typedef struct _cmp_config
{
bool enableCmp; /*!< Enable the CMP module. */
cmp_hysteresis_mode_t hysteresisMode; /*!< CMP Hysteresis mode. */
bool enableHighSpeed; /*!< Enable High-speed comparison mode. */
bool enableInvertOutput; /*!< Enable inverted comparator output. */
bool useUnfilteredOutput; /*!< Set compare output(COUT) to equal COUTA(true) or COUT(false). */
bool enablePinOut; /*!< The comparator output is available on the associated pin. */
#if defined(FSL_FEATURE_CMP_HAS_TRIGGER_MODE) && FSL_FEATURE_CMP_HAS_TRIGGER_MODE
bool enableTriggerMode; /*!< Enable the trigger mode. */
#endif /* FSL_FEATURE_CMP_HAS_TRIGGER_MODE */
} cmp_config_t;
/*!
* @brief Configuration for the filter.
*/
typedef struct _cmp_filter_config
{
#if defined(FSL_FEATURE_CMP_HAS_EXTERNAL_SAMPLE_SUPPORT) && FSL_FEATURE_CMP_HAS_EXTERNAL_SAMPLE_SUPPORT
bool enableSample; /*!< Using external SAMPLE as sampling clock input, or using divided bus clock. */
#endif /* FSL_FEATURE_CMP_HAS_EXTERNAL_SAMPLE_SUPPORT */
uint8_t filterCount; /*!< Filter Sample Count. Available range is 1-7, 0 would cause the filter disabled.*/
uint8_t filterPeriod; /*!< Filter Sample Period. The divider to bus clock. Available range is 0-255. */
} cmp_filter_config_t;
/*!
* @brief Configuration for the internal DAC.
*/
typedef struct _cmp_dac_config
{
cmp_reference_voltage_source_t referenceVoltageSource; /*!< Supply voltage reference source. */
uint8_t DACValue; /*!< Value for DAC Output Voltage. Available range is 0-63.*/
} cmp_dac_config_t;
#if defined(__cplusplus)
extern "C" {
#endif
/*******************************************************************************
* API
******************************************************************************/
/*!
* @name Initialization
* @{
*/
/*!
* @brief Initializes the CMP.
*
* This function initializes the CMP module. The operations included are:
* - Enabling the clock for CMP module.
* - Configuring the comparator.
* - Enabling the CMP module.
* Note: For some devices, multiple CMP instance share the same clock gate. In this case, to enable the clock for
* any instance enables all the CMPs. Check the chip reference manual for the clock assignment of the CMP.
*
* @param base CMP peripheral base address.
* @param config Pointer to configuration structure.
*/
void CMP_Init(CMP_Type *base, const cmp_config_t *config);
/*!
* @brief De-initializes the CMP module.
*
* This function de-initializes the CMP module. The operations included are:
* - Disabling the CMP module.
* - Disabling the clock for CMP module.
*
* This function disables the clock for the CMP.
* Note: For some devices, multiple CMP instance shares the same clock gate. In this case, before disabling the
* clock for the CMP, ensure that all the CMP instances are not used.
*
* @param base CMP peripheral base address.
*/
void CMP_Deinit(CMP_Type *base);
/*!
* @brief Enables/disables the CMP module.
*
* @param base CMP peripheral base address.
* @param enable Enable the module or not.
*/
static inline void CMP_Enable(CMP_Type *base, bool enable)
{
if (enable)
{
base->CR1 |= CMP_CR1_EN_MASK;
}
else
{
base->CR1 &= ~CMP_CR1_EN_MASK;
}
}
/*!
* @brief Initializes the CMP user configuration structure.
*
* This function initializes the user configuration structure to these default values:
* @code
* config->enableCmp = true;
* config->hysteresisMode = kCMP_HysteresisLevel0;
* config->enableHighSpeed = false;
* config->enableInvertOutput = false;
* config->useUnfilteredOutput = false;
* config->enablePinOut = false;
* config->enableTriggerMode = false;
* @endcode
* @param config Pointer to the configuration structure.
*/
void CMP_GetDefaultConfig(cmp_config_t *config);
/*!
* @brief Sets the input channels for the comparator.
*
* This function sets the input channels for the comparator.
* Note that two input channels cannot be set as same in the application. When the user selects the same input
* from the analog mux to the positive and negative port, the comparator is disabled automatically.
*
* @param base CMP peripheral base address.
* @param positiveChannel Positive side input channel number. Available range is 0-7.
* @param negativeChannel Negative side input channel number. Available range is 0-7.
*/
void CMP_SetInputChannels(CMP_Type *base, uint8_t positiveChannel, uint8_t negativeChannel);
/* @} */
/*!
* @name Advanced Features
* @{
*/
#if defined(FSL_FEATURE_CMP_HAS_DMA) && FSL_FEATURE_CMP_HAS_DMA
/*!
* @brief Enables/disables the DMA request for rising/falling events.
*
* This function enables/disables the DMA request for rising/falling events. Either event triggers the generation of
* the DMA
* request from CMP if the DMA feature is enabled. Both events are ignored for generating the DMA request from the CMP
* if the
* DMA is disabled.
*
* @param base CMP peripheral base address.
* @param enable Enable the feature or not.
*/
void CMP_EnableDMA(CMP_Type *base, bool enable);
#endif /* FSL_FEATURE_CMP_HAS_DMA */
#if defined(FSL_FEATURE_CMP_HAS_WINDOW_MODE) && FSL_FEATURE_CMP_HAS_WINDOW_MODE
/*!
* @brief Enables/disables the window mode.
*
* @param base CMP peripheral base address.
* @param enable Enable the feature or not.
*/
static inline void CMP_EnableWindowMode(CMP_Type *base, bool enable)
{
if (enable)
{
base->CR1 |= CMP_CR1_WE_MASK;
}
else
{
base->CR1 &= ~CMP_CR1_WE_MASK;
}
}
#endif /* FSL_FEATURE_CMP_HAS_WINDOW_MODE */
#if defined(FSL_FEATURE_CMP_HAS_PASS_THROUGH_MODE) && FSL_FEATURE_CMP_HAS_PASS_THROUGH_MODE
/*!
* @brief Enables/disables the pass through mode.
*
* @param base CMP peripheral base address.
* @param enable Enable the feature or not.
*/
static inline void CMP_EnablePassThroughMode(CMP_Type *base, bool enable)
{
if (enable)
{
base->MUXCR |= CMP_MUXCR_PSTM_MASK;
}
else
{
base->MUXCR &= ~CMP_MUXCR_PSTM_MASK;
}
}
#endif /* FSL_FEATURE_CMP_HAS_PASS_THROUGH_MODE */
/*!
* @brief Configures the filter.
*
* @param base CMP peripheral base address.
* @param config Pointer to configuration structure.
*/
void CMP_SetFilterConfig(CMP_Type *base, const cmp_filter_config_t *config);
/*!
* @brief Configures the internal DAC.
*
* @param base CMP peripheral base address.
* @param config Pointer to configuration structure. "NULL" is for disabling the feature.
*/
void CMP_SetDACConfig(CMP_Type *base, const cmp_dac_config_t *config);
/*!
* @brief Enables the interrupts.
*
* @param base CMP peripheral base address.
* @param mask Mask value for interrupts. See "_cmp_interrupt_enable".
*/
void CMP_EnableInterrupts(CMP_Type *base, uint32_t mask);
/*!
* @brief Disables the interrupts.
*
* @param base CMP peripheral base address.
* @param mask Mask value for interrupts. See "_cmp_interrupt_enable".
*/
void CMP_DisableInterrupts(CMP_Type *base, uint32_t mask);
/* @} */
/*!
* @name Results
* @{
*/
/*!
* @brief Gets the status flags.
*
* @param base CMP peripheral base address.
*
* @return Mask value for the asserted flags. See "_cmp_status_flags".
*/
uint32_t CMP_GetStatusFlags(CMP_Type *base);
/*!
* @brief Clears the status flags.
*
* @param base CMP peripheral base address.
* @param mask Mask value for the flags. See "_cmp_status_flags".
*/
void CMP_ClearStatusFlags(CMP_Type *base, uint32_t mask);
/* @} */
#if defined(__cplusplus)
}
#endif
/*!
* @}
*/
#endif /* _FSL_CMP_H_ */

View File

@ -0,0 +1,260 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include "fsl_cmt.h"
/*******************************************************************************
* Definitions
******************************************************************************/
/* The standard intermediate frequency (IF). */
#define CMT_INTERMEDIATEFREQUENCY_8MHZ (8000000U)
/* CMT data modulate mask. */
#define CMT_MODULATE_COUNT_WIDTH (8U)
/* CMT diver 1. */
#define CMT_CMTDIV_ONE (1)
/* CMT diver 2. */
#define CMT_CMTDIV_TWO (2)
/* CMT diver 4. */
#define CMT_CMTDIV_FOUR (4)
/* CMT diver 8. */
#define CMT_CMTDIV_EIGHT (8)
/* CMT mode bit mask. */
#define CMT_MODE_BIT_MASK (CMT_MSC_MCGEN_MASK | CMT_MSC_FSK_MASK | CMT_MSC_BASE_MASK)
/*******************************************************************************
* Prototypes
******************************************************************************/
/*!
* @brief Get instance number for CMT module.
*
* @param base CMT peripheral base address.
*/
static uint32_t CMT_GetInstance(CMT_Type *base);
/*******************************************************************************
* Variables
******************************************************************************/
/*! @brief Pointers to cmt clocks for each instance. */
static const clock_ip_name_t s_cmtClock[FSL_FEATURE_SOC_CMT_COUNT] = CMT_CLOCKS;
/*! @brief Pointers to cmt bases for each instance. */
static CMT_Type *const s_cmtBases[] = CMT_BASE_PTRS;
/*! @brief Pointers to cmt IRQ number for each instance. */
static const IRQn_Type s_cmtIrqs[] = CMT_IRQS;
/*******************************************************************************
* Codes
******************************************************************************/
static uint32_t CMT_GetInstance(CMT_Type *base)
{
uint32_t instance;
/* Find the instance index from base address mappings. */
for (instance = 0; instance < FSL_FEATURE_SOC_CMT_COUNT; instance++)
{
if (s_cmtBases[instance] == base)
{
break;
}
}
assert(instance < FSL_FEATURE_SOC_CMT_COUNT);
return instance;
}
void CMT_GetDefaultConfig(cmt_config_t *config)
{
assert(config);
/* Default infrared output is enabled and set with high active, the divider is set to 1. */
config->isInterruptEnabled = false;
config->isIroEnabled = true;
config->iroPolarity = kCMT_IROActiveHigh;
config->divider = kCMT_SecondClkDiv1;
}
void CMT_Init(CMT_Type *base, const cmt_config_t *config, uint32_t busClock_Hz)
{
assert(config);
assert(busClock_Hz >= CMT_INTERMEDIATEFREQUENCY_8MHZ);
uint8_t divider;
/* Ungate clock. */
CLOCK_EnableClock(s_cmtClock[CMT_GetInstance(base)]);
/* Sets clock divider. The divider set in pps should be set
to make sycClock_Hz/divder = 8MHz */
base->PPS = CMT_PPS_PPSDIV(busClock_Hz / CMT_INTERMEDIATEFREQUENCY_8MHZ - 1);
divider = base->MSC;
divider &= ~CMT_MSC_CMTDIV_MASK;
divider |= CMT_MSC_CMTDIV(config->divider);
base->MSC = divider;
/* Set the IRO signal. */
base->OC = CMT_OC_CMTPOL(config->iroPolarity) | CMT_OC_IROPEN(config->isIroEnabled);
/* Set interrupt. */
if (config->isInterruptEnabled)
{
CMT_EnableInterrupts(base, kCMT_EndOfCycleInterruptEnable);
EnableIRQ(s_cmtIrqs[CMT_GetInstance(base)]);
}
}
void CMT_Deinit(CMT_Type *base)
{
/*Disable the CMT modulator. */
base->MSC = 0;
/* Disable the interrupt. */
CMT_DisableInterrupts(base, kCMT_EndOfCycleInterruptEnable);
DisableIRQ(s_cmtIrqs[CMT_GetInstance(base)]);
/* Gate the clock. */
CLOCK_DisableClock(s_cmtClock[CMT_GetInstance(base)]);
}
void CMT_SetMode(CMT_Type *base, cmt_mode_t mode, cmt_modulate_config_t *modulateConfig)
{
uint8_t mscReg;
/* Set the mode. */
if (mode != kCMT_DirectIROCtl)
{
assert(modulateConfig);
/* Set carrier generator. */
CMT_SetCarrirGenerateCountOne(base, modulateConfig->highCount1, modulateConfig->lowCount1);
if (mode == kCMT_FSKMode)
{
CMT_SetCarrirGenerateCountTwo(base, modulateConfig->highCount2, modulateConfig->lowCount2);
}
/* Set carrier modulator. */
CMT_SetModulateMarkSpace(base, modulateConfig->markCount, modulateConfig->spaceCount);
}
/* Set the CMT mode. */
mscReg = base->MSC;
mscReg &= ~CMT_MODE_BIT_MASK;
mscReg |= mode;
base->MSC = mscReg;
}
cmt_mode_t CMT_GetMode(CMT_Type *base)
{
uint8_t mode = base->MSC;
if (!(mode & CMT_MSC_MCGEN_MASK))
{ /* Carrier modulator disabled and the IRO signal is in direct software control. */
return kCMT_DirectIROCtl;
}
else
{
/* Carrier modulator is enabled. */
if (mode & CMT_MSC_BASE_MASK)
{
/* Base band mode. */
return kCMT_BasebandMode;
}
else if (mode & CMT_MSC_FSK_MASK)
{
/* FSK mode. */
return kCMT_FSKMode;
}
else
{
/* Time mode. */
return kCMT_TimeMode;
}
}
}
uint32_t CMT_GetCMTFrequency(CMT_Type *base, uint32_t busClock_Hz)
{
uint32_t frequency;
uint32_t divider;
/* Get intermediate frequency. */
frequency = busClock_Hz / ((base->PPS & CMT_PPS_PPSDIV_MASK) + 1);
/* Get the second divider. */
divider = ((base->MSC & CMT_MSC_CMTDIV_MASK) >> CMT_MSC_CMTDIV_SHIFT);
/* Get CMT frequency. */
switch ((cmt_second_clkdiv_t)divider)
{
case kCMT_SecondClkDiv1:
frequency = frequency / CMT_CMTDIV_ONE;
break;
case kCMT_SecondClkDiv2:
frequency = frequency / CMT_CMTDIV_TWO;
break;
case kCMT_SecondClkDiv4:
frequency = frequency / CMT_CMTDIV_FOUR;
break;
case kCMT_SecondClkDiv8:
frequency = frequency / CMT_CMTDIV_EIGHT;
break;
default:
frequency = frequency / CMT_CMTDIV_ONE;
break;
}
return frequency;
}
void CMT_SetModulateMarkSpace(CMT_Type *base, uint32_t markCount, uint32_t spaceCount)
{
/* Set modulate mark. */
base->CMD1 = (markCount >> CMT_MODULATE_COUNT_WIDTH) & CMT_CMD1_MB_MASK;
base->CMD2 = (markCount & CMT_CMD2_MB_MASK);
/* Set modulate space. */
base->CMD3 = (spaceCount >> CMT_MODULATE_COUNT_WIDTH) & CMT_CMD3_SB_MASK;
base->CMD4 = spaceCount & CMT_CMD4_SB_MASK;
}
void CMT_SetIroState(CMT_Type *base, cmt_infrared_output_state_t state)
{
uint8_t ocReg = base->OC;
ocReg &= ~CMT_OC_IROL_MASK;
ocReg |= CMT_OC_IROL(state);
/* Set the infrared output signal control. */
base->OC = ocReg;
}

View File

@ -0,0 +1,402 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _FSL_CMT_H_
#define _FSL_CMT_H_
#include "fsl_common.h"
/*!
* @addtogroup cmt
* @{
*/
/*! @file */
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @name Driver version */
/*@{*/
/*! @brief CMT driver version 2.0.0. */
#define FSL_CMT_DRIVER_VERSION (MAKE_VERSION(2, 0, 0))
/*@}*/
/*!
* @brief The modes of CMT.
*/
typedef enum _cmt_mode
{
kCMT_DirectIROCtl = 0x00U, /*!< Carrier modulator is disabled and the IRO signal is directly in software control */
kCMT_TimeMode = 0x01U, /*!< Carrier modulator is enabled in time mode. */
kCMT_FSKMode = 0x05U, /*!< Carrier modulator is enabled in FSK mode. */
kCMT_BasebandMode = 0x09U /*!< Carrier modulator is enabled in baseband mode. */
} cmt_mode_t;
/*!
* @brief The CMT clock divide primary prescaler.
* The primary clock divider is used to divider the bus clock to
* get the intermediate frequency to approximately equal to 8 MHZ.
* When the bus clock is 8 MHZ, set primary prescaler to "kCMT_PrimaryClkDiv1".
*/
typedef enum _cmt_primary_clkdiv
{
kCMT_PrimaryClkDiv1 = 0U, /*!< The intermediate frequency is the bus clock divided by 1. */
kCMT_PrimaryClkDiv2 = 1U, /*!< The intermediate frequency is the bus clock divided by 2. */
kCMT_PrimaryClkDiv3 = 2U, /*!< The intermediate frequency is the bus clock divided by 3. */
kCMT_PrimaryClkDiv4 = 3U, /*!< The intermediate frequency is the bus clock divided by 4. */
kCMT_PrimaryClkDiv5 = 4U, /*!< The intermediate frequency is the bus clock divided by 5. */
kCMT_PrimaryClkDiv6 = 5U, /*!< The intermediate frequency is the bus clock divided by 6. */
kCMT_PrimaryClkDiv7 = 6U, /*!< The intermediate frequency is the bus clock divided by 7. */
kCMT_PrimaryClkDiv8 = 7U, /*!< The intermediate frequency is the bus clock divided by 8. */
kCMT_PrimaryClkDiv9 = 8U, /*!< The intermediate frequency is the bus clock divided by 9. */
kCMT_PrimaryClkDiv10 = 9U, /*!< The intermediate frequency is the bus clock divided by 10. */
kCMT_PrimaryClkDiv11 = 10U, /*!< The intermediate frequency is the bus clock divided by 11. */
kCMT_PrimaryClkDiv12 = 11U, /*!< The intermediate frequency is the bus clock divided by 12. */
kCMT_PrimaryClkDiv13 = 12U, /*!< The intermediate frequency is the bus clock divided by 13. */
kCMT_PrimaryClkDiv14 = 13U, /*!< The intermediate frequency is the bus clock divided by 14. */
kCMT_PrimaryClkDiv15 = 14U, /*!< The intermediate frequency is the bus clock divided by 15. */
kCMT_PrimaryClkDiv16 = 15U /*!< The intermediate frequency is the bus clock divided by 16. */
} cmt_primary_clkdiv_t;
/*!
* @brief The CMT clock divide secondary prescaler.
* The second prescaler can be used to divide the 8 MHZ CMT clock
* by 1, 2, 4, or 8 according to the specification.
*/
typedef enum _cmt_second_clkdiv
{
kCMT_SecondClkDiv1 = 0U, /*!< The CMT clock is the intermediate frequency frequency divided by 1. */
kCMT_SecondClkDiv2 = 1U, /*!< The CMT clock is the intermediate frequency frequency divided by 2. */
kCMT_SecondClkDiv4 = 2U, /*!< The CMT clock is the intermediate frequency frequency divided by 4. */
kCMT_SecondClkDiv8 = 3U /*!< The CMT clock is the intermediate frequency frequency divided by 8. */
} cmt_second_clkdiv_t;
/*!
* @brief The CMT infrared output polarity.
*/
typedef enum _cmt_infrared_output_polarity
{
kCMT_IROActiveLow = 0U, /*!< The CMT infrared output signal polarity is active-low. */
kCMT_IROActiveHigh = 1U /*!< The CMT infrared output signal polarity is active-high. */
} cmt_infrared_output_polarity_t;
/*!
* @brief The CMT infrared output signal state control.
*/
typedef enum _cmt_infrared_output_state
{
kCMT_IROCtlLow = 0U, /*!< The CMT Infrared output signal state is controlled to low. */
kCMT_IROCtlHigh = 1U /*!< The CMT Infrared output signal state is controlled to high. */
} cmt_infrared_output_state_t;
/*!
* @brief CMT interrupt configuration structure, default settings all disabled.
*
* This structure contains the settings for all of the CMT interrupt configurations.
*/
enum _cmt_interrupt_enable
{
kCMT_EndOfCycleInterruptEnable = CMT_MSC_EOCIE_MASK, /*!< CMT end of cycle interrupt. */
};
/*!
* @brief CMT carrier generator and modulator configure structure
*
*/
typedef struct _cmt_modulate_config
{
uint8_t highCount1; /*!< The high time for carrier generator first register. */
uint8_t lowCount1; /*!< The low time for carrier generator first register. */
uint8_t highCount2; /*!< The high time for carrier generator second register for FSK mode. */
uint8_t lowCount2; /*!< The low time for carrier generator second register for FSK mode. */
uint16_t markCount; /*!< The mark time for the modulator gate. */
uint16_t spaceCount; /*!< The space time for the modulator gate. */
} cmt_modulate_config_t;
/*! @brief CMT basic configuration structure. */
typedef struct _cmt_config
{
bool isInterruptEnabled; /*!< Timer interrupt 0-disable, 1-enable. */
bool isIroEnabled; /*!< The IRO output 0-disabled, 1-enabled. */
cmt_infrared_output_polarity_t iroPolarity; /*!< The IRO polarity. */
cmt_second_clkdiv_t divider; /*!< The CMT clock divide prescaler. */
} cmt_config_t;
/*******************************************************************************
* API
******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif
/*!
* @name Initialization and deinitialization
* @{
*/
/*!
* @brief Gets the CMT default configuration structure. The purpose
* of this API is to get the default configuration structure for the CMT_Init().
* Use the initialized structure unchanged in CMT_Init(), or modify
* some fields of the structure before calling the CMT_Init().
*
* @param config The CMT configuration structure pointer.
*/
void CMT_GetDefaultConfig(cmt_config_t *config);
/*!
* @brief Initializes the CMT module.
*
* This function ungates the module clock and sets the CMT internal clock,
* interrupt, and infrared output signal for the CMT module.
*
* @param base CMT peripheral base address.
* @param config The CMT basic configuration structure.
* @param busClock_Hz The CMT module input clock - bus clock frequency.
*/
void CMT_Init(CMT_Type *base, const cmt_config_t *config, uint32_t busClock_Hz);
/*!
* @brief Disables the CMT module and gate control.
*
* This function disables CMT modulator, interrupts, and gates the
* CMT clock control. CMT_Init must be called to use the CMT again.
*
* @param base CMT peripheral base address.
*/
void CMT_Deinit(CMT_Type *base);
/*! @}*/
/*!
* @name Basic Control Operations
* @{
*/
/*!
* @brief Selects the mode for CMT.
*
* @param base CMT peripheral base address.
* @param mode The CMT feature mode enumeration. See "cmt_mode_t".
* @param modulateConfig The carrier generation and modulator configuration.
*/
void CMT_SetMode(CMT_Type *base, cmt_mode_t mode, cmt_modulate_config_t *modulateConfig);
/*!
* @brief Gets the mode of the CMT module.
*
* @param base CMT peripheral base address.
* @return The CMT mode.
* kCMT_DirectIROCtl Carrier modulator is disabled, the IRO signal is directly in software control.
* kCMT_TimeMode Carrier modulator is enabled in time mode.
* kCMT_FSKMode Carrier modulator is enabled in FSK mode.
* kCMT_BasebandMode Carrier modulator is enabled in baseband mode.
*/
cmt_mode_t CMT_GetMode(CMT_Type *base);
/*!
* @brief Gets the actual CMT clock frequency.
*
* @param base CMT peripheral base address.
* @param busClock_Hz CMT module input clock - bus clock frequency.
* @return The CMT clock frequency.
*/
uint32_t CMT_GetCMTFrequency(CMT_Type *base, uint32_t busClock_Hz);
/*!
* @brief Sets the primary data set for the CMT carrier generator counter.
*
* This function sets the high time and low time of the primary data set for the
* CMT carrier generator counter to control the period and the duty cycle of the
* output carrier signal.
* If the CMT clock period is Tcmt, The period of the carrier generator signal equals
* (highCount + lowCount) * Tcmt. The duty cycle equals highCount / (highCount + lowCount).
*
* @param base CMT peripheral base address.
* @param highCount The number of CMT clocks for carrier generator signal high time,
* integer in the range of 1 ~ 0xFF.
* @param lowCount The number of CMT clocks for carrier generator signal low time,
* integer in the range of 1 ~ 0xFF.
*/
static inline void CMT_SetCarrirGenerateCountOne(CMT_Type *base, uint32_t highCount, uint32_t lowCount)
{
assert(highCount <= CMT_CGH1_PH_MASK);
assert(highCount);
assert(lowCount <= CMT_CGL1_PL_MASK);
assert(lowCount);
base->CGH1 = highCount;
base->CGL1 = lowCount;
}
/*!
* @brief Sets the secondary data set for the CMT carrier generator counter.
*
* This function is used for FSK mode setting the high time and low time of the secondary
* data set CMT carrier generator counter to control the period and the duty cycle
* of the output carrier signal.
* If the CMT clock period is Tcmt, The period of the carrier generator signal equals
* (highCount + lowCount) * Tcmt. The duty cycle equals highCount / (highCount + lowCount).
*
* @param base CMT peripheral base address.
* @param highCount The number of CMT clocks for carrier generator signal high time,
* integer in the range of 1 ~ 0xFF.
* @param lowCount The number of CMT clocks for carrier generator signal low time,
* integer in the range of 1 ~ 0xFF.
*/
static inline void CMT_SetCarrirGenerateCountTwo(CMT_Type *base, uint32_t highCount, uint32_t lowCount)
{
assert(highCount <= CMT_CGH2_SH_MASK);
assert(highCount);
assert(lowCount <= CMT_CGL2_SL_MASK);
assert(lowCount);
base->CGH2 = highCount;
base->CGL2 = lowCount;
}
/*!
* @brief Sets the modulation mark and space time period for the CMT modulator.
*
* This function sets the mark time period of the CMT modulator counter
* to control the mark time of the output modulated signal from the carrier generator output signal.
* If the CMT clock frequency is Fcmt and the carrier out signal frequency is fcg:
* - In Time and Baseband mode: The mark period of the generated signal equals (markCount + 1) / (Fcmt/8).
* The space period of the generated signal equals spaceCount / (Fcmt/8).
* - In FSK mode: The mark period of the generated signal equals (markCount + 1)/fcg.
* The space period of the generated signal equals spaceCount / fcg.
*
* @param base Base address for current CMT instance.
* @param markCount The number of clock period for CMT modulator signal mark period,
* in the range of 0 ~ 0xFFFF.
* @param spaceCount The number of clock period for CMT modulator signal space period,
* in the range of the 0 ~ 0xFFFF.
*/
void CMT_SetModulateMarkSpace(CMT_Type *base, uint32_t markCount, uint32_t spaceCount);
/*!
* @brief Enables or disables the extended space operation.
*
* This function is used to make the space period longer
* for time, baseband, and FSK modes.
*
* @param base CMT peripheral base address.
* @param enable True enable the extended space, false disable the extended space.
*/
static inline void CMT_EnableExtendedSpace(CMT_Type *base, bool enable)
{
if (enable)
{
base->MSC |= CMT_MSC_EXSPC_MASK;
}
else
{
base->MSC &= ~CMT_MSC_EXSPC_MASK;
}
}
/*!
* @brief Sets IRO - infrared output signal state.
*
* Changes the states of the IRO signal when the kCMT_DirectIROMode mode is set
* and the IRO signal is enabled.
*
* @param base CMT peripheral base address.
* @param state The control of the IRO signal. See "cmt_infrared_output_state_t"
*/
void CMT_SetIroState(CMT_Type *base, cmt_infrared_output_state_t state);
/*!
* @brief Enables the CMT interrupt.
*
* This function enables the CMT interrupts according to the provided maskIf enabled.
* The CMT only has the end of the cycle interrupt - an interrupt occurs at the end
* of the modulator cycle. This interrupt provides a means for the user
* to reload the new mark/space values into the CMT modulator data registers
* and verify the modulator mark and space.
* For example, to enable the end of cycle, do the following:
* @code
* CMT_EnableInterrupts(CMT, kCMT_EndOfCycleInterruptEnable);
* @endcode
* @param base CMT peripheral base address.
* @param mask The interrupts to enable. Logical OR of @ref _cmt_interrupt_enable.
*/
static inline void CMT_EnableInterrupts(CMT_Type *base, uint32_t mask)
{
base->MSC |= mask;
}
/*!
* @brief Disables the CMT interrupt.
*
* This function disables the CMT interrupts according to the provided maskIf enabled.
* The CMT only has the end of the cycle interrupt.
* For example, to disable the end of cycle, do the following:
* @code
* CMT_DisableInterrupts(CMT, kCMT_EndOfCycleInterruptEnable);
* @endcode
*
* @param base CMT peripheral base address.
* @param mask The interrupts to enable. Logical OR of @ref _cmt_interrupt_enable.
*/
static inline void CMT_DisableInterrupts(CMT_Type *base, uint32_t mask)
{
base->MSC &= ~mask;
}
/*!
* @brief Gets the end of the cycle status flag.
*
* The flag is set:
* - When the modulator is not currently active and carrier and modulator
* are set to start the initial CMT transmission.
* - At the end of each modulation cycle when the counter is reloaded and
* the carrier and modulator are enabled.
* @param base CMT peripheral base address.
* @return Current status of the end of cycle status flag
* @arg non-zero: End-of-cycle has occurred.
* @arg zero: End-of-cycle has not yet occurred since the flag last cleared.
*/
static inline uint32_t CMT_GetStatusFlags(CMT_Type *base)
{
return base->MSC & CMT_MSC_EOCF_MASK;
}
/*! @}*/
#if defined(__cplusplus)
}
#endif
/*! @}*/
#endif /* _FSL_CMT_H_*/

View File

@ -0,0 +1,101 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include "fsl_common.h"
/* 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 (;;)
{
__asm("bkpt #0");
}
}
#elif(defined(__GNUC__))
void __assert_func(const char *file, int line, const char *func, const char *failedExpr)
{
PRINTF("ASSERT ERROR \" %s \": file \"%s\" Line \"%d\" function name \"%s\" \n", failedExpr, file, line, func);
for (;;)
{
__asm("bkpt #0");
}
}
#endif /* (defined(__CC_ARM)) || (defined (__ICCARM__)) */
#endif /* NDEBUG */
#endif
void InstallIRQHandler(IRQn_Type irq, uint32_t irqHandler)
{
/* Addresses for VECTOR_TABLE and VECTOR_RAM come from the linker file */
#if defined(__CC_ARM)
extern uint32_t Image$$VECTOR_ROM$$Base[];
extern uint32_t Image$$VECTOR_RAM$$Base[];
extern uint32_t Image$$RW_m_data$$Base[];
#define __VECTOR_TABLE Image$$VECTOR_ROM$$Base
#define __VECTOR_RAM Image$$VECTOR_RAM$$Base
#define __RAM_VECTOR_TABLE_SIZE (((uint32_t)Image$$RW_m_data$$Base - (uint32_t)Image$$VECTOR_RAM$$Base))
#elif defined(__ICCARM__)
extern uint32_t __RAM_VECTOR_TABLE_SIZE[];
extern uint32_t __VECTOR_TABLE[];
extern uint32_t __VECTOR_RAM[];
#elif defined(__GNUC__)
extern uint32_t __VECTOR_TABLE[];
extern uint32_t __VECTOR_RAM[];
extern uint32_t __RAM_VECTOR_TABLE_SIZE_BYTES[];
uint32_t __RAM_VECTOR_TABLE_SIZE = (uint32_t)(__RAM_VECTOR_TABLE_SIZE_BYTES);
#endif /* defined(__CC_ARM) */
uint32_t n;
uint32_t interrupts_disabled;
interrupts_disabled = __get_PRIMASK();
__disable_irq();
if (SCB->VTOR != (uint32_t)__VECTOR_RAM)
{
/* Copy the vector table from ROM to RAM */
for (n = 0; n < ((uint32_t)__RAM_VECTOR_TABLE_SIZE) / sizeof(uint32_t); n++)
{
__VECTOR_RAM[n] = __VECTOR_TABLE[n];
}
/* Point the VTOR to the position of vector table */
SCB->VTOR = (uint32_t)__VECTOR_RAM;
}
/* make sure the __VECTOR_RAM is noncachable */
__VECTOR_RAM[irq + 16] = irqHandler;
if (!interrupts_disabled) {
__enable_irq();
}
}

View File

@ -0,0 +1,255 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _FSL_COMMON_H_
#define _FSL_COMMON_H_
#include <assert.h>
#include <stdbool.h>
#include <stdint.h>
#include <stddef.h>
#include <string.h>
#include "fsl_device_registers.h"
/*!
* @addtogroup ksdk_common
* @{
*/
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @brief Construct a status code value from a group and code number. */
#define MAKE_STATUS(group, code) ((((group)*100) + (code)))
/*! @brief Construct the version number for drivers. */
#define MAKE_VERSION(major, minor, bugfix) (((major) << 16) | ((minor) << 8) | (bugfix))
/* Debug console type definition. */
#define DEBUG_CONSOLE_DEVICE_TYPE_NONE 0U /*!< No debug console. */
#define DEBUG_CONSOLE_DEVICE_TYPE_UART 1U /*!< Debug console base on UART. */
#define DEBUG_CONSOLE_DEVICE_TYPE_LPUART 2U /*!< Debug console base on LPUART. */
#define DEBUG_CONSOLE_DEVICE_TYPE_LPSCI 3U /*!< Debug console base on LPSCI. */
#define DEBUG_CONSOLE_DEVICE_TYPE_USBCDC 4U /*!< Debug console base on USBCDC. */
/*! @brief Status group numbers. */
enum _status_groups
{
kStatusGroup_Generic = 0, /*!< Group number for generic status codes. */
kStatusGroup_FLASH = 1, /*!< Group number for FLASH status codes. */
kStatusGroup_LPSPI = 4, /*!< Group number for LPSPI status codes. */
kStatusGroup_FLEXIO_SPI = 5, /*!< Group number for FLEXIO SPI status codes. */
kStatusGroup_DSPI = 6, /*!< Group number for DSPI status codes. */
kStatusGroup_FLEXIO_UART = 7, /*!< Group number for FLEXIO UART status codes. */
kStatusGroup_FLEXIO_I2C = 8, /*!< Group number for FLEXIO I2C status codes. */
kStatusGroup_LPI2C = 9, /*!< Group number for LPI2C status codes. */
kStatusGroup_UART = 10, /*!< Group number for UART status codes. */
kStatusGroup_I2C = 11, /*!< Group number for UART status codes. */
kStatusGroup_LPSCI = 12, /*!< Group number for LPSCI status codes. */
kStatusGroup_LPUART = 13, /*!< Group number for LPUART status codes. */
kStatusGroup_SPI = 14, /*!< Group number for SPI status code.*/
kStatusGroup_XRDC = 15, /*!< Group number for XRDC status code.*/
kStatusGroup_SEMA42 = 16, /*!< Group number for SEMA42 status code.*/
kStatusGroup_SDHC = 17, /*!< Group number for SDHC status code */
kStatusGroup_SDMMC = 18, /*!< Group number for SDMMC status code */
kStatusGroup_SAI = 19, /*!< Group number for SAI status code */
kStatusGroup_MCG = 20, /*!< Group number for MCG status codes. */
kStatusGroup_SCG = 21, /*!< Group number for SCG status codes. */
kStatusGroup_SDSPI = 22, /*!< Group number for SDSPI status codes. */
kStatusGroup_FLEXIO_I2S = 23, /*!< Group number for FLEXIO I2S status codes */
kStatusGroup_SDRAMC = 35, /*!< Group number for SDRAMC status codes. */
kStatusGroup_POWER = 39, /*!< Group number for POWER status codes. */
kStatusGroup_ENET = 40, /*!< Group number for ENET status codes. */
kStatusGroup_PHY = 41, /*!< Group number for PHY status codes. */
kStatusGroup_TRGMUX = 42, /*!< Group number for TRGMUX status codes. */
kStatusGroup_SMARTCARD = 43, /*!< Group number for SMARTCARD status codes. */
kStatusGroup_LMEM = 44, /*!< Group number for LMEM status codes. */
kStatusGroup_QSPI = 45, /*!< Group number for QSPI status codes. */
kStatusGroup_DMA = 50, /*!< Group number for DMA status codes. */
kStatusGroup_EDMA = 51, /*!< Group number for EDMA status codes. */
kStatusGroup_DMAMGR = 52, /*!< Group number for DMAMGR status codes. */
kStatusGroup_FLEXCAN = 53, /*!< Group number for FlexCAN status codes. */
kStatusGroup_LTC = 54, /*!< Group number for LTC status codes. */
kStatusGroup_FLEXIO_CAMERA = 55, /*!< Group number for FLEXIO CAMERA status codes. */
kStatusGroup_NOTIFIER = 98, /*!< Group number for NOTIFIER status codes. */
kStatusGroup_DebugConsole = 99, /*!< Group number for debug console status codes. */
kStatusGroup_ApplicationRangeStart = 100, /*!< Starting number for application groups. */
};
/*! @brief Generic status return codes. */
enum _generic_status
{
kStatus_Success = MAKE_STATUS(kStatusGroup_Generic, 0),
kStatus_Fail = MAKE_STATUS(kStatusGroup_Generic, 1),
kStatus_ReadOnly = MAKE_STATUS(kStatusGroup_Generic, 2),
kStatus_OutOfRange = MAKE_STATUS(kStatusGroup_Generic, 3),
kStatus_InvalidArgument = MAKE_STATUS(kStatusGroup_Generic, 4),
kStatus_Timeout = MAKE_STATUS(kStatusGroup_Generic, 5),
kStatus_NoTransferInProgress = MAKE_STATUS(kStatusGroup_Generic, 6),
};
/*! @brief Type used for all status and error return values. */
typedef int32_t status_t;
/*
* The fsl_clock.h is included here because it needs MAKE_VERSION/MAKE_STATUS/status_t
* defined in previous of this file.
*/
#include "fsl_clock.h"
/*! @name Min/max macros */
/* @{ */
#if !defined(MIN)
#define MIN(a, b) ((a) < (b) ? (a) : (b))
#endif
#if !defined(MAX)
#define MAX(a, b) ((a) > (b) ? (a) : (b))
#endif
/* @} */
/*! @brief Computes the number of elements in an array. */
#define ARRAY_SIZE(x) (sizeof(x) / sizeof((x)[0]))
/*! @name UINT16_MAX/UINT32_MAX value */
/* @{ */
#if !defined(UINT16_MAX)
#define UINT16_MAX ((uint16_t)-1)
#endif
#if !defined(UINT32_MAX)
#define UINT32_MAX ((uint32_t)-1)
#endif
/* @} */
/*! @name Timer utilities */
/* @{ */
/*! Macro to convert a microsecond period to raw count value */
#define USEC_TO_COUNT(us, clockFreqInHz) (uint64_t)((uint64_t)us * clockFreqInHz / 1000000U)
/*! Macro to convert a raw count value to microsecond */
#define COUNT_TO_USEC(count, clockFreqInHz) (uint64_t)((uint64_t)count * 1000000U / clockFreqInHz)
/*! Macro to convert a millisecond period to raw count value */
#define MSEC_TO_COUNT(ms, clockFreqInHz) (uint64_t)((uint64_t)ms * clockFreqInHz / 1000U)
/*! Macro to convert a raw count value to millisecond */
#define COUNT_TO_MSEC(count, clockFreqInHz) (uint64_t)((uint64_t)count * 1000U / clockFreqInHz)
/* @} */
/*******************************************************************************
* API
******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif
/*!
* @brief Enable specific interrupt.
*
* Enable the interrupt not routed from intmux.
*
* @param interrupt The IRQ number.
*/
static inline void EnableIRQ(IRQn_Type interrupt)
{
#if defined(FSL_FEATURE_SOC_INTMUX_COUNT) && (FSL_FEATURE_SOC_INTMUX_COUNT > 0)
if (interrupt < FSL_FEATURE_INTMUX_IRQ_START_INDEX)
#endif
{
NVIC_EnableIRQ(interrupt);
}
}
/*!
* @brief Disable specific interrupt.
*
* Disable the interrupt not routed from intmux.
*
* @param interrupt The IRQ number.
*/
static inline void DisableIRQ(IRQn_Type interrupt)
{
#if defined(FSL_FEATURE_SOC_INTMUX_COUNT) && (FSL_FEATURE_SOC_INTMUX_COUNT > 0)
if (interrupt < FSL_FEATURE_INTMUX_IRQ_START_INDEX)
#endif
{
NVIC_DisableIRQ(interrupt);
}
}
/*!
* @brief Disable the global IRQ
*
* Disable the global interrupt and return the current primask register. User is required to provided the primask
* register for the EnableGlobalIRQ().
*
* @return Current primask value.
*/
static inline uint32_t DisableGlobalIRQ(void)
{
uint32_t regPrimask = __get_PRIMASK();
__disable_irq();
return regPrimask;
}
/*!
* @brief Enaable the global IRQ
*
* Set the primask register with the provided primask value but not just enable the primask. The idea is for the
* convinience of integration of RTOS. some RTOS get its own management mechanism of primask. User is required to
* use the EnableGlobalIRQ() and DisableGlobalIRQ() in pair.
*
* @param primask value of primask register to be restored. The primask value is supposed to be provided by the
* DisableGlobalIRQ().
*/
static inline void EnableGlobalIRQ(uint32_t primask)
{
__set_PRIMASK(primask);
}
/*!
* @brief install IRQ handler
*
* @param irq IRQ number
* @param irqHandler IRQ handler address
*/
void InstallIRQHandler(IRQn_Type irq, uint32_t irqHandler);
#if defined(__cplusplus)
}
#endif
/*! @} */
#endif /* _FSL_COMMON_H_ */

View File

@ -0,0 +1,77 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include "fsl_cop.h"
/*******************************************************************************
* Code
******************************************************************************/
void COP_GetDefaultConfig(cop_config_t *config)
{
assert(config);
config->enableWindowMode = false;
#if defined(FSL_FEATURE_COP_HAS_LONGTIME_MODE) && FSL_FEATURE_COP_HAS_LONGTIME_MODE
config->timeoutMode = kCOP_LongTimeoutMode;
config->enableStop = false;
config->enableDebug = false;
#endif /* FSL_FEATURE_COP_HAS_LONGTIME_MODE */
config->clockSource = kCOP_LpoClock;
config->timeoutCycles = kCOP_2Power10CyclesOr2Power18Cycles;
}
void COP_Init(SIM_Type *base, const cop_config_t *config)
{
assert(config);
uint32_t value = 0U;
#if defined(FSL_FEATURE_COP_HAS_LONGTIME_MODE) && FSL_FEATURE_COP_HAS_LONGTIME_MODE
value = SIM_COPC_COPW(config->enableWindowMode) | SIM_COPC_COPCLKS(config->timeoutMode) |
SIM_COPC_COPT(config->timeoutCycles) | SIM_COPC_COPSTPEN(config->enableStop) |
SIM_COPC_COPDBGEN(config->enableDebug) | SIM_COPC_COPCLKSEL(config->clockSource);
#else
value = SIM_COPC_COPW(config->enableWindowMode) | SIM_COPC_COPCLKS(config->clockSource) |
SIM_COPC_COPT(config->timeoutCycles);
#endif /* FSL_FEATURE_COP_HAS_LONGTIME_MODE */
base->COPC = value;
}
void COP_Refresh(SIM_Type *base)
{
uint32_t primaskValue = 0U;
/* Disable the global interrupt to protect refresh sequence */
primaskValue = DisableGlobalIRQ();
base->SRVCOP = COP_FIRST_BYTE_OF_REFRESH;
base->SRVCOP = COP_SECOND_BYTE_OF_REFRESH;
EnableGlobalIRQ(primaskValue);
}

View File

@ -0,0 +1,188 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _FSL_COP_H_
#define _FSL_COP_H_
#include "fsl_common.h"
/*!
* @addtogroup cop_driver
* @{
*/
/*! @file */
/*******************************************************************************
* Definitions
*******************************************************************************/
/*! @name Driver version */
/*@{*/
/*! @brief COP driver version 2.0.0. */
#define FSL_COP_DRIVER_VERSION (MAKE_VERSION(2, 0, 0))
/*@}*/
/*! @name COP refresh sequence. */
/*@{*/
#define COP_FIRST_BYTE_OF_REFRESH (0x55U) /*!< First byte of refresh sequence */
#define COP_SECOND_BYTE_OF_REFRESH (0xAAU) /*!< Second byte of refresh sequence */
/*@}*/
/*! @brief COP clock source selection. */
typedef enum _cop_clock_source
{
kCOP_LpoClock = 0U, /*!< COP clock sourced from LPO */
#if defined(FSL_FEATURE_COP_HAS_MORE_CLKSRC) && FSL_FEATURE_COP_HAS_MORE_CLKSRC
kCOP_McgIrClock = 1U, /*!< COP clock sourced from MCGIRCLK */
kCOP_OscErClock = 2U, /*!< COP clock sourced from OSCERCLK */
#endif /* FSL_FEATURE_COP_HAS_MORE_CLKSRC */
kCOP_BusClock = 3U, /*!< COP clock sourced from Bus clock */
} cop_clock_source_t;
/*! @brief Define the COP timeout cycles. */
typedef enum _cop_timeout_cycles
{
kCOP_2Power5CyclesOr2Power13Cycles = 1U, /*!< 2^5 or 2^13 clock cycles */
kCOP_2Power8CyclesOr2Power16Cycles = 2U, /*!< 2^8 or 2^16 clock cycles */
kCOP_2Power10CyclesOr2Power18Cycles = 3U, /*!< 2^10 or 2^18 clock cycles */
} cop_timeout_cycles_t;
#if defined(FSL_FEATURE_COP_HAS_LONGTIME_MODE) && FSL_FEATURE_COP_HAS_LONGTIME_MODE
/*! @breif Define the COP timeout mode. */
typedef enum _cop_timeout_mode
{
kCOP_ShortTimeoutMode = 0U, /*!< COP selects long timeout */
kCOP_LongTimeoutMode = 1U, /*!< COP selects short timeout */
} cop_timeout_mode_t;
#endif /* FSL_FEATURE_COP_HAS_LONGTIME_MODE */
/*! @brief Describes COP configuration structure. */
typedef struct _cop_config
{
bool enableWindowMode; /*!< COP run mode: window mode or normal mode */
#if defined(FSL_FEATURE_COP_HAS_LONGTIME_MODE) && FSL_FEATURE_COP_HAS_LONGTIME_MODE
cop_timeout_mode_t timeoutMode; /*!< COP timeout mode: long timeout or short timeout */
bool enableStop; /*!< Enable or disable COP in STOP mode */
bool enableDebug; /*!< Enable or disable COP in DEBUG mode */
#endif /* FSL_FEATURE_COP_HAS_LONGTIME_MODE */
cop_clock_source_t clockSource; /*!< Set COP clock source */
cop_timeout_cycles_t timeoutCycles; /*!< Set COP timeout value */
} cop_config_t;
/*******************************************************************************
* API
*******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif /* __cplusplus*/
/*!
* @name COP Functional Operation
* @{
*/
/*!
* @brief Initializes the COP configuration structure.
*
* This function initializes the COP configuration structure to default values. The default
* values are:
* @code
* copConfig->enableWindowMode = false;
* copConfig->timeoutMode = kCOP_LongTimeoutMode;
* copConfig->enableStop = false;
* copConfig->enableDebug = false;
* copConfig->clockSource = kCOP_LpoClock;
* copConfig->timeoutCycles = kCOP_2Power10CyclesOr2Power18Cycles;
* @endcode
*
* @param config Pointer to the COP configuration structure.
* @see cop_config_t
*/
void COP_GetDefaultConfig(cop_config_t *config);
/*!
* @brief Initializes the COP module.
*
* This function configures the COP. After it is called, the COP
* starts running according to the configuration.
* Because all COP control registers are write-once only, the COP_Init function
* and the COP_Disable function can be called only once. A second call has no effect.
*
* Example:
* @code
* cop_config_t config;
* COP_GetDefaultConfig(&config);
* config.timeoutCycles = kCOP_2Power8CyclesOr2Power16Cycles;
* COP_Init(sim_base,&config);
* @endcode
*
* @param base SIM peripheral base address.
* @param config The configuration of COP.
*/
void COP_Init(SIM_Type *base, const cop_config_t *config);
/*!
* @brief De-initializes the COP module.
* This dedicated function is not provided. Instead, the COP_Disable function can be used to disable the COP.
*/
/*!
* @brief Disables the COP module.
*
* This function disables the COP Watchdog.
* Note: The COP configuration register is a write-once after reset.
* To disable the COP Watchdog, call this function first.
*
* @param base SIM peripheral base address.
*/
static inline void COP_Disable(SIM_Type *base)
{
base->COPC &= ~SIM_COPC_COPT_MASK;
}
/*!
* @brief Refreshes the COP timer
*
* This function feeds the COP.
*
* @param base SIM peripheral base address.
*/
void COP_Refresh(SIM_Type *base);
/*@}*/
#if defined(__cplusplus)
}
#endif /* __cplusplus */
/*! @}*/
#endif /* _FSL_COP_H_ */

View File

@ -0,0 +1,214 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include "fsl_dac.h"
/*******************************************************************************
* Prototypes
******************************************************************************/
/*!
* @brief Get instance number for DAC module.
*
* @param base DAC peripheral base address
*/
static uint32_t DAC_GetInstance(DAC_Type *base);
/*******************************************************************************
* Variables
******************************************************************************/
/*! @brief Pointers to DAC bases for each instance. */
static DAC_Type *const s_dacBases[] = DAC_BASE_PTRS;
/*! @brief Pointers to DAC clocks for each instance. */
static const clock_ip_name_t s_dacClocks[] = DAC_CLOCKS;
/*******************************************************************************
* Codes
******************************************************************************/
static uint32_t DAC_GetInstance(DAC_Type *base)
{
uint32_t instance;
/* Find the instance index from base address mappings. */
for (instance = 0; instance < FSL_FEATURE_SOC_DAC_COUNT; instance++)
{
if (s_dacBases[instance] == base)
{
break;
}
}
assert(instance < FSL_FEATURE_SOC_DAC_COUNT);
return instance;
}
void DAC_Init(DAC_Type *base, const dac_config_t *config)
{
assert(NULL != config);
uint8_t tmp8;
/* Enable the clock. */
CLOCK_EnableClock(s_dacClocks[DAC_GetInstance(base)]);
/* Configure. */
/* DACx_C0. */
tmp8 = base->C0 & ~(DAC_C0_DACRFS_MASK | DAC_C0_LPEN_MASK);
if (kDAC_ReferenceVoltageSourceVref2 == config->referenceVoltageSource)
{
tmp8 |= DAC_C0_DACRFS_MASK;
}
if (config->enableLowPowerMode)
{
tmp8 |= DAC_C0_LPEN_MASK;
}
base->C0 = tmp8;
/* DAC_Enable(base, true); */
/* Tip: The DAC output can be enabled till then after user sets their own available data in application. */
}
void DAC_Deinit(DAC_Type *base)
{
DAC_Enable(base, false);
/* Disable the clock. */
CLOCK_DisableClock(s_dacClocks[DAC_GetInstance(base)]);
}
void DAC_GetDefaultConfig(dac_config_t *config)
{
assert(NULL != config);
config->referenceVoltageSource = kDAC_ReferenceVoltageSourceVref2;
config->enableLowPowerMode = false;
}
void DAC_SetBufferConfig(DAC_Type *base, const dac_buffer_config_t *config)
{
assert(NULL != config);
uint8_t tmp8;
/* DACx_C0. */
tmp8 = base->C0 & ~(DAC_C0_DACTRGSEL_MASK);
if (kDAC_BufferTriggerBySoftwareMode == config->triggerMode)
{
tmp8 |= DAC_C0_DACTRGSEL_MASK;
}
base->C0 = tmp8;
/* DACx_C1. */
tmp8 = base->C1 &
~(
#if defined(FSL_FEATURE_DAC_HAS_WATERMARK_SELECTION) && FSL_FEATURE_DAC_HAS_WATERMARK_SELECTION
DAC_C1_DACBFWM_MASK |
#endif /* FSL_FEATURE_DAC_HAS_WATERMARK_SELECTION */
DAC_C1_DACBFMD_MASK);
#if defined(FSL_FEATURE_DAC_HAS_WATERMARK_SELECTION) && FSL_FEATURE_DAC_HAS_WATERMARK_SELECTION
tmp8 |= DAC_C1_DACBFWM(config->watermark);
#endif /* FSL_FEATURE_DAC_HAS_WATERMARK_SELECTION */
tmp8 |= DAC_C1_DACBFMD(config->workMode);
base->C1 = tmp8;
/* DACx_C2. */
tmp8 = base->C2 & ~DAC_C2_DACBFUP_MASK;
tmp8 |= DAC_C2_DACBFUP(config->upperLimit);
base->C2 = tmp8;
}
void DAC_GetDefaultBufferConfig(dac_buffer_config_t *config)
{
assert(NULL != config);
config->triggerMode = kDAC_BufferTriggerBySoftwareMode;
#if defined(FSL_FEATURE_DAC_HAS_WATERMARK_SELECTION) && FSL_FEATURE_DAC_HAS_WATERMARK_SELECTION
config->watermark = kDAC_BufferWatermark1Word;
#endif /* FSL_FEATURE_DAC_HAS_WATERMARK_SELECTION */
config->workMode = kDAC_BufferWorkAsNormalMode;
config->upperLimit = DAC_DATL_COUNT - 1U;
}
void DAC_SetBufferValue(DAC_Type *base, uint8_t index, uint16_t value)
{
assert(index < DAC_DATL_COUNT);
base->DAT[index].DATL = (uint8_t)(0xFFU & value); /* Low 8-bit. */
base->DAT[index].DATH = (uint8_t)((0xF00U & value) >> 8); /* High 4-bit. */
}
void DAC_SetBufferReadPointer(DAC_Type *base, uint8_t index)
{
assert(index < DAC_DATL_COUNT);
uint8_t tmp8 = base->C2 & ~DAC_C2_DACBFRP_MASK;
tmp8 |= DAC_C2_DACBFRP(index);
base->C2 = tmp8;
}
void DAC_EnableBufferInterrupts(DAC_Type *base, uint32_t mask)
{
mask &= (
#if defined(FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION) && FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION
DAC_C0_DACBWIEN_MASK |
#endif /* FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION */
DAC_C0_DACBTIEN_MASK | DAC_C0_DACBBIEN_MASK);
base->C0 |= ((uint8_t)mask); /* Write 1 to enable. */
}
void DAC_DisableBufferInterrupts(DAC_Type *base, uint32_t mask)
{
mask &= (
#if defined(FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION) && FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION
DAC_C0_DACBWIEN_MASK |
#endif /* FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION */
DAC_C0_DACBTIEN_MASK | DAC_C0_DACBBIEN_MASK);
base->C0 &= (uint8_t)(~((uint8_t)mask)); /* Write 0 to disable. */
}
uint32_t DAC_GetBufferStatusFlags(DAC_Type *base)
{
return (uint32_t)(base->SR & (
#if defined(FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION) && FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION
DAC_SR_DACBFWMF_MASK |
#endif /* FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION */
DAC_SR_DACBFRPTF_MASK | DAC_SR_DACBFRPBF_MASK));
}
void DAC_ClearBufferStatusFlags(DAC_Type *base, uint32_t mask)
{
mask &= (
#if defined(FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION) && FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION
DAC_SR_DACBFWMF_MASK |
#endif /* FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION */
DAC_SR_DACBFRPTF_MASK | DAC_SR_DACBFRPBF_MASK);
base->SR &= (uint8_t)(~((uint8_t)mask)); /* Write 0 to clear flags. */
}

View File

@ -0,0 +1,378 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _FSL_DAC_H_
#define _FSL_DAC_H_
#include "fsl_common.h"
/*!
* @addtogroup dac
* @{
*/
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @name Driver version */
/*@{*/
/*! @brief DAC driver version 2.0.1. */
#define FSL_DAC_DRIVER_VERSION (MAKE_VERSION(2, 0, 1))
/*@}*/
/*!
* @brief DAC buffer flags.
*/
enum _dac_buffer_status_flags
{
#if defined(FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION) && FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION
kDAC_BufferWatermarkFlag = DAC_SR_DACBFWMF_MASK, /*!< DAC Buffer Watermark Flag. */
#endif /* FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION */
kDAC_BufferReadPointerTopPositionFlag = DAC_SR_DACBFRPTF_MASK, /*!< DAC Buffer Read Pointer Top Position Flag. */
kDAC_BufferReadPointerBottomPositionFlag = DAC_SR_DACBFRPBF_MASK, /*!< DAC Buffer Read Pointer Bottom Position
Flag. */
};
/*!
* @brief DAC buffer interrupts.
*/
enum _dac_buffer_interrupt_enable
{
#if defined(FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION) && FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION
kDAC_BufferWatermarkInterruptEnable = DAC_C0_DACBWIEN_MASK, /*!< DAC Buffer Watermark Interrupt Enable. */
#endif /* FSL_FEATURE_DAC_HAS_WATERMARK_DETECTION */
kDAC_BufferReadPointerTopInterruptEnable = DAC_C0_DACBTIEN_MASK, /*!< DAC Buffer Read Pointer Top Flag Interrupt
Enable. */
kDAC_BufferReadPointerBottomInterruptEnable = DAC_C0_DACBBIEN_MASK, /*!< DAC Buffer Read Pointer Bottom Flag
Interrupt Enable */
};
/*!
* @brief DAC reference voltage source.
*/
typedef enum _dac_reference_voltage_source
{
kDAC_ReferenceVoltageSourceVref1 = 0U, /*!< The DAC selects DACREF_1 as the reference voltage. */
kDAC_ReferenceVoltageSourceVref2 = 1U, /*!< The DAC selects DACREF_2 as the reference voltage. */
} dac_reference_voltage_source_t;
/*!
* @brief DAC buffer trigger mode.
*/
typedef enum _dac_buffer_trigger_mode
{
kDAC_BufferTriggerByHardwareMode = 0U, /*!< The DAC hardware trigger is selected. */
kDAC_BufferTriggerBySoftwareMode = 1U, /*!< The DAC software trigger is selected. */
} dac_buffer_trigger_mode_t;
#if defined(FSL_FEATURE_DAC_HAS_WATERMARK_SELECTION) && FSL_FEATURE_DAC_HAS_WATERMARK_SELECTION
/*!
* @brief DAC buffer watermark.
*/
typedef enum _dac_buffer_watermark
{
#if defined(FSL_FEATURE_DAC_HAS_WATERMARK_1_WORD) && FSL_FEATURE_DAC_HAS_WATERMARK_1_WORD
kDAC_BufferWatermark1Word = 0U, /*!< 1 word away from the upper limit. */
#endif /* FSL_FEATURE_DAC_HAS_WATERMARK_1_WORD */
#if defined(FSL_FEATURE_DAC_HAS_WATERMARK_2_WORDS) && FSL_FEATURE_DAC_HAS_WATERMARK_2_WORDS
kDAC_BufferWatermark2Word = 1U, /*!< 2 words away from the upper limit. */
#endif /* FSL_FEATURE_DAC_HAS_WATERMARK_2_WORDS */
#if defined(FSL_FEATURE_DAC_HAS_WATERMARK_3_WORDS) && FSL_FEATURE_DAC_HAS_WATERMARK_3_WORDS
kDAC_BufferWatermark3Word = 2U, /*!< 3 words away from the upper limit. */
#endif /* FSL_FEATURE_DAC_HAS_WATERMARK_3_WORDS */
#if defined(FSL_FEATURE_DAC_HAS_WATERMARK_4_WORDS) && FSL_FEATURE_DAC_HAS_WATERMARK_4_WORDS
kDAC_BufferWatermark4Word = 3U, /*!< 4 words away from the upper limit. */
#endif /* FSL_FEATURE_DAC_HAS_WATERMARK_4_WORDS */
} dac_buffer_watermark_t;
#endif /* FSL_FEATURE_DAC_HAS_WATERMARK_SELECTION */
/*!
* @brief DAC buffer work mode.
*/
typedef enum _dac_buffer_work_mode
{
kDAC_BufferWorkAsNormalMode = 0U, /*!< Normal mode. */
#if defined(FSL_FEATURE_DAC_HAS_BUFFER_SWING_MODE) && FSL_FEATURE_DAC_HAS_BUFFER_SWING_MODE
kDAC_BufferWorkAsSwingMode, /*!< Swing mode. */
#endif /* FSL_FEATURE_DAC_HAS_BUFFER_SWING_MODE */
kDAC_BufferWorkAsOneTimeScanMode, /*!< One-Time Scan mode. */
#if defined(FSL_FEATURE_DAC_HAS_BUFFER_FIFO_MODE) && FSL_FEATURE_DAC_HAS_BUFFER_FIFO_MODE
kDAC_BufferWorkAsFIFOMode, /*!< FIFO mode. */
#endif /* FSL_FEATURE_DAC_HAS_BUFFER_FIFO_MODE */
} dac_buffer_work_mode_t;
/*!
* @brief DAC module configuration.
*/
typedef struct _dac_config
{
dac_reference_voltage_source_t referenceVoltageSource; /*!< Select the DAC reference voltage source. */
bool enableLowPowerMode; /*!< Enable the low-power mode. */
} dac_config_t;
/*!
* @brief DAC buffer configuration.
*/
typedef struct _dac_buffer_config
{
dac_buffer_trigger_mode_t triggerMode; /*!< Select the buffer's trigger mode. */
#if defined(FSL_FEATURE_DAC_HAS_WATERMARK_SELECTION) && FSL_FEATURE_DAC_HAS_WATERMARK_SELECTION
dac_buffer_watermark_t watermark; /*!< Select the buffer's watermark. */
#endif /* FSL_FEATURE_DAC_HAS_WATERMARK_SELECTION */
dac_buffer_work_mode_t workMode; /*!< Select the buffer's work mode. */
uint8_t upperLimit; /*!< Set the upper limit for buffer index.
Normally, 0-15 is available for buffer with 16 item. */
} dac_buffer_config_t;
/*******************************************************************************
* API
******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif
/*!
* @name Initialization
* @{
*/
/*!
* @brief Initializes the DAC module.
*
* This function initializes the DAC module, including:
* - Enabling the clock for DAC module.
* - Configuring the DAC converter with a user configuration.
* - Enabling the DAC module.
*
* @param base DAC peripheral base address.
* @param config Pointer to the configuration structure. See "dac_config_t".
*/
void DAC_Init(DAC_Type *base, const dac_config_t *config);
/*!
* @brief De-initializes the DAC module.
*
* This function de-initializes the DAC module, including:
* - Disabling the DAC module.
* - Disabling the clock for the DAC module.
*
* @param base DAC peripheral base address.
*/
void DAC_Deinit(DAC_Type *base);
/*!
* @brief Initializes the DAC user configuration structure.
*
* This function initializes the user configuration structure to a default value. The default values are:
* @code
* config->referenceVoltageSource = kDAC_ReferenceVoltageSourceVref2;
* config->enableLowPowerMode = false;
* @endcode
* @param config Pointer to the configuration structure. See "dac_config_t".
*/
void DAC_GetDefaultConfig(dac_config_t *config);
/*!
* @brief Enables the DAC module.
*
* @param base DAC peripheral base address.
* @param enable Enables/disables the feature.
*/
static inline void DAC_Enable(DAC_Type *base, bool enable)
{
if (enable)
{
base->C0 |= DAC_C0_DACEN_MASK;
}
else
{
base->C0 &= ~DAC_C0_DACEN_MASK;
}
}
/* @} */
/*!
* @name Buffer
* @{
*/
/*!
* @brief Enables the DAC buffer.
*
* @param base DAC peripheral base address.
* @param enable Enables/disables the feature.
*/
static inline void DAC_EnableBuffer(DAC_Type *base, bool enable)
{
if (enable)
{
base->C1 |= DAC_C1_DACBFEN_MASK;
}
else
{
base->C1 &= ~DAC_C1_DACBFEN_MASK;
}
}
/*!
* @brief Configures the CMP buffer.
*
* @param base DAC peripheral base address.
* @param config Pointer to the configuration structure. See "dac_buffer_config_t".
*/
void DAC_SetBufferConfig(DAC_Type *base, const dac_buffer_config_t *config);
/*!
* @brief Initializes the DAC buffer configuration structure.
*
* This function initializes the DAC buffer configuration structure to a default value. The default values are:
* @code
* config->triggerMode = kDAC_BufferTriggerBySoftwareMode;
* config->watermark = kDAC_BufferWatermark1Word;
* config->workMode = kDAC_BufferWorkAsNormalMode;
* config->upperLimit = DAC_DATL_COUNT - 1U;
* @endcode
* @param config Pointer to the configuration structure. See "dac_buffer_config_t".
*/
void DAC_GetDefaultBufferConfig(dac_buffer_config_t *config);
/*!
* @brief Enables the DMA for DAC buffer.
*
* @param base DAC peripheral base address.
* @param enable Enables/disables the feature.
*/
static inline void DAC_EnableBufferDMA(DAC_Type *base, bool enable)
{
if (enable)
{
base->C1 |= DAC_C1_DMAEN_MASK;
}
else
{
base->C1 &= ~DAC_C1_DMAEN_MASK;
}
}
/*!
* @brief Sets the value for items in the buffer.
*
* @param base DAC peripheral base address.
* @param index Setting index for items in the buffer. The available index should not exceed the size of the DAC buffer.
* @param value Setting value for items in the buffer. 12-bits are available.
*/
void DAC_SetBufferValue(DAC_Type *base, uint8_t index, uint16_t value);
/*!
* @brief Triggers the buffer by software and updates the read pointer of the DAC buffer.
*
* This function triggers the function by software. The read pointer of the DAC buffer is updated with one step
* after this function is called. Changing the read pointer depends on the buffer's work mode.
*
* @param base DAC peripheral base address.
*/
static inline void DAC_DoSoftwareTriggerBuffer(DAC_Type *base)
{
base->C0 |= DAC_C0_DACSWTRG_MASK;
}
/*!
* @brief Gets the current read pointer of the DAC buffer.
*
* This function gets the current read pointer of the DAC buffer.
* The current output value depends on the item indexed by the read pointer. It is updated
* by software trigger or hardware trigger.
*
* @param base DAC peripheral base address.
*
* @return Current read pointer of DAC buffer.
*/
static inline uint8_t DAC_GetBufferReadPointer(DAC_Type *base)
{
return ((base->C2 & DAC_C2_DACBFRP_MASK) >> DAC_C2_DACBFRP_SHIFT);
}
/*!
* @brief Sets the current read pointer of the DAC buffer.
*
* This function sets the current read pointer of the DAC buffer.
* The current output value depends on the item indexed by the read pointer. It is updated by
* software trigger or hardware trigger. After the read pointer changes, the DAC output value also changes.
*
* @param base DAC peripheral base address.
* @param index Setting index value for the pointer.
*/
void DAC_SetBufferReadPointer(DAC_Type *base, uint8_t index);
/*!
* @brief Enables interrupts for the DAC buffer.
*
* @param base DAC peripheral base address.
* @param mask Mask value for interrupts. See "_dac_buffer_interrupt_enable".
*/
void DAC_EnableBufferInterrupts(DAC_Type *base, uint32_t mask);
/*!
* @brief Disables interrupts for the DAC buffer.
*
* @param base DAC peripheral base address.
* @param mask Mask value for interrupts. See "_dac_buffer_interrupt_enable".
*/
void DAC_DisableBufferInterrupts(DAC_Type *base, uint32_t mask);
/*!
* @brief Gets the flags of events for the DAC buffer.
*
* @param base DAC peripheral base address.
*
* @return Mask value for the asserted flags. See "_dac_buffer_status_flags".
*/
uint32_t DAC_GetBufferStatusFlags(DAC_Type *base);
/*!
* @brief Clears the flags of events for the DAC buffer.
*
* @param base DAC peripheral base address.
* @param mask Mask value for flags. See "_dac_buffer_status_flags_t".
*/
void DAC_ClearBufferStatusFlags(DAC_Type *base, uint32_t mask);
/* @} */
#if defined(__cplusplus)
}
#endif
/*!
* @}
*/
#endif /* _FSL_DAC_H_ */

View File

@ -0,0 +1,373 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include "fsl_dcdc.h"
/*******************************************************************************
* Prototypes
******************************************************************************/
/*!
* @brief Get instance number for DCDC module.
*
* @param base DCDC peripheral base address
*/
static uint32_t DCDC_GetInstance(DCDC_Type *base);
/*******************************************************************************
* Variables
******************************************************************************/
/*! @brief Pointers to DCDC bases for each instance. */
const DCDC_Type *s_dcdcBases[] = DCDC_BASE_PTRS;
/*! @brief Pointers to DCDC clocks for each instance. */
static const clock_ip_name_t s_dcdcClocks[] = DCDC_CLOCKS;
/*******************************************************************************
* Code
******************************************************************************/
static uint32_t DCDC_GetInstance(DCDC_Type *base)
{
uint32_t instance;
/* Find the instance index from base address mappings. */
for (instance = 0; instance < FSL_FEATURE_SOC_DCDC_COUNT; instance++)
{
if (s_dcdcBases[instance] == base)
{
break;
}
}
assert(instance < FSL_FEATURE_SOC_DCDC_COUNT);
return instance;
}
void DCDC_Init(DCDC_Type *base)
{
/* Enable the clock. */
CLOCK_EnableClock(s_dcdcClocks[DCDC_GetInstance(base)]);
}
void DCDC_Deinit(DCDC_Type *base)
{
/* Disable the clock. */
CLOCK_DisableClock(s_dcdcClocks[DCDC_GetInstance(base)]);
}
uint32_t DCDC_GetStatusFlags(DCDC_Type *base)
{
uint32_t tmp32 = 0U;
/* kDCDC_LockedOKStatus. */
if (0U != (DCDC_REG0_DCDC_STS_DC_OK_MASK & base->REG0))
{
tmp32 |= kDCDC_LockedOKStatus;
}
/* kDCDC_PSwitchStatus. */
if (0U != (DCDC_REG0_PSWITCH_STATUS_MASK & base->REG0))
{
tmp32 |= kDCDC_PSwitchStatus;
}
/* kDCDC_PSwitchInterruptStatus. */
if (0U != (DCDC_REG6_PSWITCH_INT_STS_MASK & base->REG6))
{
tmp32 |= kDCDC_PSwitchInterruptStatus;
}
return tmp32;
}
void DCDC_ClearStatusFlags(DCDC_Type *base, uint32_t mask) /* Clear flags indicated by mask. */
{
if (0U != (kDCDC_PSwitchInterruptStatus & mask))
{
/* Write 1 to clear interrupt. Set to 0 after clear. */
base->REG6 |= DCDC_REG6_PSWITCH_INT_CLEAR_MASK;
base->REG6 &= ~DCDC_REG6_PSWITCH_INT_CLEAR_MASK;
}
}
void DCDC_SetPSwitchInterruptConfig(DCDC_Type *base, uint32_t mask)
{
assert(0U == (mask & ~(DCDC_REG6_PSWITCH_INT_RISE_EN_MASK | DCDC_REG6_PSWITCH_INT_FALL_EN_MASK)));
uint32_t tmp32 = base->REG6 & ~(DCDC_REG6_PSWITCH_INT_RISE_EN_MASK | DCDC_REG6_PSWITCH_INT_FALL_EN_MASK);
tmp32 |= mask;
base->REG6 = tmp32;
}
void DCDC_GetDefaultLowPowerConfig(dcdc_low_power_config_t *config)
{
assert(NULL != config);
config->workModeInVLPRW = kDCDC_WorkInPulsedMode;
config->workModeInVLPS = kDCDC_WorkInPulsedMode;
config->enableHysteresisVoltageSense = true;
config->enableAdjustHystereticValueSense = false;
config->enableHystersisComparator = true;
config->enableAdjustHystereticValueComparator = false;
config->hystereticUpperThresholdValue = kDCDC_HystereticThresholdOffset75mV;
config->hystereticLowerThresholdValue = kDCDC_HystereticThresholdOffset0mV;
config->enableDiffComparators = false;
}
void DCDC_SetLowPowerConfig(DCDC_Type *base, const dcdc_low_power_config_t *config)
{
uint32_t tmp32;
tmp32 =
base->REG0 &
~(DCDC_REG0_VLPR_VLPW_CONFIG_DCDC_HP_MASK | DCDC_REG0_VLPS_CONFIG_DCDC_HP_MASK |
DCDC_REG0_OFFSET_RSNS_LP_DISABLE_MASK | DCDC_REG0_OFFSET_RSNS_LP_ADJ_MASK |
DCDC_REG0_HYST_LP_CMP_DISABLE_MASK | DCDC_REG0_HYST_LP_COMP_ADJ_MASK | DCDC_REG0_DCDC_LP_STATE_HYS_H_MASK |
DCDC_REG0_DCDC_LP_STATE_HYS_L_MASK | DCDC_REG0_DCDC_LP_DF_CMP_ENABLE_MASK);
if (kDCDC_WorkInContinuousMode == config->workModeInVLPRW)
{
tmp32 |= DCDC_REG0_VLPR_VLPW_CONFIG_DCDC_HP_MASK;
}
if (kDCDC_WorkInContinuousMode == config->workModeInVLPS)
{
tmp32 |= DCDC_REG0_VLPS_CONFIG_DCDC_HP_MASK;
}
if (!config->enableHysteresisVoltageSense)
{
tmp32 |= DCDC_REG0_OFFSET_RSNS_LP_DISABLE_MASK;
}
if (config->enableAdjustHystereticValueSense)
{
tmp32 |= DCDC_REG0_OFFSET_RSNS_LP_ADJ_MASK;
}
if (!config->enableHystersisComparator)
{
tmp32 |= DCDC_REG0_HYST_LP_CMP_DISABLE_MASK;
}
if (config->enableAdjustHystereticValueComparator)
{
tmp32 |= DCDC_REG0_HYST_LP_COMP_ADJ_MASK;
}
tmp32 |= DCDC_REG0_DCDC_LP_STATE_HYS_H(config->hystereticUpperThresholdValue) |
DCDC_REG0_DCDC_LP_STATE_HYS_L(config->hystereticLowerThresholdValue);
/* true - DCDC compare the lower supply(relative to target value) with DCDC_LP_STATE_HYS_L. When it is lower than
* DCDC_LP_STATE_HYS_L, re-charge output.
* false - DCDC compare the common mode sense of supply(relative to target value) with DCDC_LP_STATE_HYS_L. When it
* is lower than DCDC_LP_STATE_HYS_L, re-charge output.
*/
if (config->enableDiffComparators)
{
tmp32 |= DCDC_REG0_DCDC_LP_DF_CMP_ENABLE_MASK;
}
base->REG0 = tmp32;
}
void DCDC_GetDefaultLoopControlConfig(dcdc_loop_control_config_t *config)
{
assert(NULL != config);
config->enableDiffHysteresis = false;
config->enableCommonHysteresis = false;
config->enableDiffHysteresisThresh = false;
config->enableCommonHysteresisThresh = false;
config->enableInvertHysteresisSign = false;
}
void DCDC_SetLoopControlConfig(DCDC_Type *base, const dcdc_loop_control_config_t *config)
{
uint32_t tmp32;
/* DCDC_REG1. */
tmp32 = base->REG1 &
~(DCDC_REG1_DCDC_LOOPCTRL_EN_DF_HYST_MASK | DCDC_REG1_DCDC_LOOPCTRL_EN_CM_HYST_MASK |
DCDC_REG1_DCDC_LOOPCTRL_DF_HST_THRESH_MASK | DCDC_REG1_DCDC_LOOPCTRL_CM_HST_THRESH_MASK);
if (config->enableDiffHysteresis)
{
tmp32 |= DCDC_REG1_DCDC_LOOPCTRL_EN_DF_HYST_MASK;
}
if (config->enableCommonHysteresis)
{
tmp32 |= DCDC_REG1_DCDC_LOOPCTRL_EN_CM_HYST_MASK;
}
if (config->enableDiffHysteresisThresh)
{
tmp32 |= DCDC_REG1_DCDC_LOOPCTRL_DF_HST_THRESH_MASK;
}
if (config->enableCommonHysteresisThresh)
{
tmp32 |= DCDC_REG1_DCDC_LOOPCTRL_CM_HST_THRESH_MASK;
}
base->REG1 = tmp32;
/* DCDC_REG2. */
if (config->enableInvertHysteresisSign)
{
base->REG2 |= DCDC_REG2_DCDC_LOOPCTRL_HYST_SIGN_MASK;
}
else
{
base->REG2 &= ~DCDC_REG2_DCDC_LOOPCTRL_HYST_SIGN_MASK;
}
}
void DCDC_SetClockSource(DCDC_Type *base, dcdc_clock_source_t clockSource)
{
uint32_t tmp32;
tmp32 =
base->REG0 &
~(DCDC_REG0_DCDC_PWD_OSC_INT_MASK | DCDC_REG0_DCDC_SEL_CLK_MASK | DCDC_REG0_DCDC_DISABLE_AUTO_CLK_SWITCH_MASK);
switch (clockSource)
{
case kDCDC_ClockInternalOsc:
tmp32 |= DCDC_REG0_DCDC_DISABLE_AUTO_CLK_SWITCH_MASK;
break;
case kDCDC_ClockExternalOsc:
/* Choose the external clock and disable the internal clock. */
tmp32 |= DCDC_REG0_DCDC_DISABLE_AUTO_CLK_SWITCH_MASK | DCDC_REG0_DCDC_SEL_CLK_MASK |
DCDC_REG0_DCDC_PWD_OSC_INT_MASK;
break;
default:
break;
}
base->REG0 = tmp32;
}
void DCDC_AdjustTargetVoltage(DCDC_Type *base, uint32_t vdd1p45Boost, uint32_t vdd1p45Buck, uint32_t vdd1p8)
{
uint32_t tmp32;
/* Unlock the limitation of setting target voltage. */
base->REG3 &= ~(DCDC_REG3_DCDC_VDD1P8CTRL_DISABLE_STEP_MASK | DCDC_REG3_DCDC_VDD1P5CTRL_DISABLE_STEP_MASK);
/* Change the target voltage value. */
tmp32 = base->REG3 &
~(DCDC_REG3_DCDC_VDD1P5CTRL_TRG_BOOST_MASK | DCDC_REG3_DCDC_VDD1P5CTRL_TRG_BUCK_MASK |
DCDC_REG3_DCDC_VDD1P8CTRL_TRG_MASK);
tmp32 |= DCDC_REG3_DCDC_VDD1P5CTRL_TRG_BOOST(vdd1p45Boost) | DCDC_REG3_DCDC_VDD1P5CTRL_TRG_BUCK(vdd1p45Buck) |
DCDC_REG3_DCDC_VDD1P8CTRL_TRG(vdd1p8);
base->REG3 = tmp32;
/* DCDC_STS_DC_OK bit will be de-asserted after target register changes. After output voltage settling to new
* target value, DCDC_STS_DC_OK will be asserted. */
while (0U != (DCDC_REG0_DCDC_STS_DC_OK_MASK & base->REG0))
{
}
}
void DCDC_SetBatteryMonitorValue(DCDC_Type *base, uint32_t battValue)
{
uint32_t tmp32;
/* Disable the monitor before setting the new value */
base->REG2 &= ~DCDC_REG2_DCDC_BATTMONITOR_EN_BATADJ_MASK;
if (0U != battValue)
{
tmp32 = base->REG2 & ~DCDC_REG2_DCDC_BATTMONITOR_BATT_VAL_MASK;
/* Enable the monitor with setting value. */
tmp32 |= (DCDC_REG2_DCDC_BATTMONITOR_EN_BATADJ_MASK | DCDC_REG2_DCDC_BATTMONITOR_BATT_VAL(battValue));
base->REG2 = tmp32;
}
}
void DCDC_SetMinPowerConfig(DCDC_Type *base, const dcdc_min_power_config_t *config)
{
uint32_t tmp32 = base->REG3 &
~(DCDC_REG3_DCDC_MINPWR_HALF_FETS_MASK | DCDC_REG3_DCDC_MINPWR_DOUBLE_FETS_MASK |
DCDC_REG3_DCDC_MINPWR_DC_HALFCLK_MASK | DCDC_REG3_DCDC_MINPWR_HALF_FETS_PULSED_MASK |
DCDC_REG3_DCDC_MINPWR_DOUBLE_FETS_PULSED_MASK | DCDC_REG3_DCDC_MINPWR_DC_HALFCLK_PULSED_MASK);
/* For Continuous mode. */
if (config->enableUseHalfFetForContinuous)
{
tmp32 |= DCDC_REG3_DCDC_MINPWR_HALF_FETS_MASK;
}
if (config->enableUseDoubleFetForContinuous)
{
tmp32 |= DCDC_REG3_DCDC_MINPWR_DOUBLE_FETS_MASK;
}
if (config->enableUseHalfFreqForContinuous)
{
tmp32 |= DCDC_REG3_DCDC_MINPWR_DC_HALFCLK_MASK;
}
/* For Pulsed mode. */
if (config->enableUseHalfFetForPulsed)
{
tmp32 |= DCDC_REG3_DCDC_MINPWR_HALF_FETS_PULSED_MASK;
}
if (config->enableUseDoubleFetForPulsed)
{
tmp32 |= DCDC_REG3_DCDC_MINPWR_DOUBLE_FETS_PULSED_MASK;
}
if (config->enableUseHalfFreqForPulsed)
{
tmp32 |= DCDC_REG3_DCDC_MINPWR_DC_HALFCLK_PULSED_MASK;
}
base->REG3 = tmp32;
}
void DCDC_GetDefaultMinPowerDefault(dcdc_min_power_config_t *config)
{
assert(NULL != config);
/* For Continuous mode. */
config->enableUseHalfFetForContinuous = false;
config->enableUseDoubleFetForContinuous = false;
config->enableUseHalfFreqForContinuous = false;
/* For Pulsed mode. */
config->enableUseHalfFetForPulsed = false;
config->enableUseDoubleFetForPulsed = false;
config->enableUseHalfFreqForPulsed = false;
}
void DCDC_SetPulsedIntegratorConfig(DCDC_Type *base, const dcdc_pulsed_integrator_config_t *config)
{
if (config->enableUseUserIntegratorValue) /* Enable to use the user integrator value. */
{
base->REG7 = (base->REG7 & ~DCDC_REG7_INTEGRATOR_VALUE_MASK) | DCDC_REG7_INTEGRATOR_VALUE_SEL_MASK |
DCDC_REG7_INTEGRATOR_VALUE(config->userIntegratorValue);
if (config->enablePulseRunSpeedup)
{
base->REG7 |= DCDC_REG7_PULSE_RUN_SPEEDUP_MASK;
}
}
else
{
base->REG7 = 0U;
}
}
void DCDC_GetDefaultPulsedIntegratorConfig(dcdc_pulsed_integrator_config_t *config)
{
assert(NULL != config);
config->enableUseUserIntegratorValue = false;
config->userIntegratorValue = 0U;
config->enablePulseRunSpeedup = false;
}

View File

@ -0,0 +1,570 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _FSL_DCDC_H_
#define _FSL_DCDC_H_
#include "fsl_common.h"
/*!
* @addtogroup dcdc
* @{
*/
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @brief DCDC driver version. */
#define FSL_DCDC_DRIVER_VERSION (MAKE_VERSION(2, 0, 0)) /*!< Version 2.0.0. */
/*!
* @brief Status flags.
*/
enum _dcdc_status_flags_t
{
kDCDC_LockedOKStatus = (1U << 0), /*!< Status to indicate DCDC lock. Read only bit. */
kDCDC_PSwitchStatus = (1U << 1), /*!< Status to indicate PSWITCH signal. Read only bit. */
kDCDC_PSwitchInterruptStatus = (1U << 2), /*!< PSWITCH edge detection interrupt status. */
};
/*!
* @brief Interrupts.
*/
enum _dcdc_interrupt_enable_t
{
kDCDC_PSwitchEdgeDetectInterruptEnable = DCDC_REG6_PSWITCH_INT_MUTE_MASK, /*!< Enable the edge detect interrupt. */
};
/*!
* @brief Events for PSWITCH signal(pin).
*/
enum _dcdc_pswitch_detect_event_t
{
kDCDC_PSwitchFallingEdgeDetectEnable = DCDC_REG6_PSWITCH_INT_FALL_EN_MASK, /*!< Enable falling edge detect. */
kDCDC_PSwitchRisingEdgeDetectEnable = DCDC_REG6_PSWITCH_INT_RISE_EN_MASK, /*!< Enable rising edge detect. */
};
/*!
* @brief DCDC work mode in SoC's low power condition.
*/
typedef enum _dcdc_work_mode
{
kDCDC_WorkInContinuousMode = 0U, /*!< DCDC works in continuous mode when SOC is in low power mode. */
kDCDC_WorkInPulsedMode = 1U, /*!< DCDC works in pulsed mode when SOC is in low power mode. */
} dcdc_work_mode_t;
/*!
* @brief Hysteretic upper/lower threshold value in low power mode.
*/
typedef enum _dcdc_hysteretic_threshold_offset_value
{
kDCDC_HystereticThresholdOffset0mV = 0U, /*!< Target voltage value +/- 0mV. */
kDCDC_HystereticThresholdOffset25mV = 1U, /*!< Target voltage value +/- 25mV. */
kDCDC_HystereticThresholdOffset50mV = 2U, /*!< Target voltage value +/- 50mV. */
kDCDC_HystereticThresholdOffset75mV = 3U, /*!< Target voltage value +/- 75mV. */
} dcdc_hysteretic_threshold_offset_value_t;
/*!
* @brief VBAT voltage divider.
*/
typedef enum _dcdc_vbat_divider
{
kDCDC_VBatVoltageDividerOff = 0U, /*!< The sensor signal is disabled. */
kDCDC_VBatVoltageDivider1 = 1U, /*!< VBat. */
kDCDC_VBatVoltageDivider2 = 2U, /*!< VBat/2. */
kDCDC_VBatVoltageDivider4 = 3U, /*!< VBat/4 */
} dcdc_vbat_divider_t;
/*!
* @brief Oscillator clock option.
*/
typedef enum _dcdc_clock_source_t
{
kDCDC_ClockAutoSwitch = 0U, /*!< Automatic clock switch from internal oscillator to external clock. */
kDCDC_ClockInternalOsc, /* Use internal oscillator. */
kDCDC_ClockExternalOsc, /* Use external 32M crystal oscillator. */
} dcdc_clock_source_t;
/*!
* @brief Configuration for the low power.
*/
typedef struct _dcdc_low_power_config
{
dcdc_work_mode_t workModeInVLPRW; /*!< Select the behavior of DCDC in device VLPR and VLPW low power modes. */
dcdc_work_mode_t workModeInVLPS; /*!< Select the behavior of DCDC in device VLPS low power modes. */
bool enableHysteresisVoltageSense; /*!< Enable hysteresis in low power voltage sense. */
bool enableAdjustHystereticValueSense; /*!< Adjust hysteretic value in low power voltage sense. */
bool enableHystersisComparator; /*!< Enable hysteresis in low power comparator. */
bool enableAdjustHystereticValueComparator; /*!< Adjust hysteretic value in low power comparator. */
dcdc_hysteretic_threshold_offset_value_t hystereticUpperThresholdValue; /*!< Configure the hysteretic upper
threshold value in low power mode. */
dcdc_hysteretic_threshold_offset_value_t hystereticLowerThresholdValue; /*!< Configure the hysteretic lower
threshold value in low power mode. */
bool enableDiffComparators; /*!< Enable low power differential comparators, to sense lower supply in pulsed mode. */
} dcdc_low_power_config_t;
/*!
* @brief Configuration for the loop control.
*/
typedef struct _dcdc_loop_control_config
{
bool enableDiffHysteresis; /*!< Enable hysteresis in switching converter differential mode analog comparators. This
feature improves transient supply ripple and efficiency. */
bool enableCommonHysteresis; /*!< Enable hysteresis in switching converter common mode analog comparators. This
feature improves transient supply ripple and efficiency. */
bool enableDiffHysteresisThresh; /*!< This field act the same rule as enableDiffHysteresis. However, if this field
is enabled along with the enableDiffHysteresis, the Hysteresis wuold be
doubled. */
bool enableCommonHysteresisThresh; /*!< This field act the same rule as enableCommonHysteresis. However, if this
field is enabled along with the enableCommonHysteresis, the Hysteresis wuold
be doubled. */
bool enableInvertHysteresisSign; /*!< Invert the sign of the hysteresis in DC-DC analog comparators. */
} dcdc_loop_control_config_t;
/*!
* @brief Configuration for min power setting.
*/
typedef struct _dcdc_min_power_config
{
/* For Continuous Mode. */
bool enableUseHalfFetForContinuous; /*!< Use half switch FET for the continuous mode. */
bool enableUseDoubleFetForContinuous; /*!< Use double switch FET for the continuous mode. */
bool enableUseHalfFreqForContinuous; /*!< Set DCDC clock to half frequency for the continuous mode. */
/* For Pulsed Mode. */
bool enableUseHalfFetForPulsed; /*!< Use half switch FET for the Pulsed mode. */
bool enableUseDoubleFetForPulsed; /*!< Use double switch FET for the Pulsed mode. */
bool enableUseHalfFreqForPulsed; /*!< Set DCDC clock to half frequency for the Pulsed mode. */
} dcdc_min_power_config_t;
/*!
* @brief Configuration for the integrator in pulsed mode.
*/
typedef struct _dcdc_pulsed_integrator_config_t
{
bool enableUseUserIntegratorValue; /*!< Enable to use the setting value in userIntegratorValue field. Otherwise, the
predefined hardware setting would be applied internally. */
uint32_t userIntegratorValue; /*!< User defined integrator value. The available value is 19-bit. */
bool enablePulseRunSpeedup; /*!< Enable pulse run speedup. */
} dcdc_pulsed_integrator_config_t;
#if defined(__cplusplus)
extern "C" {
#endif
/*******************************************************************************
* API
******************************************************************************/
/*!
* @name Initialization and deinitialization
* @{
*/
/*!
* @brief Enable the access to DCDC registers.
*
* @param base DCDC peripheral base address.
*/
void DCDC_Init(DCDC_Type *base);
/*!
* @brief Disable the access to DCDC registers.
*
* @param base DCDC peripheral base address.
*/
void DCDC_Deinit(DCDC_Type *base);
/* @} */
/*!
* @name Status
* @{
*/
/*!
* @brief Get status flags.
*
* @brief base DCDC peripheral base address.
* @return Masks of asserted status flags. See to "_dcdc_status_flags_t".
*/
uint32_t DCDC_GetStatusFlags(DCDC_Type *base);
/*!
* @brief Clear status flags.
*
* @brief base DCDC peripheral base address.
* @brief mask Mask of status values that would be cleared. See to "_dcdc_status_flags_t".
*/
void DCDC_ClearStatusFlags(DCDC_Type *base, uint32_t mask);
/* @} */
/*!
* @name Interrupts
* @{
*/
/*!
* @brief Enable interrupts.
*
* @param base DCDC peripheral base address.
* @param mask Mask of interrupt events that would be enabled. See to "_dcdc_interrupt_enable_t".
*/
static inline void DCDC_EnableInterrupts(DCDC_Type *base, uint32_t mask)
{
assert(0U == (mask & ~DCDC_REG6_PSWITCH_INT_MUTE_MASK)); /* Only the PSWITCH interrupt is supported. */
/* By default, the PSWITCH is enabled. */
base->REG6 &= ~mask;
}
/*!
* @brief Disable interrupts.
*
* @param base DCDC peripheral base address.
* @param mask Mask of interrupt events that would be disabled. See to "_dcdc_interrupt_enable_t".
*/
static inline void DCDC_DisableInterrupts(DCDC_Type *base, uint32_t mask)
{
assert(0U == (mask & ~DCDC_REG6_PSWITCH_INT_MUTE_MASK)); /* Only the pswitch interrupt is supported. */
base->REG6 |= mask;
}
/*!
* @brief Configure the PSWITCH interrupts.
*
* There are PSWITCH interrupt events can be triggered by falling edge or rising edge. So user can set the interrupt
* events that would be triggered with this function. Un-asserted events would be disabled. The interrupt of PSwitch
* should be enabled as well if to sense the PSWTICH event.
* By default, no interrupt events would be enabled.
*
* @param base DCDC peripheral base address.
* @param mask Mask of interrupt events for PSwtich. See to "_dcdc_pswitch_detect_event_t".
*/
void DCDC_SetPSwitchInterruptConfig(DCDC_Type *base, uint32_t mask);
/* @} */
/*!
* @name Misc control.
* @{
*/
/*!
* @brief Get the default setting for low power configuration.
*
* The default configuration are set according to responding registers' setting when powered on.
* They are:
* @code
* config->workModeInVLPRW = kDCDC_WorkInPulsedMode;
* config->workModeInVLPS = kDCDC_WorkInPulsedMode;
* config->enableHysteresisVoltageSense = true;
* config->enableAdjustHystereticValueSense = false;
* config->enableHystersisComparator = true;
* config->enableAdjustHystereticValueComparator = false;
* config->hystereticUpperThresholdValue = kDCDC_HystereticThresholdOffset75mV;
* config->hystereticLowerThresholdValue = kDCDC_HystereticThresholdOffset0mV;
* config->enableDiffComparators = false;
* @endcode
*
* @param config Pointer to configuration structure. See to "dcdc_low_power_config_t".
*/
void DCDC_GetDefaultLowPowerConfig(dcdc_low_power_config_t *config);
/*!
* @brief Configure the low power for DCDC.
*
* @param base DCDC peripheral base address.
* @param config Pointer to configuration structure. See to "dcdc_low_power_config_t".
*/
void DCDC_SetLowPowerConfig(DCDC_Type *base, const dcdc_low_power_config_t *config);
/*!
* @brief Get the default setting for loop control configuration.
*
* The default configuration are set according to responding registers' setting when powered on.
* They are:
* @code
* config->enableDiffHysteresis = false;
* config->enableCommonHysteresis = false;
* config->enableDiffHysteresisThresh = false;
* config->enableCommonHysteresisThresh = false;
* config->enableInvertHysteresisSign = false;
* @endcode
*
* @param config Pointer to configuration structure. See to "dcdc_loop_control_config_t".
*/
void DCDC_GetDefaultLoopControlConfig(dcdc_loop_control_config_t *config);
/*!
* @brief Configure the loop control for DCDC.
*
* @param base DCDC peripheral base address.
* @param config Pointer to configuration structure. See to "dcdc_loop_control_config_t".
*/
void DCDC_SetLoopControlConfig(DCDC_Type *base, const dcdc_loop_control_config_t *config);
/*!
* @brief Enable the XTAL OK detection circuit.
*
* The XTAL OK detection circuit is enabled by default.
*
* @param base DCDC peripheral base address.
* @param enable Enable the feature or not.
*/
static inline void DCDC_EnableXtalOKDetectionCircuit(DCDC_Type *base, bool enable)
{
if (enable)
{
base->REG0 &= ~DCDC_REG0_DCDC_XTALOK_DISABLE_MASK;
}
else
{
base->REG0 |= DCDC_REG0_DCDC_XTALOK_DISABLE_MASK;
}
}
/*!
* @brief Enable the output range comparator.
*
* The output range comparator is enabled by default.
*
* @param base DCDC peripheral base address.
* @param enable Enable the feature or not.
*/
static inline void DCDC_EnableOutputRangeComparator(DCDC_Type *base, bool enable)
{
if (enable)
{
base->REG0 &= ~DCDC_REG0_PWD_CMP_OFFSET_MASK;
}
else
{
base->REG0 |= DCDC_REG0_PWD_CMP_OFFSET_MASK;
}
}
/*!
* @brief Enable to reduce the DCDC current.
*
* To enable this feature will save approximately 20 µA in RUN mode. This feature is disabled by default.
*
* @param base DCDC peripheral base address.
* @param enable Enable the feature or not.
*/
static inline void DCDC_EnableReduceCurrent(DCDC_Type *base, bool enable)
{
if (enable)
{
base->REG0 |= DCDC_REG0_DCDC_LESS_I_MASK;
}
else
{
base->REG0 &= ~DCDC_REG0_DCDC_LESS_I_MASK;
}
}
/*!
* @brief Set the clock source for DCDC.
*
* This function is to set the clock source for DCDC. By default, DCDC can switch the clock from internal oscillator to
* external clock automatically. Once the application choose to use the external clock with function, the internal
* oscillator would be powered down. However, the internal oscillator could be powered down only when 32MHz crystal
* oscillator is available.
*
* @param base DCDC peripheral base address.
* @param clockSource Clock source for DCDC. See to "dcdc_clock_source_t".
*/
void DCDC_SetClockSource(DCDC_Type *base, dcdc_clock_source_t clockSource);
/*!
* @brief Set the battery voltage divider for ADC sample.
*
* This function controls VBAT voltage divider. The divided VBAT output is input to an ADC channel which allows the
* battery voltage to be measured.
*
* @param base DCDC peripheral base address.
* @param divider Setting divider selection. See to "dcdc_vbat_divider_t"
*/
static inline void DCDC_SetBatteryVoltageDivider(DCDC_Type *base, dcdc_vbat_divider_t divider)
{
base->REG0 = (base->REG0 & ~DCDC_REG0_DCDC_VBAT_DIV_CTRL_MASK) | DCDC_REG0_DCDC_VBAT_DIV_CTRL(divider);
}
/*!
* @brief Set battery monitor value.
*
* This function is to set the battery monitor value. If the feature of monitoring battery voltage is enabled (with
* non-zero value set), user should set the battery voltage measured with an 8 mV LSB resolution from the ADC sample
* channel. It would improve efficiency and minimize ripple.
*
* @param base DCDC peripheral base address.
* @param battValue Battery voltage measured with an 8 mV LSB resolution with 10-bit ADC sample. Setting 0x0 would
* disable feature of monitoring battery voltage.
*/
void DCDC_SetBatteryMonitorValue(DCDC_Type *base, uint32_t battValue);
/*!
* @brief Software shutdown the DCDC module to stop the power supply for chip.
*
* This function is to shutdown the DCDC module and stop the power supply for chip. In case the chip is powered by DCDC,
* which means the DCDC is working as Buck/Boost mode, to shutdown the DCDC would cause the chip to reset! Then, the
* DCDC_REG4_DCDC_SW_SHUTDOWN bit would be cleared automatically during power up sequence. If the DCDC is in bypass
* mode, which depends on the board's hardware connection, to shutdown the DCDC would not be meaningful.
*
* @param base DCDC peripheral base address.
*/
static inline void DCDC_DoSoftShutdown(DCDC_Type *base)
{
base->REG4 = DCDC_REG4_UNLOCK(0x3E77) | DCDC_REG4_DCDC_SW_SHUTDOWN_MASK;
/* The unlock key must be set while set the shutdown command. */
}
/*!
* @brief Set upper limit duty cycle limit in DCDC converter in Boost mode.
*
* @param base DCDC peripheral base address.
* @param value Setting value for limit duty cycle. Available range is 0-127.
*/
static inline void DCDC_SetUpperLimitDutyCycleBoost(DCDC_Type *base, uint32_t value)
{
base->REG1 = (~DCDC_REG1_POSLIMIT_BOOST_IN_MASK & base->REG1) | DCDC_REG1_POSLIMIT_BOOST_IN(value);
}
/*!
* @brief Set upper limit duty cycle limit in DCDC converter in Buck mode.
*
* @param base DCDC peripheral base address.
* @param value Setting value for limit duty cycle. Available range is 0-127.
*/
static inline void DCDC_SetUpperLimitDutyCycleBuck(DCDC_Type *base, uint32_t value)
{
base->REG1 = (~DCDC_REG1_POSLIMIT_BUCK_IN_MASK & base->REG1) | DCDC_REG1_POSLIMIT_BUCK_IN(value);
}
/*!
* @brief Adjust value of duty cycle when switching between VDD1P45 and VDD1P8.
*
* Adjust value of duty cycle when switching between VDD1P45 and VDD1P8. The unit is 1/32 or 3.125%.
*
* @param base DCDC peripheral base address.
* @param value Setting adjust value. The available range is 0-15. The unit is 1/32 or 3.125&.
*/
static inline void DCDC_AdjustDutyCycleSwitchingTargetOutput(DCDC_Type *base, uint32_t value)
{
base->REG3 = (~DCDC_REG3_DCDC_VDD1P5CTRL_ADJTN_MASK & base->REG3) | DCDC_REG3_DCDC_VDD1P5CTRL_ADJTN(value);
}
/*!
* @brief Lock the setting of target voltage.
*
* This function is to lock the setting of target voltage. This function should be called before entering the low power
* modes to lock the target voltage.
*
* @param base DCDC peripheral base address.
*/
static inline void DCDC_LockTargetVoltage(DCDC_Type *base)
{
base->REG3 |= (DCDC_REG3_DCDC_VDD1P8CTRL_DISABLE_STEP_MASK | DCDC_REG3_DCDC_VDD1P5CTRL_DISABLE_STEP_MASK);
}
/*!
* @brief Adjust the target voltage of DCDC output.
*
* This function is to adjust the target voltage of DCDC output. It would unlock the setting of target voltages, change
* them and finally wait until the output is stabled.
*
* @param base DCDC peripheral base address.
* @param vdd1p45Boost Target value of VDD1P45 in boost mode, 25 mV each step from 0x00 to 0x0F. 0x00 is for 1.275V.
* @param vdd1p45Buck Target value of VDD1P45 in buck mode, 25 mV each step from 0x00 to 0x0F. 0x00 is for 1.275V.
* @param vdd1p8 Target value of VDD1P8, 25 mV each step in two ranges, from 0x00 to 0x11 and 0x20 to 0x3F.
* 0x00 is for 1.65V, 0x20 is for 2.8V.
*/
void DCDC_AdjustTargetVoltage(DCDC_Type *base, uint32_t vdd1p45Boost, uint32_t vdd1p45Buck, uint32_t vdd1p8);
/*!
* @brief Get the default configuration for min power.
*
* The default configuration are set according to responding registers' setting when powered on.
* They are:
* @code
* config->enableUseHalfFetForContinuous = false;
* config->enableUseDoubleFetForContinuous = false;
* config->enableUseHalfFreqForContinuous = false;
* config->enableUseHalfFetForPulsed = false;
* config->enableUseDoubleFetForPulsed = false;
* config->enableUseHalfFreqForPulsed = false;
* @endcode
*
* @param config Pointer to configuration structure. See to "dcdc_min_power_config_t".
*/
void DCDC_GetDefaultMinPowerDefault(dcdc_min_power_config_t *config);
/*!
* @brief Configure for the min power.
*
* @param base DCDC peripheral base address.
* @param config Pointer to configuration structure. See to "dcdc_min_power_config_t".
*/
void DCDC_SetMinPowerConfig(DCDC_Type *base, const dcdc_min_power_config_t *config);
/*!
* @brief Get the default setting for integrator configuration in pulsed mode.
*
* The default configuration are set according to responding registers' setting when powered on.
* They are:
* @code
* config->enableUseUserIntegratorValue = false;
* config->userIntegratorValue = 0U;
* config->enablePulseRunSpeedup = false;
* @endcode
*
* @param config Pointer to configuration structure. See to "dcdc_pulsed_integrator_config_t".
*/
void DCDC_GetDefaultPulsedIntegratorConfig(dcdc_pulsed_integrator_config_t *config);
/*!
* @brief Configure the integrator in pulsed mode.
*
* @param base DCDC peripheral base address.
* @config Pointer to configuration structure. See to "dcdc_pulsed_integrator_config_t".
*/
void DCDC_SetPulsedIntegratorConfig(DCDC_Type *base, const dcdc_pulsed_integrator_config_t *config);
/* @} */
#if defined(__cplusplus)
}
#endif
/*!
* @}
*/
#endif /* _FSL_DCDC_H_ */

View File

@ -0,0 +1,87 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include "fsl_dmamux.h"
/*******************************************************************************
* Definitions
******************************************************************************/
/*******************************************************************************
* Prototypes
******************************************************************************/
/*!
* @brief Get instance number for DMAMUX.
*
* @param base DMAMUX peripheral base address.
*/
static uint32_t DMAMUX_GetInstance(DMAMUX_Type *base);
/*******************************************************************************
* Variables
******************************************************************************/
/*! @brief Array to map DMAMUX instance number to base pointer. */
static DMAMUX_Type *const s_dmamuxBases[] = DMAMUX_BASE_PTRS;
/*! @brief Array to map DMAMUX instance number to clock name. */
static const clock_ip_name_t s_dmamuxClockName[] = DMAMUX_CLOCKS;
/*******************************************************************************
* Code
******************************************************************************/
static uint32_t DMAMUX_GetInstance(DMAMUX_Type *base)
{
uint32_t instance;
/* Find the instance index from base address mappings. */
for (instance = 0; instance < FSL_FEATURE_SOC_DMAMUX_COUNT; instance++)
{
if (s_dmamuxBases[instance] == base)
{
break;
}
}
assert(instance < FSL_FEATURE_SOC_DMAMUX_COUNT);
return instance;
}
void DMAMUX_Init(DMAMUX_Type *base)
{
CLOCK_EnableClock(s_dmamuxClockName[DMAMUX_GetInstance(base)]);
}
void DMAMUX_Deinit(DMAMUX_Type *base)
{
CLOCK_DisableClock(s_dmamuxClockName[DMAMUX_GetInstance(base)]);
}

View File

@ -0,0 +1,175 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _FSL_DMAMUX_H_
#define _FSL_DMAMUX_H_
#include "fsl_common.h"
/*!
* @addtogroup dmamux
* @{
*/
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @name Driver version */
/*@{*/
/*! @brief DMAMUX driver version 2.0.1. */
#define FSL_DMAMUX_DRIVER_VERSION (MAKE_VERSION(2, 0, 1))
/*@}*/
/*******************************************************************************
* API
******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif /* __cplusplus */
/*!
* @name DMAMUX Initialize and De-initialize
* @{
*/
/*!
* @brief Initializes DMAMUX peripheral.
*
* This function ungate the DMAMUX clock.
*
* @param base DMAMUX peripheral base address.
*
*/
void DMAMUX_Init(DMAMUX_Type *base);
/*!
* @brief Deinitializes DMAMUX peripheral.
*
* This function gate the DMAMUX clock.
*
* @param base DMAMUX peripheral base address.
*/
void DMAMUX_Deinit(DMAMUX_Type *base);
/* @} */
/*!
* @name DMAMUX Channel Operation
* @{
*/
/*!
* @brief Enable DMAMUX channel.
*
* This function enable DMAMUX channel to work.
*
* @param base DMAMUX peripheral base address.
* @param channel DMAMUX channel number.
*/
static inline void DMAMUX_EnableChannel(DMAMUX_Type *base, uint32_t channel)
{
assert(channel < FSL_FEATURE_DMAMUX_MODULE_CHANNEL);
base->CHCFG[channel] |= DMAMUX_CHCFG_ENBL_MASK;
}
/*!
* @brief Disable DMAMUX channel.
*
* This function disable DMAMUX channel.
*
* @note User must disable DMAMUX channel before configuring it.
* @param base DMAMUX peripheral base address.
* @param channel DMAMUX channel number.
*/
static inline void DMAMUX_DisableChannel(DMAMUX_Type *base, uint32_t channel)
{
assert(channel < FSL_FEATURE_DMAMUX_MODULE_CHANNEL);
base->CHCFG[channel] &= ~DMAMUX_CHCFG_ENBL_MASK;
}
/*!
* @brief Configure DMAMUX channel source.
*
* @param base DMAMUX peripheral base address.
* @param channel DMAMUX channel number.
* @param source Channel source which is used to trigger DMA transfer.
*/
static inline void DMAMUX_SetSource(DMAMUX_Type *base, uint32_t channel, uint32_t source)
{
assert(channel < FSL_FEATURE_DMAMUX_MODULE_CHANNEL);
base->CHCFG[channel] = ((base->CHCFG[channel] & ~DMAMUX_CHCFG_SOURCE_MASK) | DMAMUX_CHCFG_SOURCE(source));
}
#if defined(FSL_FEATURE_DMAMUX_HAS_TRIG) && FSL_FEATURE_DMAMUX_HAS_TRIG > 0U
/*!
* @brief Enable DMAMUX period trigger.
*
* This function enable DMAMUX period trigger feature.
*
* @param base DMAMUX peripheral base address.
* @param channel DMAMUX channel number.
*/
static inline void DMAMUX_EnablePeriodTrigger(DMAMUX_Type *base, uint32_t channel)
{
assert(channel < FSL_FEATURE_DMAMUX_MODULE_CHANNEL);
base->CHCFG[channel] |= DMAMUX_CHCFG_TRIG_MASK;
}
/*!
* @brief Disable DMAMUX period trigger.
*
* This function disable DMAMUX period trigger.
*
* @param base DMAMUX peripheral base address.
* @param channel DMAMUX channel number.
*/
static inline void DMAMUX_DisablePeriodTrigger(DMAMUX_Type *base, uint32_t channel)
{
assert(channel < FSL_FEATURE_DMAMUX_MODULE_CHANNEL);
base->CHCFG[channel] &= ~DMAMUX_CHCFG_TRIG_MASK;
}
#endif /* FSL_FEATURE_DMAMUX_HAS_TRIG */
/* @} */
#if defined(__cplusplus)
}
#endif /* __cplusplus */
/* @} */
#endif /* _FSL_DMAMUX_H_ */

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,282 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _FSL_DSPI_EDMA_H_
#define _FSL_DSPI_EDMA_H_
#include "fsl_dspi.h"
#include "fsl_edma.h"
/*!
* @addtogroup dspi_edma_driver
* @{
*/
/***********************************************************************************************************************
* Definitions
**********************************************************************************************************************/
/*!
* @brief Forward declaration of the DSPI eDMA master handle typedefs.
*/
typedef struct _dspi_master_edma_handle dspi_master_edma_handle_t;
/*!
* @brief Forward declaration of the DSPI eDMA slave handle typedefs.
*/
typedef struct _dspi_slave_edma_handle dspi_slave_edma_handle_t;
/*!
* @brief Completion callback function pointer type.
*
* @param base DSPI peripheral base address.
* @param handle Pointer to the handle for the DSPI master.
* @param status Success or error code describing whether the transfer completed.
* @param userData Arbitrary pointer-dataSized value passed from the application.
*/
typedef void (*dspi_master_edma_transfer_callback_t)(SPI_Type *base,
dspi_master_edma_handle_t *handle,
status_t status,
void *userData);
/*!
* @brief Completion callback function pointer type.
*
* @param base DSPI peripheral base address.
* @param handle Pointer to the handle for the DSPI slave.
* @param status Success or error code describing whether the transfer completed.
* @param userData Arbitrary pointer-dataSized value passed from the application.
*/
typedef void (*dspi_slave_edma_transfer_callback_t)(SPI_Type *base,
dspi_slave_edma_handle_t *handle,
status_t status,
void *userData);
/*! @brief DSPI master eDMA transfer handle structure used for transactional API. */
struct _dspi_master_edma_handle
{
uint32_t bitsPerFrame; /*!< Desired number of bits per frame. */
volatile uint32_t command; /*!< Desired data command. */
volatile uint32_t lastCommand; /*!< Desired last data command. */
uint8_t fifoSize; /*!< FIFO dataSize. */
volatile bool isPcsActiveAfterTransfer; /*!< Is PCS signal keep active after the last frame transfer.*/
volatile bool isThereExtraByte; /*!< Is there extra byte.*/
uint8_t *volatile txData; /*!< Send buffer. */
uint8_t *volatile rxData; /*!< Receive buffer. */
volatile size_t remainingSendByteCount; /*!< Number of bytes remaining to send.*/
volatile size_t remainingReceiveByteCount; /*!< Number of bytes remaining to receive.*/
size_t totalByteCount; /*!< Number of transfer bytes*/
uint32_t rxBuffIfNull; /*!< Used if there is not rxData for DMA purpose.*/
uint32_t txBuffIfNull; /*!< Used if there is not txData for DMA purpose.*/
volatile uint8_t state; /*!< DSPI transfer state , _dspi_transfer_state.*/
dspi_master_edma_transfer_callback_t callback; /*!< Completion callback. */
void *userData; /*!< Callback user data. */
edma_handle_t *edmaRxRegToRxDataHandle; /*!<edma_handle_t handle point used for RxReg to RxData buff*/
edma_handle_t *edmaTxDataToIntermediaryHandle; /*!<edma_handle_t handle point used for TxData to Intermediary*/
edma_handle_t *edmaIntermediaryToTxRegHandle; /*!<edma_handle_t handle point used for Intermediary to TxReg*/
edma_tcd_t dspiSoftwareTCD[2]; /*!<SoftwareTCD , internal used*/
};
/*! @brief DSPI slave eDMA transfer handle structure used for transactional API.*/
struct _dspi_slave_edma_handle
{
uint32_t bitsPerFrame; /*!< Desired number of bits per frame. */
volatile bool isThereExtraByte; /*!< Is there extra byte.*/
uint8_t *volatile txData; /*!< Send buffer. */
uint8_t *volatile rxData; /*!< Receive buffer. */
volatile size_t remainingSendByteCount; /*!< Number of bytes remaining to send.*/
volatile size_t remainingReceiveByteCount; /*!< Number of bytes remaining to receive.*/
size_t totalByteCount; /*!< Number of transfer bytes*/
uint32_t rxBuffIfNull; /*!< Used if there is not rxData for DMA purpose.*/
uint32_t txBuffIfNull; /*!< Used if there is not txData for DMA purpose.*/
uint32_t txLastData; /*!< Used if there is an extra byte when 16bits per frame for DMA purpose.*/
volatile uint8_t state; /*!< DSPI transfer state.*/
uint32_t errorCount; /*!< Error count for slave transfer.*/
dspi_slave_edma_transfer_callback_t callback; /*!< Completion callback. */
void *userData; /*!< Callback user data. */
edma_handle_t *edmaRxRegToRxDataHandle; /*!<edma_handle_t handle point used for RxReg to RxData buff*/
edma_handle_t *edmaTxDataToTxRegHandle; /*!<edma_handle_t handle point used for TxData to TxReg*/
edma_tcd_t dspiSoftwareTCD[2]; /*!<SoftwareTCD , internal used*/
};
/***********************************************************************************************************************
* API
**********************************************************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif /*_cplusplus*/
/*Transactional APIs*/
/*!
* @brief Initializes the DSPI master eDMA handle.
*
* This function initializes the DSPI eDMA handle which can be used for other DSPI transactional APIs. Usually, for a
* specified DSPI instance, user need only call this API once to get the initialized handle.
*
* Note that DSPI eDMA has separated (RX and TX as two sources) or shared (RX and TX are the same source) DMA request source.
* (1)For the separated DMA request source, enable and set the RX DMAMUX source for edmaRxRegToRxDataHandle and
* TX DMAMUX source for edmaIntermediaryToTxRegHandle.
* (2)For the shared DMA request source, enable and set the RX/RX DMAMUX source for the edmaRxRegToRxDataHandle.
*
* @param base DSPI peripheral base address.
* @param handle DSPI handle pointer to dspi_master_edma_handle_t.
* @param callback DSPI callback.
* @param userData callback function parameter.
* @param edmaRxRegToRxDataHandle edmaRxRegToRxDataHandle pointer to edma_handle_t.
* @param edmaTxDataToIntermediaryHandle edmaTxDataToIntermediaryHandle pointer to edma_handle_t.
* @param edmaIntermediaryToTxRegHandle edmaIntermediaryToTxRegHandle pointer to edma_handle_t.
*/
void DSPI_MasterTransferCreateHandleEDMA(SPI_Type *base,
dspi_master_edma_handle_t *handle,
dspi_master_edma_transfer_callback_t callback,
void *userData,
edma_handle_t *edmaRxRegToRxDataHandle,
edma_handle_t *edmaTxDataToIntermediaryHandle,
edma_handle_t *edmaIntermediaryToTxRegHandle);
/*!
* @brief DSPI master transfer data using eDMA.
*
* This function transfer data using eDMA. This is non-blocking function, which returns right away. When all data
* have been transfer, the callback function is called.
*
* @param base DSPI peripheral base address.
* @param handle pointer to dspi_master_edma_handle_t structure which stores the transfer state.
* @param transfer pointer to dspi_transfer_t structure.
* @return status of status_t.
*/
status_t DSPI_MasterTransferEDMA(SPI_Type *base, dspi_master_edma_handle_t *handle, dspi_transfer_t *transfer);
/*!
* @brief DSPI master aborts a transfer which using eDMA.
*
* This function aborts a transfer which using eDMA.
*
* @param base DSPI peripheral base address.
* @param handle pointer to dspi_master_edma_handle_t structure which stores the transfer state.
*/
void DSPI_MasterTransferAbortEDMA(SPI_Type *base, dspi_master_edma_handle_t *handle);
/*!
* @brief Gets the master eDMA transfer count.
*
* This function get the master eDMA transfer count.
*
* @param base DSPI peripheral base address.
* @param handle pointer to dspi_master_edma_handle_t structure which stores the transfer state.
* @param count Number of bytes transferred so far by the non-blocking transaction.
* @return status of status_t.
*/
status_t DSPI_MasterTransferGetCountEDMA(SPI_Type *base, dspi_master_edma_handle_t *handle, size_t *count);
/*!
* @brief Initializes the DSPI slave eDMA handle.
*
* This function initializes the DSPI eDMA handle which can be used for other DSPI transactional APIs. Usually, for a
* specified DSPI instance, call this API once to get the initialized handle.
*
* Note that DSPI eDMA has separated (RN and TX in 2 sources) or shared (RX and TX are the same source) DMA request source.
* (1)For the separated DMA request source, enable and set the RX DMAMUX source for edmaRxRegToRxDataHandle and
* TX DMAMUX source for edmaTxDataToTxRegHandle.
* (2)For the shared DMA request source, enable and set the RX/RX DMAMUX source for the edmaRxRegToRxDataHandle.
*
* @param base DSPI peripheral base address.
* @param handle DSPI handle pointer to dspi_slave_edma_handle_t.
* @param callback DSPI callback.
* @param userData callback function parameter.
* @param edmaRxRegToRxDataHandle edmaRxRegToRxDataHandle pointer to edma_handle_t.
* @param edmaTxDataToTxRegHandle edmaTxDataToTxRegHandle pointer to edma_handle_t.
*/
void DSPI_SlaveTransferCreateHandleEDMA(SPI_Type *base,
dspi_slave_edma_handle_t *handle,
dspi_slave_edma_transfer_callback_t callback,
void *userData,
edma_handle_t *edmaRxRegToRxDataHandle,
edma_handle_t *edmaTxDataToTxRegHandle);
/*!
* @brief DSPI slave transfer data using eDMA.
*
* This function transfer data using eDMA. This is non-blocking function, which returns right away. When all data
* have been transfer, the callback function is called.
* Note that slave EDMA transfer cannot support the situation that transfer_size is 1 when the bitsPerFrame is greater
* than 8 .
* @param base DSPI peripheral base address.
* @param handle pointer to dspi_slave_edma_handle_t structure which stores the transfer state.
* @param transfer pointer to dspi_transfer_t structure.
* @return status of status_t.
*/
status_t DSPI_SlaveTransferEDMA(SPI_Type *base, dspi_slave_edma_handle_t *handle, dspi_transfer_t *transfer);
/*!
* @brief DSPI slave aborts a transfer which using eDMA.
*
* This function aborts a transfer which using eDMA.
*
* @param base DSPI peripheral base address.
* @param handle pointer to dspi_slave_edma_handle_t structure which stores the transfer state.
*/
void DSPI_SlaveTransferAbortEDMA(SPI_Type *base, dspi_slave_edma_handle_t *handle);
/*!
* @brief Gets the slave eDMA transfer count.
*
* This function gets the slave eDMA transfer count.
*
* @param base DSPI peripheral base address.
* @param handle pointer to dspi_slave_edma_handle_t structure which stores the transfer state.
* @param count Number of bytes transferred so far by the non-blocking transaction.
* @return status of status_t.
*/
status_t DSPI_SlaveTransferGetCountEDMA(SPI_Type *base, dspi_slave_edma_handle_t *handle, size_t *count);
#if defined(__cplusplus)
}
#endif /*_cplusplus*/
/*!
*@}
*/
#endif /*_FSL_DSPI_EDMA_H_*/

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,880 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _FSL_EDMA_H_
#define _FSL_EDMA_H_
#include "fsl_common.h"
/*!
* @addtogroup edma
* @{
*/
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @name Driver version */
/*@{*/
/*! @brief eDMA driver version */
#define FSL_EDMA_DRIVER_VERSION (MAKE_VERSION(2, 0, 1)) /*!< Version 2.0.1. */
/*@}*/
/*! @brief Compute the offset unit from DCHPRI3 */
#define DMA_DCHPRI_INDEX(channel) (((channel) & ~0x03U) | (3 - ((channel)&0x03U)))
/*! @brief Get the pointer of DCHPRIn */
#define DMA_DCHPRIn(base, channel) ((volatile uint8_t *)&(base->DCHPRI3))[DMA_DCHPRI_INDEX(channel)]
/*! @brief eDMA transfer configuration */
typedef enum _edma_transfer_size
{
kEDMA_TransferSize1Bytes = 0x0U, /*!< Source/Destination data transfer size is 1 byte every time */
kEDMA_TransferSize2Bytes = 0x1U, /*!< Source/Destination data transfer size is 2 bytes every time */
kEDMA_TransferSize4Bytes = 0x2U, /*!< Source/Destination data transfer size is 4 bytes every time */
kEDMA_TransferSize16Bytes = 0x4U, /*!< Source/Destination data transfer size is 16 bytes every time */
kEDMA_TransferSize32Bytes = 0x5U, /*!< Source/Destination data transfer size is 32 bytes every time */
} edma_transfer_size_t;
/*! @brief eDMA modulo configuration */
typedef enum _edma_modulo
{
kEDMA_ModuloDisable = 0x0U, /*!< Disable modulo */
kEDMA_Modulo2bytes, /*!< Circular buffer size is 2 bytes. */
kEDMA_Modulo4bytes, /*!< Circular buffer size is 4 bytes. */
kEDMA_Modulo8bytes, /*!< Circular buffer size is 8 bytes. */
kEDMA_Modulo16bytes, /*!< Circular buffer size is 16 bytes. */
kEDMA_Modulo32bytes, /*!< Circular buffer size is 32 bytes. */
kEDMA_Modulo64bytes, /*!< Circular buffer size is 64 bytes. */
kEDMA_Modulo128bytes, /*!< Circular buffer size is 128 bytes. */
kEDMA_Modulo256bytes, /*!< Circular buffer size is 256 bytes. */
kEDMA_Modulo512bytes, /*!< Circular buffer size is 512 bytes. */
kEDMA_Modulo1Kbytes, /*!< Circular buffer size is 1K bytes. */
kEDMA_Modulo2Kbytes, /*!< Circular buffer size is 2K bytes. */
kEDMA_Modulo4Kbytes, /*!< Circular buffer size is 4K bytes. */
kEDMA_Modulo8Kbytes, /*!< Circular buffer size is 8K bytes. */
kEDMA_Modulo16Kbytes, /*!< Circular buffer size is 16K bytes. */
kEDMA_Modulo32Kbytes, /*!< Circular buffer size is 32K bytes. */
kEDMA_Modulo64Kbytes, /*!< Circular buffer size is 64K bytes. */
kEDMA_Modulo128Kbytes, /*!< Circular buffer size is 128K bytes. */
kEDMA_Modulo256Kbytes, /*!< Circular buffer size is 256K bytes. */
kEDMA_Modulo512Kbytes, /*!< Circular buffer size is 512K bytes. */
kEDMA_Modulo1Mbytes, /*!< Circular buffer size is 1M bytes. */
kEDMA_Modulo2Mbytes, /*!< Circular buffer size is 2M bytes. */
kEDMA_Modulo4Mbytes, /*!< Circular buffer size is 4M bytes. */
kEDMA_Modulo8Mbytes, /*!< Circular buffer size is 8M bytes. */
kEDMA_Modulo16Mbytes, /*!< Circular buffer size is 16M bytes. */
kEDMA_Modulo32Mbytes, /*!< Circular buffer size is 32M bytes. */
kEDMA_Modulo64Mbytes, /*!< Circular buffer size is 64M bytes. */
kEDMA_Modulo128Mbytes, /*!< Circular buffer size is 128M bytes. */
kEDMA_Modulo256Mbytes, /*!< Circular buffer size is 256M bytes. */
kEDMA_Modulo512Mbytes, /*!< Circular buffer size is 512M bytes. */
kEDMA_Modulo1Gbytes, /*!< Circular buffer size is 1G bytes. */
kEDMA_Modulo2Gbytes, /*!< Circular buffer size is 2G bytes. */
} edma_modulo_t;
/*! @brief Bandwidth control */
typedef enum _edma_bandwidth
{
kEDMA_BandwidthStallNone = 0x0U, /*!< No eDMA engine stalls. */
kEDMA_BandwidthStall4Cycle = 0x2U, /*!< eDMA engine stalls for 4 cycles after each read/write. */
kEDMA_BandwidthStall8Cycle = 0x3U, /*!< eDMA engine stalls for 8 cycles after each read/write. */
} edma_bandwidth_t;
/*! @brief Channel link type */
typedef enum _edma_channel_link_type
{
kEDMA_LinkNone = 0x0U, /*!< No channel link */
kEDMA_MinorLink, /*!< Channel link after each minor loop */
kEDMA_MajorLink, /*!< Channel link while major loop count exhausted */
} edma_channel_link_type_t;
/*!@brief eDMA channel status flags. */
enum _edma_channel_status_flags
{
kEDMA_DoneFlag = 0x1U, /*!< DONE flag, set while transfer finished, CITER value exhausted*/
kEDMA_ErrorFlag = 0x2U, /*!< eDMA error flag, an error occurred in a transfer */
kEDMA_InterruptFlag = 0x4U, /*!< eDMA interrupt flag, set while an interrupt occurred of this channel */
};
/*! @brief eDMA channel error status flags. */
enum _edma_error_status_flags
{
kEDMA_DestinationBusErrorFlag = DMA_ES_DBE_MASK, /*!< Bus error on destination address */
kEDMA_SourceBusErrorFlag = DMA_ES_SBE_MASK, /*!< Bus error on the source address */
kEDMA_ScatterGatherErrorFlag = DMA_ES_SGE_MASK, /*!< Error on the Scatter/Gather address, not 32byte aligned. */
kEDMA_NbytesErrorFlag = DMA_ES_NCE_MASK, /*!< NBYTES/CITER configuration error */
kEDMA_DestinationOffsetErrorFlag = DMA_ES_DOE_MASK, /*!< Destination offset not aligned with destination size */
kEDMA_DestinationAddressErrorFlag = DMA_ES_DAE_MASK, /*!< Destination address not aligned with destination size */
kEDMA_SourceOffsetErrorFlag = DMA_ES_SOE_MASK, /*!< Source offset not aligned with source size */
kEDMA_SourceAddressErrorFlag = DMA_ES_SAE_MASK, /*!< Source address not aligned with source size*/
kEDMA_ErrorChannelFlag = DMA_ES_ERRCHN_MASK, /*!< Error channel number of the cancelled channel number */
kEDMA_ChannelPriorityErrorFlag = DMA_ES_CPE_MASK, /*!< Channel priority is not unique. */
kEDMA_TransferCanceledFlag = DMA_ES_ECX_MASK, /*!< Transfer cancelled */
#if defined(FSL_FEATURE_EDMA_CHANNEL_GROUP_COUNT) && FSL_FEATURE_EDMA_CHANNEL_GROUP_COUNT > 1
kEDMA_GroupPriorityErrorFlag = DMA_ES_GPE_MASK, /*!< Group priority is not unique. */
#endif
kEDMA_ValidFlag = DMA_ES_VLD_MASK, /*!< No error occurred, this bit is 0. Otherwise, it is 1. */
};
/*! @brief eDMA interrupt source */
typedef enum _edma_interrupt_enable
{
kEDMA_ErrorInterruptEnable = 0x1U, /*!< Enable interrupt while channel error occurs. */
kEDMA_MajorInterruptEnable = DMA_CSR_INTMAJOR_MASK, /*!< Enable interrupt while major count exhausted. */
kEDMA_HalfInterruptEnable = DMA_CSR_INTHALF_MASK, /*!< Enable interrupt while major count to half value. */
} edma_interrupt_enable_t;
/*! @brief eDMA transfer type */
typedef enum _edma_transfer_type
{
kEDMA_MemoryToMemory = 0x0U, /*!< Transfer from memory to memory */
kEDMA_PeripheralToMemory, /*!< Transfer from peripheral to memory */
kEDMA_MemoryToPeripheral, /*!< Transfer from memory to peripheral */
} edma_transfer_type_t;
/*! @brief eDMA transfer status */
enum _edma_transfer_status
{
kStatus_EDMA_QueueFull = MAKE_STATUS(kStatusGroup_EDMA, 0), /*!< TCD queue is full. */
kStatus_EDMA_Busy = MAKE_STATUS(kStatusGroup_EDMA, 1), /*!< Channel is busy and can't handle the
transfer request. */
};
/*! @brief eDMA global configuration structure.*/
typedef struct _edma_config
{
bool enableContinuousLinkMode; /*!< Enable (true) continuous link mode. Upon minor loop completion, the channel
activates again if that channel has a minor loop channel link enabled and
the link channel is itself. */
bool enableHaltOnError; /*!< Enable (true) transfer halt on error. Any error causes the HALT bit to set.
Subsequently, all service requests are ignored until the HALT bit is cleared.*/
bool enableRoundRobinArbitration; /*!< Enable (true) round robin channel arbitration method, or fixed priority
arbitration is used for channel selection */
bool enableDebugMode; /*!< Enable(true) eDMA debug mode. When in debug mode, the eDMA stalls the start of
a new channel. Executing channels are allowed to complete. */
} edma_config_t;
/*!
* @brief eDMA transfer configuration
*
* This structure configures the source/destination transfer attribute.
* This figure shows the eDMA's transfer model:
* _________________________________________________
* | Transfer Size | |
* Minor Loop |_______________| Major loop Count 1 |
* Bytes | Transfer Size | |
* ____________|_______________|____________________|--> Minor loop complete
* ____________________________________
* | | |
* |_______________| Major Loop Count 2 |
* | | |
* |_______________|____________________|--> Minor loop Complete
*
* ---------------------------------------------------------> Transfer complete
*/
typedef struct _edma_transfer_config
{
uint32_t srcAddr; /*!< Source data address. */
uint32_t destAddr; /*!< Destination data address. */
edma_transfer_size_t srcTransferSize; /*!< Source data transfer size. */
edma_transfer_size_t destTransferSize; /*!< Destination data transfer size. */
int16_t srcOffset; /*!< Sign-extended offset applied to the current source address to
form the next-state value as each source read is completed. */
int16_t destOffset; /*!< Sign-extended offset applied to the current destination address to
form the next-state value as each destination write is completed. */
uint16_t minorLoopBytes; /*!< Bytes to transfer in a minor loop*/
uint32_t majorLoopCounts; /*!< Major loop iteration count. */
} edma_transfer_config_t;
/*! @brief eDMA channel priority configuration */
typedef struct _edma_channel_Preemption_config
{
bool enableChannelPreemption; /*!< If true: channel can be suspended by other channel with higher priority */
bool enablePreemptAbility; /*!< If true: channel can suspend other channel with low priority */
uint8_t channelPriority; /*!< Channel priority */
} edma_channel_Preemption_config_t;
/*! @brief eDMA minor offset configuration */
typedef struct _edma_minor_offset_config
{
bool enableSrcMinorOffset; /*!< Enable(true) or Disable(false) source minor loop offset. */
bool enableDestMinorOffset; /*!< Enable(true) or Disable(false) destination minor loop offset. */
uint32_t minorOffset; /*!< Offset for minor loop mapping. */
} edma_minor_offset_config_t;
/*!
* @brief eDMA TCD.
*
* This structure is same as TCD register which is described in reference manual,
* and is used to configure the scatter/gather feature as a next hardware TCD.
*/
typedef struct _edma_tcd
{
__IO uint32_t SADDR; /*!< SADDR register, used to save source address */
__IO uint16_t SOFF; /*!< SOFF register, save offset bytes every transfer */
__IO uint16_t ATTR; /*!< ATTR register, source/destination transfer size and modulo */
__IO uint32_t NBYTES; /*!< Nbytes register, minor loop length in bytes */
__IO uint32_t SLAST; /*!< SLAST register */
__IO uint32_t DADDR; /*!< DADDR register, used for destination address */
__IO uint16_t DOFF; /*!< DOFF register, used for destination offset */
__IO uint16_t CITER; /*!< CITER register, current minor loop numbers, for unfinished minor loop.*/
__IO uint32_t DLAST_SGA; /*!< DLASTSGA register, next stcd address used in scatter-gather mode */
__IO uint16_t CSR; /*!< CSR register, for TCD control status */
__IO uint16_t BITER; /*!< BITER register, begin minor loop count. */
} edma_tcd_t;
/*! @brief Callback for eDMA */
struct _edma_handle;
/*! @brief Define Callback function for eDMA. */
typedef void (*edma_callback)(struct _edma_handle *handle, void *userData, bool transferDone, uint32_t tcds);
/*! @brief eDMA transfer handle structure */
typedef struct _edma_handle
{
edma_callback callback; /*!< Callback function for major count exhausted. */
void *userData; /*!< Callback function parameter. */
DMA_Type *base; /*!< eDMA peripheral base address. */
edma_tcd_t *tcdPool; /*!< Pointer to memory stored TCDs. */
uint8_t channel; /*!< eDMA channel number. */
volatile int8_t header; /*!< The first TCD index. */
volatile int8_t tail; /*!< The last TCD index. */
volatile int8_t tcdUsed; /*!< The number of used TCD slots. */
volatile int8_t tcdSize; /*!< The total number of TCD slots in the queue. */
uint8_t flags; /*!< The status of the current channel. */
} edma_handle_t;
/*******************************************************************************
* APIs
******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif /* __cplusplus */
/*!
* @name eDMA initialization and De-initialization
* @{
*/
/*!
* @brief Initializes eDMA peripheral.
*
* This function ungates the eDMA clock and configures the eDMA peripheral according
* to the configuration structure.
*
* @param base eDMA peripheral base address.
* @param config Pointer to configuration structure, see "edma_config_t".
* @note This function enable the minor loop map feature.
*/
void EDMA_Init(DMA_Type *base, const edma_config_t *config);
/*!
* @brief Deinitializes eDMA peripheral.
*
* This function gates the eDMA clock.
*
* @param base eDMA peripheral base address.
*/
void EDMA_Deinit(DMA_Type *base);
/*!
* @brief Gets the eDMA default configuration structure.
*
* This function sets the configuration structure to a default value.
* The default configuration is set to the following value:
* @code
* config.enableContinuousLinkMode = false;
* config.enableHaltOnError = true;
* config.enableRoundRobinArbitration = false;
* config.enableDebugMode = false;
* @endcode
*
* @param config Pointer to eDMA configuration structure.
*/
void EDMA_GetDefaultConfig(edma_config_t *config);
/* @} */
/*!
* @name eDMA Channel Operation
* @{
*/
/*!
* @brief Sets all TCD registers to a default value.
*
* This function sets TCD registers for this channel to default value.
*
* @param base eDMA peripheral base address.
* @param channel eDMA channel number.
* @note This function must not be called while the channel transfer is on-going,
* or it causes unpredictable results.
* @note This function enables the auto stop request feature.
*/
void EDMA_ResetChannel(DMA_Type *base, uint32_t channel);
/*!
* @brief Configures the eDMA transfer attribute.
*
* This function configures the transfer attribute, including source address, destination address,
* transfer size, address offset, and so on. It also configures the scatter gather feature if the
* user supplies the TCD address.
* Example:
* @code
* edma_transfer_t config;
* edma_tcd_t tcd;
* config.srcAddr = ..;
* config.destAddr = ..;
* ...
* EDMA_SetTransferConfig(DMA0, channel, &config, &stcd);
* @endcode
*
* @param base eDMA peripheral base address.
* @param channel eDMA channel number.
* @param config Pointer to eDMA transfer configuration structure.
* @param nextTcd Point to TCD structure. It can be NULL if users
* do not want to enable scatter/gather feature.
* @note If nextTcd is not NULL, it means scatter gather feature is enabled
* and DREQ bit is cleared in the previous transfer configuration, which
* is set in eDMA_ResetChannel.
*/
void EDMA_SetTransferConfig(DMA_Type *base,
uint32_t channel,
const edma_transfer_config_t *config,
edma_tcd_t *nextTcd);
/*!
* @brief Configures the eDMA minor offset feature.
*
* Minor offset means signed-extended value added to source address or destination
* address after each minor loop.
*
* @param base eDMA peripheral base address.
* @param channel eDMA channel number.
* @param config Pointer to Minor offset configuration structure.
*/
void EDMA_SetMinorOffsetConfig(DMA_Type *base, uint32_t channel, const edma_minor_offset_config_t *config);
/*!
* @brief Configures the eDMA channel preemption feature.
*
* This function configures the channel preemption attribute and the priority of the channel.
*
* @param base eDMA peripheral base address.
* @param channel eDMA channel number
* @param config Pointer to channel preemption configuration structure.
*/
static inline void EDMA_SetChannelPreemptionConfig(DMA_Type *base,
uint32_t channel,
const edma_channel_Preemption_config_t *config)
{
assert(channel < FSL_FEATURE_EDMA_MODULE_CHANNEL);
assert(config != NULL);
DMA_DCHPRIn(base, channel) =
(DMA_DCHPRI0_DPA(!config->enablePreemptAbility) | DMA_DCHPRI0_ECP(config->enableChannelPreemption) |
DMA_DCHPRI0_CHPRI(config->channelPriority));
}
/*!
* @brief Sets the channel link for the eDMA transfer.
*
* This function configures minor link or major link mode. The minor link means that the channel link is
* triggered every time CITER decreases by 1. The major link means that the channel link is triggered when the CITER is
* exhausted.
*
* @param base eDMA peripheral base address.
* @param channel eDMA channel number.
* @param type Channel link type, it can be one of:
* @arg kEDMA_LinkNone
* @arg kEDMA_MinorLink
* @arg kEDMA_MajorLink
* @param linkedChannel The linked channel number.
* @note Users should ensure that DONE flag is cleared before calling this interface, or the configuration is invalid.
*/
void EDMA_SetChannelLink(DMA_Type *base, uint32_t channel, edma_channel_link_type_t type, uint32_t linkedChannel);
/*!
* @brief Sets the bandwidth for the eDMA transfer.
*
* In general, because the eDMA processes the minor loop, it continuously generates read/write sequences
* until the minor count is exhausted. The bandwidth forces the eDMA to stall after the completion of
* each read/write access to control the bus request bandwidth seen by the crossbar switch.
*
* @param base eDMA peripheral base address.
* @param channel eDMA channel number.
* @param bandWidth Bandwidth setting, it can be one of:
* @arg kEDMABandwidthStallNone
* @arg kEDMABandwidthStall4Cycle
* @arg kEDMABandwidthStall8Cycle
*/
void EDMA_SetBandWidth(DMA_Type *base, uint32_t channel, edma_bandwidth_t bandWidth);
/*!
* @brief Sets the source modulo and destination modulo for eDMA transfer.
*
* This function defines a specific address range specified to be the value after (SADDR + SOFF)/(DADDR + DOFF)
* calculation is performed or the original register value. It provides the ability to implement a circular data
* queue easily.
*
* @param base eDMA peripheral base address.
* @param channel eDMA channel number.
* @param srcModulo Source modulo value.
* @param destModulo Destination modulo value.
*/
void EDMA_SetModulo(DMA_Type *base, uint32_t channel, edma_modulo_t srcModulo, edma_modulo_t destModulo);
#if defined(FSL_FEATURE_EDMA_ASYNCHRO_REQUEST_CHANNEL_COUNT) && FSL_FEATURE_EDMA_ASYNCHRO_REQUEST_CHANNEL_COUNT
/*!
* @brief Enables an async request for the eDMA transfer.
*
* @param base eDMA peripheral base address.
* @param channel eDMA channel number.
* @param enable The command for enable(ture) or disable(false).
*/
static inline void EDMA_EnableAsyncRequest(DMA_Type *base, uint32_t channel, bool enable)
{
assert(channel < FSL_FEATURE_DMAMUX_MODULE_CHANNEL);
base->EARS = (base->EARS & (~(1U << channel))) | ((uint32_t)enable << channel);
}
#endif /* FSL_FEATURE_EDMA_ASYNCHRO_REQUEST_CHANNEL_COUNT */
/*!
* @brief Enables an auto stop request for the eDMA transfer.
*
* If enabling the auto stop request, the eDMA hardware automatically disables the hardware channel request.
*
* @param base eDMA peripheral base address.
* @param channel eDMA channel number.
* @param enable The command for enable (true) or disable (false).
*/
static inline void EDMA_EnableAutoStopRequest(DMA_Type *base, uint32_t channel, bool enable)
{
assert(channel < FSL_FEATURE_DMAMUX_MODULE_CHANNEL);
base->TCD[channel].CSR = (base->TCD[channel].CSR & (~DMA_CSR_DREQ_MASK)) | DMA_CSR_DREQ(enable);
}
/*!
* @brief Enables the interrupt source for the eDMA transfer.
*
* @param base eDMA peripheral base address.
* @param channel eDMA channel number.
* @param mask The mask of interrupt source to be set. Users need to use
* the defined edma_interrupt_enable_t type.
*/
void EDMA_EnableChannelInterrupts(DMA_Type *base, uint32_t channel, uint32_t mask);
/*!
* @brief Disables the interrupt source for the eDMA transfer.
*
* @param base eDMA peripheral base address.
* @param channel eDMA channel number.
* @param mask The mask of interrupt source to be set. Use
* the defined edma_interrupt_enable_t type.
*/
void EDMA_DisableChannelInterrupts(DMA_Type *base, uint32_t channel, uint32_t mask);
/* @} */
/*!
* @name eDMA TCD Operation
* @{
*/
/*!
* @brief Sets all fields to default values for the TCD structure.
*
* This function sets all fields for this TCD structure to default value.
*
* @param tcd Pointer to the TCD structure.
* @note This function enables the auto stop request feature.
*/
void EDMA_TcdReset(edma_tcd_t *tcd);
/*!
* @brief Configures the eDMA TCD transfer attribute.
*
* TCD is a transfer control descriptor. The content of the TCD is the same as hardware TCD registers.
* STCD is used in scatter-gather mode.
* This function configures the TCD transfer attribute, including source address, destination address,
* transfer size, address offset, and so on. It also configures the scatter gather feature if the
* user supplies the next TCD address.
* Example:
* @code
* edma_transfer_t config = {
* ...
* }
* edma_tcd_t tcd __aligned(32);
* edma_tcd_t nextTcd __aligned(32);
* EDMA_TcdSetTransferConfig(&tcd, &config, &nextTcd);
* @endcode
*
* @param tcd Pointer to the TCD structure.
* @param config Pointer to eDMA transfer configuration structure.
* @param nextTcd Pointer to the next TCD structure. It can be NULL if users
* do not want to enable scatter/gather feature.
* @note TCD address should be 32 bytes aligned, or it causes an eDMA error.
* @note If the nextTcd is not NULL, the scatter gather feature is enabled
* and DREQ bit is cleared in the previous transfer configuration, which
* is set in the EDMA_TcdReset.
*/
void EDMA_TcdSetTransferConfig(edma_tcd_t *tcd, const edma_transfer_config_t *config, edma_tcd_t *nextTcd);
/*!
* @brief Configures the eDMA TCD minor offset feature.
*
* Minor offset is a signed-extended value added to the source address or destination
* address after each minor loop.
*
* @param tcd Point to the TCD structure.
* @param config Pointer to Minor offset configuration structure.
*/
void EDMA_TcdSetMinorOffsetConfig(edma_tcd_t *tcd, const edma_minor_offset_config_t *config);
/*!
* @brief Sets the channel link for eDMA TCD.
*
* This function configures either a minor link or a major link. The minor link means the channel link is
* triggered every time CITER decreases by 1. The major link means that the channel link is triggered when the CITER is
* exhausted.
*
* @note Users should ensure that DONE flag is cleared before calling this interface, or the configuration is invalid.
* @param tcd Point to the TCD structure.
* @param type Channel link type, it can be one of:
* @arg kEDMA_LinkNone
* @arg kEDMA_MinorLink
* @arg kEDMA_MajorLink
* @param linkedChannel The linked channel number.
*/
void EDMA_TcdSetChannelLink(edma_tcd_t *tcd, edma_channel_link_type_t type, uint32_t linkedChannel);
/*!
* @brief Sets the bandwidth for the eDMA TCD.
*
* In general, because the eDMA processes the minor loop, it continuously generates read/write sequences
* until the minor count is exhausted. Bandwidth forces the eDMA to stall after the completion of
* each read/write access to control the bus request bandwidth seen by the crossbar switch.
* @param tcd Point to the TCD structure.
* @param bandWidth Bandwidth setting, it can be one of:
* @arg kEDMABandwidthStallNone
* @arg kEDMABandwidthStall4Cycle
* @arg kEDMABandwidthStall8Cycle
*/
static inline void EDMA_TcdSetBandWidth(edma_tcd_t *tcd, edma_bandwidth_t bandWidth)
{
assert(tcd != NULL);
assert(((uint32_t)tcd & 0x1FU) == 0);
tcd->CSR = (tcd->CSR & (~DMA_CSR_BWC_MASK)) | DMA_CSR_BWC(bandWidth);
}
/*!
* @brief Sets the source modulo and destination modulo for eDMA TCD.
*
* This function defines a specific address range specified to be the value after (SADDR + SOFF)/(DADDR + DOFF)
* calculation is performed or the original register value. It provides the ability to implement a circular data
* queue easily.
*
* @param tcd Point to the TCD structure.
* @param srcModulo Source modulo value.
* @param destModulo Destination modulo value.
*/
void EDMA_TcdSetModulo(edma_tcd_t *tcd, edma_modulo_t srcModulo, edma_modulo_t destModulo);
/*!
* @brief Sets the auto stop request for the eDMA TCD.
*
* If enabling the auto stop request, the eDMA hardware automatically disables the hardware channel request.
*
* @param tcd Point to the TCD structure.
* @param enable The command for enable(ture) or disable(false).
*/
static inline void EDMA_TcdEnableAutoStopRequest(edma_tcd_t *tcd, bool enable)
{
assert(tcd != NULL);
assert(((uint32_t)tcd & 0x1FU) == 0);
tcd->CSR = (tcd->CSR & (~DMA_CSR_DREQ_MASK)) | DMA_CSR_DREQ(enable);
}
/*!
* @brief Enables the interrupt source for the eDMA TCD.
*
* @param tcd Point to the TCD structure.
* @param mask The mask of interrupt source to be set. Users need to use
* the defined edma_interrupt_enable_t type.
*/
void EDMA_TcdEnableInterrupts(edma_tcd_t *tcd, uint32_t mask);
/*!
* @brief Disables the interrupt source for the eDMA TCD.
*
* @param tcd Point to the TCD structure.
* @param mask The mask of interrupt source to be set. Users need to use
* the defined edma_interrupt_enable_t type.
*/
void EDMA_TcdDisableInterrupts(edma_tcd_t *tcd, uint32_t mask);
/*! @} */
/*!
* @name eDMA Channel Transfer Operation
* @{
*/
/*!
* @brief Enables the eDMA hardware channel request.
*
* This function enables the hardware channel request.
*
* @param base eDMA peripheral base address.
* @param channel eDMA channel number.
*/
static inline void EDMA_EnableChannelRequest(DMA_Type *base, uint32_t channel)
{
assert(channel < FSL_FEATURE_DMAMUX_MODULE_CHANNEL);
base->SERQ = DMA_SERQ_SERQ(channel);
}
/*!
* @brief Disables the eDMA hardware channel request.
*
* This function disables the hardware channel request.
*
* @param base eDMA peripheral base address.
* @param channel eDMA channel number.
*/
static inline void EDMA_DisableChannelRequest(DMA_Type *base, uint32_t channel)
{
assert(channel < FSL_FEATURE_DMAMUX_MODULE_CHANNEL);
base->CERQ = DMA_CERQ_CERQ(channel);
}
/*!
* @brief Starts the eDMA transfer by software trigger.
*
* This function starts a minor loop transfer.
*
* @param base eDMA peripheral base address.
* @param channel eDMA channel number.
*/
static inline void EDMA_TriggerChannelStart(DMA_Type *base, uint32_t channel)
{
assert(channel < FSL_FEATURE_DMAMUX_MODULE_CHANNEL);
base->SSRT = DMA_SSRT_SSRT(channel);
}
/*! @} */
/*!
* @name eDMA Channel Status Operation
* @{
*/
/*!
* @brief Gets the Remaining bytes from the eDMA current channel TCD.
*
* This function checks the TCD (Task Control Descriptor) status for a specified
* eDMA channel and returns the the number of bytes that have not finished.
*
* @param base eDMA peripheral base address.
* @param channel eDMA channel number.
* @return Bytes have not been transferred yet for the current TCD.
* @note This function can only be used to get unfinished bytes of transfer without
* the next TCD, or it might be inaccuracy.
*/
uint32_t EDMA_GetRemainingBytes(DMA_Type *base, uint32_t channel);
/*!
* @brief Gets the eDMA channel error status flags.
*
* @param base eDMA peripheral base address.
* @return The mask of error status flags. Users need to use the
* _edma_error_status_flags type to decode the return variables.
*/
static inline uint32_t EDMA_GetErrorStatusFlags(DMA_Type *base)
{
return base->ES;
}
/*!
* @brief Gets the eDMA channel status flags.
*
* @param base eDMA peripheral base address.
* @param channel eDMA channel number.
* @return The mask of channel status flags. Users need to use the
* _edma_channel_status_flags type to decode the return variables.
*/
uint32_t EDMA_GetChannelStatusFlags(DMA_Type *base, uint32_t channel);
/*!
* @brief Clears the eDMA channel status flags.
*
* @param base eDMA peripheral base address.
* @param channel eDMA channel number.
* @param mask The mask of channel status to be cleared. Users need to use
* the defined _edma_channel_status_flags type.
*/
void EDMA_ClearChannelStatusFlags(DMA_Type *base, uint32_t channel, uint32_t mask);
/*! @} */
/*!
* @name eDMA Transactional Operation
*/
/*!
* @brief Creates the eDMA handle.
*
* This function is called if using transaction API for eDMA. This function
* initializes the internal state of eDMA handle.
*
* @param handle eDMA handle pointer. The eDMA handle stores callback function and
* parameters.
* @param base eDMA peripheral base address.
* @param channel eDMA channel number.
*/
void EDMA_CreateHandle(edma_handle_t *handle, DMA_Type *base, uint32_t channel);
/*!
* @brief Installs the TCDs memory pool into eDMA handle.
*
* This function is called after the EDMA_CreateHandle to use scatter/gather feature.
*
* @param handle eDMA handle pointer.
* @param tcdPool Memory pool to store TCDs. It must be 32 bytes aligned.
* @param tcdSize The number of TCD slots.
*/
void EDMA_InstallTCDMemory(edma_handle_t *handle, edma_tcd_t *tcdPool, uint32_t tcdSize);
/*!
* @brief Installs a callback function for the eDMA transfer.
*
* This callback is called in eDMA IRQ handler. Use the callback to do something after
* the current major loop transfer completes.
*
* @param handle eDMA handle pointer.
* @param callback eDMA callback function pointer.
* @param userData Parameter for callback function.
*/
void EDMA_SetCallback(edma_handle_t *handle, edma_callback callback, void *userData);
/*!
* @brief Prepares the eDMA transfer structure.
*
* This function prepares the transfer configuration structure according to the user input.
*
* @param config The user configuration structure of type edma_transfer_t.
* @param srcAddr eDMA transfer source address.
* @param srcWidth eDMA transfer source address width(bytes).
* @param destAddr eDMA transfer destination address.
* @param destWidth eDMA transfer destination address width(bytes).
* @param bytesEachRequest eDMA transfer bytes per channel request.
* @param transferBytes eDMA transfer bytes to be transferred.
* @param type eDMA transfer type.
* @note The data address and the data width must be consistent. For example, if the SRC
* is 4 bytes, so the source address must be 4 bytes aligned, or it shall result in
* source address error(SAE).
*/
void EDMA_PrepareTransfer(edma_transfer_config_t *config,
void *srcAddr,
uint32_t srcWidth,
void *destAddr,
uint32_t destWidth,
uint32_t bytesEachRequest,
uint32_t transferBytes,
edma_transfer_type_t type);
/*!
* @brief Submits the eDMA transfer request.
*
* This function submits the eDMA transfer request according to the transfer configuration structure.
* If the user submits the transfer request repeatedly, this function packs an unprocessed request as
* a TCD and enables scatter/gather feature to process it in the next time.
*
* @param handle eDMA handle pointer.
* @param config Pointer to eDMA transfer configuration structure.
* @retval kStatus_EDMA_Success It means submit transfer request succeed.
* @retval kStatus_EDMA_QueueFull It means TCD queue is full. Submit transfer request is not allowed.
* @retval kStatus_EDMA_Busy It means the given channel is busy, need to submit request later.
*/
status_t EDMA_SubmitTransfer(edma_handle_t *handle, const edma_transfer_config_t *config);
/*!
* @brief eDMA start transfer.
*
* This function enables the channel request. Users can call this function after submitting the transfer request
* or before submitting the transfer request.
*
* @param handle eDMA handle pointer.
*/
void EDMA_StartTransfer(edma_handle_t *handle);
/*!
* @brief eDMA stop transfer.
*
* This function disables the channel request to pause the transfer. Users can call EDMA_StartTransfer()
* again to resume the transfer.
*
* @param handle eDMA handle pointer.
*/
void EDMA_StopTransfer(edma_handle_t *handle);
/*!
* @brief eDMA abort transfer.
*
* This function disables the channel request and clear transfer status bits.
* Users can submit another transfer after calling this API.
*
* @param handle DMA handle pointer.
*/
void EDMA_AbortTransfer(edma_handle_t *handle);
/*!
* @brief eDMA IRQ handler for current major loop transfer complete.
*
* This function clears the channel major interrupt flag and call
* the callback function if it is not NULL.
*
* @param handle eDMA handle pointer.
*/
void EDMA_HandleIRQ(edma_handle_t *handle);
/* @} */
#if defined(__cplusplus)
}
#endif /* __cplusplus */
/* @} */
#endif /*_FSL_EDMA_H_*/

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,179 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include "fsl_gpio.h"
/*******************************************************************************
* Variables
******************************************************************************/
static PORT_Type *const s_portBases[] = PORT_BASE_PTRS;
static GPIO_Type *const s_gpioBases[] = GPIO_BASE_PTRS;
/*******************************************************************************
* Prototypes
******************************************************************************/
/*!
* @brief Gets the GPIO instance according to the GPIO base
*
* @param base GPIO peripheral base pointer(PTA, PTB, PTC, etc.)
* @retval GPIO instance
*/
static uint32_t GPIO_GetInstance(GPIO_Type *base);
/*******************************************************************************
* Code
******************************************************************************/
static uint32_t GPIO_GetInstance(GPIO_Type *base)
{
uint32_t instance;
/* Find the instance index from base address mappings. */
for (instance = 0; instance < FSL_FEATURE_SOC_GPIO_COUNT; instance++)
{
if (s_gpioBases[instance] == base)
{
break;
}
}
assert(instance < FSL_FEATURE_SOC_GPIO_COUNT);
return instance;
}
void GPIO_PinInit(GPIO_Type *base, uint32_t pin, const gpio_pin_config_t *config)
{
assert(config);
if (config->pinDirection == kGPIO_DigitalInput)
{
base->PDDR &= ~(1U << pin);
}
else
{
GPIO_WritePinOutput(base, pin, config->outputLogic);
base->PDDR |= (1U << pin);
}
}
uint32_t GPIO_GetPinsInterruptFlags(GPIO_Type *base)
{
uint8_t instance;
PORT_Type *portBase;
instance = GPIO_GetInstance(base);
portBase = s_portBases[instance];
return portBase->ISFR;
}
void GPIO_ClearPinsInterruptFlags(GPIO_Type *base, uint32_t mask)
{
uint8_t instance;
PORT_Type *portBase;
instance = GPIO_GetInstance(base);
portBase = s_portBases[instance];
portBase->ISFR = mask;
}
#if defined(FSL_FEATURE_SOC_FGPIO_COUNT) && FSL_FEATURE_SOC_FGPIO_COUNT
/*******************************************************************************
* Variables
******************************************************************************/
static FGPIO_Type *const s_fgpioBases[] = FGPIO_BASE_PTRS;
/*******************************************************************************
* Prototypes
******************************************************************************/
/*!
* @brief Gets the FGPIO instance according to the GPIO base
*
* @param base FGPIO peripheral base pointer(PTA, PTB, PTC, etc.)
* @retval FGPIO instance
*/
static uint32_t FGPIO_GetInstance(FGPIO_Type *base);
/*******************************************************************************
* Code
******************************************************************************/
static uint32_t FGPIO_GetInstance(FGPIO_Type *base)
{
uint32_t instance;
/* Find the instance index from base address mappings. */
for (instance = 0; instance < FSL_FEATURE_SOC_FGPIO_COUNT; instance++)
{
if (s_fgpioBases[instance] == base)
{
break;
}
}
assert(instance < FSL_FEATURE_SOC_FGPIO_COUNT);
return instance;
}
void FGPIO_PinInit(FGPIO_Type *base, uint32_t pin, const gpio_pin_config_t *config)
{
assert(config);
if (config->pinDirection == kGPIO_DigitalInput)
{
base->PDDR &= ~(1U << pin);
}
else
{
FGPIO_WritePinOutput(base, pin, config->outputLogic);
base->PDDR |= (1U << pin);
}
}
uint32_t FGPIO_GetPinsInterruptFlags(FGPIO_Type *base)
{
uint8_t instance;
instance = FGPIO_GetInstance(base);
PORT_Type *portBase;
portBase = s_portBases[instance];
return portBase->ISFR;
}
void FGPIO_ClearPinsInterruptFlags(FGPIO_Type *base, uint32_t mask)
{
uint8_t instance;
instance = FGPIO_GetInstance(base);
PORT_Type *portBase;
portBase = s_portBases[instance];
portBase->ISFR = mask;
}
#endif /* FSL_FEATURE_SOC_FGPIO_COUNT */

View File

@ -0,0 +1,389 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SDRVL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _FSL_GPIO_H_
#define _FSL_GPIO_H_
#include "fsl_common.h"
/*!
* @addtogroup gpio
* @{
*/
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @name Driver version */
/*@{*/
/*! @brief GPIO driver version 2.1.0. */
#define FSL_GPIO_DRIVER_VERSION (MAKE_VERSION(2, 1, 0))
/*@}*/
/*! @brief GPIO direction definition*/
typedef enum _gpio_pin_direction
{
kGPIO_DigitalInput = 0U, /*!< Set current pin as digital input*/
kGPIO_DigitalOutput = 1U, /*!< Set current pin as digital output*/
} gpio_pin_direction_t;
/*!
* @brief The GPIO pin configuration structure.
*
* Every pin can only be configured as either output pin or input pin at a time.
* If configured as a input pin, then leave the outputConfig unused
* Note : In some use cases, the corresponding port property should be configured in advance
* with the PORT_SetPinConfig()
*/
typedef struct _gpio_pin_config
{
gpio_pin_direction_t pinDirection; /*!< GPIO direction, input or output */
/* Output configurations, please ignore if configured as a input one */
uint8_t outputLogic; /*!< Set default output logic, no use in input */
} gpio_pin_config_t;
/*! @} */
/*******************************************************************************
* API
******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif
/*!
* @addtogroup gpio_driver
* @{
*/
/*! @name GPIO Configuration */
/*@{*/
/*!
* @brief Initializes a GPIO pin used by the board.
*
* To initialize the GPIO, define a pin configuration, either input or output, in the user file.
* Then, call the GPIO_PinInit() function.
*
* This is an example to define an input pin or output pin configuration:
* @code
* // Define a digital input pin configuration,
* gpio_pin_config_t config =
* {
* kGPIO_DigitalInput,
* 0,
* }
* //Define a digital output pin configuration,
* gpio_pin_config_t config =
* {
* kGPIO_DigitalOutput,
* 0,
* }
* @endcode
*
* @param base GPIO peripheral base pointer(GPIOA, GPIOB, GPIOC, and so on.)
* @param pin GPIO port pin number
* @param config GPIO pin configuration pointer
*/
void GPIO_PinInit(GPIO_Type *base, uint32_t pin, const gpio_pin_config_t *config);
/*@}*/
/*! @name GPIO Output Operations */
/*@{*/
/*!
* @brief Sets the output level of the multiple GPIO pins to the logic 1 or 0.
*
* @param base GPIO peripheral base pointer(GPIOA, GPIOB, GPIOC, and so on.)
* @param pin GPIO pin number
* @param output GPIO pin output logic level.
* - 0: corresponding pin output low-logic level.
* - 1: corresponding pin output high-logic level.
*/
static inline void GPIO_WritePinOutput(GPIO_Type *base, uint32_t pin, uint8_t output)
{
if (output == 0U)
{
base->PCOR = 1 << pin;
}
else
{
base->PSOR = 1 << pin;
}
}
/*!
* @brief Sets the output level of the multiple GPIO pins to the logic 1.
*
* @param base GPIO peripheral base pointer(GPIOA, GPIOB, GPIOC, and so on.)
* @param mask GPIO pin number macro
*/
static inline void GPIO_SetPinsOutput(GPIO_Type *base, uint32_t mask)
{
base->PSOR = mask;
}
/*!
* @brief Sets the output level of the multiple GPIO pins to the logic 0.
*
* @param base GPIO peripheral base pointer(GPIOA, GPIOB, GPIOC, and so on.)
* @param mask GPIO pin number macro
*/
static inline void GPIO_ClearPinsOutput(GPIO_Type *base, uint32_t mask)
{
base->PCOR = mask;
}
/*!
* @brief Reverses current output logic of the multiple GPIO pins.
*
* @param base GPIO peripheral base pointer(GPIOA, GPIOB, GPIOC, and so on.)
* @param mask GPIO pin number macro
*/
static inline void GPIO_TogglePinsOutput(GPIO_Type *base, uint32_t mask)
{
base->PTOR = mask;
}
/*@}*/
/*! @name GPIO Input Operations */
/*@{*/
/*!
* @brief Reads the current input value of the whole GPIO port.
*
* @param base GPIO peripheral base pointer(GPIOA, GPIOB, GPIOC, and so on.)
* @param pin GPIO pin number
* @retval GPIO port input value
* - 0: corresponding pin input low-logic level.
* - 1: corresponding pin input high-logic level.
*/
static inline uint32_t GPIO_ReadPinInput(GPIO_Type *base, uint32_t pin)
{
return (((base->PDIR) >> pin) & 0x01U);
}
/*@}*/
/*! @name GPIO Interrupt */
/*@{*/
/*!
* @brief Reads whole GPIO port interrupt status flag.
*
* If a pin is configured to generate the DMA request, the corresponding flag
* is cleared automatically at the completion of the requested DMA transfer.
* Otherwise, the flag remains set until a logic one is written to that flag.
* If configured for a level sensitive interrupt that remains asserted, the flag
* is set again immediately.
*
* @param base GPIO peripheral base pointer(GPIOA, GPIOB, GPIOC, and so on.)
* @retval Current GPIO port interrupt status flag, for example, 0x00010001 means the
* pin 0 and 17 have the interrupt.
*/
uint32_t GPIO_GetPinsInterruptFlags(GPIO_Type *base);
/*!
* @brief Clears multiple GPIO pin interrupt status flag.
*
* @param base GPIO peripheral base pointer(GPIOA, GPIOB, GPIOC, and so on.)
* @param mask GPIO pin number macro
*/
void GPIO_ClearPinsInterruptFlags(GPIO_Type *base, uint32_t mask);
/*@}*/
/*! @} */
/*!
* @addtogroup fgpio_driver
* @{
*/
/*
* Introduce the FGPIO feature.
*
* The FGPIO features are only support on some of Kinetis chips. The FGPIO registers are aliased to the IOPORT
* interface. Accesses via the IOPORT interface occur in parallel with any instruction fetches and will therefore
* complete in a single cycle. This aliased Fast GPIO memory map is called FGPIO.
*/
#if defined(FSL_FEATURE_SOC_FGPIO_COUNT) && FSL_FEATURE_SOC_FGPIO_COUNT
/*! @name FGPIO Configuration */
/*@{*/
/*!
* @brief Initializes a FGPIO pin used by the board.
*
* To initialize the FGPIO driver, define a pin configuration, either input or output, in the user file.
* Then, call the FGPIO_PinInit() function.
*
* This is an example to define an input pin or output pin configuration:
* @code
* // Define a digital input pin configuration,
* gpio_pin_config_t config =
* {
* kGPIO_DigitalInput,
* 0,
* }
* //Define a digital output pin configuration,
* gpio_pin_config_t config =
* {
* kGPIO_DigitalOutput,
* 0,
* }
* @endcode
*
* @param base FGPIO peripheral base pointer(GPIOA, GPIOB, GPIOC, and so on.)
* @param pin FGPIO port pin number
* @param config FGPIO pin configuration pointer
*/
void FGPIO_PinInit(FGPIO_Type *base, uint32_t pin, const gpio_pin_config_t *config);
/*@}*/
/*! @name FGPIO Output Operations */
/*@{*/
/*!
* @brief Sets the output level of the multiple FGPIO pins to the logic 1 or 0.
*
* @param base FGPIO peripheral base pointer(GPIOA, GPIOB, GPIOC, and so on.)
* @param pin FGPIO pin number
* @param output FGPIOpin output logic level.
* - 0: corresponding pin output low-logic level.
* - 1: corresponding pin output high-logic level.
*/
static inline void FGPIO_WritePinOutput(FGPIO_Type *base, uint32_t pin, uint8_t output)
{
if (output == 0U)
{
base->PCOR = 1 << pin;
}
else
{
base->PSOR = 1 << pin;
}
}
/*!
* @brief Sets the output level of the multiple FGPIO pins to the logic 1.
*
* @param base FGPIO peripheral base pointer(GPIOA, GPIOB, GPIOC, and so on.)
* @param mask FGPIO pin number macro
*/
static inline void FGPIO_SetPinsOutput(FGPIO_Type *base, uint32_t mask)
{
base->PSOR = mask;
}
/*!
* @brief Sets the output level of the multiple FGPIO pins to the logic 0.
*
* @param base FGPIO peripheral base pointer(GPIOA, GPIOB, GPIOC, and so on.)
* @param mask FGPIO pin number macro
*/
static inline void FGPIO_ClearPinsOutput(FGPIO_Type *base, uint32_t mask)
{
base->PCOR = mask;
}
/*!
* @brief Reverses current output logic of the multiple FGPIO pins.
*
* @param base FGPIO peripheral base pointer(GPIOA, GPIOB, GPIOC, and so on.)
* @param mask FGPIO pin number macro
*/
static inline void FGPIO_TogglePinsOutput(FGPIO_Type *base, uint32_t mask)
{
base->PTOR = mask;
}
/*@}*/
/*! @name FGPIO Input Operations */
/*@{*/
/*!
* @brief Reads the current input value of the whole FGPIO port.
*
* @param base FGPIO peripheral base pointer(GPIOA, GPIOB, GPIOC, and so on.)
* @param pin FGPIO pin number
* @retval FGPIO port input value
* - 0: corresponding pin input low-logic level.
* - 1: corresponding pin input high-logic level.
*/
static inline uint32_t FGPIO_ReadPinInput(FGPIO_Type *base, uint32_t pin)
{
return (((base->PDIR) >> pin) & 0x01U);
}
/*@}*/
/*! @name FGPIO Interrupt */
/*@{*/
/*!
* @brief Reads the whole FGPIO port interrupt status flag.
*
* If a pin is configured to generate the DMA request, the corresponding flag
* is cleared automatically at the completion of the requested DMA transfer.
* Otherwise, the flag remains set until a logic one is written to that flag.
* If configured for a level sensitive interrupt that remains asserted, the flag
* is set again immediately.
*
* @param base FGPIO peripheral base pointer(GPIOA, GPIOB, GPIOC, and so on.)
* @retval Current FGPIO port interrupt status flags, for example, 0x00010001 means the
* pin 0 and 17 have the interrupt.
*/
uint32_t FGPIO_GetPinsInterruptFlags(FGPIO_Type *base);
/*!
* @brief Clears the multiple FGPIO pin interrupt status flag.
*
* @param base FGPIO peripheral base pointer(GPIOA, GPIOB, GPIOC, and so on.)
* @param mask FGPIO pin number macro
*/
void FGPIO_ClearPinsInterruptFlags(FGPIO_Type *base, uint32_t mask);
/*@}*/
#endif /* FSL_FEATURE_SOC_FGPIO_COUNT */
#if defined(__cplusplus)
}
#endif
/*!
* @}
*/
#endif /* _FSL_GPIO_H_*/

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,788 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _FSL_I2C_H_
#define _FSL_I2C_H_
#include "fsl_common.h"
/*!
* @addtogroup i2c_driver
* @{
*/
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @name Driver version */
/*@{*/
/*! @brief I2C driver version 2.0.1. */
#define FSL_I2C_DRIVER_VERSION (MAKE_VERSION(2, 0, 1))
/*@}*/
#if (defined(FSL_FEATURE_I2C_HAS_START_STOP_DETECT) && FSL_FEATURE_I2C_HAS_START_STOP_DETECT || \
defined(FSL_FEATURE_I2C_HAS_STOP_DETECT) && FSL_FEATURE_I2C_HAS_STOP_DETECT)
#define I2C_HAS_STOP_DETECT
#endif /* FSL_FEATURE_I2C_HAS_START_STOP_DETECT / FSL_FEATURE_I2C_HAS_STOP_DETECT */
/*! @brief I2C status return codes. */
enum _i2c_status
{
kStatus_I2C_Busy = MAKE_STATUS(kStatusGroup_I2C, 0), /*!< I2C is busy with current transfer. */
kStatus_I2C_Idle = MAKE_STATUS(kStatusGroup_I2C, 1), /*!< Bus is Idle. */
kStatus_I2C_Nak = MAKE_STATUS(kStatusGroup_I2C, 2), /*!< NAK received during transfer. */
kStatus_I2C_ArbitrationLost = MAKE_STATUS(kStatusGroup_I2C, 3), /*!< Arbitration lost during transfer. */
kStatus_I2C_Timeout = MAKE_STATUS(kStatusGroup_I2C, 4), /*!< Wait event timeout. */
};
/*!
* @brief I2C peripheral flags
*
* The following status register flags can be cleared:
* - #kI2C_ArbitrationLostFlag
* - #kI2C_IntPendingFlag
* - #kI2C_StartDetectFlag
* - #kI2C_StopDetectFlag
*
* @note These enumerations are meant to be OR'd together to form a bit mask.
*
*/
enum _i2c_flags
{
kI2C_ReceiveNakFlag = I2C_S_RXAK_MASK, /*!< I2C receive NAK flag. */
kI2C_IntPendingFlag = I2C_S_IICIF_MASK, /*!< I2C interrupt pending flag. */
kI2C_TransferDirectionFlag = I2C_S_SRW_MASK, /*!< I2C transfer direction flag. */
kI2C_RangeAddressMatchFlag = I2C_S_RAM_MASK, /*!< I2C range address match flag. */
kI2C_ArbitrationLostFlag = I2C_S_ARBL_MASK, /*!< I2C arbitration lost flag. */
kI2C_BusBusyFlag = I2C_S_BUSY_MASK, /*!< I2C bus busy flag. */
kI2C_AddressMatchFlag = I2C_S_IAAS_MASK, /*!< I2C address match flag. */
kI2C_TransferCompleteFlag = I2C_S_TCF_MASK, /*!< I2C transfer complete flag. */
#ifdef I2C_HAS_STOP_DETECT
kI2C_StopDetectFlag = I2C_FLT_STOPF_MASK << 8, /*!< I2C stop detect flag. */
#endif /* FSL_FEATURE_I2C_HAS_START_STOP_DETECT / FSL_FEATURE_I2C_HAS_STOP_DETECT */
#if defined(FSL_FEATURE_I2C_HAS_START_STOP_DETECT) && FSL_FEATURE_I2C_HAS_START_STOP_DETECT
kI2C_StartDetectFlag = I2C_FLT_STARTF_MASK << 8, /*!< I2C start detect flag. */
#endif /* FSL_FEATURE_I2C_HAS_START_STOP_DETECT */
};
/*! @brief I2C feature interrupt source. */
enum _i2c_interrupt_enable
{
kI2C_GlobalInterruptEnable = I2C_C1_IICIE_MASK, /*!< I2C global interrupt. */
#if defined(FSL_FEATURE_I2C_HAS_STOP_DETECT) && FSL_FEATURE_I2C_HAS_STOP_DETECT
kI2C_StopDetectInterruptEnable = I2C_FLT_STOPIE_MASK, /*!< I2C stop detect interrupt. */
#endif /* FSL_FEATURE_I2C_HAS_STOP_DETECT */
#if defined(FSL_FEATURE_I2C_HAS_START_STOP_DETECT) && FSL_FEATURE_I2C_HAS_START_STOP_DETECT
kI2C_StartStopDetectInterruptEnable = I2C_FLT_SSIE_MASK, /*!< I2C start&stop detect interrupt. */
#endif /* FSL_FEATURE_I2C_HAS_START_STOP_DETECT */
};
/*! @brief Direction of master and slave transfers. */
typedef enum _i2c_direction
{
kI2C_Write = 0x0U, /*!< Master transmit to slave. */
kI2C_Read = 0x1U, /*!< Master receive from slave. */
} i2c_direction_t;
/*! @brief Addressing mode. */
typedef enum _i2c_slave_address_mode
{
kI2C_Address7bit = 0x0U, /*!< 7-bit addressing mode. */
kI2C_RangeMatch = 0X2U, /*!< Range address match addressing mode. */
} i2c_slave_address_mode_t;
/*! @brief I2C transfer control flag. */
enum _i2c_master_transfer_flags
{
kI2C_TransferDefaultFlag = 0x0U, /*!< Transfer starts with a start signal, stops with a stop signal. */
kI2C_TransferNoStartFlag = 0x1U, /*!< Transfer starts without a start signal. */
kI2C_TransferRepeatedStartFlag = 0x2U, /*!< Transfer starts with a repeated start signal. */
kI2C_TransferNoStopFlag = 0x4U, /*!< Transfer ends without a stop signal. */
};
/*!
* @brief Set of events sent to the callback for nonblocking slave transfers.
*
* These event enumerations are used for two related purposes. First, a bit mask created by OR'ing together
* events is passed to I2C_SlaveTransferNonBlocking() in order to specify which events to enable.
* Then, when the slave callback is invoked, it is passed the current event through its @a transfer
* parameter.
*
* @note These enumerations are meant to be OR'd together to form a bit mask of events.
*/
typedef enum _i2c_slave_transfer_event
{
kI2C_SlaveAddressMatchEvent = 0x01U, /*!< Received the slave address after a start or repeated start. */
kI2C_SlaveTransmitEvent = 0x02U, /*!< Callback is requested to provide data to transmit
(slave-transmitter role). */
kI2C_SlaveReceiveEvent = 0x04U, /*!< Callback is requested to provide a buffer in which to place received
data (slave-receiver role). */
kI2C_SlaveTransmitAckEvent = 0x08U, /*!< Callback needs to either transmit an ACK or NACK. */
#if defined(FSL_FEATURE_I2C_HAS_START_STOP_DETECT) && FSL_FEATURE_I2C_HAS_START_STOP_DETECT
kI2C_SlaveStartEvent = 0x10U, /*!< A start/repeated start was detected. */
#endif
kI2C_SlaveCompletionEvent = 0x20U, /*!< A stop was detected or finished transfer, completing the transfer. */
/*! Bit mask of all available events. */
kI2C_SlaveAllEvents = kI2C_SlaveAddressMatchEvent | kI2C_SlaveTransmitEvent | kI2C_SlaveReceiveEvent |
#if defined(FSL_FEATURE_I2C_HAS_START_STOP_DETECT) && FSL_FEATURE_I2C_HAS_START_STOP_DETECT
kI2C_SlaveStartEvent |
#endif
kI2C_SlaveCompletionEvent,
} i2c_slave_transfer_event_t;
/*! @brief I2C master user configuration. */
typedef struct _i2c_master_config
{
bool enableMaster; /*!< Enables the I2C peripheral at initialization time. */
#if defined(FSL_FEATURE_I2C_HAS_HIGH_DRIVE_SELECTION) && FSL_FEATURE_I2C_HAS_HIGH_DRIVE_SELECTION
bool enableHighDrive; /*!< Controls the drive capability of the I2C pads. */
#endif
#if defined(FSL_FEATURE_I2C_HAS_STOP_HOLD_OFF) && FSL_FEATURE_I2C_HAS_STOP_HOLD_OFF
bool enableStopHold; /*!< Controls the stop hold enable. */
#endif
#if defined(FSL_FEATURE_I2C_HAS_DOUBLE_BUFFER_ENABLE) && FSL_FEATURE_I2C_HAS_DOUBLE_BUFFER_ENABLE
bool enableDoubleBuffering; /*!< Controls double buffer enable, notice that
enabling the double buffer disables the clock stretch. */
#endif
uint32_t baudRate_Bps; /*!< Baud rate configuration of I2C peripheral. */
uint8_t glitchFilterWidth; /*!< Controls the width of the glitch. */
} i2c_master_config_t;
/*! @brief I2C slave user configuration. */
typedef struct _i2c_slave_config
{
bool enableSlave; /*!< Enables the I2C peripheral at initialization time. */
bool enableGeneralCall; /*!< Enable general call addressing mode. */
bool enableWakeUp; /*!< Enables/disables waking up MCU from low-power mode. */
#if defined(FSL_FEATURE_I2C_HAS_HIGH_DRIVE_SELECTION) && FSL_FEATURE_I2C_HAS_HIGH_DRIVE_SELECTION
bool enableHighDrive; /*!< Controls the drive capability of the I2C pads. */
#endif
#if defined(FSL_FEATURE_I2C_HAS_DOUBLE_BUFFER_ENABLE) && FSL_FEATURE_I2C_HAS_DOUBLE_BUFFER_ENABLE
bool enableDoubleBuffering; /*!< Controls double buffer enable, notice that
enabling the double buffer disables the clock stretch. */
#endif
bool enableBaudRateCtl; /*!< Enables/disables independent slave baud rate on SCL in very fast I2C modes. */
uint16_t slaveAddress; /*!< Slave address configuration. */
uint16_t upperAddress; /*!< Maximum boundary slave address used in range matching mode. */
i2c_slave_address_mode_t addressingMode; /*!< Addressing mode configuration of i2c_slave_address_mode_config_t. */
} i2c_slave_config_t;
/*! @brief I2C master handle typedef. */
typedef struct _i2c_master_handle i2c_master_handle_t;
/*! @brief I2C master transfer callback typedef. */
typedef void (*i2c_master_transfer_callback_t)(I2C_Type *base,
i2c_master_handle_t *handle,
status_t status,
void *userData);
/*! @brief I2C slave handle typedef. */
typedef struct _i2c_slave_handle i2c_slave_handle_t;
/*! @brief I2C master transfer structure. */
typedef struct _i2c_master_transfer
{
uint32_t flags; /*!< Transfer flag which controls the transfer. */
uint8_t slaveAddress; /*!< 7-bit slave address. */
i2c_direction_t direction; /*!< Transfer direction, read or write. */
uint32_t subaddress; /*!< Sub address. Transferred MSB first. */
uint8_t subaddressSize; /*!< Size of command buffer. */
uint8_t *volatile data; /*!< Transfer buffer. */
volatile size_t dataSize; /*!< Transfer size. */
} i2c_master_transfer_t;
/*! @brief I2C master handle structure. */
struct _i2c_master_handle
{
i2c_master_transfer_t transfer; /*!< I2C master transfer copy. */
size_t transferSize; /*!< Total bytes to be transferred. */
uint8_t state; /*!< Transfer state maintained during transfer. */
i2c_master_transfer_callback_t completionCallback; /*!< Callback function called when transfer finished. */
void *userData; /*!< Callback parameter passed to callback function. */
};
/*! @brief I2C slave transfer structure. */
typedef struct _i2c_slave_transfer
{
i2c_slave_transfer_event_t event; /*!< Reason the callback is being invoked. */
uint8_t *volatile data; /*!< Transfer buffer. */
volatile size_t dataSize; /*!< Transfer size. */
status_t completionStatus; /*!< Success or error code describing how the transfer completed. Only applies for
#kI2C_SlaveCompletionEvent. */
size_t transferredCount; /*!< Number of bytes actually transferred since start or last repeated start. */
} i2c_slave_transfer_t;
/*! @brief I2C slave transfer callback typedef. */
typedef void (*i2c_slave_transfer_callback_t)(I2C_Type *base, i2c_slave_transfer_t *xfer, void *userData);
/*! @brief I2C slave handle structure. */
struct _i2c_slave_handle
{
bool isBusy; /*!< Whether transfer is busy. */
i2c_slave_transfer_t transfer; /*!< I2C slave transfer copy. */
uint32_t eventMask; /*!< Mask of enabled events. */
i2c_slave_transfer_callback_t callback; /*!< Callback function called at transfer event. */
void *userData; /*!< Callback parameter passed to callback. */
};
/*******************************************************************************
* API
******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif /*_cplusplus. */
/*!
* @name Initialization and deinitialization
* @{
*/
/*!
* @brief Initializes the I2C peripheral. Call this API to ungate the I2C clock
* and configure the I2C with master configuration.
*
* @note This API should be called at the beginning of the application to use
* the I2C driver, or any operation to the I2C module may cause a hard fault
* because clock is not enabled. The configuration structure can be filled by user
* from scratch, or be set with default values by I2C_MasterGetDefaultConfig().
* After calling this API, the master is ready to transfer.
* Example:
* @code
* i2c_master_config_t config = {
* .enableMaster = true,
* .enableStopHold = false,
* .highDrive = false,
* .baudRate_Bps = 100000,
* .glitchFilterWidth = 0
* };
* I2C_MasterInit(I2C0, &config, 12000000U);
* @endcode
*
* @param base I2C base pointer
* @param masterConfig pointer to master configuration structure
* @param srcClock_Hz I2C peripheral clock frequency in Hz
*/
void I2C_MasterInit(I2C_Type *base, const i2c_master_config_t *masterConfig, uint32_t srcClock_Hz);
/*!
* @brief Initializes the I2C peripheral. Call this API to ungate the I2C clock
* and initializes the I2C with slave configuration.
*
* @note This API should be called at the beginning of the application to use
* the I2C driver, or any operation to the I2C module can cause a hard fault
* because the clock is not enabled. The configuration structure can partly be set
* with default values by I2C_SlaveGetDefaultConfig(), or can be filled by the user.
* Example
* @code
* i2c_slave_config_t config = {
* .enableSlave = true,
* .enableGeneralCall = false,
* .addressingMode = kI2C_Address7bit,
* .slaveAddress = 0x1DU,
* .enableWakeUp = false,
* .enablehighDrive = false,
* .enableBaudRateCtl = false
* };
* I2C_SlaveInit(I2C0, &config);
* @endcode
*
* @param base I2C base pointer
* @param slaveConfig pointer to slave configuration structure
*/
void I2C_SlaveInit(I2C_Type *base, const i2c_slave_config_t *slaveConfig);
/*!
* @brief De-initializes the I2C master peripheral. Call this API to gate the I2C clock.
* The I2C master module can't work unless the I2C_MasterInit is called.
* @param base I2C base pointer
*/
void I2C_MasterDeinit(I2C_Type *base);
/*!
* @brief De-initializes the I2C slave peripheral. Calling this API gates the I2C clock.
* The I2C slave module can't work unless the I2C_SlaveInit is called to enable the clock.
* @param base I2C base pointer
*/
void I2C_SlaveDeinit(I2C_Type *base);
/*!
* @brief Sets the I2C master configuration structure to default values.
*
* The purpose of this API is to get the configuration structure initialized for use in the I2C_MasterConfigure().
* Use the initialized structure unchanged in I2C_MasterConfigure(), or modify some fields of
* the structure before calling I2C_MasterConfigure().
* Example:
* @code
* i2c_master_config_t config;
* I2C_MasterGetDefaultConfig(&config);
* @endcode
* @param masterConfig Pointer to the master configuration structure.
*/
void I2C_MasterGetDefaultConfig(i2c_master_config_t *masterConfig);
/*!
* @brief Sets the I2C slave configuration structure to default values.
*
* The purpose of this API is to get the configuration structure initialized for use in I2C_SlaveConfigure().
* Modify fields of the structure before calling the I2C_SlaveConfigure().
* Example:
* @code
* i2c_slave_config_t config;
* I2C_SlaveGetDefaultConfig(&config);
* @endcode
* @param slaveConfig Pointer to the slave configuration structure.
*/
void I2C_SlaveGetDefaultConfig(i2c_slave_config_t *slaveConfig);
/*!
* @brief Enables or disabless the I2C peripheral operation.
*
* @param base I2C base pointer
* @param enable pass true to enable module, false to disable module
*/
static inline void I2C_Enable(I2C_Type *base, bool enable)
{
if (enable)
{
base->C1 |= I2C_C1_IICEN_MASK;
}
else
{
base->C1 &= ~I2C_C1_IICEN_MASK;
}
}
/* @} */
/*!
* @name Status
* @{
*/
/*!
* @brief Gets the I2C status flags.
*
* @param base I2C base pointer
* @return status flag, use status flag to AND #_i2c_flags to get the related status.
*/
uint32_t I2C_MasterGetStatusFlags(I2C_Type *base);
/*!
* @brief Gets the I2C status flags.
*
* @param base I2C base pointer
* @return status flag, use status flag to AND #_i2c_flags to get the related status.
*/
static inline uint32_t I2C_SlaveGetStatusFlags(I2C_Type *base)
{
return I2C_MasterGetStatusFlags(base);
}
/*!
* @brief Clears the I2C status flag state.
*
* The following status register flags can be cleared: kI2C_ArbitrationLostFlag and kI2C_IntPendingFlag
*
* @param base I2C base pointer
* @param statusMask The status flag mask, defined in type i2c_status_flag_t.
* The parameter can be any combination of the following values:
* @arg kI2C_StartDetectFlag (if available)
* @arg kI2C_StopDetectFlag (if available)
* @arg kI2C_ArbitrationLostFlag
* @arg kI2C_IntPendingFlagFlag
*/
static inline void I2C_MasterClearStatusFlags(I2C_Type *base, uint32_t statusMask)
{
/* Must clear the STARTF / STOPF bits prior to clearing IICIF */
#if defined(FSL_FEATURE_I2C_HAS_START_STOP_DETECT) && FSL_FEATURE_I2C_HAS_START_STOP_DETECT
if (statusMask & kI2C_StartDetectFlag)
{
/* Shift the odd-ball flags back into place. */
base->FLT |= (uint8_t)(statusMask >> 8U);
}
#endif
#ifdef I2C_HAS_STOP_DETECT
if (statusMask & kI2C_StopDetectFlag)
{
/* Shift the odd-ball flags back into place. */
base->FLT |= (uint8_t)(statusMask >> 8U);
}
#endif
base->S = (uint8_t)statusMask;
}
/*!
* @brief Clears the I2C status flag state.
*
* The following status register flags can be cleared: kI2C_ArbitrationLostFlag and kI2C_IntPendingFlag
*
* @param base I2C base pointer
* @param statusMask The status flag mask, defined in type i2c_status_flag_t.
* The parameter can be any combination of the following values:
* @arg kI2C_StartDetectFlag (if available)
* @arg kI2C_StopDetectFlag (if available)
* @arg kI2C_ArbitrationLostFlag
* @arg kI2C_IntPendingFlagFlag
*/
static inline void I2C_SlaveClearStatusFlags(I2C_Type *base, uint32_t statusMask)
{
I2C_MasterClearStatusFlags(base, statusMask);
}
/* @} */
/*!
* @name Interrupts
* @{
*/
/*!
* @brief Enables I2C interrupt requests.
*
* @param base I2C base pointer
* @param mask interrupt source
* The parameter can be combination of the following source if defined:
* @arg kI2C_GlobalInterruptEnable
* @arg kI2C_StopDetectInterruptEnable/kI2C_StartDetectInterruptEnable
* @arg kI2C_SdaTimeoutInterruptEnable
*/
void I2C_EnableInterrupts(I2C_Type *base, uint32_t mask);
/*!
* @brief Disables I2C interrupt requests.
*
* @param base I2C base pointer
* @param mask interrupt source
* The parameter can be combination of the following source if defined:
* @arg kI2C_GlobalInterruptEnable
* @arg kI2C_StopDetectInterruptEnable/kI2C_StartDetectInterruptEnable
* @arg kI2C_SdaTimeoutInterruptEnable
*/
void I2C_DisableInterrupts(I2C_Type *base, uint32_t mask);
/*!
* @name DMA Control
* @{
*/
#if defined(FSL_FEATURE_I2C_HAS_DMA_SUPPORT) && FSL_FEATURE_I2C_HAS_DMA_SUPPORT
/*!
* @brief Enables/disables the I2C DMA interrupt.
*
* @param base I2C base pointer
* @param enable true to enable, false to disable
*/
static inline void I2C_EnableDMA(I2C_Type *base, bool enable)
{
if (enable)
{
base->C1 |= I2C_C1_DMAEN_MASK;
}
else
{
base->C1 &= ~I2C_C1_DMAEN_MASK;
}
}
#endif /* FSL_FEATURE_I2C_HAS_DMA_SUPPORT */
/*!
* @brief Gets the I2C tx/rx data register address. This API is used to provide a transfer address
* for I2C DMA transfer configuration.
*
* @param base I2C base pointer
* @return data register address
*/
static inline uint32_t I2C_GetDataRegAddr(I2C_Type *base)
{
return (uint32_t)(&(base->D));
}
/* @} */
/*!
* @name Bus Operations
* @{
*/
/*!
* @brief Sets the I2C master transfer baud rate.
*
* @param base I2C base pointer
* @param baudRate_Bps the baud rate value in bps
* @param srcClock_Hz Source clock
*/
void I2C_MasterSetBaudRate(I2C_Type *base, uint32_t baudRate_Bps, uint32_t srcClock_Hz);
/*!
* @brief Sends a START on the I2C bus.
*
* This function is used to initiate a new master mode transfer by sending the START signal.
* The slave address is sent following the I2C START signal.
*
* @param base I2C peripheral base pointer
* @param address 7-bit slave device address.
* @param direction Master transfer directions(transmit/receive).
* @retval kStatus_Success Successfully send the start signal.
* @retval kStatus_I2C_Busy Current bus is busy.
*/
status_t I2C_MasterStart(I2C_Type *base, uint8_t address, i2c_direction_t direction);
/*!
* @brief Sends a STOP signal on the I2C bus.
*
* @retval kStatus_Success Successfully send the stop signal.
* @retval kStatus_I2C_Timeout Send stop signal failed, timeout.
*/
status_t I2C_MasterStop(I2C_Type *base);
/*!
* @brief Sends a REPEATED START on the I2C bus.
*
* @param base I2C peripheral base pointer
* @param address 7-bit slave device address.
* @param direction Master transfer directions(transmit/receive).
* @retval kStatus_Success Successfully send the start signal.
* @retval kStatus_I2C_Busy Current bus is busy but not occupied by current I2C master.
*/
status_t I2C_MasterRepeatedStart(I2C_Type *base, uint8_t address, i2c_direction_t direction);
/*!
* @brief Performs a polling send transaction on the I2C bus without a STOP signal.
*
* @param base The I2C peripheral base pointer.
* @param txBuff The pointer to the data to be transferred.
* @param txSize The length in bytes of the data to be transferred.
* @retval kStatus_Success Successfully complete the data transmission.
* @retval kStatus_I2C_ArbitrationLost Transfer error, arbitration lost.
* @retval kStataus_I2C_Nak Transfer error, receive NAK during transfer.
*/
status_t I2C_MasterWriteBlocking(I2C_Type *base, const uint8_t *txBuff, size_t txSize);
/*!
* @brief Performs a polling receive transaction on the I2C bus with a STOP signal.
*
* @note The I2C_MasterReadBlocking function stops the bus before reading the final byte.
* Without stopping the bus prior for the final read, the bus issues another read, resulting
* in garbage data being read into the data register.
*
* @param base I2C peripheral base pointer.
* @param rxBuff The pointer to the data to store the received data.
* @param rxSize The length in bytes of the data to be received.
* @retval kStatus_Success Successfully complete the data transmission.
* @retval kStatus_I2C_Timeout Send stop signal failed, timeout.
*/
status_t I2C_MasterReadBlocking(I2C_Type *base, uint8_t *rxBuff, size_t rxSize);
/*!
* @brief Performs a polling send transaction on the I2C bus.
*
* @param base The I2C peripheral base pointer.
* @param txBuff The pointer to the data to be transferred.
* @param txSize The length in bytes of the data to be transferred.
* @retval kStatus_Success Successfully complete the data transmission.
* @retval kStatus_I2C_ArbitrationLost Transfer error, arbitration lost.
* @retval kStataus_I2C_Nak Transfer error, receive NAK during transfer.
*/
status_t I2C_SlaveWriteBlocking(I2C_Type *base, const uint8_t *txBuff, size_t txSize);
/*!
* @brief Performs a polling receive transaction on the I2C bus.
*
* @param base I2C peripheral base pointer.
* @param rxBuff The pointer to the data to store the received data.
* @param rxSize The length in bytes of the data to be received.
*/
void I2C_SlaveReadBlocking(I2C_Type *base, uint8_t *rxBuff, size_t rxSize);
/*!
* @brief Performs a master polling transfer on the I2C bus.
*
* @note The API does not return until the transfer succeeds or fails due
* to arbitration lost or receiving a NAK.
*
* @param base I2C peripheral base address.
* @param xfer Pointer to the transfer structure.
* @retval kStatus_Success Successfully complete the data transmission.
* @retval kStatus_I2C_Busy Previous transmission still not finished.
* @retval kStatus_I2C_Timeout Transfer error, wait signal timeout.
* @retval kStatus_I2C_ArbitrationLost Transfer error, arbitration lost.
* @retval kStataus_I2C_Nak Transfer error, receive NAK during transfer.
*/
status_t I2C_MasterTransferBlocking(I2C_Type *base, i2c_master_transfer_t *xfer);
/* @} */
/*!
* @name Transactional
* @{
*/
/*!
* @brief Initializes the I2C handle which is used in transactional functions.
*
* @param base I2C base pointer.
* @param handle pointer to i2c_master_handle_t structure to store the transfer state.
* @param callback pointer to user callback function.
* @param userData user parameter passed to the callback function.
*/
void I2C_MasterTransferCreateHandle(I2C_Type *base,
i2c_master_handle_t *handle,
i2c_master_transfer_callback_t callback,
void *userData);
/*!
* @brief Performs a master interrupt non-blocking transfer on the I2C bus.
*
* @note Calling the API returns immediately after transfer initiates. The user needs
* to call I2C_MasterGetTransferCount to poll the transfer status to check whether
* the transfer is finished. If the return status is not kStatus_I2C_Busy, the transfer
* is finished.
*
* @param base I2C base pointer.
* @param handle pointer to i2c_master_handle_t structure which stores the transfer state.
* @param xfer pointer to i2c_master_transfer_t structure.
* @retval kStatus_Success Successfully start the data transmission.
* @retval kStatus_I2C_Busy Previous transmission still not finished.
* @retval kStatus_I2C_Timeout Transfer error, wait signal timeout.
*/
status_t I2C_MasterTransferNonBlocking(I2C_Type *base, i2c_master_handle_t *handle, i2c_master_transfer_t *xfer);
/*!
* @brief Gets the master transfer status during a interrupt non-blocking transfer.
*
* @param base I2C base pointer.
* @param handle pointer to i2c_master_handle_t structure which stores the transfer state.
* @param count Number of bytes transferred so far by the non-blocking transaction.
* @retval kStatus_InvalidArgument count is Invalid.
* @retval kStatus_Success Successfully return the count.
*/
status_t I2C_MasterTransferGetCount(I2C_Type *base, i2c_master_handle_t *handle, size_t *count);
/*!
* @brief Aborts an interrupt non-blocking transfer early.
*
* @note This API can be called at any time when an interrupt non-blocking transfer initiates
* to abort the transfer early.
*
* @param base I2C base pointer.
* @param handle pointer to i2c_master_handle_t structure which stores the transfer state
*/
void I2C_MasterTransferAbort(I2C_Type *base, i2c_master_handle_t *handle);
/*!
* @brief Master interrupt handler.
*
* @param base I2C base pointer.
* @param i2cHandle pointer to i2c_master_handle_t structure.
*/
void I2C_MasterTransferHandleIRQ(I2C_Type *base, void *i2cHandle);
/*!
* @brief Initializes the I2C handle which is used in transactional functions.
*
* @param base I2C base pointer.
* @param handle pointer to i2c_slave_handle_t structure to store the transfer state.
* @param callback pointer to user callback function.
* @param userData user parameter passed to the callback function.
*/
void I2C_SlaveTransferCreateHandle(I2C_Type *base,
i2c_slave_handle_t *handle,
i2c_slave_transfer_callback_t callback,
void *userData);
/*!
* @brief Starts accepting slave transfers.
*
* Call this API after calling the I2C_SlaveInit() and I2C_SlaveTransferCreateHandle() to start processing
* transactions driven by an I2C master. The slave monitors the I2C bus and passes events to the
* callback that was passed into the call to I2C_SlaveTransferCreateHandle(). The callback is always invoked
* from the interrupt context.
*
* The set of events received by the callback is customizable. To do so, set the @a eventMask parameter to
* the OR'd combination of #i2c_slave_transfer_event_t enumerators for the events you wish to receive.
* The #kI2C_SlaveTransmitEvent and #kLPI2C_SlaveReceiveEvent events are always enabled and do not need
* to be included in the mask. Alternatively, pass 0 to get a default set of only the transmit and
* receive events that are always enabled. In addition, the #kI2C_SlaveAllEvents constant is provided as
* a convenient way to enable all events.
*
* @param base The I2C peripheral base address.
* @param handle Pointer to #i2c_slave_handle_t structure which stores the transfer state.
* @param eventMask Bit mask formed by OR'ing together #i2c_slave_transfer_event_t enumerators to specify
* which events to send to the callback. Other accepted values are 0 to get a default set of
* only the transmit and receive events, and #kI2C_SlaveAllEvents to enable all events.
*
* @retval #kStatus_Success Slave transfers were successfully started.
* @retval #kStatus_I2C_Busy Slave transfers have already been started on this handle.
*/
status_t I2C_SlaveTransferNonBlocking(I2C_Type *base, i2c_slave_handle_t *handle, uint32_t eventMask);
/*!
* @brief Aborts the slave transfer.
*
* @note This API can be called at any time to stop slave for handling the bus events.
*
* @param base I2C base pointer.
* @param handle pointer to i2c_slave_handle_t structure which stores the transfer state.
*/
void I2C_SlaveTransferAbort(I2C_Type *base, i2c_slave_handle_t *handle);
/*!
* @brief Gets the slave transfer remaining bytes during a interrupt non-blocking transfer.
*
* @param base I2C base pointer.
* @param handle pointer to i2c_slave_handle_t structure.
* @param count Number of bytes transferred so far by the non-blocking transaction.
* @retval kStatus_InvalidArgument count is Invalid.
* @retval kStatus_Success Successfully return the count.
*/
status_t I2C_SlaveTransferGetCount(I2C_Type *base, i2c_slave_handle_t *handle, size_t *count);
/*!
* @brief Slave interrupt handler.
*
* @param base I2C base pointer.
* @param i2cHandle pointer to i2c_slave_handle_t structure which stores the transfer state
*/
void I2C_SlaveTransferHandleIRQ(I2C_Type *base, void *i2cHandle);
/* @} */
#if defined(__cplusplus)
}
#endif /*_cplusplus. */
/*@}*/
#endif /* _FSL_I2C_H_*/

View File

@ -0,0 +1,526 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include "fsl_i2c_edma.h"
/*******************************************************************************
* Definitions
******************************************************************************/
/*<! @breif Structure definition for i2c_master_edma_private_handle_t. The structure is private. */
typedef struct _i2c_master_edma_private_handle
{
I2C_Type *base;
i2c_master_edma_handle_t *handle;
} i2c_master_edma_private_handle_t;
/*! @brief i2c master DMA transfer state. */
enum _i2c_master_dma_transfer_states
{
kIdleState = 0x0U, /*!< I2C bus idle. */
kTransferDataState = 0x1U, /*!< 7-bit address check state. */
};
/*! @brief Common sets of flags used by the driver. */
enum _i2c_flag_constants
{
/*! All flags which are cleared by the driver upon starting a transfer. */
#if defined(FSL_FEATURE_I2C_HAS_START_STOP_DETECT) && FSL_FEATURE_I2C_HAS_START_STOP_DETECT
kClearFlags = kI2C_ArbitrationLostFlag | kI2C_IntPendingFlag | kI2C_StartDetectFlag | kI2C_StopDetectFlag,
#elif defined(FSL_FEATURE_I2C_HAS_STOP_DETECT) && FSL_FEATURE_I2C_HAS_STOP_DETECT
kClearFlags = kI2C_ArbitrationLostFlag | kI2C_IntPendingFlag | kI2C_StopDetectFlag,
#else
kClearFlags = kI2C_ArbitrationLostFlag | kI2C_IntPendingFlag,
#endif
};
/*******************************************************************************
* Prototypes
******************************************************************************/
/*!
* @brief EDMA callback for I2C master EDMA driver.
*
* @param handle EDMA handler for I2C master EDMA driver
* @param userData user param passed to the callback function
*/
static void I2C_MasterTransferCallbackEDMA(edma_handle_t *handle, void *userData, bool transferDone, uint32_t tcds);
/*!
* @brief Check and clear status operation.
*
* @param base I2C peripheral base address.
* @param status current i2c hardware status.
* @retval kStatus_Success No error found.
* @retval kStatus_I2C_ArbitrationLost Transfer error, arbitration lost.
* @retval kStatus_I2C_Nak Received Nak error.
*/
static status_t I2C_CheckAndClearError(I2C_Type *base, uint32_t status);
/*!
* @brief EDMA config for I2C master driver.
*
* @param base I2C peripheral base address.
* @param handle pointer to i2c_master_edma_handle_t structure which stores the transfer state
*/
static void I2C_MasterTransferEDMAConfig(I2C_Type *base, i2c_master_edma_handle_t *handle);
/*!
* @brief Set up master transfer, send slave address and sub address(if any), wait until the
* wait until address sent status return.
*
* @param base I2C peripheral base address.
* @param handle pointer to i2c_master_edma_handle_t structure which stores the transfer state
* @param xfer pointer to i2c_master_transfer_t structure
*/
static status_t I2C_InitTransferStateMachineEDMA(I2C_Type *base,
i2c_master_edma_handle_t *handle,
i2c_master_transfer_t *xfer);
/*!
* @brief Get the I2C instance from peripheral base address.
*
* @param base I2C peripheral base address.
* @return I2C instance.
*/
extern uint32_t I2C_GetInstance(I2C_Type *base);
/*******************************************************************************
* Variables
******************************************************************************/
/*<! Private handle only used for internally. */
static i2c_master_edma_private_handle_t s_edmaPrivateHandle[FSL_FEATURE_SOC_I2C_COUNT];
/*******************************************************************************
* Codes
******************************************************************************/
static void I2C_MasterTransferCallbackEDMA(edma_handle_t *handle, void *userData, bool transferDone, uint32_t tcds)
{
i2c_master_edma_private_handle_t *i2cPrivateHandle = (i2c_master_edma_private_handle_t *)userData;
status_t result = kStatus_Success;
/* Disable DMA. */
I2C_EnableDMA(i2cPrivateHandle->base, false);
/* Send stop if kI2C_TransferNoStop flag is not asserted. */
if (!(i2cPrivateHandle->handle->transfer.flags & kI2C_TransferNoStopFlag))
{
if (i2cPrivateHandle->handle->transfer.direction == kI2C_Read)
{
/* Change to send NAK at the last byte. */
i2cPrivateHandle->base->C1 |= I2C_C1_TXAK_MASK;
/* Wait the last data to be received. */
while (!(i2cPrivateHandle->base->S & kI2C_TransferCompleteFlag))
{
}
/* Send stop signal. */
result = I2C_MasterStop(i2cPrivateHandle->base);
/* Read the last data byte. */
*(i2cPrivateHandle->handle->transfer.data + i2cPrivateHandle->handle->transfer.dataSize - 1) =
i2cPrivateHandle->base->D;
}
else
{
/* Wait the last data to be sent. */
while (!(i2cPrivateHandle->base->S & kI2C_TransferCompleteFlag))
{
}
/* Send stop signal. */
result = I2C_MasterStop(i2cPrivateHandle->base);
}
}
i2cPrivateHandle->handle->state = kIdleState;
if (i2cPrivateHandle->handle->completionCallback)
{
i2cPrivateHandle->handle->completionCallback(i2cPrivateHandle->base, i2cPrivateHandle->handle, result,
i2cPrivateHandle->handle->userData);
}
}
static status_t I2C_CheckAndClearError(I2C_Type *base, uint32_t status)
{
status_t result = kStatus_Success;
/* Check arbitration lost. */
if (status & kI2C_ArbitrationLostFlag)
{
/* Clear arbitration lost flag. */
base->S = kI2C_ArbitrationLostFlag;
result = kStatus_I2C_ArbitrationLost;
}
/* Check NAK */
else if (status & kI2C_ReceiveNakFlag)
{
result = kStatus_I2C_Nak;
}
else
{
}
return result;
}
static status_t I2C_InitTransferStateMachineEDMA(I2C_Type *base,
i2c_master_edma_handle_t *handle,
i2c_master_transfer_t *xfer)
{
assert(handle);
assert(xfer);
status_t result = kStatus_Success;
uint16_t timeout = UINT16_MAX;
if (handle->state != kIdleState)
{
return kStatus_I2C_Busy;
}
else
{
i2c_direction_t direction = xfer->direction;
/* Init the handle member. */
handle->transfer = *xfer;
/* Save total transfer size. */
handle->transferSize = xfer->dataSize;
handle->state = kTransferDataState;
/* Wait until ready to complete. */
while ((!(base->S & kI2C_TransferCompleteFlag)) && (--timeout))
{
}
/* Failed to start the transfer. */
if (timeout == 0)
{
return kStatus_I2C_Timeout;
}
/* Clear all status before transfer. */
I2C_MasterClearStatusFlags(base, kClearFlags);
/* Change to send write address when it's a read operation with command. */
if ((xfer->subaddressSize > 0) && (xfer->direction == kI2C_Read))
{
direction = kI2C_Write;
}
/* If repeated start is requested, send repeated start. */
if (handle->transfer.flags & kI2C_TransferRepeatedStartFlag)
{
result = I2C_MasterRepeatedStart(base, handle->transfer.slaveAddress, direction);
}
else /* For normal transfer, send start. */
{
result = I2C_MasterStart(base, handle->transfer.slaveAddress, direction);
}
/* Send subaddress. */
if (handle->transfer.subaddressSize)
{
do
{
/* Wait until data transfer complete. */
while (!(base->S & kI2C_IntPendingFlag))
{
}
/* Clear interrupt pending flag. */
base->S = kI2C_IntPendingFlag;
handle->transfer.subaddressSize--;
base->D = ((handle->transfer.subaddress) >> (8 * handle->transfer.subaddressSize));
/* Check if there's transfer error. */
result = I2C_CheckAndClearError(base, base->S);
if (result)
{
return result;
}
} while ((handle->transfer.subaddressSize > 0) && (result == kStatus_Success));
if (handle->transfer.direction == kI2C_Read)
{
/* Wait until data transfer complete. */
while (!(base->S & kI2C_IntPendingFlag))
{
}
/* Clear pending flag. */
base->S = kI2C_IntPendingFlag;
/* Send repeated start and slave address. */
result = I2C_MasterRepeatedStart(base, handle->transfer.slaveAddress, kI2C_Read);
}
}
if (result)
{
return result;
}
/* Wait until data transfer complete. */
while (!(base->S & kI2C_IntPendingFlag))
{
}
/* Clear pending flag. */
base->S = kI2C_IntPendingFlag;
/* Check if there's transfer error. */
result = I2C_CheckAndClearError(base, base->S);
}
return result;
}
static void I2C_MasterTransferEDMAConfig(I2C_Type *base, i2c_master_edma_handle_t *handle)
{
edma_transfer_config_t transfer_config;
if (handle->transfer.direction == kI2C_Read)
{
transfer_config.srcAddr = (uint32_t)I2C_GetDataRegAddr(base);
transfer_config.destAddr = (uint32_t)(handle->transfer.data);
/* Send stop if kI2C_TransferNoStop flag is not asserted. */
if (!(handle->transfer.flags & kI2C_TransferNoStopFlag))
{
transfer_config.majorLoopCounts = (handle->transfer.dataSize - 1);
}
else
{
transfer_config.majorLoopCounts = handle->transfer.dataSize;
}
transfer_config.srcTransferSize = kEDMA_TransferSize1Bytes;
transfer_config.srcOffset = 0;
transfer_config.destTransferSize = kEDMA_TransferSize1Bytes;
transfer_config.destOffset = 1;
transfer_config.minorLoopBytes = 1;
}
else
{
transfer_config.srcAddr = (uint32_t)(handle->transfer.data + 1);
transfer_config.destAddr = (uint32_t)I2C_GetDataRegAddr(base);
transfer_config.majorLoopCounts = (handle->transfer.dataSize - 1);
transfer_config.srcTransferSize = kEDMA_TransferSize1Bytes;
transfer_config.srcOffset = 1;
transfer_config.destTransferSize = kEDMA_TransferSize1Bytes;
transfer_config.destOffset = 0;
transfer_config.minorLoopBytes = 1;
}
EDMA_SubmitTransfer(handle->dmaHandle, &transfer_config);
EDMA_StartTransfer(handle->dmaHandle);
}
void I2C_MasterCreateEDMAHandle(I2C_Type *base,
i2c_master_edma_handle_t *handle,
i2c_master_edma_transfer_callback_t callback,
void *userData,
edma_handle_t *edmaHandle)
{
assert(handle);
assert(edmaHandle);
uint32_t instance = I2C_GetInstance(base);
/* Zero handle. */
memset(handle, 0, sizeof(*handle));
/* Set the user callback and userData. */
handle->completionCallback = callback;
handle->userData = userData;
/* Set the base for the handle. */
base = base;
/* Set the handle for EDMA. */
handle->dmaHandle = edmaHandle;
s_edmaPrivateHandle[instance].base = base;
s_edmaPrivateHandle[instance].handle = handle;
EDMA_SetCallback(edmaHandle, (edma_callback)I2C_MasterTransferCallbackEDMA, &s_edmaPrivateHandle[instance]);
}
status_t I2C_MasterTransferEDMA(I2C_Type *base, i2c_master_edma_handle_t *handle, i2c_master_transfer_t *xfer)
{
assert(handle);
assert(xfer);
status_t result;
uint8_t tmpReg;
volatile uint8_t dummy = 0;
/* Add this to avoid build warning. */
dummy++;
/* Disable dma xfer. */
I2C_EnableDMA(base, false);
/* Send address and command buffer(if there is), until senddata phase or receive data phase. */
result = I2C_InitTransferStateMachineEDMA(base, handle, xfer);
if (result)
{
/* Send stop if received Nak. */
if (result == kStatus_I2C_Nak)
{
if (I2C_MasterStop(base) != kStatus_Success)
{
result = kStatus_I2C_Timeout;
}
}
/* Reset the state to idle state. */
handle->state = kIdleState;
return result;
}
/* Configure dma transfer. */
/* For i2c send, need to send 1 byte first to trigger the dma, for i2c read,
need to send stop before reading the last byte, so the dma transfer size should
be (xSize - 1). */
if (handle->transfer.dataSize > 1)
{
I2C_MasterTransferEDMAConfig(base, handle);
if (handle->transfer.direction == kI2C_Read)
{
/* Change direction for receive. */
base->C1 &= ~I2C_C1_TX_MASK;
/* Read dummy to release the bus. */
dummy = base->D;
/* Enabe dma transfer. */
I2C_EnableDMA(base, true);
}
else
{
/* Enabe dma transfer. */
I2C_EnableDMA(base, true);
/* Send the first data. */
base->D = *handle->transfer.data;
}
}
else /* If transfer size is 1, use polling method. */
{
if (handle->transfer.direction == kI2C_Read)
{
tmpReg = base->C1;
/* Change direction to Rx. */
tmpReg &= ~I2C_C1_TX_MASK;
/* Configure send NAK */
tmpReg |= I2C_C1_TXAK_MASK;
base->C1 = tmpReg;
/* Read dummy to release the bus. */
dummy = base->D;
}
else
{
base->D = *handle->transfer.data;
}
/* Wait until data transfer complete. */
while (!(base->S & kI2C_IntPendingFlag))
{
}
/* Clear pending flag. */
base->S = kI2C_IntPendingFlag;
/* Send stop if kI2C_TransferNoStop flag is not asserted. */
if (!(handle->transfer.flags & kI2C_TransferNoStopFlag))
{
result = I2C_MasterStop(base);
}
/* Read the last byte of data. */
if (handle->transfer.direction == kI2C_Read)
{
*handle->transfer.data = base->D;
}
/* Reset the state to idle. */
handle->state = kIdleState;
}
return result;
}
status_t I2C_MasterTransferGetCountEDMA(I2C_Type *base, i2c_master_edma_handle_t *handle, size_t *count)
{
assert(handle->dmaHandle);
if (!count)
{
return kStatus_InvalidArgument;
}
if (kIdleState != handle->state)
{
*count = (handle->transferSize - EDMA_GetRemainingBytes(handle->dmaHandle->base, handle->dmaHandle->channel));
}
else
{
*count = handle->transferSize;
}
return kStatus_Success;
}
void I2C_MasterTransferAbortEDMA(I2C_Type *base, i2c_master_edma_handle_t *handle)
{
EDMA_AbortTransfer(handle->dmaHandle);
/* Disable dma transfer. */
I2C_EnableDMA(base, false);
/* Reset the state to idle. */
handle->state = kIdleState;
}

View File

@ -0,0 +1,132 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _FSL_I2C_DMA_H_
#define _FSL_I2C_DMA_H_
#include "fsl_i2c.h"
#include "fsl_dmamux.h"
#include "fsl_edma.h"
/*!
* @addtogroup i2c_edma_driver
* @{
*/
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @brief I2C master eDMA handle typedef. */
typedef struct _i2c_master_edma_handle i2c_master_edma_handle_t;
/*! @brief I2C master eDMA transfer callback typedef. */
typedef void (*i2c_master_edma_transfer_callback_t)(I2C_Type *base,
i2c_master_edma_handle_t *handle,
status_t status,
void *userData);
/*! @brief I2C master eDMA transfer structure. */
struct _i2c_master_edma_handle
{
i2c_master_transfer_t transfer; /*!< I2C master transfer struct. */
size_t transferSize; /*!< Total bytes to be transferred. */
uint8_t state; /*!< I2C master transfer status. */
edma_handle_t *dmaHandle; /*!< The eDMA handler used. */
i2c_master_edma_transfer_callback_t
completionCallback; /*!< Callback function called after eDMA transfer finished. */
void *userData; /*!< Callback parameter passed to callback function. */
};
/*******************************************************************************
* API
******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif /*_cplusplus. */
/*!
* @name I2C Block eDMA Transfer Operation
* @{
*/
/*!
* @brief Init the I2C handle which is used in transcational functions.
*
* @param base I2C peripheral base address.
* @param handle pointer to i2c_master_edma_handle_t structure.
* @param callback pointer to user callback function.
* @param userData user param passed to the callback function.
* @param edmaHandle eDMA handle pointer.
*/
void I2C_MasterCreateEDMAHandle(I2C_Type *base,
i2c_master_edma_handle_t *handle,
i2c_master_edma_transfer_callback_t callback,
void *userData,
edma_handle_t *edmaHandle);
/*!
* @brief Performs a master eDMA non-blocking transfer on the I2C bus.
*
* @param base I2C peripheral base address.
* @param handle pointer to i2c_master_edma_handle_t structure.
* @param xfer pointer to transfer structure of i2c_master_transfer_t.
* @retval kStatus_Success Sucessully complete the data transmission.
* @retval kStatus_I2C_Busy Previous transmission still not finished.
* @retval kStatus_I2C_Timeout Transfer error, wait signal timeout.
* @retval kStatus_I2C_ArbitrationLost Transfer error, arbitration lost.
* @retval kStataus_I2C_Nak Transfer error, receive Nak during transfer.
*/
status_t I2C_MasterTransferEDMA(I2C_Type *base, i2c_master_edma_handle_t *handle, i2c_master_transfer_t *xfer);
/*!
* @brief Get master transfer status during a eDMA non-blocking transfer.
*
* @param base I2C peripheral base address.
* @param handle pointer to i2c_master_edma_handle_t structure.
* @param count Number of bytes transferred so far by the non-blocking transaction.
*/
status_t I2C_MasterTransferGetCountEDMA(I2C_Type *base, i2c_master_edma_handle_t *handle, size_t *count);
/*!
* @brief Abort a master eDMA non-blocking transfer in a early time.
*
* @param base I2C peripheral base address.
* @param handle pointer to i2c_master_edma_handle_t structure.
*/
void I2C_MasterTransferAbortEDMA(I2C_Type *base, i2c_master_edma_handle_t *handle);
/* @} */
#if defined(__cplusplus)
}
#endif /*_cplusplus. */
/*@}*/
#endif /*_FSL_I2C_DMA_H_*/

View File

@ -0,0 +1,404 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include "fsl_llwu.h"
#if (defined(FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN) && FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN)
void LLWU_SetExternalWakeupPinMode(LLWU_Type *base, uint32_t pinIndex, llwu_external_pin_mode_t pinMode)
{
#if (defined(FSL_FEATURE_LLWU_REG_BITWIDTH) && (FSL_FEATURE_LLWU_REG_BITWIDTH == 32))
volatile uint32_t *regBase;
uint32_t regOffset;
uint32_t reg;
switch (pinIndex >> 4U)
{
case 0U:
regBase = &base->PE1;
break;
#if (defined(FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN) && (FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN > 16))
case 1U:
regBase = &base->PE2;
break;
#endif
default:
regBase = NULL;
break;
}
#else
volatile uint8_t *regBase;
uint8_t regOffset;
uint8_t reg;
switch (pinIndex >> 2U)
{
case 0U:
regBase = &base->PE1;
break;
case 1U:
regBase = &base->PE2;
break;
#if (defined(FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN) && (FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN > 8))
case 2U:
regBase = &base->PE3;
break;
#endif
#if (defined(FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN) && (FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN > 12))
case 3U:
regBase = &base->PE4;
break;
#endif
#if (defined(FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN) && (FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN > 16))
case 4U:
regBase = &base->PE5;
break;
#endif
#if (defined(FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN) && (FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN > 20))
case 5U:
regBase = &base->PE6;
break;
#endif
#if (defined(FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN) && (FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN > 24))
case 6U:
regBase = &base->PE7;
break;
#endif
#if (defined(FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN) && (FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN > 28))
case 7U:
regBase = &base->PE8;
break;
#endif
default:
regBase = NULL;
break;
}
#endif /* FSL_FEATURE_LLWU_REG_BITWIDTH == 32 */
if (regBase)
{
reg = *regBase;
#if (defined(FSL_FEATURE_LLWU_REG_BITWIDTH) && (FSL_FEATURE_LLWU_REG_BITWIDTH == 32))
regOffset = ((pinIndex & 0x0FU) << 1U);
#else
regOffset = ((pinIndex & 0x03U) << 1U);
#endif
reg &= ~(0x3U << regOffset);
reg |= ((uint32_t)pinMode << regOffset);
*regBase = reg;
}
}
bool LLWU_GetExternalWakeupPinFlag(LLWU_Type *base, uint32_t pinIndex)
{
#if (defined(FSL_FEATURE_LLWU_REG_BITWIDTH) && (FSL_FEATURE_LLWU_REG_BITWIDTH == 32))
return (bool)(base->PF & (1U << pinIndex));
#else
volatile uint8_t *regBase;
switch (pinIndex >> 3U)
{
#if (defined(FSL_FEATURE_LLWU_HAS_PF) && FSL_FEATURE_LLWU_HAS_PF)
case 0U:
regBase = &base->PF1;
break;
#if (defined(FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN) && (FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN > 8))
case 1U:
regBase = &base->PF2;
break;
#endif /* FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN */
#if (defined(FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN) && (FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN > 16))
case 2U:
regBase = &base->PF3;
break;
#endif /* FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN */
#if (defined(FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN) && (FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN > 24))
case 3U:
regBase = &base->PF4;
break;
#endif /* FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN */
#else
case 0U:
regBase = &base->F1;
break;
#if (defined(FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN) && (FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN > 8))
case 1U:
regBase = &base->F2;
break;
#endif /* FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN */
#if (defined(FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN) && (FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN > 16))
case 2U:
regBase = &base->F3;
break;
#endif /* FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN */
#if (defined(FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN) && (FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN > 24))
case 3U:
regBase = &base->F4;
break;
#endif /* FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN */
#endif /* FSL_FEATURE_LLWU_HAS_PF */
default:
regBase = NULL;
break;
}
if (regBase)
{
return (bool)(*regBase & (1U << pinIndex % 8));
}
else
{
return false;
}
#endif /* FSL_FEATURE_LLWU_REG_BITWIDTH */
}
void LLWU_ClearExternalWakeupPinFlag(LLWU_Type *base, uint32_t pinIndex)
{
#if (defined(FSL_FEATURE_LLWU_REG_BITWIDTH) && (FSL_FEATURE_LLWU_REG_BITWIDTH == 32))
base->PF = (1U << pinIndex);
#else
volatile uint8_t *regBase;
switch (pinIndex >> 3U)
{
#if (defined(FSL_FEATURE_LLWU_HAS_PF) && FSL_FEATURE_LLWU_HAS_PF)
case 0U:
regBase = &base->PF1;
break;
#if (defined(FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN) && (FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN > 8))
case 1U:
regBase = &base->PF2;
break;
#endif /* FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN */
#if (defined(FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN) && (FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN > 16))
case 2U:
regBase = &base->PF3;
break;
#endif /* FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN */
#if (defined(FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN) && (FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN > 24))
case 3U:
regBase = &base->PF4;
break;
#endif /* FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN */
#else
case 0U:
regBase = &base->F1;
break;
#if (defined(FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN) && (FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN > 8))
case 1U:
regBase = &base->F2;
break;
#endif /* FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN */
#if (defined(FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN) && (FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN > 16))
case 2U:
regBase = &base->F3;
break;
#endif /* FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN */
#if (defined(FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN) && (FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN > 24))
case 3U:
regBase = &base->F4;
break;
#endif /* FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN */
#endif /* FSL_FEATURE_LLWU_HAS_PF */
default:
regBase = NULL;
break;
}
if (regBase)
{
*regBase = (1U << pinIndex % 8U);
}
#endif /* FSL_FEATURE_LLWU_REG_BITWIDTH */
}
#endif /* FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN */
#if (defined(FSL_FEATURE_LLWU_HAS_PIN_FILTER) && FSL_FEATURE_LLWU_HAS_PIN_FILTER)
void LLWU_SetPinFilterMode(LLWU_Type *base, uint32_t filterIndex, llwu_external_pin_filter_mode_t filterMode)
{
#if (defined(FSL_FEATURE_LLWU_REG_BITWIDTH) && (FSL_FEATURE_LLWU_REG_BITWIDTH == 32))
uint32_t reg;
reg = base->FILT;
reg &= ~((LLWU_FILT_FILTSEL1_MASK | LLWU_FILT_FILTE1_MASK) << (filterIndex * 8U - 1U));
reg |= (((filterMode.pinIndex << LLWU_FILT_FILTSEL1_SHIFT) | (filterMode.filterMode << LLWU_FILT_FILTE1_SHIFT)
/* Clear the Filter Detect Flag */
| LLWU_FILT_FILTF1_MASK)
<< (filterIndex * 8U - 1U));
base->FILT = reg;
#else
volatile uint8_t *regBase;
uint8_t reg;
switch (filterIndex)
{
case 1:
regBase = &base->FILT1;
break;
#if (defined(FSL_FEATURE_LLWU_HAS_PIN_FILTER) && (FSL_FEATURE_LLWU_HAS_PIN_FILTER > 1))
case 2:
regBase = &base->FILT2;
break;
#endif /* FSL_FEATURE_LLWU_HAS_PIN_FILTER */
#if (defined(FSL_FEATURE_LLWU_HAS_PIN_FILTER) && (FSL_FEATURE_LLWU_HAS_PIN_FILTER > 2))
case 3:
regBase = &base->FILT3;
break;
#endif /* FSL_FEATURE_LLWU_HAS_PIN_FILTER */
#if (defined(FSL_FEATURE_LLWU_HAS_PIN_FILTER) && (FSL_FEATURE_LLWU_HAS_PIN_FILTER > 3))
case 4:
regBase = &base->FILT4;
break;
#endif /* FSL_FEATURE_LLWU_HAS_PIN_FILTER */
default:
regBase = NULL;
break;
}
if (regBase)
{
reg = *regBase;
reg &= ~(LLWU_FILT1_FILTSEL_MASK | LLWU_FILT1_FILTE_MASK);
reg |= ((uint32_t)filterMode.pinIndex << LLWU_FILT1_FILTSEL_SHIFT);
reg |= ((uint32_t)filterMode.filterMode << LLWU_FILT1_FILTE_SHIFT);
/* Clear the Filter Detect Flag */
reg |= LLWU_FILT1_FILTF_MASK;
*regBase = reg;
}
#endif /* FSL_FEATURE_LLWU_REG_BITWIDTH */
}
bool LLWU_GetPinFilterFlag(LLWU_Type *base, uint32_t filterIndex)
{
#if (defined(FSL_FEATURE_LLWU_REG_BITWIDTH) && (FSL_FEATURE_LLWU_REG_BITWIDTH == 32))
return (bool)(base->FILT & (1U << (filterIndex * 8U - 1)));
#else
bool status = false;
switch (filterIndex)
{
case 1:
status = (base->FILT1 & LLWU_FILT1_FILTF_MASK);
break;
#if (defined(FSL_FEATURE_LLWU_HAS_PIN_FILTER) && (FSL_FEATURE_LLWU_HAS_PIN_FILTER > 1))
case 2:
status = (base->FILT2 & LLWU_FILT2_FILTF_MASK);
break;
#endif /* FSL_FEATURE_LLWU_HAS_PIN_FILTER */
#if (defined(FSL_FEATURE_LLWU_HAS_PIN_FILTER) && (FSL_FEATURE_LLWU_HAS_PIN_FILTER > 2))
case 3:
status = (base->FILT3 & LLWU_FILT3_FILTF_MASK);
break;
#endif /* FSL_FEATURE_LLWU_HAS_PIN_FILTER */
#if (defined(FSL_FEATURE_LLWU_HAS_PIN_FILTER) && (FSL_FEATURE_LLWU_HAS_PIN_FILTER > 3))
case 4:
status = (base->FILT4 & LLWU_FILT4_FILTF_MASK);
break;
#endif /* FSL_FEATURE_LLWU_HAS_PIN_FILTER */
default:
break;
}
return status;
#endif /* FSL_FEATURE_LLWU_REG_BITWIDTH */
}
void LLWU_ClearPinFilterFlag(LLWU_Type *base, uint32_t filterIndex)
{
#if (defined(FSL_FEATURE_LLWU_REG_BITWIDTH) && (FSL_FEATURE_LLWU_REG_BITWIDTH == 32))
uint32_t reg;
reg = base->FILT;
switch (filterIndex)
{
case 1:
reg |= LLWU_FILT_FILTF1_MASK;
break;
case 2:
reg |= LLWU_FILT_FILTF2_MASK;
break;
case 3:
reg |= LLWU_FILT_FILTF3_MASK;
break;
case 4:
reg |= LLWU_FILT_FILTF4_MASK;
break;
default:
break;
}
base->FILT = reg;
#else
volatile uint8_t *regBase;
uint8_t reg;
switch (filterIndex)
{
case 1:
regBase = &base->FILT1;
break;
#if (defined(FSL_FEATURE_LLWU_HAS_PIN_FILTER) && (FSL_FEATURE_LLWU_HAS_PIN_FILTER > 1))
case 2:
regBase = &base->FILT2;
break;
#endif /* FSL_FEATURE_LLWU_HAS_PIN_FILTER */
#if (defined(FSL_FEATURE_LLWU_HAS_PIN_FILTER) && (FSL_FEATURE_LLWU_HAS_PIN_FILTER > 2))
case 3:
regBase = &base->FILT3;
break;
#endif /* FSL_FEATURE_LLWU_HAS_PIN_FILTER */
#if (defined(FSL_FEATURE_LLWU_HAS_PIN_FILTER) && (FSL_FEATURE_LLWU_HAS_PIN_FILTER > 3))
case 4:
regBase = &base->FILT4;
break;
#endif /* FSL_FEATURE_LLWU_HAS_PIN_FILTER */
default:
regBase = NULL;
break;
}
if (regBase)
{
reg = *regBase;
reg |= LLWU_FILT1_FILTF_MASK;
*regBase = reg;
}
#endif /* FSL_FEATURE_LLWU_REG_BITWIDTH */
}
#endif /* FSL_FEATURE_LLWU_HAS_PIN_FILTER */
#if (defined(FSL_FEATURE_LLWU_HAS_RESET_ENABLE) && FSL_FEATURE_LLWU_HAS_RESET_ENABLE)
void LLWU_SetResetPinMode(LLWU_Type *base, bool pinEnable, bool enableInLowLeakageMode)
{
uint8_t reg;
reg = base->RST;
reg &= ~(LLWU_RST_LLRSTE_MASK | LLWU_RST_RSTFILT_MASK);
reg |=
(((uint32_t)pinEnable << LLWU_RST_LLRSTE_SHIFT) | ((uint32_t)enableInLowLeakageMode << LLWU_RST_RSTFILT_SHIFT));
base->RST = reg;
}
#endif /* FSL_FEATURE_LLWU_HAS_RESET_ENABLE */

View File

@ -0,0 +1,320 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _FSL_LLWU_H_
#define _FSL_LLWU_H_
#include "fsl_common.h"
/*! @addtogroup llwu */
/*! @{ */
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @name Driver version */
/*@{*/
/*! @brief LLWU driver version 2.0.1. */
#define FSL_LLWU_DRIVER_VERSION (MAKE_VERSION(2, 0, 1))
/*@}*/
/*!
* @brief External input pin control modes
*/
typedef enum _llwu_external_pin_mode
{
kLLWU_ExternalPinDisable = 0U, /*!< Pin disabled as wakeup input. */
kLLWU_ExternalPinRisingEdge = 1U, /*!< Pin enabled with rising edge detection. */
kLLWU_ExternalPinFallingEdge = 2U, /*!< Pin enabled with falling edge detection.*/
kLLWU_ExternalPinAnyEdge = 3U /*!< Pin enabled with any change detection. */
} llwu_external_pin_mode_t;
/*!
* @brief Digital filter control modes
*/
typedef enum _llwu_pin_filter_mode
{
kLLWU_PinFilterDisable = 0U, /*!< Filter disabled. */
kLLWU_PinFilterRisingEdge = 1U, /*!< Filter positive edge detection.*/
kLLWU_PinFilterFallingEdge = 2U, /*!< Filter negative edge detection.*/
kLLWU_PinFilterAnyEdge = 3U /*!< Filter any edge detection. */
} llwu_pin_filter_mode_t;
#if (defined(FSL_FEATURE_LLWU_HAS_VERID) && FSL_FEATURE_LLWU_HAS_VERID)
/*!
* @brief IP version ID definition.
*/
typedef struct _llwu_version_id
{
uint16_t feature; /*!< Feature Specification Number. */
uint8_t minor; /*!< Minor version number. */
uint8_t major; /*!< Major version number. */
} llwu_version_id_t;
#endif /* FSL_FEATURE_LLWU_HAS_VERID */
#if (defined(FSL_FEATURE_LLWU_HAS_PARAM) && FSL_FEATURE_LLWU_HAS_PARAM)
/*!
* @brief IP parameter definition.
*/
typedef struct _llwu_param
{
uint8_t filters; /*!< Number of pin filter. */
uint8_t dmas; /*!< Number of wakeup DMA. */
uint8_t modules; /*!< Number of wakeup module. */
uint8_t pins; /*!< Number of wake up pin. */
} llwu_param_t;
#endif /* FSL_FEATURE_LLWU_HAS_PARAM */
#if (defined(FSL_FEATURE_LLWU_HAS_PIN_FILTER) && FSL_FEATURE_LLWU_HAS_PIN_FILTER)
/*!
* @brief External input pin filter control structure
*/
typedef struct _llwu_external_pin_filter_mode
{
uint32_t pinIndex; /*!< Pin number */
llwu_pin_filter_mode_t filterMode; /*!< Filter mode */
} llwu_external_pin_filter_mode_t;
#endif /* FSL_FEATURE_LLWU_HAS_PIN_FILTER */
/*******************************************************************************
* API
******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif
/*!
* @name Low-Leakage Wakeup Unit Control APIs
* @{
*/
#if (defined(FSL_FEATURE_LLWU_HAS_VERID) && FSL_FEATURE_LLWU_HAS_VERID)
/*!
* @brief Gets the LLWU version ID.
*
* This function gets the LLWU version ID, including major version number,
* minor version number, and feature specification number.
*
* @param base LLWU peripheral base address.
* @param versionId Pointer to version ID structure.
*/
static inline void LLWU_GetVersionId(LLWU_Type *base, llwu_version_id_t *versionId)
{
*((uint32_t *)versionId) = base->VERID;
}
#endif /* FSL_FEATURE_LLWU_HAS_VERID */
#if (defined(FSL_FEATURE_LLWU_HAS_PARAM) && FSL_FEATURE_LLWU_HAS_PARAM)
/*!
* @brief Gets the LLWU parameter.
*
* This function gets the LLWU parameter, including wakeup pin number, module
* number, DMA number, and pin filter number.
*
* @param base LLWU peripheral base address.
* @param param Pointer to LLWU param structure.
*/
static inline void LLWU_GetParam(LLWU_Type *base, llwu_param_t *param)
{
*((uint32_t *)param) = base->PARAM;
}
#endif /* FSL_FEATURE_LLWU_HAS_PARAM */
#if (defined(FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN) && FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN)
/*!
* @brief Sets the external input pin source mode.
*
* This function sets the external input pin source mode that is used
* as a wake up source.
*
* @param base LLWU peripheral base address.
* @param pinIndex pin index which to be enabled as external wakeup source, start from 1.
* @param pinMode pin configuration mode defined in llwu_external_pin_modes_t
*/
void LLWU_SetExternalWakeupPinMode(LLWU_Type *base, uint32_t pinIndex, llwu_external_pin_mode_t pinMode);
/*!
* @brief Gets the external wakeup source flag.
*
* This function checks the external pin flag to detect whether the MCU is
* woke up by the specific pin.
*
* @param base LLWU peripheral base address.
* @param pinIndex pin index, start from 1.
* @return true if the specific pin is wake up source.
*/
bool LLWU_GetExternalWakeupPinFlag(LLWU_Type *base, uint32_t pinIndex);
/*!
* @brief Clears the external wakeup source flag.
*
* This function clears the external wakeup source flag for a specific pin.
*
* @param base LLWU peripheral base address.
* @param pinIndex pin index, start from 1.
*/
void LLWU_ClearExternalWakeupPinFlag(LLWU_Type *base, uint32_t pinIndex);
#endif /* FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN */
#if (defined(FSL_FEATURE_LLWU_HAS_INTERNAL_MODULE) && FSL_FEATURE_LLWU_HAS_INTERNAL_MODULE)
/*!
* @brief Enables/disables the internal module source.
*
* This function enables/disables the internal module source mode that is used
* as a wake up source.
*
* @param base LLWU peripheral base address.
* @param moduleIndex module index which to be enabled as internal wakeup source, start from 1.
* @param enable enable or disable setting
*/
static inline void LLWU_EnableInternalModuleInterruptWakup(LLWU_Type *base, uint32_t moduleIndex, bool enable)
{
if (enable)
{
base->ME |= 1U << moduleIndex;
}
else
{
base->ME &= ~(1U << moduleIndex);
}
}
/*!
* @brief Gets the external wakeup source flag.
*
* This function checks the external pin flag to detect whether the system is
* woke up by the specific pin.
*
* @param base LLWU peripheral base address.
* @param moduleIndex module index, start from 1.
* @return true if the specific pin is wake up source.
*/
static inline bool LLWU_GetInternalWakeupModuleFlag(LLWU_Type *base, uint32_t moduleIndex)
{
#if (defined(FSL_FEATURE_LLWU_HAS_MF) && FSL_FEATURE_LLWU_HAS_MF)
#if (defined(FSL_FEATURE_LLWU_REG_BITWIDTH) && (FSL_FEATURE_LLWU_REG_BITWIDTH == 32))
return (bool)(base->MF & (1U << moduleIndex));
#else
return (bool)(base->MF5 & (1U << moduleIndex));
#endif /* FSL_FEATURE_LLWU_REG_BITWIDTH */
#else
#if (defined(FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN) && (FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN > 16))
return (bool)(base->F5 & (1U << moduleIndex));
#else
#if (defined(FSL_FEATURE_LLWU_HAS_PF) && FSL_FEATURE_LLWU_HAS_PF)
return (bool)(base->PF3 & (1U << moduleIndex));
#else
return (bool)(base->F3 & (1U << moduleIndex));
#endif /* FSL_FEATURE_LLWU_HAS_PF */
#endif /* FSL_FEATURE_LLWU_HAS_EXTERNAL_PIN */
#endif /* FSL_FEATURE_LLWU_HAS_MF */
}
#endif /* FSL_FEATURE_LLWU_HAS_INTERNAL_MODULE */
#if (defined(FSL_FEATURE_LLWU_HAS_DMA_ENABLE_REG) && FSL_FEATURE_LLWU_HAS_DMA_ENABLE_REG)
/*!
* @brief Enables/disables the internal module DMA wakeup source.
*
* This function enables/disables the internal DMA that is used as a wake up source.
*
* @param base LLWU peripheral base address.
* @param moduleIndex Internal module index which used as DMA request source, start from 1.
* @param enable Enable or disable DMA request source
*/
static inline void LLWU_EnableInternalModuleDmaRequestWakup(LLWU_Type *base, uint32_t moduleIndex, bool enable)
{
if (enable)
{
base->DE |= 1U << moduleIndex;
}
else
{
base->DE &= ~(1U << moduleIndex);
}
}
#endif /* FSL_FEATURE_LLWU_HAS_DMA_ENABLE_REG */
#if (defined(FSL_FEATURE_LLWU_HAS_PIN_FILTER) && FSL_FEATURE_LLWU_HAS_PIN_FILTER)
/*!
* @brief Sets the pin filter configuration.
*
* This function sets the pin filter configuration.
*
* @param base LLWU peripheral base address.
* @param filterIndex pin filter index which used to enable/disable the digital filter, start from 1.
* @param filterMode filter mode configuration
*/
void LLWU_SetPinFilterMode(LLWU_Type *base, uint32_t filterIndex, llwu_external_pin_filter_mode_t filterMode);
/*!
* @brief Gets the pin filter configuration.
*
* This function gets the pin filter flag.
*
* @param base LLWU peripheral base address.
* @param filterIndex pin filter index, start from 1.
* @return true if the flag is a source of existing a low-leakage power mode.
*/
bool LLWU_GetPinFilterFlag(LLWU_Type *base, uint32_t filterIndex);
/*!
* @brief Clear the pin filter configuration.
*
* This function clear the pin filter flag.
*
* @param base LLWU peripheral base address.
* @param filterIndex pin filter index which to be clear the flag, start from 1.
*/
void LLWU_ClearPinFilterFlag(LLWU_Type *base, uint32_t filterIndex);
#endif /* FSL_FEATURE_LLWU_HAS_PIN_FILTER */
#if (defined(FSL_FEATURE_LLWU_HAS_RESET_ENABLE) && FSL_FEATURE_LLWU_HAS_RESET_ENABLE)
/*!
* @brief Sets the reset pin mode.
*
* This function sets how the reset pin is used as a low leakage mode exit source.
*
* @param pinEnable Enable reset pin filter
* @param pinFilterEnable Specify whether pin filter is enabled in Low-Leakage power mode.
*/
void LLWU_SetResetPinMode(LLWU_Type *base, bool pinEnable, bool enableInLowLeakageMode);
#endif /* FSL_FEATURE_LLWU_HAS_RESET_ENABLE */
/*@}*/
#if defined(__cplusplus)
}
#endif
/*! @}*/
#endif /* _FSL_LLWU_H_*/

View File

@ -0,0 +1,117 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include "fsl_lptmr.h"
/*******************************************************************************
* Prototypes
******************************************************************************/
/*!
* @brief Gets the instance from the base address to be used to gate or ungate the module clock
*
* @param base LPTMR peripheral base address
*
* @return The LPTMR instance
*/
static uint32_t LPTMR_GetInstance(LPTMR_Type *base);
/*******************************************************************************
* Variables
******************************************************************************/
/*! @brief Pointers to LPTMR bases for each instance. */
static LPTMR_Type *const s_lptmrBases[] = LPTMR_BASE_PTRS;
/*! @brief Pointers to LPTMR clocks for each instance. */
static const clock_ip_name_t s_lptmrClocks[] = LPTMR_CLOCKS;
/*******************************************************************************
* Code
******************************************************************************/
static uint32_t LPTMR_GetInstance(LPTMR_Type *base)
{
uint32_t instance;
/* Find the instance index from base address mappings. */
for (instance = 0; instance < FSL_FEATURE_SOC_LPTMR_COUNT; instance++)
{
if (s_lptmrBases[instance] == base)
{
break;
}
}
assert(instance < FSL_FEATURE_SOC_LPTMR_COUNT);
return instance;
}
void LPTMR_Init(LPTMR_Type *base, const lptmr_config_t *config)
{
assert(config);
/* Ungate the LPTMR clock*/
CLOCK_EnableClock(s_lptmrClocks[LPTMR_GetInstance(base)]);
/* Configure the timers operation mode and input pin setup */
base->CSR = (LPTMR_CSR_TMS(config->timerMode) | LPTMR_CSR_TFC(config->enableFreeRunning) |
LPTMR_CSR_TPP(config->pinPolarity) | LPTMR_CSR_TPS(config->pinSelect));
/* Configure the prescale value and clock source */
base->PSR = (LPTMR_PSR_PRESCALE(config->value) | LPTMR_PSR_PBYP(config->bypassPrescaler) |
LPTMR_PSR_PCS(config->prescalerClockSource));
}
void LPTMR_Deinit(LPTMR_Type *base)
{
/* Disable the LPTMR and reset the internal logic */
base->CSR &= ~LPTMR_CSR_TEN_MASK;
/* Gate the LPTMR clock*/
CLOCK_DisableClock(s_lptmrClocks[LPTMR_GetInstance(base)]);
}
void LPTMR_GetDefaultConfig(lptmr_config_t *config)
{
assert(config);
/* Use time counter mode */
config->timerMode = kLPTMR_TimerModeTimeCounter;
/* Use input 0 as source in pulse counter mode */
config->pinSelect = kLPTMR_PinSelectInput_0;
/* Pulse input pin polarity is active-high */
config->pinPolarity = kLPTMR_PinPolarityActiveHigh;
/* Counter resets whenever TCF flag is set */
config->enableFreeRunning = false;
/* Bypass the prescaler */
config->bypassPrescaler = true;
/* LPTMR clock source */
config->prescalerClockSource = kLPTMR_PrescalerClock_1;
/* Divide the prescaler clock by 2 */
config->value = kLPTMR_Prescale_Glitch_0;
}

View File

@ -0,0 +1,370 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _FSL_LPTMR_H_
#define _FSL_LPTMR_H_
#include "fsl_common.h"
/*!
* @addtogroup lptmr
* @{
*/
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @name Driver version */
/*@{*/
#define FSL_LPTMR_DRIVER_VERSION (MAKE_VERSION(2, 0, 0)) /*!< Version 2.0.0 */
/*@}*/
/*! @brief LPTMR pin selection, used in pulse counter mode.*/
typedef enum _lptmr_pin_select
{
kLPTMR_PinSelectInput_0 = 0x0U, /*!< Pulse counter input 0 is selected */
kLPTMR_PinSelectInput_1 = 0x1U, /*!< Pulse counter input 1 is selected */
kLPTMR_PinSelectInput_2 = 0x2U, /*!< Pulse counter input 2 is selected */
kLPTMR_PinSelectInput_3 = 0x3U /*!< Pulse counter input 3 is selected */
} lptmr_pin_select_t;
/*! @brief LPTMR pin polarity, used in pulse counter mode.*/
typedef enum _lptmr_pin_polarity
{
kLPTMR_PinPolarityActiveHigh = 0x0U, /*!< Pulse Counter input source is active-high */
kLPTMR_PinPolarityActiveLow = 0x1U /*!< Pulse Counter input source is active-low */
} lptmr_pin_polarity_t;
/*! @brief LPTMR timer mode selection.*/
typedef enum _lptmr_timer_mode
{
kLPTMR_TimerModeTimeCounter = 0x0U, /*!< Time Counter mode */
kLPTMR_TimerModePulseCounter = 0x1U /*!< Pulse Counter mode */
} lptmr_timer_mode_t;
/*! @brief LPTMR prescaler/glitch filter values*/
typedef enum _lptmr_prescaler_glitch_value
{
kLPTMR_Prescale_Glitch_0 = 0x0U, /*!< Prescaler divide 2, glitch filter does not support this setting */
kLPTMR_Prescale_Glitch_1 = 0x1U, /*!< Prescaler divide 4, glitch filter 2 */
kLPTMR_Prescale_Glitch_2 = 0x2U, /*!< Prescaler divide 8, glitch filter 4 */
kLPTMR_Prescale_Glitch_3 = 0x3U, /*!< Prescaler divide 16, glitch filter 8 */
kLPTMR_Prescale_Glitch_4 = 0x4U, /*!< Prescaler divide 32, glitch filter 16 */
kLPTMR_Prescale_Glitch_5 = 0x5U, /*!< Prescaler divide 64, glitch filter 32 */
kLPTMR_Prescale_Glitch_6 = 0x6U, /*!< Prescaler divide 128, glitch filter 64 */
kLPTMR_Prescale_Glitch_7 = 0x7U, /*!< Prescaler divide 256, glitch filter 128 */
kLPTMR_Prescale_Glitch_8 = 0x8U, /*!< Prescaler divide 512, glitch filter 256 */
kLPTMR_Prescale_Glitch_9 = 0x9U, /*!< Prescaler divide 1024, glitch filter 512*/
kLPTMR_Prescale_Glitch_10 = 0xAU, /*!< Prescaler divide 2048 glitch filter 1024 */
kLPTMR_Prescale_Glitch_11 = 0xBU, /*!< Prescaler divide 4096, glitch filter 2048 */
kLPTMR_Prescale_Glitch_12 = 0xCU, /*!< Prescaler divide 8192, glitch filter 4096 */
kLPTMR_Prescale_Glitch_13 = 0xDU, /*!< Prescaler divide 16384, glitch filter 8192 */
kLPTMR_Prescale_Glitch_14 = 0xEU, /*!< Prescaler divide 32768, glitch filter 16384 */
kLPTMR_Prescale_Glitch_15 = 0xFU /*!< Prescaler divide 65536, glitch filter 32768 */
} lptmr_prescaler_glitch_value_t;
/*!
* @brief LPTMR prescaler/glitch filter clock select.
* @note Clock connections are SoC-specific
*/
typedef enum _lptmr_prescaler_clock_select
{
kLPTMR_PrescalerClock_0 = 0x0U, /*!< Prescaler/glitch filter clock 0 selected. */
kLPTMR_PrescalerClock_1 = 0x1U, /*!< Prescaler/glitch filter clock 1 selected. */
kLPTMR_PrescalerClock_2 = 0x2U, /*!< Prescaler/glitch filter clock 2 selected. */
kLPTMR_PrescalerClock_3 = 0x3U, /*!< Prescaler/glitch filter clock 3 selected. */
} lptmr_prescaler_clock_select_t;
/*! @brief List of LPTMR interrupts */
typedef enum _lptmr_interrupt_enable
{
kLPTMR_TimerInterruptEnable = LPTMR_CSR_TIE_MASK, /*!< Timer interrupt enable */
} lptmr_interrupt_enable_t;
/*! @brief List of LPTMR status flags */
typedef enum _lptmr_status_flags
{
kLPTMR_TimerCompareFlag = LPTMR_CSR_TCF_MASK, /*!< Timer compare flag */
} lptmr_status_flags_t;
/*!
* @brief LPTMR config structure
*
* This structure holds the configuration settings for the LPTMR peripheral. To initialize this
* structure to reasonable defaults, call the LPTMR_GetDefaultConfig() function and pass a
* pointer to your config structure instance.
*
* The config struct can be made const so it resides in flash
*/
typedef struct _lptmr_config
{
lptmr_timer_mode_t timerMode; /*!< Time counter mode or pulse counter mode */
lptmr_pin_select_t pinSelect; /*!< LPTMR pulse input pin select; used only in pulse counter mode */
lptmr_pin_polarity_t pinPolarity; /*!< LPTMR pulse input pin polarity; used only in pulse counter mode */
bool enableFreeRunning; /*!< true: enable free running, counter is reset on overflow
false: counter is reset when the compare flag is set */
bool bypassPrescaler; /*!< true: bypass prescaler; false: use clock from prescaler */
lptmr_prescaler_clock_select_t prescalerClockSource; /*!< LPTMR clock source */
lptmr_prescaler_glitch_value_t value; /*!< Prescaler or glitch filter value */
} lptmr_config_t;
/*******************************************************************************
* API
******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif
/*!
* @name Initialization and deinitialization
* @{
*/
/*!
* @brief Ungate the LPTMR clock and configures the peripheral for basic operation.
*
* @note This API should be called at the beginning of the application using the LPTMR driver.
*
* @param base LPTMR peripheral base address
* @param config Pointer to user's LPTMR config structure.
*/
void LPTMR_Init(LPTMR_Type *base, const lptmr_config_t *config);
/*!
* @brief Gate the LPTMR clock
*
* @param base LPTMR peripheral base address
*/
void LPTMR_Deinit(LPTMR_Type *base);
/*!
* @brief Fill in the LPTMR config struct with the default settings
*
* The default values are:
* @code
* config->timerMode = kLPTMR_TimerModeTimeCounter;
* config->pinSelect = kLPTMR_PinSelectInput_0;
* config->pinPolarity = kLPTMR_PinPolarityActiveHigh;
* config->enableFreeRunning = false;
* config->bypassPrescaler = true;
* config->prescalerClockSource = kLPTMR_PrescalerClock_1;
* config->value = kLPTMR_Prescale_Glitch_0;
* @endcode
* @param config Pointer to user's LPTMR config structure.
*/
void LPTMR_GetDefaultConfig(lptmr_config_t *config);
/*! @}*/
/*!
* @name Interrupt Interface
* @{
*/
/*!
* @brief Enables the selected LPTMR interrupts.
*
* @param base LPTMR peripheral base address
* @param mask The interrupts to enable. This is a logical OR of members of the
* enumeration ::lptmr_interrupt_enable_t
*/
static inline void LPTMR_EnableInterrupts(LPTMR_Type *base, uint32_t mask)
{
uint32_t reg = base->CSR;
/* Clear the TCF bit so that we don't clear this w1c bit when writing back */
reg &= ~(LPTMR_CSR_TCF_MASK);
reg |= mask;
base->CSR = reg;
}
/*!
* @brief Disables the selected LPTMR interrupts.
*
* @param base LPTMR peripheral base address
* @param mask The interrupts to disable. This is a logical OR of members of the
* enumeration ::lptmr_interrupt_enable_t
*/
static inline void LPTMR_DisableInterrupts(LPTMR_Type *base, uint32_t mask)
{
uint32_t reg = base->CSR;
/* Clear the TCF bit so that we don't clear this w1c bit when writing back */
reg &= ~(LPTMR_CSR_TCF_MASK);
reg &= ~mask;
base->CSR = reg;
}
/*!
* @brief Gets the enabled LPTMR interrupts.
*
* @param base LPTMR peripheral base address
*
* @return The enabled interrupts. This is the logical OR of members of the
* enumeration ::lptmr_interrupt_enable_t
*/
static inline uint32_t LPTMR_GetEnabledInterrupts(LPTMR_Type *base)
{
return (base->CSR & LPTMR_CSR_TIE_MASK);
}
/*! @}*/
/*!
* @name Status Interface
* @{
*/
/*!
* @brief Gets the LPTMR status flags
*
* @param base LPTMR peripheral base address
*
* @return The status flags. This is the logical OR of members of the
* enumeration ::lptmr_status_flags_t
*/
static inline uint32_t LPTMR_GetStatusFlags(LPTMR_Type *base)
{
return (base->CSR & LPTMR_CSR_TCF_MASK);
}
/*!
* @brief Clears the LPTMR status flags
*
* @param base LPTMR peripheral base address
* @param mask The status flags to clear. This is a logical OR of members of the
* enumeration ::lptmr_status_flags_t
*/
static inline void LPTMR_ClearStatusFlags(LPTMR_Type *base, uint32_t mask)
{
base->CSR |= mask;
}
/*! @}*/
/*!
* @name Read and Write the timer period
* @{
*/
/*!
* @brief Sets the timer period in units of count.
*
* Timers counts from 0 till it equals the count value set here. The count value is written to
* the CMR register.
*
* @note
* 1. The TCF flag is set with the CNR equals the count provided here and then increments.
* 2. User can call the utility macros provided in fsl_common.h to convert to ticks
*
* @param base LPTMR peripheral base address
* @param ticks Timer period in units of ticks
*/
static inline void LPTMR_SetTimerPeriod(LPTMR_Type *base, uint16_t ticks)
{
base->CMR = ticks;
}
/*!
* @brief Reads the current timer counting value.
*
* This function returns the real-time timer counting value, in a range from 0 to a
* timer period.
*
* @note User can call the utility macros provided in fsl_common.h to convert ticks to usec or msec
*
* @param base LPTMR peripheral base address
*
* @return Current counter value in ticks
*/
static inline uint16_t LPTMR_GetCurrentTimerCount(LPTMR_Type *base)
{
/* Must first write any value to the CNR. This synchronizes and registers the current value
* of the CNR into a temporary register which can then be read
*/
base->CNR = 0U;
return (uint16_t)base->CNR;
}
/*! @}*/
/*!
* @name Timer Start and Stop
* @{
*/
/*!
* @brief Starts the timer counting.
*
* After calling this function, the timer counts up to the CMR register value.
* Each time the timer reaches CMR value and then increments, it generates a
* trigger pulse and sets the timeout interrupt flag. An interrupt is also
* triggered if the timer interrupt is enabled.
*
* @param base LPTMR peripheral base address
*/
static inline void LPTMR_StartTimer(LPTMR_Type *base)
{
uint32_t reg = base->CSR;
/* Clear the TCF bit so that we don't clear this w1c bit when writing back */
reg &= ~(LPTMR_CSR_TCF_MASK);
reg |= LPTMR_CSR_TEN_MASK;
base->CSR = reg;
}
/*!
* @brief Stops the timer counting.
*
* This function stops the timer counting and resets the timer's counter register
*
* @param base LPTMR peripheral base address
*/
static inline void LPTMR_StopTimer(LPTMR_Type *base)
{
uint32_t reg = base->CSR;
/* Clear the TCF bit so that we don't clear this w1c bit when writing back */
reg &= ~(LPTMR_CSR_TCF_MASK);
reg &= ~LPTMR_CSR_TEN_MASK;
base->CSR = reg;
}
/*! @}*/
#if defined(__cplusplus)
}
#endif
/*! @}*/
#endif /* _FSL_LPTMR_H_ */

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,792 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _FSL_LPUART_H_
#define _FSL_LPUART_H_
#include "fsl_common.h"
/*!
* @addtogroup lpuart_driver
* @{
*/
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @name Driver version */
/*@{*/
/*! @brief LPUART driver version 2.2.1. */
#define FSL_LPUART_DRIVER_VERSION (MAKE_VERSION(2, 2, 1))
/*@}*/
/*! @brief Error codes for the LPUART driver. */
enum _lpuart_status
{
kStatus_LPUART_TxBusy = MAKE_STATUS(kStatusGroup_LPUART, 0), /*!< TX busy */
kStatus_LPUART_RxBusy = MAKE_STATUS(kStatusGroup_LPUART, 1), /*!< RX busy */
kStatus_LPUART_TxIdle = MAKE_STATUS(kStatusGroup_LPUART, 2), /*!< LPUART transmitter is idle. */
kStatus_LPUART_RxIdle = MAKE_STATUS(kStatusGroup_LPUART, 3), /*!< LPUART receiver is idle. */
kStatus_LPUART_TxWatermarkTooLarge = MAKE_STATUS(kStatusGroup_LPUART, 4), /*!< TX FIFO watermark too large */
kStatus_LPUART_RxWatermarkTooLarge = MAKE_STATUS(kStatusGroup_LPUART, 5), /*!< RX FIFO watermark too large */
kStatus_LPUART_FlagCannotClearManually =
MAKE_STATUS(kStatusGroup_LPUART, 6), /*!< Some flag can't manually clear */
kStatus_LPUART_Error = MAKE_STATUS(kStatusGroup_LPUART, 7), /*!< Error happens on LPUART. */
kStatus_LPUART_RxRingBufferOverrun =
MAKE_STATUS(kStatusGroup_LPUART, 8), /*!< LPUART RX software ring buffer overrun. */
kStatus_LPUART_RxHardwareOverrun = MAKE_STATUS(kStatusGroup_LPUART, 9), /*!< LPUART RX receiver overrun. */
kStatus_LPUART_NoiseError = MAKE_STATUS(kStatusGroup_LPUART, 10), /*!< LPUART noise error. */
kStatus_LPUART_FramingError = MAKE_STATUS(kStatusGroup_LPUART, 11), /*!< LPUART framing error. */
kStatus_LPUART_ParityError = MAKE_STATUS(kStatusGroup_LPUART, 12), /*!< LPUART parity error. */
kStatus_LPUART_BaudrateNotSupport =
MAKE_STATUS(kStatusGroup_LPUART, 13), /*!< Baudrate is not support in current clock source */
};
/*! @brief LPUART parity mode. */
typedef enum _lpuart_parity_mode
{
kLPUART_ParityDisabled = 0x0U, /*!< Parity disabled */
kLPUART_ParityEven = 0x2U, /*!< Parity enabled, type even, bit setting: PE|PT = 10 */
kLPUART_ParityOdd = 0x3U, /*!< Parity enabled, type odd, bit setting: PE|PT = 11 */
} lpuart_parity_mode_t;
/*! @brief LPUART data bits count. */
typedef enum _lpuart_data_bits
{
kLPUART_EightDataBits = 0x0U, /*!< Eight data bit */
#if defined(FSL_FEATURE_LPUART_HAS_7BIT_DATA_SUPPORT) && FSL_FEATURE_LPUART_HAS_7BIT_DATA_SUPPORT
kLPUART_SevenDataBits = 0x1U, /*!< Seven data bit */
#endif
} lpuart_data_bits_t;
/*! @brief LPUART stop bit count. */
typedef enum _lpuart_stop_bit_count
{
kLPUART_OneStopBit = 0U, /*!< One stop bit */
kLPUART_TwoStopBit = 1U, /*!< Two stop bits */
} lpuart_stop_bit_count_t;
/*!
* @brief LPUART interrupt configuration structure, default settings all disabled.
*
* This structure contains the settings for all LPUART interrupt configurations.
*/
enum _lpuart_interrupt_enable
{
#if defined(FSL_FEATURE_LPUART_HAS_LIN_BREAK_DETECT) && FSL_FEATURE_LPUART_HAS_LIN_BREAK_DETECT
kLPUART_LinBreakInterruptEnable = (LPUART_BAUD_LBKDIE_MASK >> 8), /*!< LIN break detect. */
#endif
kLPUART_RxActiveEdgeInterruptEnable = (LPUART_BAUD_RXEDGIE_MASK >> 8), /*!< Receive Active Edge. */
kLPUART_TxDataRegEmptyInterruptEnable = (LPUART_CTRL_TIE_MASK), /*!< Transmit data register empty. */
kLPUART_TransmissionCompleteInterruptEnable = (LPUART_CTRL_TCIE_MASK), /*!< Transmission complete. */
kLPUART_RxDataRegFullInterruptEnable = (LPUART_CTRL_RIE_MASK), /*!< Receiver data register full. */
kLPUART_IdleLineInterruptEnable = (LPUART_CTRL_ILIE_MASK), /*!< Idle line. */
kLPUART_RxOverrunInterruptEnable = (LPUART_CTRL_ORIE_MASK), /*!< Receiver Overrun. */
kLPUART_NoiseErrorInterruptEnable = (LPUART_CTRL_NEIE_MASK), /*!< Noise error flag. */
kLPUART_FramingErrorInterruptEnable = (LPUART_CTRL_FEIE_MASK), /*!< Framing error flag. */
kLPUART_ParityErrorInterruptEnable = (LPUART_CTRL_PEIE_MASK), /*!< Parity error flag. */
#if defined(FSL_FEATURE_LPUART_HAS_FIFO) && FSL_FEATURE_LPUART_HAS_FIFO
kLPUART_TxFifoOverflowInterruptEnable = (LPUART_FIFO_TXOFE_MASK >> 8), /*!< Transmit FIFO Overflow. */
kLPUART_RxFifoUnderflowInterruptEnable = (LPUART_FIFO_RXUFE_MASK >> 8), /*!< Receive FIFO Underflow. */
#endif
};
/*!
* @brief LPUART status flags.
*
* This provides constants for the LPUART status flags for use in the LPUART functions.
*/
enum _lpuart_flags
{
kLPUART_TxDataRegEmptyFlag =
(LPUART_STAT_TDRE_MASK), /*!< Transmit data register empty flag, sets when transmit buffer is empty */
kLPUART_TransmissionCompleteFlag =
(LPUART_STAT_TC_MASK), /*!< Transmission complete flag, sets when transmission activity complete */
kLPUART_RxDataRegFullFlag =
(LPUART_STAT_RDRF_MASK), /*!< Receive data register full flag, sets when the receive data buffer is full */
kLPUART_IdleLineFlag = (LPUART_STAT_IDLE_MASK), /*!< Idle line detect flag, sets when idle line detected */
kLPUART_RxOverrunFlag = (LPUART_STAT_OR_MASK), /*!< Receive Overrun, sets when new data is received before data is
read from receive register */
kLPUART_NoiseErrorFlag = (LPUART_STAT_NF_MASK), /*!< Receive takes 3 samples of each received bit. If any of these
samples differ, noise flag sets */
kLPUART_FramingErrorFlag =
(LPUART_STAT_FE_MASK), /*!< Frame error flag, sets if logic 0 was detected where stop bit expected */
kLPUART_ParityErrorFlag = (LPUART_STAT_PF_MASK), /*!< If parity enabled, sets upon parity error detection */
#if defined(FSL_FEATURE_LPUART_HAS_LIN_BREAK_DETECT) && FSL_FEATURE_LPUART_HAS_LIN_BREAK_DETECT
kLPUART_LinBreakFlag = (LPUART_STAT_LBKDIF_MASK), /*!< LIN break detect interrupt flag, sets when LIN break char
detected and LIN circuit enabled */
#endif
kLPUART_RxActiveEdgeFlag =
(LPUART_STAT_RXEDGIF_MASK), /*!< Receive pin active edge interrupt flag, sets when active edge detected */
kLPUART_RxActiveFlag =
(LPUART_STAT_RAF_MASK), /*!< Receiver Active Flag (RAF), sets at beginning of valid start bit */
#if defined(FSL_FEATURE_LPUART_HAS_ADDRESS_MATCHING) && FSL_FEATURE_LPUART_HAS_ADDRESS_MATCHING
kLPUART_DataMatch1Flag = LPUART_STAT_MA1F_MASK, /*!< The next character to be read from LPUART_DATA matches MA1*/
kLPUART_DataMatch2Flag = LPUART_STAT_MA2F_MASK, /*!< The next character to be read from LPUART_DATA matches MA2*/
#endif
#if defined(FSL_FEATURE_LPUART_HAS_EXTENDED_DATA_REGISTER_FLAGS) && FSL_FEATURE_LPUART_HAS_EXTENDED_DATA_REGISTER_FLAGS
kLPUART_NoiseErrorInRxDataRegFlag =
(LPUART_DATA_NOISY_MASK >> 10), /*!< NOISY bit, sets if noise detected in current data word */
kLPUART_ParityErrorInRxDataRegFlag =
(LPUART_DATA_PARITYE_MASK >> 10), /*!< PARITYE bit, sets if noise detected in current data word */
#endif
#if defined(FSL_FEATURE_LPUART_HAS_FIFO) && FSL_FEATURE_LPUART_HAS_FIFO
kLPUART_TxFifoEmptyFlag = (LPUART_FIFO_TXEMPT_MASK >> 16), /*!< TXEMPT bit, sets if transmit buffer is empty */
kLPUART_RxFifoEmptyFlag = (LPUART_FIFO_RXEMPT_MASK >> 16), /*!< RXEMPT bit, sets if receive buffer is empty */
kLPUART_TxFifoOverflowFlag =
(LPUART_FIFO_TXOF_MASK >> 16), /*!< TXOF bit, sets if transmit buffer overflow occurred */
kLPUART_RxFifoUnderflowFlag =
(LPUART_FIFO_RXUF_MASK >> 16), /*!< RXUF bit, sets if receive buffer underflow occurred */
#endif
};
/*! @brief LPUART configure structure. */
typedef struct _lpuart_config
{
uint32_t baudRate_Bps; /*!< LPUART baud rate */
lpuart_parity_mode_t parityMode; /*!< Parity mode, disabled (default), even, odd */
lpuart_data_bits_t dataBitsCount; /*!< Data bits count, eight (default), seven */
bool isMsb; /*!< Data bits order, LSB (default), MSB */
#if defined(FSL_FEATURE_LPUART_HAS_STOP_BIT_CONFIG_SUPPORT) && FSL_FEATURE_LPUART_HAS_STOP_BIT_CONFIG_SUPPORT
lpuart_stop_bit_count_t stopBitCount; /*!< Number of stop bits, 1 stop bit (default) or 2 stop bits */
#endif
#if defined(FSL_FEATURE_LPUART_HAS_FIFO) && FSL_FEATURE_LPUART_HAS_FIFO
uint8_t txFifoWatermark; /*!< TX FIFO watermark */
uint8_t rxFifoWatermark; /*!< RX FIFO watermark */
#endif
bool enableTx; /*!< Enable TX */
bool enableRx; /*!< Enable RX */
} lpuart_config_t;
/*! @brief LPUART transfer structure. */
typedef struct _lpuart_transfer
{
uint8_t *data; /*!< The buffer of data to be transfer.*/
size_t dataSize; /*!< The byte count to be transfer. */
} lpuart_transfer_t;
/* Forward declaration of the handle typedef. */
typedef struct _lpuart_handle lpuart_handle_t;
/*! @brief LPUART transfer callback function. */
typedef void (*lpuart_transfer_callback_t)(LPUART_Type *base, lpuart_handle_t *handle, status_t status, void *userData);
/*! @brief LPUART handle structure. */
struct _lpuart_handle
{
uint8_t *volatile txData; /*!< Address of remaining data to send. */
volatile size_t txDataSize; /*!< Size of the remaining data to send. */
size_t txDataSizeAll; /*!< Size of the data to send out. */
uint8_t *volatile rxData; /*!< Address of remaining data to receive. */
volatile size_t rxDataSize; /*!< Size of the remaining data to receive. */
size_t rxDataSizeAll; /*!< Size of the data to receive. */
uint8_t *rxRingBuffer; /*!< Start address of the receiver ring buffer. */
size_t rxRingBufferSize; /*!< Size of the ring buffer. */
volatile uint16_t rxRingBufferHead; /*!< Index for the driver to store received data into ring buffer. */
volatile uint16_t rxRingBufferTail; /*!< Index for the user to get data from the ring buffer. */
lpuart_transfer_callback_t callback; /*!< Callback function. */
void *userData; /*!< LPUART callback function parameter.*/
volatile uint8_t txState; /*!< TX transfer state. */
volatile uint8_t rxState; /*!< RX transfer state. */
#if defined(FSL_FEATURE_LPUART_HAS_7BIT_DATA_SUPPORT) && FSL_FEATURE_LPUART_HAS_7BIT_DATA_SUPPORT
bool isSevenDataBits; /*!< Seven data bits flag. */
#endif
};
/*******************************************************************************
* API
******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif /* _cplusplus */
/*!
* @name Initialization and deinitialization
* @{
*/
/*!
* @brief Initializes an LPUART instance with the user configuration structure and the peripheral clock.
*
* This function configures the LPUART module with user-defined settings. Call the LPUART_GetDefaultConfig() function
* to configure the configuration structure and get the default configuration.
* The example below shows how to use this API to configure the LPUART.
* @code
* lpuart_config_t lpuartConfig;
* lpuartConfig.baudRate_Bps = 115200U;
* lpuartConfig.parityMode = kLPUART_ParityDisabled;
* lpuartConfig.dataBitsCount = kLPUART_EightDataBits;
* lpuartConfig.isMsb = false;
* lpuartConfig.stopBitCount = kLPUART_OneStopBit;
* lpuartConfig.txFifoWatermark = 0;
* lpuartConfig.rxFifoWatermark = 1;
* LPUART_Init(LPUART1, &lpuartConfig, 20000000U);
* @endcode
*
* @param base LPUART peripheral base address.
* @param config Pointer to a user-defined configuration structure.
* @param srcClock_Hz LPUART clock source frequency in HZ.
* @retval kStatus_LPUART_BaudrateNotSupport Baudrate is not support in current clock source.
* @retval kStatus_Success LPUART initialize succeed
*/
status_t LPUART_Init(LPUART_Type *base, const lpuart_config_t *config, uint32_t srcClock_Hz);
/*!
* @brief Deinitializes a LPUART instance.
*
* This function waits for transmit to complete, disables TX and RX, and disables the LPUART clock.
*
* @param base LPUART peripheral base address.
*/
void LPUART_Deinit(LPUART_Type *base);
/*!
* @brief Gets the default configuration structure.
*
* This function initializes the LPUART configuration structure to a default value. The default
* values are:
* lpuartConfig->baudRate_Bps = 115200U;
* lpuartConfig->parityMode = kLPUART_ParityDisabled;
* lpuartConfig->dataBitsCount = kLPUART_EightDataBits;
* lpuartConfig->isMsb = false;
* lpuartConfig->stopBitCount = kLPUART_OneStopBit;
* lpuartConfig->txFifoWatermark = 0;
* lpuartConfig->rxFifoWatermark = 1;
* lpuartConfig->enableTx = false;
* lpuartConfig->enableRx = false;
*
* @param config Pointer to a configuration structure.
*/
void LPUART_GetDefaultConfig(lpuart_config_t *config);
/*!
* @brief Sets the LPUART instance baudrate.
*
* This function configures the LPUART module baudrate. This function is used to update
* the LPUART module baudrate after the LPUART module is initialized by the LPUART_Init.
* @code
* LPUART_SetBaudRate(LPUART1, 115200U, 20000000U);
* @endcode
*
* @param base LPUART peripheral base address.
* @param baudRate_Bps LPUART baudrate to be set.
* @param srcClock_Hz LPUART clock source frequency in HZ.
* @retval kStatus_LPUART_BaudrateNotSupport Baudrate is not supported in the current clock source.
* @retval kStatus_Success Set baudrate succeeded.
*/
status_t LPUART_SetBaudRate(LPUART_Type *base, uint32_t baudRate_Bps, uint32_t srcClock_Hz);
/* @} */
/*!
* @name Status
* @{
*/
/*!
* @brief Gets LPUART status flags.
*
* This function gets all LPUART status flags. The flags are returned as the logical
* OR value of the enumerators @ref _lpuart_flags. To check for a specific status,
* compare the return value with enumerators in the @ref _lpuart_flags.
* For example, to check whether the TX is empty:
* @code
* if (kLPUART_TxDataRegEmptyFlag & LPUART_GetStatusFlags(LPUART1))
* {
* ...
* }
* @endcode
*
* @param base LPUART peripheral base address.
* @return LPUART status flags which are ORed by the enumerators in the _lpuart_flags.
*/
uint32_t LPUART_GetStatusFlags(LPUART_Type *base);
/*!
* @brief Clears status flags with a provided mask.
*
* This function clears LPUART status flags with a provided mask. Automatically cleared flags
* can't be cleared by this function.
* Flags that can only cleared or set by hardware are:
* kLPUART_TxDataRegEmptyFlag, kLPUART_TransmissionCompleteFlag, kLPUART_RxDataRegFullFlag,
* kLPUART_RxActiveFlag, kLPUART_NoiseErrorInRxDataRegFlag, kLPUART_ParityErrorInRxDataRegFlag,
* kLPUART_TxFifoEmptyFlag,kLPUART_RxFifoEmptyFlag
* Note: This API should be called when the Tx/Rx is idle, otherwise it takes no effects.
*
* @param base LPUART peripheral base address.
* @param mask the status flags to be cleared. The user can use the enumerators in the
* _lpuart_status_flag_t to do the OR operation and get the mask.
* @return 0 succeed, others failed.
* @retval kStatus_LPUART_FlagCannotClearManually The flag can't be cleared by this function but
* it is cleared automatically by hardware.
* @retval kStatus_Success Status in the mask are cleared.
*/
status_t LPUART_ClearStatusFlags(LPUART_Type *base, uint32_t mask);
/* @} */
/*!
* @name Interrupts
* @{
*/
/*!
* @brief Enables LPUART interrupts according to a provided mask.
*
* This function enables the LPUART interrupts according to a provided mask. The mask
* is a logical OR of enumeration members. See the @ref _lpuart_interrupt_enable.
* This examples shows how to enable TX empty interrupt and RX full interrupt:
* @code
* LPUART_EnableInterrupts(LPUART1,kLPUART_TxDataRegEmptyInterruptEnable | kLPUART_RxDataRegFullInterruptEnable);
* @endcode
*
* @param base LPUART peripheral base address.
* @param mask The interrupts to enable. Logical OR of @ref _uart_interrupt_enable.
*/
void LPUART_EnableInterrupts(LPUART_Type *base, uint32_t mask);
/*!
* @brief Disables LPUART interrupts according to a provided mask.
*
* This function disables the LPUART interrupts according to a provided mask. The mask
* is a logical OR of enumeration members. See @ref _lpuart_interrupt_enable.
* This example shows how to disable the TX empty interrupt and RX full interrupt:
* @code
* LPUART_DisableInterrupts(LPUART1,kLPUART_TxDataRegEmptyInterruptEnable | kLPUART_RxDataRegFullInterruptEnable);
* @endcode
*
* @param base LPUART peripheral base address.
* @param mask The interrupts to disable. Logical OR of @ref _lpuart_interrupt_enable.
*/
void LPUART_DisableInterrupts(LPUART_Type *base, uint32_t mask);
/*!
* @brief Gets enabled LPUART interrupts.
*
* This function gets the enabled LPUART interrupts. The enabled interrupts are returned
* as the logical OR value of the enumerators @ref _lpuart_interrupt_enable. To check
* a specific interrupt enable status, compare the return value with enumerators
* in @ref _lpuart_interrupt_enable.
* For example, to check whether the TX empty interrupt is enabled:
* @code
* uint32_t enabledInterrupts = LPUART_GetEnabledInterrupts(LPUART1);
*
* if (kLPUART_TxDataRegEmptyInterruptEnable & enabledInterrupts)
* {
* ...
* }
* @endcode
*
* @param base LPUART peripheral base address.
* @return LPUART interrupt flags which are logical OR of the enumerators in @ref _lpuart_interrupt_enable.
*/
uint32_t LPUART_GetEnabledInterrupts(LPUART_Type *base);
#if defined(FSL_FEATURE_LPUART_HAS_DMA_ENABLE) && FSL_FEATURE_LPUART_HAS_DMA_ENABLE
/*!
* @brief Gets the LPUART data register address.
*
* This function returns the LPUART data register address, which is mainly used by the DMA/eDMA.
*
* @param base LPUART peripheral base address.
* @return LPUART data register addresses which are used both by the transmitter and receiver.
*/
static inline uint32_t LPUART_GetDataRegisterAddress(LPUART_Type *base)
{
return (uint32_t) & (base->DATA);
}
/*!
* @brief Enables or disables the LPUART transmitter DMA request.
*
* This function enables or disables the transmit data register empty flag, STAT[TDRE], to generate DMA requests.
*
* @param base LPUART peripheral base address.
* @param enable True to enable, false to disable.
*/
static inline void LPUART_EnableTxDMA(LPUART_Type *base, bool enable)
{
if (enable)
{
base->BAUD |= LPUART_BAUD_TDMAE_MASK;
base->CTRL |= LPUART_CTRL_TIE_MASK;
}
else
{
base->BAUD &= ~LPUART_BAUD_TDMAE_MASK;
base->CTRL &= ~LPUART_CTRL_TIE_MASK;
}
}
/*!
* @brief Enables or disables the LPUART receiver DMA.
*
* This function enables or disables the receiver data register full flag, STAT[RDRF], to generate DMA requests.
*
* @param base LPUART peripheral base address.
* @param enable True to enable, false to disable.
*/
static inline void LPUART_EnableRxDMA(LPUART_Type *base, bool enable)
{
if (enable)
{
base->BAUD |= LPUART_BAUD_RDMAE_MASK;
base->CTRL |= LPUART_CTRL_RIE_MASK;
}
else
{
base->BAUD &= ~LPUART_BAUD_RDMAE_MASK;
base->CTRL &= ~LPUART_CTRL_RIE_MASK;
}
}
/* @} */
#endif /* FSL_FEATURE_LPUART_HAS_DMA_ENABLE */
/*!
* @name Bus Operations
* @{
*/
/*!
* @brief Enables or disables the LPUART transmitter.
*
* This function enables or disables the LPUART transmitter.
*
* @param base LPUART peripheral base address.
* @param enable True to enable, false to disable.
*/
static inline void LPUART_EnableTx(LPUART_Type *base, bool enable)
{
if (enable)
{
base->CTRL |= LPUART_CTRL_TE_MASK;
}
else
{
base->CTRL &= ~LPUART_CTRL_TE_MASK;
}
}
/*!
* @brief Enables or disables the LPUART receiver.
*
* This function enables or disables the LPUART receiver.
*
* @param base LPUART peripheral base address.
* @param enable True to enable, false to disable.
*/
static inline void LPUART_EnableRx(LPUART_Type *base, bool enable)
{
if (enable)
{
base->CTRL |= LPUART_CTRL_RE_MASK;
}
else
{
base->CTRL &= ~LPUART_CTRL_RE_MASK;
}
}
/*!
* @brief Writes to the transmitter register.
*
* This function writes data to the transmitter register directly. The upper layer must
* ensure that the TX register is empty or that the TX FIFO has room before calling this function.
*
* @param base LPUART peripheral base address.
* @param data Data write to the TX register.
*/
static inline void LPUART_WriteByte(LPUART_Type *base, uint8_t data)
{
base->DATA = data;
}
/*!
* @brief Reads the RX register.
*
* This function reads data from the receiver register directly. The upper layer must
* ensure that the RX register is full or that the RX FIFO has data before calling this function.
*
* @param base LPUART peripheral base address.
* @return Data read from data register.
*/
static inline uint8_t LPUART_ReadByte(LPUART_Type *base)
{
#if defined(FSL_FEATURE_LPUART_HAS_7BIT_DATA_SUPPORT) && FSL_FEATURE_LPUART_HAS_7BIT_DATA_SUPPORT
uint32_t ctrl = base->CTRL;
bool isSevenDataBits = ((ctrl & LPUART_CTRL_M7_MASK) ||
((!(ctrl & LPUART_CTRL_M7_MASK)) && (!(ctrl & LPUART_CTRL_M_MASK)) && (ctrl & LPUART_CTRL_PE_MASK)));
if (isSevenDataBits)
{
return (base->DATA & 0x7F);
}
else
{
return base->DATA;
}
#else
return base->DATA;
#endif
}
/*!
* @brief Writes to transmitter register using a blocking method.
*
* This function polls the transmitter register, waits for the register to be empty or for TX FIFO to have
* room and then writes data to the transmitter buffer.
*
* @note This function does not check whether all data has been sent out to the bus.
* Before disabling the transmitter, check the kLPUART_TransmissionCompleteFlag to ensure that the transmit is
* finished.
*
* @param base LPUART peripheral base address.
* @param data Start address of the data to write.
* @param length Size of the data to write.
*/
void LPUART_WriteBlocking(LPUART_Type *base, const uint8_t *data, size_t length);
/*!
* @brief Reads the RX data register using a blocking method.
*
* This function polls the RX register, waits for the RX register full or RX FIFO
* has data then reads data from the TX register.
*
* @param base LPUART peripheral base address.
* @param data Start address of the buffer to store the received data.
* @param length Size of the buffer.
* @retval kStatus_LPUART_RxHardwareOverrun Receiver overrun happened while receiving data.
* @retval kStatus_LPUART_NoiseError Noise error happened while receiving data.
* @retval kStatus_LPUART_FramingError Framing error happened while receiving data.
* @retval kStatus_LPUART_ParityError Parity error happened while receiving data.
* @retval kStatus_Success Successfully received all data.
*/
status_t LPUART_ReadBlocking(LPUART_Type *base, uint8_t *data, size_t length);
/* @} */
/*!
* @name Transactional
* @{
*/
/*!
* @brief Initializes the LPUART handle.
*
* This function initializes the LPUART handle, which can be used for other LPUART
* transactional APIs. Usually, for a specified LPUART instance,
* call this API once to get the initialized handle.
*
* The LPUART driver supports the "background" receiving, which means that user can set up
* an RX ring buffer optionally. Data received is stored into the ring buffer even when the
* user doesn't call the LPUART_TransferReceiveNonBlocking() API. If there is already data received
* in the ring buffer, the user can get the received data from the ring buffer directly.
* The ring buffer is disabled if passing NULL as @p ringBuffer.
*
* @param base LPUART peripheral base address.
* @param handle LPUART handle pointer.
* @param callback Callback function.
* @param userData User data.
*/
void LPUART_TransferCreateHandle(LPUART_Type *base,
lpuart_handle_t *handle,
lpuart_transfer_callback_t callback,
void *userData);
/*!
* @brief Transmits a buffer of data using the interrupt method.
*
* This function send data using an interrupt method. This is a non-blocking function, which
* returns directly without waiting for all data written to the transmitter register. When
* all data is written to the TX register in the ISR, the LPUART driver calls the callback
* function and passes the @ref kStatus_LPUART_TxIdle as status parameter.
*
* @note The kStatus_LPUART_TxIdle is passed to the upper layer when all data are written
* to the TX register. However, there is no check to ensure that all the data sent out. Before disabling the TX,
* check the kLPUART_TransmissionCompleteFlag to ensure that the transmit is finished.
*
* @param base LPUART peripheral base address.
* @param handle LPUART handle pointer.
* @param xfer LPUART transfer structure, see #lpuart_transfer_t.
* @retval kStatus_Success Successfully start the data transmission.
* @retval kStatus_LPUART_TxBusy Previous transmission still not finished, data not all written to the TX register.
* @retval kStatus_InvalidArgument Invalid argument.
*/
status_t LPUART_TransferSendNonBlocking(LPUART_Type *base, lpuart_handle_t *handle, lpuart_transfer_t *xfer);
/*!
* @brief Sets up the RX ring buffer.
*
* This function sets up the RX ring buffer to a specific UART handle.
*
* When the RX ring buffer is used, data received is stored into the ring buffer even when
* the user doesn't call the UART_TransferReceiveNonBlocking() API. If there is already data received
* in the ring buffer, the user can get the received data from the ring buffer directly.
*
* @note When using RX ring buffer, one byte is reserved for internal use. In other
* words, if @p ringBufferSize is 32, then only 31 bytes are used for saving data.
*
* @param base LPUART peripheral base address.
* @param handle LPUART handle pointer.
* @param ringBuffer Start address of ring buffer for background receiving. Pass NULL to disable the ring buffer.
* @param ringBufferSize size of the ring buffer.
*/
void LPUART_TransferStartRingBuffer(LPUART_Type *base,
lpuart_handle_t *handle,
uint8_t *ringBuffer,
size_t ringBufferSize);
/*!
* @brief Abort the background transfer and uninstall the ring buffer.
*
* This function aborts the background transfer and uninstalls the ring buffer.
*
* @param base LPUART peripheral base address.
* @param handle LPUART handle pointer.
*/
void LPUART_TransferStopRingBuffer(LPUART_Type *base, lpuart_handle_t *handle);
/*!
* @brief Aborts the interrupt-driven data transmit.
*
* This function aborts the interrupt driven data sending. The user can get the remainBtyes to find out
* how many bytes are still not sent out.
*
* @param base LPUART peripheral base address.
* @param handle LPUART handle pointer.
*/
void LPUART_TransferAbortSend(LPUART_Type *base, lpuart_handle_t *handle);
/*!
* @brief Get the number of bytes that have been written to LPUART TX register.
*
* This function gets the number of bytes that have been written to LPUART TX
* register by interrupt method.
*
* @param base LPUART peripheral base address.
* @param handle LPUART handle pointer.
* @param count Send bytes count.
* @retval kStatus_NoTransferInProgress No send in progress.
* @retval kStatus_InvalidArgument Parameter is invalid.
* @retval kStatus_Success Get successfully through the parameter \p count;
*/
status_t LPUART_TransferGetSendCount(LPUART_Type *base, lpuart_handle_t *handle, uint32_t *count);
/*!
* @brief Receives a buffer of data using the interrupt method.
*
* This function receives data using an interrupt method. This is a non-blocking function
* which returns without waiting to ensure that all data are received.
* If the RX ring buffer is used and not empty, the data in the ring buffer is copied and
* the parameter @p receivedBytes shows how many bytes are copied from the ring buffer.
* After copying, if the data in the ring buffer is not enough for read, the receive
* request is saved by the LPUART driver. When the new data arrives, the receive request
* is serviced first. When all data is received, the LPUART driver notifies the upper layer
* through a callback function and passes a status parameter @ref kStatus_UART_RxIdle.
* For example, the upper layer needs 10 bytes but there are only 5 bytes in ring buffer.
* The 5 bytes are copied to xfer->data, which returns with the
* parameter @p receivedBytes set to 5. For the remaining 5 bytes, the newly arrived data is
* saved from xfer->data[5]. When 5 bytes are received, the LPUART driver notifies the upper layer.
* If the RX ring buffer is not enabled, this function enables the RX and RX interrupt
* to receive data to xfer->data. When all data is received, the upper layer is notified.
*
* @param base LPUART peripheral base address.
* @param handle LPUART handle pointer.
* @param xfer LPUART transfer structure, see #uart_transfer_t.
* @param receivedBytes Bytes received from the ring buffer directly.
* @retval kStatus_Success Successfully queue the transfer into the transmit queue.
* @retval kStatus_LPUART_RxBusy Previous receive request is not finished.
* @retval kStatus_InvalidArgument Invalid argument.
*/
status_t LPUART_TransferReceiveNonBlocking(LPUART_Type *base,
lpuart_handle_t *handle,
lpuart_transfer_t *xfer,
size_t *receivedBytes);
/*!
* @brief Aborts the interrupt-driven data receiving.
*
* This function aborts the interrupt-driven data receiving. The user can get the remainBytes to find out
* how many bytes not received yet.
*
* @param base LPUART peripheral base address.
* @param handle LPUART handle pointer.
*/
void LPUART_TransferAbortReceive(LPUART_Type *base, lpuart_handle_t *handle);
/*!
* @brief Get the number of bytes that have been received.
*
* This function gets the number of bytes that have been received.
*
* @param base LPUART peripheral base address.
* @param handle LPUART handle pointer.
* @param count Receive bytes count.
* @retval kStatus_NoTransferInProgress No receive in progress.
* @retval kStatus_InvalidArgument Parameter is invalid.
* @retval kStatus_Success Get successfully through the parameter \p count;
*/
status_t LPUART_TransferGetReceiveCount(LPUART_Type *base, lpuart_handle_t *handle, uint32_t *count);
/*!
* @brief LPUART IRQ handle function.
*
* This function handles the LPUART transmit and receive IRQ request.
*
* @param base LPUART peripheral base address.
* @param handle LPUART handle pointer.
*/
void LPUART_TransferHandleIRQ(LPUART_Type *base, lpuart_handle_t *handle);
/*!
* @brief LPUART Error IRQ handle function.
*
* This function handles the LPUART error IRQ request.
*
* @param base LPUART peripheral base address.
* @param handle LPUART handle pointer.
*/
void LPUART_TransferHandleErrorIRQ(LPUART_Type *base, lpuart_handle_t *handle);
/* @} */
#if defined(__cplusplus)
}
#endif
/*! @}*/
#endif /* _FSL_LPUART_H_ */

View File

@ -0,0 +1,331 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include "fsl_lpuart_edma.h"
#include "fsl_dmamux.h"
/*******************************************************************************
* Definitions
******************************************************************************/
/*<! Structure definition for lpuart_edma_private_handle_t. The structure is private. */
typedef struct _lpuart_edma_private_handle
{
LPUART_Type *base;
lpuart_edma_handle_t *handle;
} lpuart_edma_private_handle_t;
/* LPUART EDMA transfer handle. */
enum _lpuart_edma_tansfer_states
{
kLPUART_TxIdle, /* TX idle. */
kLPUART_TxBusy, /* TX busy. */
kLPUART_RxIdle, /* RX idle. */
kLPUART_RxBusy /* RX busy. */
};
/*******************************************************************************
* Definitions
******************************************************************************/
/*<! Private handle only used for internally. */
static lpuart_edma_private_handle_t s_edmaPrivateHandle[FSL_FEATURE_SOC_LPUART_COUNT];
/*******************************************************************************
* Prototypes
******************************************************************************/
/*!
* @brief LPUART EDMA send finished callback function.
*
* This function is called when LPUART EDMA send finished. It disables the LPUART
* TX EDMA request and sends @ref kStatus_LPUART_TxIdle to LPUART callback.
*
* @param handle The EDMA handle.
* @param param Callback function parameter.
*/
static void LPUART_SendEDMACallback(edma_handle_t *handle, void *param, bool transferDone, uint32_t tcds);
/*!
* @brief LPUART EDMA receive finished callback function.
*
* This function is called when LPUART EDMA receive finished. It disables the LPUART
* RX EDMA request and sends @ref kStatus_LPUART_RxIdle to LPUART callback.
*
* @param handle The EDMA handle.
* @param param Callback function parameter.
*/
static void LPUART_ReceiveEDMACallback(edma_handle_t *handle, void *param, bool transferDone, uint32_t tcds);
/*!
* @brief Get the LPUART instance from peripheral base address.
*
* @param base LPUART peripheral base address.
* @return LPUART instance.
*/
extern uint32_t LPUART_GetInstance(LPUART_Type *base);
/*******************************************************************************
* Code
******************************************************************************/
static void LPUART_SendEDMACallback(edma_handle_t *handle, void *param, bool transferDone, uint32_t tcds)
{
assert(param);
lpuart_edma_private_handle_t *lpuartPrivateHandle = (lpuart_edma_private_handle_t *)param;
/* Avoid the warning for unused variables. */
handle = handle;
tcds = tcds;
if (transferDone)
{
LPUART_TransferAbortSendEDMA(lpuartPrivateHandle->base, lpuartPrivateHandle->handle);
if (lpuartPrivateHandle->handle->callback)
{
lpuartPrivateHandle->handle->callback(lpuartPrivateHandle->base, lpuartPrivateHandle->handle,
kStatus_LPUART_TxIdle, lpuartPrivateHandle->handle->userData);
}
}
}
static void LPUART_ReceiveEDMACallback(edma_handle_t *handle, void *param, bool transferDone, uint32_t tcds)
{
assert(param);
lpuart_edma_private_handle_t *lpuartPrivateHandle = (lpuart_edma_private_handle_t *)param;
/* Avoid warning for unused parameters. */
handle = handle;
tcds = tcds;
if (transferDone)
{
/* Disable transfer. */
LPUART_TransferAbortReceiveEDMA(lpuartPrivateHandle->base, lpuartPrivateHandle->handle);
if (lpuartPrivateHandle->handle->callback)
{
lpuartPrivateHandle->handle->callback(lpuartPrivateHandle->base, lpuartPrivateHandle->handle,
kStatus_LPUART_RxIdle, lpuartPrivateHandle->handle->userData);
}
}
}
void LPUART_TransferCreateHandleEDMA(LPUART_Type *base,
lpuart_edma_handle_t *handle,
lpuart_edma_transfer_callback_t callback,
void *userData,
edma_handle_t *txEdmaHandle,
edma_handle_t *rxEdmaHandle)
{
assert(handle);
uint32_t instance = LPUART_GetInstance(base);
s_edmaPrivateHandle[instance].base = base;
s_edmaPrivateHandle[instance].handle = handle;
memset(handle, 0, sizeof(*handle));
handle->rxState = kLPUART_RxIdle;
handle->txState = kLPUART_TxIdle;
handle->rxEdmaHandle = rxEdmaHandle;
handle->txEdmaHandle = txEdmaHandle;
handle->callback = callback;
handle->userData = userData;
#if defined(FSL_FEATURE_LPUART_HAS_FIFO) && FSL_FEATURE_LPUART_HAS_FIFO
/* Note:
Take care of the RX FIFO, EDMA request only assert when received bytes
equal or more than RX water mark, there is potential issue if RX water
mark larger than 1.
For example, if RX FIFO water mark is 2, upper layer needs 5 bytes and
5 bytes are received. the last byte will be saved in FIFO but not trigger
EDMA transfer because the water mark is 2.
*/
if (rxEdmaHandle)
{
base->WATER &= (~LPUART_WATER_RXWATER_MASK);
}
#endif
/* Configure TX. */
if (txEdmaHandle)
{
EDMA_SetCallback(handle->txEdmaHandle, LPUART_SendEDMACallback, &s_edmaPrivateHandle[instance]);
}
/* Configure RX. */
if (rxEdmaHandle)
{
EDMA_SetCallback(handle->rxEdmaHandle, LPUART_ReceiveEDMACallback, &s_edmaPrivateHandle[instance]);
}
}
status_t LPUART_SendEDMA(LPUART_Type *base, lpuart_edma_handle_t *handle, lpuart_transfer_t *xfer)
{
assert(handle);
assert(handle->txEdmaHandle);
assert(xfer);
assert(xfer->data);
assert(xfer->dataSize);
edma_transfer_config_t xferConfig;
status_t status;
/* If previous TX not finished. */
if (kLPUART_TxBusy == handle->txState)
{
status = kStatus_LPUART_TxBusy;
}
else
{
handle->txState = kLPUART_TxBusy;
handle->txDataSizeAll = xfer->dataSize;
/* Prepare transfer. */
EDMA_PrepareTransfer(&xferConfig, xfer->data, sizeof(uint8_t), (void *)LPUART_GetDataRegisterAddress(base),
sizeof(uint8_t), sizeof(uint8_t), xfer->dataSize, kEDMA_MemoryToPeripheral);
/* Submit transfer. */
EDMA_SubmitTransfer(handle->txEdmaHandle, &xferConfig);
EDMA_StartTransfer(handle->txEdmaHandle);
/* Enable LPUART TX EDMA. */
LPUART_EnableTxDMA(base, true);
status = kStatus_Success;
}
return status;
}
status_t LPUART_ReceiveEDMA(LPUART_Type *base, lpuart_edma_handle_t *handle, lpuart_transfer_t *xfer)
{
assert(handle);
assert(handle->rxEdmaHandle);
assert(xfer);
assert(xfer->data);
assert(xfer->dataSize);
edma_transfer_config_t xferConfig;
status_t status;
/* If previous RX not finished. */
if (kLPUART_RxBusy == handle->rxState)
{
status = kStatus_LPUART_RxBusy;
}
else
{
handle->rxState = kLPUART_RxBusy;
handle->rxDataSizeAll = xfer->dataSize;
/* Prepare transfer. */
EDMA_PrepareTransfer(&xferConfig, (void *)LPUART_GetDataRegisterAddress(base), sizeof(uint8_t), xfer->data,
sizeof(uint8_t), sizeof(uint8_t), xfer->dataSize, kEDMA_PeripheralToMemory);
/* Submit transfer. */
EDMA_SubmitTransfer(handle->rxEdmaHandle, &xferConfig);
EDMA_StartTransfer(handle->rxEdmaHandle);
/* Enable LPUART RX EDMA. */
LPUART_EnableRxDMA(base, true);
status = kStatus_Success;
}
return status;
}
void LPUART_TransferAbortSendEDMA(LPUART_Type *base, lpuart_edma_handle_t *handle)
{
assert(handle);
assert(handle->txEdmaHandle);
/* Disable LPUART TX EDMA. */
LPUART_EnableTxDMA(base, false);
/* Stop transfer. */
EDMA_AbortTransfer(handle->txEdmaHandle);
handle->txState = kLPUART_TxIdle;
}
void LPUART_TransferAbortReceiveEDMA(LPUART_Type *base, lpuart_edma_handle_t *handle)
{
assert(handle);
assert(handle->rxEdmaHandle);
/* Disable LPUART RX EDMA. */
LPUART_EnableRxDMA(base, false);
/* Stop transfer. */
EDMA_AbortTransfer(handle->rxEdmaHandle);
handle->rxState = kLPUART_RxIdle;
}
status_t LPUART_TransferGetReceiveCountEDMA(LPUART_Type *base, lpuart_edma_handle_t *handle, uint32_t *count)
{
assert(handle);
assert(handle->rxEdmaHandle);
assert(count);
if (kLPUART_RxIdle == handle->rxState)
{
return kStatus_NoTransferInProgress;
}
*count = handle->rxDataSizeAll - EDMA_GetRemainingBytes(handle->rxEdmaHandle->base, handle->rxEdmaHandle->channel);
return kStatus_Success;
}
status_t LPUART_TransferGetSendCountEDMA(LPUART_Type *base, lpuart_edma_handle_t *handle, uint32_t *count)
{
assert(handle);
assert(handle->txEdmaHandle);
assert(count);
if (kLPUART_TxIdle == handle->txState)
{
return kStatus_NoTransferInProgress;
}
*count = handle->txDataSizeAll - EDMA_GetRemainingBytes(handle->txEdmaHandle->base, handle->txEdmaHandle->channel);
return kStatus_Success;
}

View File

@ -0,0 +1,189 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _FSL_LPUART_EDMA_H_
#define _FSL_LPUART_EDMA_H_
#include "fsl_lpuart.h"
#include "fsl_dmamux.h"
#include "fsl_edma.h"
/*!
* @addtogroup lpuart_edma_driver
* @{
*/
/*******************************************************************************
* Definitions
******************************************************************************/
/* Forward declaration of the handle typedef. */
typedef struct _lpuart_edma_handle lpuart_edma_handle_t;
/*! @brief LPUART transfer callback function. */
typedef void (*lpuart_edma_transfer_callback_t)(LPUART_Type *base,
lpuart_edma_handle_t *handle,
status_t status,
void *userData);
/*!
* @brief LPUART eDMA handle
*/
struct _lpuart_edma_handle
{
lpuart_edma_transfer_callback_t callback; /*!< Callback function. */
void *userData; /*!< LPUART callback function parameter.*/
size_t rxDataSizeAll; /*!< Size of the data to receive. */
size_t txDataSizeAll; /*!< Size of the data to send out. */
edma_handle_t *txEdmaHandle; /*!< The eDMA TX channel used. */
edma_handle_t *rxEdmaHandle; /*!< The eDMA RX channel used. */
volatile uint8_t txState; /*!< TX transfer state. */
volatile uint8_t rxState; /*!< RX transfer state */
};
/*******************************************************************************
* API
******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif
/*!
* @name eDMA transactional
* @{
*/
/*!
* @brief Initializes the LPUART handle which is used in transactional functions.
* @param base LPUART peripheral base address.
* @param handle Pointer to lpuart_edma_handle_t structure.
* @param callback Callback function.
* @param userData User data.
* @param txEdmaHandle User requested DMA handle for TX DMA transfer.
* @param rxEdmaHandle User requested DMA handle for RX DMA transfer.
*/
void LPUART_TransferCreateHandleEDMA(LPUART_Type *base,
lpuart_edma_handle_t *handle,
lpuart_edma_transfer_callback_t callback,
void *userData,
edma_handle_t *txEdmaHandle,
edma_handle_t *rxEdmaHandle);
/*!
* @brief Sends data using eDMA.
*
* This function sends data using eDMA. This is a non-blocking function, which returns
* right away. When all data is sent, the send callback function is called.
*
* @param base LPUART peripheral base address.
* @param handle LPUART handle pointer.
* @param xfer LPUART eDMA transfer structure. See #lpuart_transfer_t.
* @retval kStatus_Success if succeed, others failed.
* @retval kStatus_LPUART_TxBusy Previous transfer on going.
* @retval kStatus_InvalidArgument Invalid argument.
*/
status_t LPUART_SendEDMA(LPUART_Type *base, lpuart_edma_handle_t *handle, lpuart_transfer_t *xfer);
/*!
* @brief Receives data using eDMA.
*
* This function receives data using eDMA. This is non-blocking function, which returns
* right away. When all data is received, the receive callback function is called.
*
* @param base LPUART peripheral base address.
* @param handle Pointer to lpuart_edma_handle_t structure.
* @param xfer LPUART eDMA transfer structure, see #lpuart_transfer_t.
* @retval kStatus_Success if succeed, others fail.
* @retval kStatus_LPUART_RxBusy Previous transfer ongoing.
* @retval kStatus_InvalidArgument Invalid argument.
*/
status_t LPUART_ReceiveEDMA(LPUART_Type *base, lpuart_edma_handle_t *handle, lpuart_transfer_t *xfer);
/*!
* @brief Aborts the sent data using eDMA.
*
* This function aborts the sent data using eDMA.
*
* @param base LPUART peripheral base address.
* @param handle Pointer to lpuart_edma_handle_t structure.
*/
void LPUART_TransferAbortSendEDMA(LPUART_Type *base, lpuart_edma_handle_t *handle);
/*!
* @brief Aborts the received data using eDMA.
*
* This function aborts the received data using eDMA.
*
* @param base LPUART peripheral base address.
* @param handle Pointer to lpuart_edma_handle_t structure.
*/
void LPUART_TransferAbortReceiveEDMA(LPUART_Type *base, lpuart_edma_handle_t *handle);
/*!
* @brief Get the number of bytes that have been written to LPUART TX register.
*
* This function gets the number of bytes that have been written to LPUART TX
* register by DMA.
*
* @param base LPUART peripheral base address.
* @param handle LPUART handle pointer.
* @param count Send bytes count.
* @retval kStatus_NoTransferInProgress No send in progress.
* @retval kStatus_InvalidArgument Parameter is invalid.
* @retval kStatus_Success Get successfully through the parameter \p count;
*/
status_t LPUART_TransferGetSendCountEDMA(LPUART_Type *base, lpuart_edma_handle_t *handle, uint32_t *count);
/*!
* @brief Get the number of bytes that have been received.
*
* This function gets the number of bytes that have been received.
*
* @param base LPUART peripheral base address.
* @param handle LPUART handle pointer.
* @param count Receive bytes count.
* @retval kStatus_NoTransferInProgress No receive in progress.
* @retval kStatus_InvalidArgument Parameter is invalid.
* @retval kStatus_Success Get successfully through the parameter \p count;
*/
status_t LPUART_TransferGetReceiveCountEDMA(LPUART_Type *base, lpuart_edma_handle_t *handle, uint32_t *count);
/*@}*/
#if defined(__cplusplus)
}
#endif
/*! @}*/
#endif /* _FSL_LPUART_EDMA_H_ */

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,850 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _FSL_LTC_EDMA_H_
#define _FSL_LTC_EDMA_H_
#include "fsl_common.h"
#include "fsl_ltc.h"
#include "fsl_dmamux.h"
#include "fsl_edma.h"
/*!
* @addtogroup ltc_edma_driver
* @{
*/
/*******************************************************************************
* Definitions
******************************************************************************/
/* @brief The LTC eDMA handle type. */
typedef struct _ltc_edma_handle ltc_edma_handle_t;
/*! @brief LTC eDMA callback function. */
typedef void (*ltc_edma_callback_t)(LTC_Type *base, ltc_edma_handle_t *handle, status_t status, void *userData);
/*! @brief LTC eDMA state machine function. It is defined only for private usage inside LTC eDMA driver. */
typedef status_t (*ltc_edma_state_machine_t)(LTC_Type *base, ltc_edma_handle_t *handle);
/*!
* @brief LTC eDMA handle. It is defined only for private usage inside LTC eDMA driver.
*/
struct _ltc_edma_handle
{
ltc_edma_callback_t callback; /*!< Callback function. */
void *userData; /*!< LTC callback function parameter.*/
edma_handle_t *inputFifoEdmaHandle; /*!< The eDMA TX channel used. */
edma_handle_t *outputFifoEdmaHandle; /*!< The eDMA RX channel used. */
ltc_edma_state_machine_t state_machine; /*!< State machine. */
uint32_t state; /*!< Internal state. */
const uint8_t *inData; /*!< Input data. */
uint8_t *outData; /*!< Output data. */
uint32_t size; /*!< Size of input and output data in bytes.*/
uint32_t modeReg; /*!< LTC mode register.*/
/* Used by AES CTR*/
uint8_t *counter; /*!< Input counter (updates on return)*/
const uint8_t *key; /*!< Input key to use for forward AES cipher*/
uint32_t keySize; /*!< Size of the input key, in bytes. Must be 16, 24, or 32.*/
uint8_t
*counterlast; /*!< Output cipher of last counter, for chained CTR calls. NULL can be passed if chained calls are
not used.*/
uint32_t *szLeft; /*!< Output number of bytes in left unused in counterlast block. NULL can be passed if chained
calls are not used.*/
uint32_t lastSize; /*!< Last size.*/
};
/*******************************************************************************
* API
******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif
/*!
* @brief Init the LTC eDMA handle which is used in transcational functions
* @param base LTC module base address
* @param handle Pointer to ltc_edma_handle_t structure
* @param callback Callback function, NULL means no callback.
* @param userData Callback function parameter.
* @param inputFifoEdmaHandle User requested eDMA handle for Input FIFO eDMA.
* @param outputFifoEdmaHandle User requested eDMA handle for Output FIFO eDMA.
*/
void LTC_CreateHandleEDMA(LTC_Type *base,
ltc_edma_handle_t *handle,
ltc_edma_callback_t callback,
void *userData,
edma_handle_t *inputFifoEdmaHandle,
edma_handle_t *outputFifoEdmaHandle);
/*! @}*/
/*******************************************************************************
* AES API
******************************************************************************/
/*!
* @addtogroup ltc_edma_driver_aes
* @{
*/
/*!
* @brief Encrypts AES using the ECB block mode.
*
* Encrypts AES using the ECB block mode.
*
* @param base LTC peripheral base address
* @param handle pointer to ltc_edma_handle_t structure which stores the transaction state.
* @param plaintext Input plain text to encrypt
* @param[out] ciphertext Output cipher text
* @param size Size of input and output data in bytes. Must be multiple of 16 bytes.
* @param key Input key to use for encryption
* @param keySize Size of the input key, in bytes. Must be 16, 24, or 32.
* @return Status from encrypt operation
*/
status_t LTC_AES_EncryptEcbEDMA(LTC_Type *base,
ltc_edma_handle_t *handle,
const uint8_t *plaintext,
uint8_t *ciphertext,
uint32_t size,
const uint8_t *key,
uint32_t keySize);
/*!
* @brief Decrypts AES using ECB block mode.
*
* Decrypts AES using ECB block mode.
*
* @param base LTC peripheral base address
* @param handle pointer to ltc_edma_handle_t structure which stores the transaction state.
* @param ciphertext Input cipher text to decrypt
* @param[out] plaintext Output plain text
* @param size Size of input and output data in bytes. Must be multiple of 16 bytes.
* @param key Input key.
* @param keySize Size of the input key, in bytes. Must be 16, 24, or 32.
* @param keyType Input type of the key (allows to directly load decrypt key for AES ECB decrypt operation.)
* @return Status from decrypt operation
*/
status_t LTC_AES_DecryptEcbEDMA(LTC_Type *base,
ltc_edma_handle_t *handle,
const uint8_t *ciphertext,
uint8_t *plaintext,
uint32_t size,
const uint8_t *key,
uint32_t keySize,
ltc_aes_key_t keyType);
/*!
* @brief Encrypts AES using CBC block mode.
*
* @param base LTC peripheral base address
* @param handle pointer to ltc_edma_handle_t structure which stores the transaction state.
* @param plaintext Input plain text to encrypt
* @param[out] ciphertext Output cipher text
* @param size Size of input and output data in bytes. Must be multiple of 16 bytes.
* @param iv Input initial vector to combine with the first input block.
* @param key Input key to use for encryption
* @param keySize Size of the input key, in bytes. Must be 16, 24, or 32.
* @return Status from encrypt operation
*/
status_t LTC_AES_EncryptCbcEDMA(LTC_Type *base,
ltc_edma_handle_t *handle,
const uint8_t *plaintext,
uint8_t *ciphertext,
uint32_t size,
const uint8_t iv[LTC_AES_IV_SIZE],
const uint8_t *key,
uint32_t keySize);
/*!
* @brief Decrypts AES using CBC block mode.
*
* @param base LTC peripheral base address
* @param handle pointer to ltc_edma_handle_t structure which stores the transaction state.
* @param ciphertext Input cipher text to decrypt
* @param[out] plaintext Output plain text
* @param size Size of input and output data in bytes. Must be multiple of 16 bytes.
* @param iv Input initial vector to combine with the first input block.
* @param key Input key to use for decryption
* @param keySize Size of the input key, in bytes. Must be 16, 24, or 32.
* @param keyType Input type of the key (allows to directly load decrypt key for AES CBC decrypt operation.)
* @return Status from decrypt operation
*/
status_t LTC_AES_DecryptCbcEDMA(LTC_Type *base,
ltc_edma_handle_t *handle,
const uint8_t *ciphertext,
uint8_t *plaintext,
uint32_t size,
const uint8_t iv[LTC_AES_IV_SIZE],
const uint8_t *key,
uint32_t keySize,
ltc_aes_key_t keyType);
/*!
* @brief Encrypts or decrypts AES using CTR block mode.
*
* Encrypts or decrypts AES using CTR block mode.
* AES CTR mode uses only forward AES cipher and same algorithm for encryption and decryption.
* The only difference between encryption and decryption is that, for encryption, the input argument
* is plain text and the output argument is cipher text. For decryption, the input argument is cipher text
* and the output argument is plain text.
*
* @param base LTC peripheral base address
* @param handle pointer to ltc_edma_handle_t structure which stores the transaction state.
* @param input Input data for CTR block mode
* @param[out] output Output data for CTR block mode
* @param size Size of input and output data in bytes
* @param[in,out] counter Input counter (updates on return)
* @param key Input key to use for forward AES cipher
* @param keySize Size of the input key, in bytes. Must be 16, 24, or 32.
* @param[out] counterlast Output cipher of last counter, for chained CTR calls. NULL can be passed if chained calls are
* not used.
* @param[out] szLeft Output number of bytes in left unused in counterlast block. NULL can be passed if chained calls
* are not used.
* @return Status from encrypt operation
*/
status_t LTC_AES_CryptCtrEDMA(LTC_Type *base,
ltc_edma_handle_t *handle,
const uint8_t *input,
uint8_t *output,
uint32_t size,
uint8_t counter[LTC_AES_BLOCK_SIZE],
const uint8_t *key,
uint32_t keySize,
uint8_t counterlast[LTC_AES_BLOCK_SIZE],
uint32_t *szLeft);
/*! AES CTR decrypt is mapped to the AES CTR generic operation */
#define LTC_AES_DecryptCtrEDMA(base, handle, input, output, size, counter, key, keySize, counterlast, szLeft) \
LTC_AES_CryptCtrEDMA(base, handle, input, output, size, counter, key, keySize, counterlast, szLeft)
/*! AES CTR encrypt is mapped to the AES CTR generic operation */
#define LTC_AES_EncryptCtrEDMA(base, handle, input, output, size, counter, key, keySize, counterlast, szLeft) \
LTC_AES_CryptCtrEDMA(base, handle, input, output, size, counter, key, keySize, counterlast, szLeft)
/*!
*@}
*/
/*******************************************************************************
* DES API
******************************************************************************/
/*!
* @addtogroup ltc_edma_driver_des
* @{
*/
/*!
* @brief Encrypts DES using ECB block mode.
*
* Encrypts DES using ECB block mode.
*
* @param base LTC peripheral base address
* @param handle pointer to ltc_edma_handle_t structure which stores the transaction state.
* @param plaintext Input plaintext to encrypt
* @param[out] ciphertext Output ciphertext
* @param size Size of input and output data in bytes. Must be multiple of 8 bytes.
* @param key Input key to use for encryption
* @return Status from encrypt/decrypt operation
*/
status_t LTC_DES_EncryptEcbEDMA(LTC_Type *base,
ltc_edma_handle_t *handle,
const uint8_t *plaintext,
uint8_t *ciphertext,
uint32_t size,
const uint8_t key[LTC_DES_KEY_SIZE]);
/*!
* @brief Decrypts DES using ECB block mode.
*
* Decrypts DES using ECB block mode.
*
* @param base LTC peripheral base address
* @param handle pointer to ltc_edma_handle_t structure which stores the transaction state.
* @param ciphertext Input ciphertext to decrypt
* @param[out] plaintext Output plaintext
* @param size Size of input and output data in bytes. Must be multiple of 8 bytes.
* @param key Input key to use for decryption
* @return Status from encrypt/decrypt operation
*/
status_t LTC_DES_DecryptEcbEDMA(LTC_Type *base,
ltc_edma_handle_t *handle,
const uint8_t *ciphertext,
uint8_t *plaintext,
uint32_t size,
const uint8_t key[LTC_DES_KEY_SIZE]);
/*!
* @brief Encrypts DES using CBC block mode.
*
* Encrypts DES using CBC block mode.
*
* @param base LTC peripheral base address
* @param handle pointer to ltc_edma_handle_t structure which stores the transaction state.
* @param plaintext Input plaintext to encrypt
* @param[out] ciphertext Ouput ciphertext
* @param size Size of input and output data in bytes
* @param iv Input initial vector to combine with the first plaintext block.
* The iv does not need to be secret, but it must be unpredictable.
* @param key Input key to use for encryption
* @return Status from encrypt/decrypt operation
*/
status_t LTC_DES_EncryptCbcEDMA(LTC_Type *base,
ltc_edma_handle_t *handle,
const uint8_t *plaintext,
uint8_t *ciphertext,
uint32_t size,
const uint8_t iv[LTC_DES_IV_SIZE],
const uint8_t key[LTC_DES_KEY_SIZE]);
/*!
* @brief Decrypts DES using CBC block mode.
*
* Decrypts DES using CBC block mode.
*
* @param base LTC peripheral base address
* @param handle pointer to ltc_edma_handle_t structure which stores the transaction state.
* @param ciphertext Input ciphertext to decrypt
* @param[out] plaintext Output plaintext
* @param size Size of input data in bytes
* @param iv Input initial vector to combine with the first plaintext block.
* The iv does not need to be secret, but it must be unpredictable.
* @param key Input key to use for decryption
* @return Status from encrypt/decrypt operation
*/
status_t LTC_DES_DecryptCbcEDMA(LTC_Type *base,
ltc_edma_handle_t *handle,
const uint8_t *ciphertext,
uint8_t *plaintext,
uint32_t size,
const uint8_t iv[LTC_DES_IV_SIZE],
const uint8_t key[LTC_DES_KEY_SIZE]);
/*!
* @brief Encrypts DES using CFB block mode.
*
* Encrypts DES using CFB block mode.
*
* @param base LTC peripheral base address
* @param handle pointer to ltc_edma_handle_t structure which stores the transaction state.
* @param plaintext Input plaintext to encrypt
* @param size Size of input data in bytes
* @param iv Input initial block.
* @param key Input key to use for encryption
* @param[out] ciphertext Output ciphertext
* @return Status from encrypt/decrypt operation
*/
status_t LTC_DES_EncryptCfbEDMA(LTC_Type *base,
ltc_edma_handle_t *handle,
const uint8_t *plaintext,
uint8_t *ciphertext,
uint32_t size,
const uint8_t iv[LTC_DES_IV_SIZE],
const uint8_t key[LTC_DES_KEY_SIZE]);
/*!
* @brief Decrypts DES using CFB block mode.
*
* Decrypts DES using CFB block mode.
*
* @param base LTC peripheral base address
* @param handle pointer to ltc_edma_handle_t structure which stores the transaction state.
* @param ciphertext Input ciphertext to decrypt
* @param[out] plaintext Output plaintext
* @param size Size of input and output data in bytes
* @param iv Input initial block.
* @param key Input key to use for decryption
* @return Status from encrypt/decrypt operation
*/
status_t LTC_DES_DecryptCfbEDMA(LTC_Type *base,
ltc_edma_handle_t *handle,
const uint8_t *ciphertext,
uint8_t *plaintext,
uint32_t size,
const uint8_t iv[LTC_DES_IV_SIZE],
const uint8_t key[LTC_DES_KEY_SIZE]);
/*!
* @brief Encrypts DES using OFB block mode.
*
* Encrypts DES using OFB block mode.
*
* @param base LTC peripheral base address
* @param handle pointer to ltc_edma_handle_t structure which stores the transaction state.
* @param plaintext Input plaintext to encrypt
* @param[out] ciphertext Output ciphertext
* @param size Size of input and output data in bytes
* @param iv Input unique input vector. The OFB mode requires that the IV be unique
* for each execution of the mode under the given key.
* @param key Input key to use for encryption
* @return Status from encrypt/decrypt operation
*/
status_t LTC_DES_EncryptOfbEDMA(LTC_Type *base,
ltc_edma_handle_t *handle,
const uint8_t *plaintext,
uint8_t *ciphertext,
uint32_t size,
const uint8_t iv[LTC_DES_IV_SIZE],
const uint8_t key[LTC_DES_KEY_SIZE]);
/*!
* @brief Decrypts DES using OFB block mode.
*
* Decrypts DES using OFB block mode.
*
* @param base LTC peripheral base address
* @param handle pointer to ltc_edma_handle_t structure which stores the transaction state.
* @param ciphertext Input ciphertext to decrypt
* @param[out] plaintext Output plaintext
* @param size Size of input and output data in bytes. Must be multiple of 8 bytes.
* @param iv Input unique input vector. The OFB mode requires that the IV be unique
* for each execution of the mode under the given key.
* @param key Input key to use for decryption
* @return Status from encrypt/decrypt operation
*/
status_t LTC_DES_DecryptOfbEDMA(LTC_Type *base,
ltc_edma_handle_t *handle,
const uint8_t *ciphertext,
uint8_t *plaintext,
uint32_t size,
const uint8_t iv[LTC_DES_IV_SIZE],
const uint8_t key[LTC_DES_KEY_SIZE]);
/*!
* @brief Encrypts triple DES using ECB block mode with two keys.
*
* Encrypts triple DES using ECB block mode with two keys.
*
* @param base LTC peripheral base address
* @param handle pointer to ltc_edma_handle_t structure which stores the transaction state.
* @param plaintext Input plaintext to encrypt
* @param[out] ciphertext Output ciphertext
* @param size Size of input and output data in bytes. Must be multiple of 8 bytes.
* @param key1 First input key for key bundle
* @param key2 Second input key for key bundle
* @return Status from encrypt/decrypt operation
*/
status_t LTC_DES2_EncryptEcbEDMA(LTC_Type *base,
ltc_edma_handle_t *handle,
const uint8_t *plaintext,
uint8_t *ciphertext,
uint32_t size,
const uint8_t key1[LTC_DES_KEY_SIZE],
const uint8_t key2[LTC_DES_KEY_SIZE]);
/*!
* @brief Decrypts triple DES using ECB block mode with two keys.
*
* Decrypts triple DES using ECB block mode with two keys.
*
* @param base LTC peripheral base address
* @param handle pointer to ltc_edma_handle_t structure which stores the transaction state.
* @param ciphertext Input ciphertext to decrypt
* @param[out] plaintext Output plaintext
* @param size Size of input and output data in bytes. Must be multiple of 8 bytes.
* @param key1 First input key for key bundle
* @param key2 Second input key for key bundle
* @return Status from encrypt/decrypt operation
*/
status_t LTC_DES2_DecryptEcbEDMA(LTC_Type *base,
ltc_edma_handle_t *handle,
const uint8_t *ciphertext,
uint8_t *plaintext,
uint32_t size,
const uint8_t key1[LTC_DES_KEY_SIZE],
const uint8_t key2[LTC_DES_KEY_SIZE]);
/*!
* @brief Encrypts triple DES using CBC block mode with two keys.
*
* Encrypts triple DES using CBC block mode with two keys.
*
* @param base LTC peripheral base address
* @param handle pointer to ltc_edma_handle_t structure which stores the transaction state.
* @param plaintext Input plaintext to encrypt
* @param[out] ciphertext Output ciphertext
* @param size Size of input and output data in bytes
* @param iv Input initial vector to combine with the first plaintext block.
* The iv does not need to be secret, but it must be unpredictable.
* @param key1 First input key for key bundle
* @param key2 Second input key for key bundle
* @return Status from encrypt/decrypt operation
*/
status_t LTC_DES2_EncryptCbcEDMA(LTC_Type *base,
ltc_edma_handle_t *handle,
const uint8_t *plaintext,
uint8_t *ciphertext,
uint32_t size,
const uint8_t iv[LTC_DES_IV_SIZE],
const uint8_t key1[LTC_DES_KEY_SIZE],
const uint8_t key2[LTC_DES_KEY_SIZE]);
/*!
* @brief Decrypts triple DES using CBC block mode with two keys.
*
* Decrypts triple DES using CBC block mode with two keys.
*
* @param base LTC peripheral base address
* @param handle pointer to ltc_edma_handle_t structure which stores the transaction state.
* @param ciphertext Input ciphertext to decrypt
* @param[out] plaintext Output plaintext
* @param size Size of input and output data in bytes
* @param iv Input initial vector to combine with the first plaintext block.
* The iv does not need to be secret, but it must be unpredictable.
* @param key1 First input key for key bundle
* @param key2 Second input key for key bundle
* @return Status from encrypt/decrypt operation
*/
status_t LTC_DES2_DecryptCbcEDMA(LTC_Type *base,
ltc_edma_handle_t *handle,
const uint8_t *ciphertext,
uint8_t *plaintext,
uint32_t size,
const uint8_t iv[LTC_DES_IV_SIZE],
const uint8_t key1[LTC_DES_KEY_SIZE],
const uint8_t key2[LTC_DES_KEY_SIZE]);
/*!
* @brief Encrypts triple DES using CFB block mode with two keys.
*
* Encrypts triple DES using CFB block mode with two keys.
*
* @param base LTC peripheral base address
* @param handle pointer to ltc_edma_handle_t structure which stores the transaction state.
* @param plaintext Input plaintext to encrypt
* @param[out] ciphertext Output ciphertext
* @param size Size of input and output data in bytes
* @param iv Input initial block.
* @param key1 First input key for key bundle
* @param key2 Second input key for key bundle
* @return Status from encrypt/decrypt operation
*/
status_t LTC_DES2_EncryptCfbEDMA(LTC_Type *base,
ltc_edma_handle_t *handle,
const uint8_t *plaintext,
uint8_t *ciphertext,
uint32_t size,
const uint8_t iv[LTC_DES_IV_SIZE],
const uint8_t key1[LTC_DES_KEY_SIZE],
const uint8_t key2[LTC_DES_KEY_SIZE]);
/*!
* @brief Decrypts triple DES using CFB block mode with two keys.
*
* Decrypts triple DES using CFB block mode with two keys.
*
* @param base LTC peripheral base address
* @param handle pointer to ltc_edma_handle_t structure which stores the transaction state.
* @param ciphertext Input ciphertext to decrypt
* @param[out] plaintext Output plaintext
* @param size Size of input and output data in bytes
* @param iv Input initial block.
* @param key1 First input key for key bundle
* @param key2 Second input key for key bundle
* @return Status from encrypt/decrypt operation
*/
status_t LTC_DES2_DecryptCfbEDMA(LTC_Type *base,
ltc_edma_handle_t *handle,
const uint8_t *ciphertext,
uint8_t *plaintext,
uint32_t size,
const uint8_t iv[LTC_DES_IV_SIZE],
const uint8_t key1[LTC_DES_KEY_SIZE],
const uint8_t key2[LTC_DES_KEY_SIZE]);
/*!
* @brief Encrypts triple DES using OFB block mode with two keys.
*
* Encrypts triple DES using OFB block mode with two keys.
*
* @param base LTC peripheral base address
* @param handle pointer to ltc_edma_handle_t structure which stores the transaction state.
* @param plaintext Input plaintext to encrypt
* @param[out] ciphertext Output ciphertext
* @param size Size of input and output data in bytes
* @param iv Input unique input vector. The OFB mode requires that the IV be unique
* for each execution of the mode under the given key.
* @param key1 First input key for key bundle
* @param key2 Second input key for key bundle
* @return Status from encrypt/decrypt operation
*/
status_t LTC_DES2_EncryptOfbEDMA(LTC_Type *base,
ltc_edma_handle_t *handle,
const uint8_t *plaintext,
uint8_t *ciphertext,
uint32_t size,
const uint8_t iv[LTC_DES_IV_SIZE],
const uint8_t key1[LTC_DES_KEY_SIZE],
const uint8_t key2[LTC_DES_KEY_SIZE]);
/*!
* @brief Decrypts triple DES using OFB block mode with two keys.
*
* Decrypts triple DES using OFB block mode with two keys.
*
* @param base LTC peripheral base address
* @param handle pointer to ltc_edma_handle_t structure which stores the transaction state.
* @param ciphertext Input ciphertext to decrypt
* @param[out] plaintext Output plaintext
* @param size Size of input and output data in bytes
* @param iv Input unique input vector. The OFB mode requires that the IV be unique
* for each execution of the mode under the given key.
* @param key1 First input key for key bundle
* @param key2 Second input key for key bundle
* @return Status from encrypt/decrypt operation
*/
status_t LTC_DES2_DecryptOfbEDMA(LTC_Type *base,
ltc_edma_handle_t *handle,
const uint8_t *ciphertext,
uint8_t *plaintext,
uint32_t size,
const uint8_t iv[LTC_DES_IV_SIZE],
const uint8_t key1[LTC_DES_KEY_SIZE],
const uint8_t key2[LTC_DES_KEY_SIZE]);
/*!
* @brief Encrypts triple DES using ECB block mode with three keys.
*
* Encrypts triple DES using ECB block mode with three keys.
*
* @param base LTC peripheral base address
* @param handle pointer to ltc_edma_handle_t structure which stores the transaction state.
* @param plaintext Input plaintext to encrypt
* @param[out] ciphertext Output ciphertext
* @param size Size of input and output data in bytes. Must be multiple of 8 bytes.
* @param key1 First input key for key bundle
* @param key2 Second input key for key bundle
* @param key3 Third input key for key bundle
* @return Status from encrypt/decrypt operation
*/
status_t LTC_DES3_EncryptEcbEDMA(LTC_Type *base,
ltc_edma_handle_t *handle,
const uint8_t *plaintext,
uint8_t *ciphertext,
uint32_t size,
const uint8_t key1[LTC_DES_KEY_SIZE],
const uint8_t key2[LTC_DES_KEY_SIZE],
const uint8_t key3[LTC_DES_KEY_SIZE]);
/*!
* @brief Decrypts triple DES using ECB block mode with three keys.
*
* Decrypts triple DES using ECB block mode with three keys.
*
* @param base LTC peripheral base address
* @param handle pointer to ltc_edma_handle_t structure which stores the transaction state.
* @param ciphertext Input ciphertext to decrypt
* @param[out] plaintext Output plaintext
* @param size Size of input and output data in bytes. Must be multiple of 8 bytes.
* @param key1 First input key for key bundle
* @param key2 Second input key for key bundle
* @param key3 Third input key for key bundle
* @return Status from encrypt/decrypt operation
*/
status_t LTC_DES3_DecryptEcbEDMA(LTC_Type *base,
ltc_edma_handle_t *handle,
const uint8_t *ciphertext,
uint8_t *plaintext,
uint32_t size,
const uint8_t key1[LTC_DES_KEY_SIZE],
const uint8_t key2[LTC_DES_KEY_SIZE],
const uint8_t key3[LTC_DES_KEY_SIZE]);
/*!
* @brief Encrypts triple DES using CBC block mode with three keys.
*
* Encrypts triple DES using CBC block mode with three keys.
*
* @param base LTC peripheral base address
* @param handle pointer to ltc_edma_handle_t structure which stores the transaction state.
* @param plaintext Input plaintext to encrypt
* @param[out] ciphertext Output ciphertext
* @param size Size of input data in bytes
* @param iv Input initial vector to combine with the first plaintext block.
* The iv does not need to be secret, but it must be unpredictable.
* @param key1 First input key for key bundle
* @param key2 Second input key for key bundle
* @param key3 Third input key for key bundle
* @return Status from encrypt/decrypt operation
*/
status_t LTC_DES3_EncryptCbcEDMA(LTC_Type *base,
ltc_edma_handle_t *handle,
const uint8_t *plaintext,
uint8_t *ciphertext,
uint32_t size,
const uint8_t iv[LTC_DES_IV_SIZE],
const uint8_t key1[LTC_DES_KEY_SIZE],
const uint8_t key2[LTC_DES_KEY_SIZE],
const uint8_t key3[LTC_DES_KEY_SIZE]);
/*!
* @brief Decrypts triple DES using CBC block mode with three keys.
*
* Decrypts triple DES using CBC block mode with three keys.
*
* @param base LTC peripheral base address
* @param handle pointer to ltc_edma_handle_t structure which stores the transaction state.
* @param ciphertext Input ciphertext to decrypt
* @param[out] plaintext Output plaintext
* @param size Size of input and output data in bytes
* @param iv Input initial vector to combine with the first plaintext block.
* The iv does not need to be secret, but it must be unpredictable.
* @param key1 First input key for key bundle
* @param key2 Second input key for key bundle
* @param key3 Third input key for key bundle
* @return Status from encrypt/decrypt operation
*/
status_t LTC_DES3_DecryptCbcEDMA(LTC_Type *base,
ltc_edma_handle_t *handle,
const uint8_t *ciphertext,
uint8_t *plaintext,
uint32_t size,
const uint8_t iv[LTC_DES_IV_SIZE],
const uint8_t key1[LTC_DES_KEY_SIZE],
const uint8_t key2[LTC_DES_KEY_SIZE],
const uint8_t key3[LTC_DES_KEY_SIZE]);
/*!
* @brief Encrypts triple DES using CFB block mode with three keys.
*
* Encrypts triple DES using CFB block mode with three keys.
*
* @param base LTC peripheral base address
* @param handle pointer to ltc_edma_handle_t structure which stores the transaction state.
* @param plaintext Input plaintext to encrypt
* @param[out] ciphertext Output ciphertext
* @param size Size of input and ouput data in bytes
* @param iv Input initial block.
* @param key1 First input key for key bundle
* @param key2 Second input key for key bundle
* @param key3 Third input key for key bundle
* @return Status from encrypt/decrypt operation
*/
status_t LTC_DES3_EncryptCfbEDMA(LTC_Type *base,
ltc_edma_handle_t *handle,
const uint8_t *plaintext,
uint8_t *ciphertext,
uint32_t size,
const uint8_t iv[LTC_DES_IV_SIZE],
const uint8_t key1[LTC_DES_KEY_SIZE],
const uint8_t key2[LTC_DES_KEY_SIZE],
const uint8_t key3[LTC_DES_KEY_SIZE]);
/*!
* @brief Decrypts triple DES using CFB block mode with three keys.
*
* Decrypts triple DES using CFB block mode with three keys.
*
* @param base LTC peripheral base address
* @param handle pointer to ltc_edma_handle_t structure which stores the transaction state.
* @param ciphertext Input ciphertext to decrypt
* @param[out] plaintext Output plaintext
* @param size Size of input data in bytes
* @param iv Input initial block.
* @param key1 First input key for key bundle
* @param key2 Second input key for key bundle
* @param key3 Third input key for key bundle
* @return Status from encrypt/decrypt operation
*/
status_t LTC_DES3_DecryptCfbEDMA(LTC_Type *base,
ltc_edma_handle_t *handle,
const uint8_t *ciphertext,
uint8_t *plaintext,
uint32_t size,
const uint8_t iv[LTC_DES_IV_SIZE],
const uint8_t key1[LTC_DES_KEY_SIZE],
const uint8_t key2[LTC_DES_KEY_SIZE],
const uint8_t key3[LTC_DES_KEY_SIZE]);
/*!
* @brief Encrypts triple DES using OFB block mode with three keys.
*
* Encrypts triple DES using OFB block mode with three keys.
*
* @param base LTC peripheral base address
* @param handle pointer to ltc_edma_handle_t structure which stores the transaction state.
* @param plaintext Input plaintext to encrypt
* @param[out] ciphertext Output ciphertext
* @param size Size of input and output data in bytes
* @param iv Input unique input vector. The OFB mode requires that the IV be unique
* for each execution of the mode under the given key.
* @param key1 First input key for key bundle
* @param key2 Second input key for key bundle
* @param key3 Third input key for key bundle
* @return Status from encrypt/decrypt operation
*/
status_t LTC_DES3_EncryptOfbEDMA(LTC_Type *base,
ltc_edma_handle_t *handle,
const uint8_t *plaintext,
uint8_t *ciphertext,
uint32_t size,
const uint8_t iv[LTC_DES_IV_SIZE],
const uint8_t key1[LTC_DES_KEY_SIZE],
const uint8_t key2[LTC_DES_KEY_SIZE],
const uint8_t key3[LTC_DES_KEY_SIZE]);
/*!
* @brief Decrypts triple DES using OFB block mode with three keys.
*
* Decrypts triple DES using OFB block mode with three keys.
*
* @param base LTC peripheral base address
* @param handle pointer to ltc_edma_handle_t structure which stores the transaction state.
* @param ciphertext Input ciphertext to decrypt
* @param[out] plaintext Output plaintext
* @param size Size of input and output data in bytes
* @param iv Input unique input vector. The OFB mode requires that the IV be unique
* for each execution of the mode under the given key.
* @param key1 First input key for key bundle
* @param key2 Second input key for key bundle
* @param key3 Third input key for key bundle
* @return Status from encrypt/decrypt operation
*/
status_t LTC_DES3_DecryptOfbEDMA(LTC_Type *base,
ltc_edma_handle_t *handle,
const uint8_t *ciphertext,
uint8_t *plaintext,
uint32_t size,
const uint8_t iv[LTC_DES_IV_SIZE],
const uint8_t key1[LTC_DES_KEY_SIZE],
const uint8_t key2[LTC_DES_KEY_SIZE],
const uint8_t key3[LTC_DES_KEY_SIZE]);
/*!
*@}
*/
#if defined(__cplusplus)
}
#endif
#endif /* _FSL_LTC_EDMA_H_ */

View File

@ -0,0 +1,119 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include "fsl_pit.h"
/*******************************************************************************
* Prototypes
******************************************************************************/
/*!
* @brief Gets the instance from the base address to be used to gate or ungate the module clock
*
* @param base PIT peripheral base address
*
* @return The PIT instance
*/
static uint32_t PIT_GetInstance(PIT_Type *base);
/*******************************************************************************
* Variables
******************************************************************************/
/*! @brief Pointers to PIT bases for each instance. */
static PIT_Type *const s_pitBases[] = PIT_BASE_PTRS;
/*! @brief Pointers to PIT clocks for each instance. */
static const clock_ip_name_t s_pitClocks[] = PIT_CLOCKS;
/*******************************************************************************
* Code
******************************************************************************/
static uint32_t PIT_GetInstance(PIT_Type *base)
{
uint32_t instance;
/* Find the instance index from base address mappings. */
for (instance = 0; instance < FSL_FEATURE_SOC_PIT_COUNT; instance++)
{
if (s_pitBases[instance] == base)
{
break;
}
}
assert(instance < FSL_FEATURE_SOC_PIT_COUNT);
return instance;
}
void PIT_Init(PIT_Type *base, const pit_config_t *config)
{
assert(config);
/* Ungate the PIT clock*/
CLOCK_EnableClock(s_pitClocks[PIT_GetInstance(base)]);
/* Enable PIT timers */
base->MCR &= ~PIT_MCR_MDIS_MASK;
/* Config timer operation when in debug mode */
if (config->enableRunInDebug)
{
base->MCR &= ~PIT_MCR_FRZ_MASK;
}
else
{
base->MCR |= PIT_MCR_FRZ_MASK;
}
}
void PIT_Deinit(PIT_Type *base)
{
/* Disable PIT timers */
base->MCR |= PIT_MCR_MDIS_MASK;
/* Gate the PIT clock*/
CLOCK_DisableClock(s_pitClocks[PIT_GetInstance(base)]);
}
#if defined(FSL_FEATURE_PIT_HAS_LIFETIME_TIMER) && FSL_FEATURE_PIT_HAS_LIFETIME_TIMER
uint64_t PIT_GetLifetimeTimerCount(PIT_Type *base)
{
uint32_t valueH = 0U;
uint32_t valueL = 0U;
/* LTMR64H should be read before LTMR64L */
valueH = base->LTMR64H;
valueL = base->LTMR64L;
return (((uint64_t)valueH << 32U) + (uint64_t)(valueL));
}
#endif /* FSL_FEATURE_PIT_HAS_LIFETIME_TIMER */

View File

@ -0,0 +1,354 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _FSL_PIT_H_
#define _FSL_PIT_H_
#include "fsl_common.h"
/*!
* @addtogroup pit
* @{
*/
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @name Driver version */
/*@{*/
#define FSL_PIT_DRIVER_VERSION (MAKE_VERSION(2, 0, 0)) /*!< Version 2.0.0 */
/*@}*/
/*!
* @brief List of PIT channels
* @note Actual number of available channels is SoC dependent
*/
typedef enum _pit_chnl
{
kPIT_Chnl_0 = 0U, /*!< PIT channel number 0*/
kPIT_Chnl_1, /*!< PIT channel number 1 */
kPIT_Chnl_2, /*!< PIT channel number 2 */
kPIT_Chnl_3, /*!< PIT channel number 3 */
} pit_chnl_t;
/*! @brief List of PIT interrupts */
typedef enum _pit_interrupt_enable
{
kPIT_TimerInterruptEnable = PIT_TCTRL_TIE_MASK, /*!< Timer interrupt enable*/
} pit_interrupt_enable_t;
/*! @brief List of PIT status flags */
typedef enum _pit_status_flags
{
kPIT_TimerFlag = PIT_TFLG_TIF_MASK, /*!< Timer flag */
} pit_status_flags_t;
/*!
* @brief PIT config structure
*
* This structure holds the configuration settings for the PIT peripheral. To initialize this
* structure to reasonable defaults, call the PIT_GetDefaultConfig() function and pass a
* pointer to your config structure instance.
*
* The config struct can be made const so it resides in flash
*/
typedef struct _pit_config
{
bool enableRunInDebug; /*!< true: Timers run in debug mode; false: Timers stop in debug mode */
} pit_config_t;
/*******************************************************************************
* API
******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif
/*!
* @name Initialization and deinitialization
* @{
*/
/*!
* @brief Ungates the PIT clock, enables the PIT module and configures the peripheral for basic operation.
*
* @note This API should be called at the beginning of the application using the PIT driver.
*
* @param base PIT peripheral base address
* @param config Pointer to user's PIT config structure
*/
void PIT_Init(PIT_Type *base, const pit_config_t *config);
/*!
* @brief Gate the PIT clock and disable the PIT module
*
* @param base PIT peripheral base address
*/
void PIT_Deinit(PIT_Type *base);
/*!
* @brief Fill in the PIT config struct with the default settings
*
* The default values are:
* @code
* config->enableRunInDebug = false;
* @endcode
* @param config Pointer to user's PIT config structure.
*/
static inline void PIT_GetDefaultConfig(pit_config_t *config)
{
assert(config);
/* Timers are stopped in Debug mode */
config->enableRunInDebug = false;
}
#if defined(FSL_FEATURE_PIT_HAS_CHAIN_MODE) && FSL_FEATURE_PIT_HAS_CHAIN_MODE
/*!
* @brief Enables or disables chaining a timer with the previous timer.
*
* When a timer has a chain mode enabled, it only counts after the previous
* timer has expired. If the timer n-1 has counted down to 0, counter n
* decrements the value by one. Each timer is 32-bits, this allows the developers
* to chain timers together and form a longer timer (64-bits and larger). The first timer
* (timer 0) cannot be chained to any other timer.
*
* @param base PIT peripheral base address
* @param channel Timer channel number which is chained with the previous timer
* @param enable Enable or disable chain.
* true: Current timer is chained with the previous timer.
* false: Timer doesn't chain with other timers.
*/
static inline void PIT_SetTimerChainMode(PIT_Type *base, pit_chnl_t channel, bool enable)
{
if (enable)
{
base->CHANNEL[channel].TCTRL |= PIT_TCTRL_CHN_MASK;
}
else
{
base->CHANNEL[channel].TCTRL &= ~PIT_TCTRL_CHN_MASK;
}
}
#endif /* FSL_FEATURE_PIT_HAS_CHAIN_MODE */
/*! @}*/
/*!
* @name Interrupt Interface
* @{
*/
/*!
* @brief Enables the selected PIT interrupts.
*
* @param base PIT peripheral base address
* @param channel Timer channel number
* @param mask The interrupts to enable. This is a logical OR of members of the
* enumeration ::pit_interrupt_enable_t
*/
static inline void PIT_EnableInterrupts(PIT_Type *base, pit_chnl_t channel, uint32_t mask)
{
base->CHANNEL[channel].TCTRL |= mask;
}
/*!
* @brief Disables the selected PIT interrupts.
*
* @param base PIT peripheral base address
* @param channel Timer channel number
* @param mask The interrupts to disable. This is a logical OR of members of the
* enumeration ::pit_interrupt_enable_t
*/
static inline void PIT_DisableInterrupts(PIT_Type *base, pit_chnl_t channel, uint32_t mask)
{
base->CHANNEL[channel].TCTRL &= ~mask;
}
/*!
* @brief Gets the enabled PIT interrupts.
*
* @param base PIT peripheral base address
* @param channel Timer channel number
*
* @return The enabled interrupts. This is the logical OR of members of the
* enumeration ::pit_interrupt_enable_t
*/
static inline uint32_t PIT_GetEnabledInterrupts(PIT_Type *base, pit_chnl_t channel)
{
return (base->CHANNEL[channel].TCTRL & PIT_TCTRL_TIE_MASK);
}
/*! @}*/
/*!
* @name Status Interface
* @{
*/
/*!
* @brief Gets the PIT status flags
*
* @param base PIT peripheral base address
* @param channel Timer channel number
*
* @return The status flags. This is the logical OR of members of the
* enumeration ::pit_status_flags_t
*/
static inline uint32_t PIT_GetStatusFlags(PIT_Type *base, pit_chnl_t channel)
{
return (base->CHANNEL[channel].TFLG & PIT_TFLG_TIF_MASK);
}
/*!
* @brief Clears the PIT status flags.
*
* @param base PIT peripheral base address
* @param channel Timer channel number
* @param mask The status flags to clear. This is a logical OR of members of the
* enumeration ::pit_status_flags_t
*/
static inline void PIT_ClearStatusFlags(PIT_Type *base, pit_chnl_t channel, uint32_t mask)
{
base->CHANNEL[channel].TFLG = mask;
}
/*! @}*/
/*!
* @name Read and Write the timer period
* @{
*/
/*!
* @brief Sets the timer period in units of count.
*
* Timers begin counting from the value set by this function until it reaches 0,
* then it generates an interrupt and load this register value again.
* Writing a new value to this register does not restart the timer. Instead, the value
* is loaded after the timer expires.
*
* @note User can call the utility macros provided in fsl_common.h to convert to ticks
*
* @param base PIT peripheral base address
* @param channel Timer channel number
* @param count Timer period in units of ticks
*/
static inline void PIT_SetTimerPeriod(PIT_Type *base, pit_chnl_t channel, uint32_t count)
{
base->CHANNEL[channel].LDVAL = count;
}
/*!
* @brief Reads the current timer counting value.
*
* This function returns the real-time timer counting value, in a range from 0 to a
* timer period.
*
* @note User can call the utility macros provided in fsl_common.h to convert ticks to usec or msec
*
* @param base PIT peripheral base address
* @param channel Timer channel number
*
* @return Current timer counting value in ticks
*/
static inline uint32_t PIT_GetCurrentTimerCount(PIT_Type *base, pit_chnl_t channel)
{
return base->CHANNEL[channel].CVAL;
}
/*! @}*/
/*!
* @name Timer Start and Stop
* @{
*/
/*!
* @brief Starts the timer counting.
*
* After calling this function, timers load period value, count down to 0 and
* then load the respective start value again. Each time a timer reaches 0,
* it generates a trigger pulse and sets the timeout interrupt flag.
*
* @param base PIT peripheral base address
* @param channel Timer channel number.
*/
static inline void PIT_StartTimer(PIT_Type *base, pit_chnl_t channel)
{
base->CHANNEL[channel].TCTRL |= PIT_TCTRL_TEN_MASK;
}
/*!
* @brief Stops the timer counting.
*
* This function stops every timer counting. Timers reload their periods
* respectively after the next time they call the PIT_DRV_StartTimer.
*
* @param base PIT peripheral base address
* @param channel Timer channel number.
*/
static inline void PIT_StopTimer(PIT_Type *base, pit_chnl_t channel)
{
base->CHANNEL[channel].TCTRL &= ~PIT_TCTRL_TEN_MASK;
}
/*! @}*/
#if defined(FSL_FEATURE_PIT_HAS_LIFETIME_TIMER) && FSL_FEATURE_PIT_HAS_LIFETIME_TIMER
/*!
* @brief Reads the current lifetime counter value.
*
* The lifetime timer is a 64-bit timer which chains timer 0 and timer 1 together.
* Timer 0 and 1 are chained by calling the PIT_SetTimerChainMode before using this timer.
* The period of lifetime timer is equal to the "period of timer 0 * period of timer 1".
* For the 64-bit value, the higher 32-bit has the value of timer 1, and the lower 32-bit
* has the value of timer 0.
*
* @param base PIT peripheral base address
*
* @return Current lifetime timer value
*/
uint64_t PIT_GetLifetimeTimerCount(PIT_Type *base);
#endif /* FSL_FEATURE_PIT_HAS_LIFETIME_TIMER */
#if defined(__cplusplus)
}
#endif
/*! @}*/
#endif /* _FSL_PIT_H_ */

View File

@ -0,0 +1,93 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include "fsl_pmc.h"
#if (defined(FSL_FEATURE_PMC_HAS_PARAM) && FSL_FEATURE_PMC_HAS_PARAM)
void PMC_GetParam(PMC_Type *base, pmc_param_t *param)
{
uint32_t reg = base->PARAM;
;
param->vlpoEnable = (bool)(reg & PMC_PARAM_VLPOE_MASK);
param->hvdEnable = (bool)(reg & PMC_PARAM_HVDE_MASK);
}
#endif /* FSL_FEATURE_PMC_HAS_PARAM */
void PMC_ConfigureLowVoltDetect(PMC_Type *base, const pmc_low_volt_detect_config_t *config)
{
base->LVDSC1 = (0U |
#if (defined(FSL_FEATURE_PMC_HAS_LVDV) && FSL_FEATURE_PMC_HAS_LVDV)
((uint32_t)config->voltSelect << PMC_LVDSC1_LVDV_SHIFT) |
#endif
((uint32_t)config->enableInt << PMC_LVDSC1_LVDIE_SHIFT) |
((uint32_t)config->enableReset << PMC_LVDSC1_LVDRE_SHIFT)
/* Clear the Low Voltage Detect Flag with previouse power detect setting */
| PMC_LVDSC1_LVDACK_MASK);
}
void PMC_ConfigureLowVoltWarning(PMC_Type *base, const pmc_low_volt_warning_config_t *config)
{
base->LVDSC2 = (0U |
#if (defined(FSL_FEATURE_PMC_HAS_LVWV) && FSL_FEATURE_PMC_HAS_LVWV)
((uint32_t)config->voltSelect << PMC_LVDSC2_LVWV_SHIFT) |
#endif
((uint32_t)config->enableInt << PMC_LVDSC2_LVWIE_SHIFT)
/* Clear the Low Voltage Warning Flag with previouse power detect setting */
| PMC_LVDSC2_LVWACK_MASK);
}
#if (defined(FSL_FEATURE_PMC_HAS_HVDSC1) && FSL_FEATURE_PMC_HAS_HVDSC1)
void PMC_ConfigureHighVoltDetect(PMC_Type *base, const pmc_high_volt_detect_config_t *config)
{
base->HVDSC1 = (((uint32_t)config->voltSelect << PMC_HVDSC1_HVDV_SHIFT) |
((uint32_t)config->enableInt << PMC_HVDSC1_HVDIE_SHIFT) |
((uint32_t)config->enableReset << PMC_HVDSC1_HVDRE_SHIFT)
/* Clear the High Voltage Detect Flag with previouse power detect setting */
| PMC_HVDSC1_HVDACK_MASK);
}
#endif /* FSL_FEATURE_PMC_HAS_HVDSC1 */
#if ((defined(FSL_FEATURE_PMC_HAS_BGBE) && FSL_FEATURE_PMC_HAS_BGBE) || \
(defined(FSL_FEATURE_PMC_HAS_BGEN) && FSL_FEATURE_PMC_HAS_BGEN) || \
(defined(FSL_FEATURE_PMC_HAS_BGBDS) && FSL_FEATURE_PMC_HAS_BGBDS))
void PMC_ConfigureBandgapBuffer(PMC_Type *base, const pmc_bandgap_buffer_config_t *config)
{
base->REGSC = (0U
#if (defined(FSL_FEATURE_PMC_HAS_BGBE) && FSL_FEATURE_PMC_HAS_BGBE)
| ((uint32_t)config->enable << PMC_REGSC_BGBE_SHIFT)
#endif /* FSL_FEATURE_PMC_HAS_BGBE */
#if (defined(FSL_FEATURE_PMC_HAS_BGEN) && FSL_FEATURE_PMC_HAS_BGEN)
| (((uint32_t)config->enableInLowPowerMode << PMC_REGSC_BGEN_SHIFT))
#endif /* FSL_FEATURE_PMC_HAS_BGEN */
#if (defined(FSL_FEATURE_PMC_HAS_BGBDS) && FSL_FEATURE_PMC_HAS_BGBDS)
| ((uint32_t)config->drive << PMC_REGSC_BGBDS_SHIFT)
#endif /* FSL_FEATURE_PMC_HAS_BGBDS */
);
}
#endif

View File

@ -0,0 +1,421 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _FSL_PMC_H_
#define _FSL_PMC_H_
#include "fsl_common.h"
/*! @addtogroup pmc */
/*! @{ */
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @name Driver version */
/*@{*/
/*! @brief PMC driver version */
#define FSL_PMC_DRIVER_VERSION (MAKE_VERSION(2, 0, 0)) /*!< Version 2.0.0. */
/*@}*/
#if (defined(FSL_FEATURE_PMC_HAS_LVDV) && FSL_FEATURE_PMC_HAS_LVDV)
/*!
* @brief Low-Voltage Detect Voltage Select
*/
typedef enum _pmc_low_volt_detect_volt_select
{
kPMC_LowVoltDetectLowTrip = 0U, /*!< Low trip point selected (VLVD = VLVDL )*/
kPMC_LowVoltDetectHighTrip = 1U /*!< High trip point selected (VLVD = VLVDH )*/
} pmc_low_volt_detect_volt_select_t;
#endif
#if (defined(FSL_FEATURE_PMC_HAS_LVWV) && FSL_FEATURE_PMC_HAS_LVWV)
/*!
* @brief Low-Voltage Warning Voltage Select
*/
typedef enum _pmc_low_volt_warning_volt_select
{
kPMC_LowVoltWarningLowTrip = 0U, /*!< Low trip point selected (VLVW = VLVW1)*/
kPMC_LowVoltWarningMid1Trip = 1U, /*!< Mid 1 trip point selected (VLVW = VLVW2)*/
kPMC_LowVoltWarningMid2Trip = 2U, /*!< Mid 2 trip point selected (VLVW = VLVW3)*/
kPMC_LowVoltWarningHighTrip = 3U /*!< High trip point selected (VLVW = VLVW4)*/
} pmc_low_volt_warning_volt_select_t;
#endif
#if (defined(FSL_FEATURE_PMC_HAS_HVDSC1) && FSL_FEATURE_PMC_HAS_HVDSC1)
/*!
* @brief High-Voltage Detect Voltage Select
*/
typedef enum _pmc_high_volt_detect_volt_select
{
kPMC_HighVoltDetectLowTrip = 0U, /*!< Low trip point selected (VHVD = VHVDL )*/
kPMC_HighVoltDetectHighTrip = 1U /*!< High trip point selected (VHVD = VHVDH )*/
} pmc_high_volt_detect_volt_select_t;
#endif /* FSL_FEATURE_PMC_HAS_HVDSC1 */
#if (defined(FSL_FEATURE_PMC_HAS_BGBDS) && FSL_FEATURE_PMC_HAS_BGBDS)
/*!
* @brief Bandgap Buffer Drive Select.
*/
typedef enum _pmc_bandgap_buffer_drive_select
{
kPMC_BandgapBufferDriveLow = 0U, /*!< Low drive. */
kPMC_BandgapBufferDriveHigh = 1U /*!< High drive. */
} pmc_bandgap_buffer_drive_select_t;
#endif /* FSL_FEATURE_PMC_HAS_BGBDS */
#if (defined(FSL_FEATURE_PMC_HAS_VLPO) && FSL_FEATURE_PMC_HAS_VLPO)
/*!
* @brief VLPx Option
*/
typedef enum _pmc_vlp_freq_option
{
kPMC_FreqRestrict = 0U, /*!< Frequency is restricted in VLPx mode. */
kPMC_FreqUnrestrict = 1U /*!< Frequency is unrestricted in VLPx mode. */
} pmc_vlp_freq_mode_t;
#endif /* FSL_FEATURE_PMC_HAS_VLPO */
#if (defined(FSL_FEATURE_PMC_HAS_VERID) && FSL_FEATURE_PMC_HAS_VERID)
/*!
@brief IP version ID definition.
*/
typedef struct _pmc_version_id
{
uint16_t feature; /*!< Feature Specification Number. */
uint8_t minor; /*!< Minor version number. */
uint8_t major; /*!< Major version number. */
} pmc_version_id_t;
#endif /* FSL_FEATURE_PMC_HAS_VERID */
#if (defined(FSL_FEATURE_PMC_HAS_PARAM) && FSL_FEATURE_PMC_HAS_PARAM)
/*! @brief IP parameter definition. */
typedef struct _pmc_param
{
bool vlpoEnable; /*!< VLPO enable. */
bool hvdEnable; /*!< HVD enable. */
} pmc_param_t;
#endif /* FSL_FEATURE_PMC_HAS_PARAM */
/*!
* @brief Low-Voltage Detect Configuration Structure
*/
typedef struct _pmc_low_volt_detect_config
{
bool enableInt; /*!< Enable interrupt when low-voltage detect*/
bool enableReset; /*!< Enable system reset when low-voltage detect*/
#if (defined(FSL_FEATURE_PMC_HAS_LVDV) && FSL_FEATURE_PMC_HAS_LVDV)
pmc_low_volt_detect_volt_select_t voltSelect; /*!< Low-voltage detect trip point voltage selection*/
#endif
} pmc_low_volt_detect_config_t;
/*!
* @brief Low-Voltage Warning Configuration Structure
*/
typedef struct _pmc_low_volt_warning_config
{
bool enableInt; /*!< Enable interrupt when low-voltage warning*/
#if (defined(FSL_FEATURE_PMC_HAS_LVWV) && FSL_FEATURE_PMC_HAS_LVWV)
pmc_low_volt_warning_volt_select_t voltSelect; /*!< Low-voltage warning trip point voltage selection*/
#endif
} pmc_low_volt_warning_config_t;
#if (defined(FSL_FEATURE_PMC_HAS_HVDSC1) && FSL_FEATURE_PMC_HAS_HVDSC1)
/*!
* @brief High-Voltage Detect Configuration Structure
*/
typedef struct _pmc_high_volt_detect_config
{
bool enableInt; /*!< Enable interrupt when high-voltage detect*/
bool enableReset; /*!< Enable system reset when high-voltage detect*/
pmc_high_volt_detect_volt_select_t voltSelect; /*!< High-voltage detect trip point voltage selection*/
} pmc_high_volt_detect_config_t;
#endif /* FSL_FEATURE_PMC_HAS_HVDSC1 */
#if ((defined(FSL_FEATURE_PMC_HAS_BGBE) && FSL_FEATURE_PMC_HAS_BGBE) || \
(defined(FSL_FEATURE_PMC_HAS_BGEN) && FSL_FEATURE_PMC_HAS_BGEN) || \
(defined(FSL_FEATURE_PMC_HAS_BGBDS) && FSL_FEATURE_PMC_HAS_BGBDS))
/*!
* @brief Bandgap Buffer configuration.
*/
typedef struct _pmc_bandgap_buffer_config
{
#if (defined(FSL_FEATURE_PMC_HAS_BGBE) && FSL_FEATURE_PMC_HAS_BGBE)
bool enable; /*!< Enable bandgap buffer. */
#endif
#if (defined(FSL_FEATURE_PMC_HAS_BGEN) && FSL_FEATURE_PMC_HAS_BGEN)
bool enableInLowPowerMode; /*!< Enable bandgap buffer in low-power mode. */
#endif /* FSL_FEATURE_PMC_HAS_BGEN */
#if (defined(FSL_FEATURE_PMC_HAS_BGBDS) && FSL_FEATURE_PMC_HAS_BGBDS)
pmc_bandgap_buffer_drive_select_t drive; /*!< Bandgap buffer drive select. */
#endif /* FSL_FEATURE_PMC_HAS_BGBDS */
} pmc_bandgap_buffer_config_t;
#endif
/*******************************************************************************
* API
******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif /* __cplusplus*/
/*! @name Power Management Controller Control APIs*/
/*@{*/
#if (defined(FSL_FEATURE_PMC_HAS_VERID) && FSL_FEATURE_PMC_HAS_VERID)
/*!
* @brief Gets the PMC version ID.
*
* This function gets the PMC version ID, including major version number,
* minor version number and feature specification number.
*
* @param base PMC peripheral base address.
* @param versionId Pointer to version ID structure.
*/
static inline void PMC_GetVersionId(PMC_Type *base, pmc_version_id_t *versionId)
{
*((uint32_t *)versionId) = base->VERID;
}
#endif /* FSL_FEATURE_PMC_HAS_VERID */
#if (defined(FSL_FEATURE_PMC_HAS_PARAM) && FSL_FEATURE_PMC_HAS_PARAM)
/*!
* @brief Gets the PMC parameter.
*
* This function gets the PMC parameter, including VLPO enable and HVD enable.
*
* @param base PMC peripheral base address.
* @param param Pointer to PMC param structure.
*/
void PMC_GetParam(PMC_Type *base, pmc_param_t *param);
#endif
/*!
* @brief Configure the low-voltage detect setting.
*
* This function configures the low-voltage detect setting, including the trip
* point voltage setting, enable interrupt or not, enable system reset or not.
*
* @param base PMC peripheral base address.
* @param config Low-Voltage detect configuration structure.
*/
void PMC_ConfigureLowVoltDetect(PMC_Type *base, const pmc_low_volt_detect_config_t *config);
/*!
* @brief Get Low-Voltage Detect Flag status
*
* This function reads the current LVDF status. If it returns 1, a low-voltage event is detected.
*
* @param base PMC peripheral base address.
* @return Current low-voltage detect flag
* - true: Low-voltage detected
* - false: Low-voltage not detected
*/
static inline bool PMC_GetLowVoltDetectFlag(PMC_Type *base)
{
return (bool)(base->LVDSC1 & PMC_LVDSC1_LVDF_MASK);
}
/*!
* @brief Acknowledge to clear the Low-voltage Detect flag
*
* This function acknowledges the low-voltage detection errors (write 1 to
* clear LVDF).
*
* @param base PMC peripheral base address.
*/
static inline void PMC_ClearLowVoltDetectFlag(PMC_Type *base)
{
base->LVDSC1 |= PMC_LVDSC1_LVDACK_MASK;
}
/*!
* @brief Configure the low-voltage warning setting.
*
* This function configures the low-voltage warning setting, including the trip
* point voltage setting and enable interrupt or not.
*
* @param base PMC peripheral base address.
* @param config Low-Voltage warning configuration structure.
*/
void PMC_ConfigureLowVoltWarning(PMC_Type *base, const pmc_low_volt_warning_config_t *config);
/*!
* @brief Get Low-Voltage Warning Flag status
*
* This function polls the current LVWF status. When 1 is returned, it
* indicates a low-voltage warning event. LVWF is set when V Supply transitions
* below the trip point or after reset and V Supply is already below the V LVW.
*
* @param base PMC peripheral base address.
* @return Current LVWF status
* - true: Low-Voltage Warning Flag is set.
* - false: the Low-Voltage Warning does not happen.
*/
static inline bool PMC_GetLowVoltWarningFlag(PMC_Type *base)
{
return (bool)(base->LVDSC2 & PMC_LVDSC2_LVWF_MASK);
}
/*!
* @brief Acknowledge to Low-Voltage Warning flag
*
* This function acknowledges the low voltage warning errors (write 1 to
* clear LVWF).
*
* @param base PMC peripheral base address.
*/
static inline void PMC_ClearLowVoltWarningFlag(PMC_Type *base)
{
base->LVDSC2 |= PMC_LVDSC2_LVWACK_MASK;
}
#if (defined(FSL_FEATURE_PMC_HAS_HVDSC1) && FSL_FEATURE_PMC_HAS_HVDSC1)
/*!
* @brief Configure the high-voltage detect setting.
*
* This function configures the high-voltage detect setting, including the trip
* point voltage setting, enable interrupt or not, enable system reset or not.
*
* @param base PMC peripheral base address.
* @param config High-voltage detect configuration structure.
*/
void PMC_ConfigureHighVoltDetect(PMC_Type *base, const pmc_high_volt_detect_config_t *config);
/*!
* @brief Get High-Voltage Detect Flag status
*
* This function reads the current HVDF status. If it returns 1, a low
* voltage event is detected.
*
* @param base PMC peripheral base address.
* @return Current high-voltage detect flag
* - true: High-Voltage detected
* - false: High-Voltage not detected
*/
static inline bool PMC_GetHighVoltDetectFlag(PMC_Type *base)
{
return (bool)(base->HVDSC1 & PMC_HVDSC1_HVDF_MASK);
}
/*!
* @brief Acknowledge to clear the High-Voltage Detect flag
*
* This function acknowledges the high-voltage detection errors (write 1 to
* clear HVDF).
*
* @param base PMC peripheral base address.
*/
static inline void PMC_ClearHighVoltDetectFlag(PMC_Type *base)
{
base->HVDSC1 |= PMC_HVDSC1_HVDACK_MASK;
}
#endif /* FSL_FEATURE_PMC_HAS_HVDSC1 */
#if ((defined(FSL_FEATURE_PMC_HAS_BGBE) && FSL_FEATURE_PMC_HAS_BGBE) || \
(defined(FSL_FEATURE_PMC_HAS_BGEN) && FSL_FEATURE_PMC_HAS_BGEN) || \
(defined(FSL_FEATURE_PMC_HAS_BGBDS) && FSL_FEATURE_PMC_HAS_BGBDS))
/*!
* @brief Configure the PMC bandgap
*
* This function configures the PMC bandgap, including the drive select and
* behavior in low-power mode.
*
* @param base PMC peripheral base address.
* @param config Pointer to the configuration structure
*/
void PMC_ConfigureBandgapBuffer(PMC_Type *base, const pmc_bandgap_buffer_config_t *config);
#endif
#if (defined(FSL_FEATURE_PMC_HAS_ACKISO) && FSL_FEATURE_PMC_HAS_ACKISO)
/*!
* @brief Gets the acknowledge Peripherals and I/O pads isolation flag.
*
* This function reads the Acknowledge Isolation setting that indicates
* whether certain peripherals and the I/O pads are in a latched state as
* a result of having been in the VLLS mode.
*
* @param base PMC peripheral base address.
* @param base Base address for current PMC instance.
* @return ACK isolation
* 0 - Peripherals and I/O pads are in a normal run state.
* 1 - Certain peripherals and I/O pads are in an isolated and
* latched state.
*/
static inline bool PMC_GetPeriphIOIsolationFlag(PMC_Type *base)
{
return (bool)(base->REGSC & PMC_REGSC_ACKISO_MASK);
}
/*!
* @brief Acknowledge to Peripherals and I/O pads isolation flag.
*
* This function clears the ACK Isolation flag. Writing one to this setting
* when it is set releases the I/O pads and certain peripherals to their normal
* run mode state.
*
* @param base PMC peripheral base address.
*/
static inline void PMC_ClearPeriphIOIsolationFlag(PMC_Type *base)
{
base->REGSC |= PMC_REGSC_ACKISO_MASK;
}
#endif /* FSL_FEATURE_PMC_HAS_ACKISO */
#if (defined(FSL_FEATURE_PMC_HAS_REGONS) && FSL_FEATURE_PMC_HAS_REGONS)
/*!
* @brief Gets the Regulator regulation status.
*
* This function returns the regulator to a run regulation status. It provides
* the current status of the internal voltage regulator.
*
* @param base PMC peripheral base address.
* @param base Base address for current PMC instance.
* @return Regulation status
* 0 - Regulator is in a stop regulation or in transition to/from the regulation.
* 1 - Regulator is in a run regulation.
*
*/
static inline bool PMC_IsRegulatorInRunRegulation(PMC_Type *base)
{
return (bool)(base->REGSC & PMC_REGSC_REGONS_MASK);
}
#endif /* FSL_FEATURE_PMC_HAS_REGONS */
/*@}*/
#if defined(__cplusplus)
}
#endif /* __cplusplus*/
/*! @}*/
#endif /* _FSL_PMC_H_*/

View File

@ -0,0 +1,381 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SDRVL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _FSL_PORT_H_
#define _FSL_PORT_H_
#include "fsl_common.h"
/*!
* @addtogroup port
* @{
*/
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @name Driver version */
/*@{*/
/*! Version 2.0.1. */
#define FSL_PORT_DRIVER_VERSION (MAKE_VERSION(2, 0, 1))
/*@}*/
/*! @brief Internal resistor pull feature selection */
enum _port_pull
{
kPORT_PullDisable = 0U, /*!< Internal pull-up/down resistor is disabled. */
kPORT_PullDown = 2U, /*!< Internal pull-down resistor is enabled. */
kPORT_PullUp = 3U, /*!< Internal pull-up resistor is enabled. */
};
/*! @brief Slew rate selection */
enum _port_slew_rate
{
kPORT_FastSlewRate = 0U, /*!< Fast slew rate is configured. */
kPORT_SlowSlewRate = 1U, /*!< Slow slew rate is configured. */
};
#if defined(FSL_FEATURE_PORT_HAS_OPEN_DRAIN) && FSL_FEATURE_PORT_HAS_OPEN_DRAIN
/*! @brief Internal resistor pull feature enable/disable */
enum _port_open_drain_enable
{
kPORT_OpenDrainDisable = 0U, /*!< Internal pull-down resistor is disabled. */
kPORT_OpenDrainEnable = 1U, /*!< Internal pull-up resistor is enabled. */
};
#endif /* FSL_FEATURE_PORT_HAS_OPEN_DRAIN */
/*! @brief Passive filter feature enable/disable */
enum _port_passive_filter_enable
{
kPORT_PassiveFilterDisable = 0U, /*!< Fast slew rate is configured. */
kPORT_PassiveFilterEnable = 1U, /*!< Slow slew rate is configured. */
};
/*! @brief Configures the drive strength. */
enum _port_drive_strength
{
kPORT_LowDriveStrength = 0U, /*!< Low-drive strength is configured. */
kPORT_HighDriveStrength = 1U, /*!< High-drive strength is configured. */
};
#if defined(FSL_FEATURE_PORT_HAS_PIN_CONTROL_LOCK) && FSL_FEATURE_PORT_HAS_PIN_CONTROL_LOCK
/*! @brief Unlock/lock the pin control register field[15:0] */
enum _port_lock_register
{
kPORT_UnlockRegister = 0U, /*!< Pin Control Register fields [15:0] are not locked. */
kPORT_LockRegister = 1U, /*!< Pin Control Register fields [15:0] are locked. */
};
#endif /* FSL_FEATURE_PORT_HAS_PIN_CONTROL_LOCK */
/*! @brief Pin mux selection */
typedef enum _port_mux
{
kPORT_PinDisabledOrAnalog = 0U, /*!< Corresponding pin is disabled, but is used as an analog pin. */
kPORT_MuxAsGpio = 1U, /*!< Corresponding pin is configured as GPIO. */
kPORT_MuxAlt2 = 2U, /*!< Chip-specific */
kPORT_MuxAlt3 = 3U, /*!< Chip-specific */
kPORT_MuxAlt4 = 4U, /*!< Chip-specific */
kPORT_MuxAlt5 = 5U, /*!< Chip-specific */
kPORT_MuxAlt6 = 6U, /*!< Chip-specific */
kPORT_MuxAlt7 = 7U, /*!< Chip-specific */
} port_mux_t;
/*! @brief Configures the interrupt generation condition. */
typedef enum _port_interrupt
{
kPORT_InterruptOrDMADisabled = 0x0U, /*!< Interrupt/DMA request is disabled. */
#if defined(FSL_FEATURE_PORT_HAS_DMA_REQUEST) && FSL_FEATURE_PORT_HAS_DMA_REQUEST
kPORT_DMARisingEdge = 0x1U, /*!< DMA request on rising edge. */
kPORT_DMAFallingEdge = 0x2U, /*!< DMA request on falling edge. */
kPORT_DMAEitherEdge = 0x3U, /*!< DMA request on either edge. */
#endif
#if defined(FSL_FEATURE_PORT_HAS_IRQC_FLAG) && FSL_FEATURE_PORT_HAS_IRQC_FLAG
kPORT_FlagRisingEdge = 0x05U, /*!< Flag sets on rising edge. */
kPORT_FlagFallingEdge = 0x06U, /*!< Flag sets on falling edge. */
kPORT_FlagEitherEdge = 0x07U, /*!< Flag sets on either edge. */
#endif
kPORT_InterruptLogicZero = 0x8U, /*!< Interrupt when logic zero. */
kPORT_InterruptRisingEdge = 0x9U, /*!< Interrupt on rising edge. */
kPORT_InterruptFallingEdge = 0xAU, /*!< Interrupt on falling edge. */
kPORT_InterruptEitherEdge = 0xBU, /*!< Interrupt on either edge. */
kPORT_InterruptLogicOne = 0xCU, /*!< Interrupt when logic one. */
#if defined(FSL_FEATURE_PORT_HAS_IRQC_TRIGGER) && FSL_FEATURE_PORT_HAS_IRQC_TRIGGER
kPORT_ActiveHighTriggerOutputEnable = 0xDU, /*!< Enable active high-trigger output. */
kPORT_ActiveLowTriggerOutputEnable = 0xEU, /*!< Enable active low-trigger output. */
#endif
} port_interrupt_t;
#if defined(FSL_FEATURE_PORT_HAS_DIGITAL_FILTER) && FSL_FEATURE_PORT_HAS_DIGITAL_FILTER
/*! @brief Digital filter clock source selection */
typedef enum _port_digital_filter_clock_source
{
kPORT_BusClock = 0U, /*!< Digital filters are clocked by the bus clock. */
kPORT_LpoClock = 1U, /*!< Digital filters are clocked by the 1 kHz LPO clock. */
} port_digital_filter_clock_source_t;
/*! @brief PORT digital filter feature configuration definition */
typedef struct _port_digital_filter_config
{
uint32_t digitalFilterWidth; /*!< Set digital filter width */
port_digital_filter_clock_source_t clockSource; /*!< Set digital filter clockSource */
} port_digital_filter_config_t;
#endif /* FSL_FEATURE_PORT_HAS_DIGITAL_FILTER */
/*! @brief PORT pin configuration structure */
typedef struct _port_pin_config
{
uint16_t pullSelect : 2; /*!< No-pull/pull-down/pull-up select */
uint16_t slewRate : 1; /*!< Fast/slow slew rate Configure */
uint16_t : 1;
uint16_t passiveFilterEnable : 1; /*!< Passive filter enable/disable */
#if defined(FSL_FEATURE_PORT_HAS_OPEN_DRAIN) && FSL_FEATURE_PORT_HAS_OPEN_DRAIN
uint16_t openDrainEnable : 1; /*!< Open drain enable/disable */
#else
uint16_t : 1;
#endif /* FSL_FEATURE_PORT_HAS_OPEN_DRAIN */
uint16_t driveStrength : 1; /*!< Fast/slow drive strength configure */
uint16_t : 1;
uint16_t mux : 3; /*!< Pin mux Configure */
uint16_t : 4;
#if defined(FSL_FEATURE_PORT_HAS_PIN_CONTROL_LOCK) && FSL_FEATURE_PORT_HAS_PIN_CONTROL_LOCK
uint16_t lockRegister : 1; /*!< Lock/unlock the PCR field[15:0] */
#else
uint16_t : 1;
#endif /* FSL_FEATURE_PORT_HAS_PIN_CONTROL_LOCK */
} port_pin_config_t;
/*******************************************************************************
* API
******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif
/*! @name Configuration */
/*@{*/
/*!
* @brief Sets the port PCR register.
*
* This is an example to define an input pin or output pin PCR configuration:
* @code
* // Define a digital input pin PCR configuration
* port_pin_config_t config = {
* kPORT_PullUp,
* kPORT_FastSlewRate,
* kPORT_PassiveFilterDisable,
* kPORT_OpenDrainDisable,
* kPORT_LowDriveStrength,
* kPORT_MuxAsGpio,
* kPORT_UnLockRegister,
* };
* @endcode
*
* @param base PORT peripheral base pointer.
* @param pin PORT pin number.
* @param config PORT PCR register configuration structure.
*/
static inline void PORT_SetPinConfig(PORT_Type *base, uint32_t pin, const port_pin_config_t *config)
{
assert(config);
uint32_t addr = (uint32_t)&base->PCR[pin];
*(volatile uint16_t *)(addr) = *((const uint16_t *)config);
}
/*!
* @brief Sets the port PCR register for multiple pins.
*
* This is an example to define input pins or output pins PCR configuration:
* @code
* // Define a digital input pin PCR configuration
* port_pin_config_t config = {
* kPORT_PullUp ,
* kPORT_PullEnable,
* kPORT_FastSlewRate,
* kPORT_PassiveFilterDisable,
* kPORT_OpenDrainDisable,
* kPORT_LowDriveStrength,
* kPORT_MuxAsGpio,
* kPORT_UnlockRegister,
* };
* @endcode
*
* @param base PORT peripheral base pointer.
* @param mask PORT pin number macro.
* @param config PORT PCR register configuration structure.
*/
static inline void PORT_SetMultiplePinsConfig(PORT_Type *base, uint32_t mask, const port_pin_config_t *config)
{
assert(config);
uint16_t pcrl = *((const uint16_t *)config);
if (mask & 0xffffU)
{
base->GPCLR = ((mask & 0xffffU) << 16) | pcrl;
}
if (mask >> 16)
{
base->GPCHR = (mask & 0xffff0000U) | pcrl;
}
}
/*!
* @brief Configures the pin muxing.
*
* @param base PORT peripheral base pointer.
* @param pin PORT pin number.
* @param mux pin muxing slot selection.
* - #kPORT_PinDisabledOrAnalog: Pin disabled or work in analog function.
* - #kPORT_MuxAsGpio : Set as GPIO.
* - #kPORT_MuxAlt2 : chip-specific.
* - #kPORT_MuxAlt3 : chip-specific.
* - #kPORT_MuxAlt4 : chip-specific.
* - #kPORT_MuxAlt5 : chip-specific.
* - #kPORT_MuxAlt6 : chip-specific.
* - #kPORT_MuxAlt7 : chip-specific.
* @Note : This function is NOT recommended to use together with the PORT_SetPinsConfig, because
* the PORT_SetPinsConfig need to configure the pin mux anyway (Otherwise the pin mux is
* reset to zero : kPORT_PinDisabledOrAnalog).
* This function is recommended to use to reset the pin mux
*
*/
static inline void PORT_SetPinMux(PORT_Type *base, uint32_t pin, port_mux_t mux)
{
base->PCR[pin] = (base->PCR[pin] & ~PORT_PCR_MUX_MASK) | PORT_PCR_MUX(mux);
}
#if defined(FSL_FEATURE_PORT_HAS_DIGITAL_FILTER) && FSL_FEATURE_PORT_HAS_DIGITAL_FILTER
/*!
* @brief Enables the digital filter in one port, each bit of the 32-bit register represents one pin.
*
* @param base PORT peripheral base pointer.
* @param mask PORT pin number macro.
*/
static inline void PORT_EnablePinsDigitalFilter(PORT_Type *base, uint32_t mask, bool enable)
{
if (enable == true)
{
base->DFER |= mask;
}
else
{
base->DFER &= ~mask;
}
}
/*!
* @brief Sets the digital filter in one port, each bit of the 32-bit register represents one pin.
*
* @param base PORT peripheral base pointer.
* @param config PORT digital filter configuration structure.
*/
static inline void PORT_SetDigitalFilterConfig(PORT_Type *base, const port_digital_filter_config_t *config)
{
assert(config);
base->DFCR = PORT_DFCR_CS(config->clockSource);
base->DFWR = PORT_DFWR_FILT(config->digitalFilterWidth);
}
#endif /* FSL_FEATURE_PORT_HAS_DIGITAL_FILTER */
/*@}*/
/*! @name Interrupt */
/*@{*/
/*!
* @brief Configures the port pin interrupt/DMA request.
*
* @param base PORT peripheral base pointer.
* @param pin PORT pin number.
* @param config PORT pin interrupt configuration.
* - #kPORT_InterruptOrDMADisabled: Interrupt/DMA request disabled.
* - #kPORT_DMARisingEdge : DMA request on rising edge(if the DMA requests exit).
* - #kPORT_DMAFallingEdge: DMA request on falling edge(if the DMA requests exit).
* - #kPORT_DMAEitherEdge : DMA request on either edge(if the DMA requests exit).
* - #kPORT_FlagRisingEdge : Flag sets on rising edge(if the Flag states exit).
* - #kPORT_FlagFallingEdge : Flag sets on falling edge(if the Flag states exit).
* - #kPORT_FlagEitherEdge : Flag sets on either edge(if the Flag states exit).
* - #kPORT_InterruptLogicZero : Interrupt when logic zero.
* - #kPORT_InterruptRisingEdge : Interrupt on rising edge.
* - #kPORT_InterruptFallingEdge: Interrupt on falling edge.
* - #kPORT_InterruptEitherEdge : Interrupt on either edge.
* - #kPORT_InterruptLogicOne : Interrupt when logic one.
* - #kPORT_ActiveHighTriggerOutputEnable : Enable active high-trigger output (if the trigger states exit).
* - #kPORT_ActiveLowTriggerOutputEnable : Enable active low-trigger output (if the trigger states exit).
*/
static inline void PORT_SetPinInterruptConfig(PORT_Type *base, uint32_t pin, port_interrupt_t config)
{
base->PCR[pin] = (base->PCR[pin] & ~PORT_PCR_IRQC_MASK) | PORT_PCR_IRQC(config);
}
/*!
* @brief Reads the whole port status flag.
*
* If a pin is configured to generate the DMA request, the corresponding flag
* is cleared automatically at the completion of the requested DMA transfer.
* Otherwise, the flag remains set until a logic one is written to that flag.
* If configured for a level sensitive interrupt that remains asserted, the flag
* is set again immediately.
*
* @param base PORT peripheral base pointer.
* @return Current port interrupt status flags, for example, 0x00010001 means the
* pin 0 and 17 have the interrupt.
*/
static inline uint32_t PORT_GetPinsInterruptFlags(PORT_Type *base)
{
return base->ISFR;
}
/*!
* @brief Clears the multiple pin interrupt status flag.
*
* @param base PORT peripheral base pointer.
* @param mask PORT pin number macro.
*/
static inline void PORT_ClearPinsInterruptFlags(PORT_Type *base, uint32_t mask)
{
base->ISFR = mask;
}
/*@}*/
#if defined(__cplusplus)
}
#endif
/*! @}*/
#endif /* _FSL_PORT_H_ */

View File

@ -0,0 +1,65 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include "fsl_rcm.h"
void RCM_ConfigureResetPinFilter(RCM_Type *base, const rcm_reset_pin_filter_config_t *config)
{
assert(config);
#if (defined(FSL_FEATURE_RCM_REG_WIDTH) && (FSL_FEATURE_RCM_REG_WIDTH == 32))
uint32_t reg;
reg = (((uint32_t)config->enableFilterInStop << RCM_RPC_RSTFLTSS_SHIFT) | (uint32_t)config->filterInRunWait);
if (config->filterInRunWait == kRCM_FilterBusClock)
{
reg |= ((uint32_t)config->busClockFilterCount << RCM_RPC_RSTFLTSEL_SHIFT);
}
base->RPC = reg;
#else
base->RPFC = ((uint8_t)(config->enableFilterInStop << RCM_RPFC_RSTFLTSS_SHIFT) | (uint8_t)config->filterInRunWait);
if (config->filterInRunWait == kRCM_FilterBusClock)
{
base->RPFW = config->busClockFilterCount;
}
#endif /* FSL_FEATURE_RCM_REG_WIDTH */
}
#if (defined(FSL_FEATURE_RCM_HAS_BOOTROM) && FSL_FEATURE_RCM_HAS_BOOTROM)
void RCM_SetForceBootRomSource(RCM_Type *base, rcm_boot_rom_config_t config)
{
uint32_t reg;
reg = base->FM;
reg &= ~RCM_FM_FORCEROM_MASK;
reg |= ((uint32_t)config << RCM_FM_FORCEROM_SHIFT);
base->FM = reg;
}
#endif /* #if FSL_FEATURE_RCM_HAS_BOOTROM */

View File

@ -0,0 +1,431 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _FSL_RCM_H_
#define _FSL_RCM_H_
#include "fsl_common.h"
/*! @addtogroup rcm */
/*! @{*/
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @name Driver version */
/*@{*/
/*! @brief RCM driver version 2.0.1. */
#define FSL_RCM_DRIVER_VERSION (MAKE_VERSION(2, 0, 1))
/*@}*/
/*!
* @brief System Reset Source Name definitions
*/
typedef enum _rcm_reset_source
{
#if (defined(FSL_FEATURE_RCM_REG_WIDTH) && (FSL_FEATURE_RCM_REG_WIDTH == 32))
/* RCM register bit width is 32. */
#if (defined(FSL_FEATURE_RCM_HAS_WAKEUP) && FSL_FEATURE_RCM_HAS_WAKEUP)
kRCM_SourceWakeup = RCM_SRS_WAKEUP_MASK, /*!< Low-leakage wakeup reset */
#endif
kRCM_SourceLvd = RCM_SRS_LVD_MASK, /*!< Low-voltage detect reset */
#if (defined(FSL_FEATURE_RCM_HAS_LOC) && FSL_FEATURE_RCM_HAS_LOC)
kRCM_SourceLoc = RCM_SRS_LOC_MASK, /*!< Loss of clock reset */
#endif /* FSL_FEATURE_RCM_HAS_LOC */
#if (defined(FSL_FEATURE_RCM_HAS_LOL) && FSL_FEATURE_RCM_HAS_LOL)
kRCM_SourceLol = RCM_SRS_LOL_MASK, /*!< Loss of lock reset */
#endif /* FSL_FEATURE_RCM_HAS_LOL */
kRCM_SourceWdog = RCM_SRS_WDOG_MASK, /*!< Watchdog reset */
kRCM_SourcePin = RCM_SRS_PIN_MASK, /*!< External pin reset */
kRCM_SourcePor = RCM_SRS_POR_MASK, /*!< Power on reset */
#if (defined(FSL_FEATURE_RCM_HAS_JTAG) && FSL_FEATURE_RCM_HAS_JTAG)
kRCM_SourceJtag = RCM_SRS_JTAG_MASK, /*!< JTAG generated reset */
#endif /* FSL_FEATURE_RCM_HAS_JTAG */
kRCM_SourceLockup = RCM_SRS_LOCKUP_MASK, /*!< Core lock up reset */
kRCM_SourceSw = RCM_SRS_SW_MASK, /*!< Software reset */
#if (defined(FSL_FEATURE_RCM_HAS_MDM_AP) && FSL_FEATURE_RCM_HAS_MDM_AP)
kRCM_SourceMdmap = RCM_SRS_MDM_AP_MASK, /*!< MDM-AP system reset */
#endif /* FSL_FEATURE_RCM_HAS_MDM_AP */
#if (defined(FSL_FEATURE_RCM_HAS_EZPORT) && FSL_FEATURE_RCM_HAS_EZPORT)
kRCM_SourceEzpt = RCM_SRS_EZPT_MASK, /*!< EzPort reset */
#endif /* FSL_FEATURE_RCM_HAS_EZPORT */
kRCM_SourceSackerr = RCM_SRS_SACKERR_MASK, /*!< Parameter could get all reset flags */
#else /* (FSL_FEATURE_RCM_REG_WIDTH == 32) */
/* RCM register bit width is 8. */
#if (defined(FSL_FEATURE_RCM_HAS_WAKEUP) && FSL_FEATURE_RCM_HAS_WAKEUP)
kRCM_SourceWakeup = RCM_SRS0_WAKEUP_MASK, /*!< Low-leakage wakeup reset */
#endif
kRCM_SourceLvd = RCM_SRS0_LVD_MASK, /*!< Low-voltage detect reset */
#if (defined(FSL_FEATURE_RCM_HAS_LOC) && FSL_FEATURE_RCM_HAS_LOC)
kRCM_SourceLoc = RCM_SRS0_LOC_MASK, /*!< Loss of clock reset */
#endif /* FSL_FEATURE_RCM_HAS_LOC */
#if (defined(FSL_FEATURE_RCM_HAS_LOL) && FSL_FEATURE_RCM_HAS_LOL)
kRCM_SourceLol = RCM_SRS0_LOL_MASK, /*!< Loss of lock reset */
#endif /* FSL_FEATURE_RCM_HAS_LOL */
kRCM_SourceWdog = RCM_SRS0_WDOG_MASK, /*!< Watchdog reset */
kRCM_SourcePin = RCM_SRS0_PIN_MASK, /*!< External pin reset */
kRCM_SourcePor = RCM_SRS0_POR_MASK, /*!< Power on reset */
#if (defined(FSL_FEATURE_RCM_HAS_JTAG) && FSL_FEATURE_RCM_HAS_JTAG)
kRCM_SourceJtag = RCM_SRS1_JTAG_MASK << 8U, /*!< JTAG generated reset */
#endif /* FSL_FEATURE_RCM_HAS_JTAG */
kRCM_SourceLockup = RCM_SRS1_LOCKUP_MASK << 8U, /*!< Core lock up reset */
kRCM_SourceSw = RCM_SRS1_SW_MASK << 8U, /*!< Software reset */
#if (defined(FSL_FEATURE_RCM_HAS_MDM_AP) && FSL_FEATURE_RCM_HAS_MDM_AP)
kRCM_SourceMdmap = RCM_SRS1_MDM_AP_MASK << 8U, /*!< MDM-AP system reset */
#endif /* FSL_FEATURE_RCM_HAS_MDM_AP */
#if (defined(FSL_FEATURE_RCM_HAS_EZPORT) && FSL_FEATURE_RCM_HAS_EZPORT)
kRCM_SourceEzpt = RCM_SRS1_EZPT_MASK << 8U, /*!< EzPort reset */
#endif /* FSL_FEATURE_RCM_HAS_EZPORT */
kRCM_SourceSackerr = RCM_SRS1_SACKERR_MASK << 8U, /*!< Parameter could get all reset flags */
#endif /* (FSL_FEATURE_RCM_REG_WIDTH == 32) */
kRCM_SourceAll = 0xffffffffU,
} rcm_reset_source_t;
/*!
* @brief Reset pin filter select in Run and Wait modes
*/
typedef enum _rcm_run_wait_filter_mode
{
kRCM_FilterDisable = 0U, /*!< All filtering disabled */
kRCM_FilterBusClock = 1U, /*!< Bus clock filter enabled */
kRCM_FilterLpoClock = 2U /*!< LPO clock filter enabled */
} rcm_run_wait_filter_mode_t;
#if (defined(FSL_FEATURE_RCM_HAS_BOOTROM) && FSL_FEATURE_RCM_HAS_BOOTROM)
/*!
* @brief Boot from ROM configuration.
*/
typedef enum _rcm_boot_rom_config
{
kRCM_BootFlash = 0U, /*!< Boot from flash */
kRCM_BootRomCfg0 = 1U, /*!< Boot from boot ROM due to BOOTCFG0 */
kRCM_BootRomFopt = 2U, /*!< Boot from boot ROM due to FOPT[7] */
kRCM_BootRomBoth = 3U /*!< Boot from boot ROM due to both BOOTCFG0 and FOPT[7] */
} rcm_boot_rom_config_t;
#endif /* FSL_FEATURE_RCM_HAS_BOOTROM */
#if (defined(FSL_FEATURE_RCM_HAS_SRIE) && FSL_FEATURE_RCM_HAS_SRIE)
/*!
* @brief Max delay time from interrupt asserts to system reset.
*/
typedef enum _rcm_reset_delay
{
kRCM_ResetDelay8Lpo = 0U, /*!< Delay 8 LPO cycles. */
kRCM_ResetDelay32Lpo = 1U, /*!< Delay 32 LPO cycles. */
kRCM_ResetDelay128Lpo = 2U, /*!< Delay 128 LPO cycles. */
kRCM_ResetDelay512Lpo = 3U /*!< Delay 512 LPO cycles. */
} rcm_reset_delay_t;
/*!
* @brief System reset interrupt enable bit definitions.
*/
typedef enum _rcm_interrupt_enable
{
kRCM_IntNone = 0U, /*!< No interrupt enabled. */
kRCM_IntLossOfClk = RCM_SRIE_LOC_MASK, /*!< Loss of clock interrupt. */
kRCM_IntLossOfLock = RCM_SRIE_LOL_MASK, /*!< Loss of lock interrupt. */
kRCM_IntWatchDog = RCM_SRIE_WDOG_MASK, /*!< Watch dog interrupt. */
kRCM_IntExternalPin = RCM_SRIE_PIN_MASK, /*!< External pin interrupt. */
kRCM_IntGlobal = RCM_SRIE_GIE_MASK, /*!< Global interrupts. */
kRCM_IntCoreLockup = RCM_SRIE_LOCKUP_MASK, /*!< Core lock up interrupt */
kRCM_IntSoftware = RCM_SRIE_SW_MASK, /*!< software interrupt */
kRCM_IntStopModeAckErr = RCM_SRIE_SACKERR_MASK, /*!< Stop mode ACK error interrupt. */
#if (defined(FSL_FEATURE_RCM_HAS_CORE1) && FSL_FEATURE_RCM_HAS_CORE1)
kRCM_IntCore1 = RCM_SRIE_CORE1_MASK, /*!< Core 1 interrupt. */
#endif
kRCM_IntAll = RCM_SRIE_LOC_MASK /*!< Enable all interrupts. */
|
RCM_SRIE_LOL_MASK | RCM_SRIE_WDOG_MASK | RCM_SRIE_PIN_MASK | RCM_SRIE_GIE_MASK |
RCM_SRIE_LOCKUP_MASK | RCM_SRIE_SW_MASK | RCM_SRIE_SACKERR_MASK
#if (defined(FSL_FEATURE_RCM_HAS_CORE1) && FSL_FEATURE_RCM_HAS_CORE1)
|
RCM_SRIE_CORE1_MASK
#endif
} rcm_interrupt_enable_t;
#endif /* FSL_FEATURE_RCM_HAS_SRIE */
#if (defined(FSL_FEATURE_RCM_HAS_VERID) && FSL_FEATURE_RCM_HAS_VERID)
/*!
* @brief IP version ID definition.
*/
typedef struct _rcm_version_id
{
uint16_t feature; /*!< Feature Specification Number. */
uint8_t minor; /*!< Minor version number. */
uint8_t major; /*!< Major version number. */
} rcm_version_id_t;
#endif
/*!
* @brief Reset pin filter configuration
*/
typedef struct _rcm_reset_pin_filter_config
{
bool enableFilterInStop; /*!< Reset pin filter select in stop mode. */
rcm_run_wait_filter_mode_t filterInRunWait; /*!< Reset pin filter in run/wait mode. */
uint8_t busClockFilterCount; /*!< Reset pin bus clock filter width. */
} rcm_reset_pin_filter_config_t;
/*******************************************************************************
* API
******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif /* __cplusplus*/
/*! @name Reset Control Module APIs*/
/*@{*/
#if (defined(FSL_FEATURE_RCM_HAS_VERID) && FSL_FEATURE_RCM_HAS_VERID)
/*!
* @brief Gets the RCM version ID.
*
* This function gets the RCM version ID including the major version number,
* the minor version number, and the feature specification number.
*
* @param base RCM peripheral base address.
* @param versionId Pointer to version ID structure.
*/
static inline void RCM_GetVersionId(RCM_Type *base, rcm_version_id_t *versionId)
{
*((uint32_t *)versionId) = base->VERID;
}
#endif
#if (defined(FSL_FEATURE_RCM_HAS_PARAM) && FSL_FEATURE_RCM_HAS_PARAM)
/*!
* @brief Gets the reset source implemented status.
*
* This function gets the RCM parameter that indicates whether the corresponding reset source is implemented.
* Use source masks defined in the rcm_reset_source_t to get the desired source status.
*
* Example:
@code
uint32_t status;
// To test whether the MCU is reset using Watchdog.
status = RCM_GetResetSourceImplementedStatus(RCM) & (kRCM_SourceWdog | kRCM_SourcePin);
@endcode
*
* @param base RCM peripheral base address.
* @return All reset source implemented status bit map.
*/
static inline uint32_t RCM_GetResetSourceImplementedStatus(RCM_Type *base)
{
return base->PARAM;
}
#endif /* FSL_FEATURE_RCM_HAS_PARAM */
/*!
* @brief Gets the reset source status which caused a previous reset.
*
* This function gets the current reset source status. Use source masks
* defined in the rcm_reset_source_t to get the desired source status.
*
* Example:
@code
uint32_t resetStatus;
// To get all reset source statuses.
resetStatus = RCM_GetPreviousResetSources(RCM) & kRCM_SourceAll;
// To test whether the MCU is reset using Watchdog.
resetStatus = RCM_GetPreviousResetSources(RCM) & kRCM_SourceWdog;
// To test multiple reset sources.
resetStatus = RCM_GetPreviousResetSources(RCM) & (kRCM_SourceWdog | kRCM_SourcePin);
@endcode
*
* @param base RCM peripheral base address.
* @return All reset source status bit map.
*/
static inline uint32_t RCM_GetPreviousResetSources(RCM_Type *base)
{
#if (defined(FSL_FEATURE_RCM_REG_WIDTH) && (FSL_FEATURE_RCM_REG_WIDTH == 32))
return base->SRS;
#else
return (uint32_t)((uint32_t)base->SRS0 | ((uint32_t)base->SRS1 << 8U));
#endif /* (FSL_FEATURE_RCM_REG_WIDTH == 32) */
}
#if (defined(FSL_FEATURE_RCM_HAS_SSRS) && FSL_FEATURE_RCM_HAS_SSRS)
/*!
* @brief Gets the sticky reset source status.
*
* This function gets the current reset source status that has not been cleared
* by software for some specific source.
*
* Example:
@code
uint32_t resetStatus;
// To get all reset source statuses.
resetStatus = RCM_GetStickyResetSources(RCM) & kRCM_SourceAll;
// To test whether the MCU is reset using Watchdog.
resetStatus = RCM_GetStickyResetSources(RCM) & kRCM_SourceWdog;
// To test multiple reset sources.
resetStatus = RCM_GetStickyResetSources(RCM) & (kRCM_SourceWdog | kRCM_SourcePin);
@endcode
*
* @param base RCM peripheral base address.
* @return All reset source status bit map.
*/
static inline uint32_t RCM_GetStickyResetSources(RCM_Type *base)
{
#if (defined(FSL_FEATURE_RCM_REG_WIDTH) && (FSL_FEATURE_RCM_REG_WIDTH == 32))
return base->SSRS;
#else
return (base->SSRS0 | ((uint32_t)base->SSRS1 << 8U));
#endif /* (FSL_FEATURE_RCM_REG_WIDTH == 32) */
}
/*!
* @brief Clears the sticky reset source status.
*
* This function clears the sticky system reset flags indicated by source masks.
*
* Example:
@code
// Clears multiple reset sources.
RCM_ClearStickyResetSources(kRCM_SourceWdog | kRCM_SourcePin);
@endcode
*
* @param base RCM peripheral base address.
* @param sourceMasks reset source status bit map
*/
static inline void RCM_ClearStickyResetSources(RCM_Type *base, uint32_t sourceMasks)
{
#if (defined(FSL_FEATURE_RCM_REG_WIDTH) && (FSL_FEATURE_RCM_REG_WIDTH == 32))
base->SSRS = sourceMasks;
#else
base->SSRS0 = (sourceMasks & 0xffU);
base->SSRS1 = ((sourceMasks >> 8U) & 0xffU);
#endif /* (FSL_FEATURE_RCM_REG_WIDTH == 32) */
}
#endif /* FSL_FEATURE_RCM_HAS_SSRS */
/*!
* @brief Configures the reset pin filter.
*
* This function sets the reset pin filter including the filter source, filter
* width, and so on.
*
* @param base RCM peripheral base address.
* @param config Pointer to the configuration structure.
*/
void RCM_ConfigureResetPinFilter(RCM_Type *base, const rcm_reset_pin_filter_config_t *config);
#if (defined(FSL_FEATURE_RCM_HAS_EZPMS) && FSL_FEATURE_RCM_HAS_EZPMS)
/*!
* @brief Gets the EZP_MS_B pin assert status.
*
* This function gets the easy port mode status (EZP_MS_B) pin assert status.
*
* @param base RCM peripheral base address.
* @return status true - asserted, false - reasserted
*/
static inline bool RCM_GetEasyPortModePinStatus(RCM_Type *base)
{
return (bool)(base->MR & RCM_MR_EZP_MS_MASK);
}
#endif /* FSL_FEATURE_RCM_HAS_EZPMS */
#if (defined(FSL_FEATURE_RCM_HAS_BOOTROM) && FSL_FEATURE_RCM_HAS_BOOTROM)
/*!
* @brief Gets the ROM boot source.
*
* This function gets the ROM boot source during the last chip reset.
*
* @param base RCM peripheral base address.
* @return The ROM boot source.
*/
static inline rcm_boot_rom_config_t RCM_GetBootRomSource(RCM_Type *base)
{
return (rcm_boot_rom_config_t)((base->MR & RCM_MR_BOOTROM_MASK) >> RCM_MR_BOOTROM_SHIFT);
}
/*!
* @brief Clears the ROM boot source flag.
*
* This function clears the ROM boot source flag.
*
* @param base Register base address of RCM
*/
static inline void RCM_ClearBootRomSource(RCM_Type *base)
{
base->MR |= RCM_MR_BOOTROM_MASK;
}
/*!
* @brief Forces the boot from ROM.
*
* This function forces booting from ROM during all subsequent system resets.
*
* @param base RCM peripheral base address.
* @param config Boot configuration.
*/
void RCM_SetForceBootRomSource(RCM_Type *base, rcm_boot_rom_config_t config);
#endif /* FSL_FEATURE_RCM_HAS_BOOTROM */
#if (defined(FSL_FEATURE_RCM_HAS_SRIE) && FSL_FEATURE_RCM_HAS_SRIE)
/*!
* @brief Sets the system reset interrupt configuration.
*
* For a graceful shut down, the RCM supports delaying the assertion of the system
* reset for a period of time when the reset interrupt is generated. This function
* can be used to enable the interrupt and the delay period. The interrupts
* are passed in as bit mask. See rcm_int_t for details. For example, to
* delay a reset for 512 LPO cycles after the WDOG timeout or loss-of-clock occurs,
* configure as follows:
* RCM_SetSystemResetInterruptConfig(kRCM_IntWatchDog | kRCM_IntLossOfClk, kRCM_ResetDelay512Lpo);
*
* @param base RCM peripheral base address.
* @param intMask Bit mask of the system reset interrupts to enable. See
* rcm_interrupt_enable_t for details.
* @param Delay Bit mask of the system reset interrupts to enable.
*/
static inline void RCM_SetSystemResetInterruptConfig(RCM_Type *base, uint32_t intMask, rcm_reset_delay_t delay)
{
base->SRIE = (intMask | delay);
}
#endif /* FSL_FEATURE_RCM_HAS_SRIE */
/*@}*/
#if defined(__cplusplus)
}
#endif /* __cplusplus*/
/*! @}*/
#endif /* _FSL_RCM_H_ */

View File

@ -0,0 +1,379 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include "fsl_rtc.h"
/*******************************************************************************
* Definitions
******************************************************************************/
#define SECONDS_IN_A_DAY (86400U)
#define SECONDS_IN_A_HOUR (3600U)
#define SECONDS_IN_A_MINUTE (60U)
#define DAYS_IN_A_YEAR (365U)
#define YEAR_RANGE_START (1970U)
#define YEAR_RANGE_END (2099U)
/*******************************************************************************
* Prototypes
******************************************************************************/
/*!
* @brief Checks whether the date and time passed in is valid
*
* @param datetime Pointer to structure where the date and time details are stored
*
* @return Returns false if the date & time details are out of range; true if in range
*/
static bool RTC_CheckDatetimeFormat(const rtc_datetime_t *datetime);
/*!
* @brief Converts time data from datetime to seconds
*
* @param datetime Pointer to datetime structure where the date and time details are stored
*
* @return The result of the conversion in seconds
*/
static uint32_t RTC_ConvertDatetimeToSeconds(const rtc_datetime_t *datetime);
/*!
* @brief Converts time data from seconds to a datetime structure
*
* @param seconds Seconds value that needs to be converted to datetime format
* @param datetime Pointer to the datetime structure where the result of the conversion is stored
*/
static void RTC_ConvertSecondsToDatetime(uint32_t seconds, rtc_datetime_t *datetime);
/*******************************************************************************
* Code
******************************************************************************/
static bool RTC_CheckDatetimeFormat(const rtc_datetime_t *datetime)
{
assert(datetime);
/* Table of days in a month for a non leap year. First entry in the table is not used,
* valid months start from 1
*/
uint8_t daysPerMonth[] = {0U, 31U, 28U, 31U, 30U, 31U, 30U, 31U, 31U, 30U, 31U, 30U, 31U};
/* Check year, month, hour, minute, seconds */
if ((datetime->year < YEAR_RANGE_START) || (datetime->year > YEAR_RANGE_END) || (datetime->month > 12U) ||
(datetime->month < 1U) || (datetime->hour >= 24U) || (datetime->minute >= 60U) || (datetime->second >= 60U))
{
/* If not correct then error*/
return false;
}
/* Adjust the days in February for a leap year */
if ((((datetime->year & 3U) == 0) && (datetime->year % 100 != 0)) || (datetime->year % 400 == 0))
{
daysPerMonth[2] = 29U;
}
/* Check the validity of the day */
if ((datetime->day > daysPerMonth[datetime->month]) || (datetime->day < 1U))
{
return false;
}
return true;
}
static uint32_t RTC_ConvertDatetimeToSeconds(const rtc_datetime_t *datetime)
{
assert(datetime);
/* Number of days from begin of the non Leap-year*/
/* Number of days from begin of the non Leap-year*/
uint16_t monthDays[] = {0U, 0U, 31U, 59U, 90U, 120U, 151U, 181U, 212U, 243U, 273U, 304U, 334U};
uint32_t seconds;
/* Compute number of days from 1970 till given year*/
seconds = (datetime->year - 1970U) * DAYS_IN_A_YEAR;
/* Add leap year days */
seconds += ((datetime->year / 4) - (1970U / 4));
/* Add number of days till given month*/
seconds += monthDays[datetime->month];
/* Add days in given month. We subtract the current day as it is
* represented in the hours, minutes and seconds field*/
seconds += (datetime->day - 1);
/* For leap year if month less than or equal to Febraury, decrement day counter*/
if ((!(datetime->year & 3U)) && (datetime->month <= 2U))
{
seconds--;
}
seconds = (seconds * SECONDS_IN_A_DAY) + (datetime->hour * SECONDS_IN_A_HOUR) +
(datetime->minute * SECONDS_IN_A_MINUTE) + datetime->second;
return seconds;
}
static void RTC_ConvertSecondsToDatetime(uint32_t seconds, rtc_datetime_t *datetime)
{
assert(datetime);
uint32_t x;
uint32_t secondsRemaining, days;
uint16_t daysInYear;
/* Table of days in a month for a non leap year. First entry in the table is not used,
* valid months start from 1
*/
uint8_t daysPerMonth[] = {0U, 31U, 28U, 31U, 30U, 31U, 30U, 31U, 31U, 30U, 31U, 30U, 31U};
/* Start with the seconds value that is passed in to be converted to date time format */
secondsRemaining = seconds;
/* Calcuate the number of days, we add 1 for the current day which is represented in the
* hours and seconds field
*/
days = secondsRemaining / SECONDS_IN_A_DAY + 1;
/* Update seconds left*/
secondsRemaining = secondsRemaining % SECONDS_IN_A_DAY;
/* Calculate the datetime hour, minute and second fields */
datetime->hour = secondsRemaining / SECONDS_IN_A_HOUR;
secondsRemaining = secondsRemaining % SECONDS_IN_A_HOUR;
datetime->minute = secondsRemaining / 60U;
datetime->second = secondsRemaining % SECONDS_IN_A_MINUTE;
/* Calculate year */
daysInYear = DAYS_IN_A_YEAR;
datetime->year = YEAR_RANGE_START;
while (days > daysInYear)
{
/* Decrease day count by a year and increment year by 1 */
days -= daysInYear;
datetime->year++;
/* Adjust the number of days for a leap year */
if (datetime->year & 3U)
{
daysInYear = DAYS_IN_A_YEAR;
}
else
{
daysInYear = DAYS_IN_A_YEAR + 1;
}
}
/* Adjust the days in February for a leap year */
if (!(datetime->year & 3U))
{
daysPerMonth[2] = 29U;
}
for (x = 1U; x <= 12U; x++)
{
if (days <= daysPerMonth[x])
{
datetime->month = x;
break;
}
else
{
days -= daysPerMonth[x];
}
}
datetime->day = days;
}
void RTC_Init(RTC_Type *base, const rtc_config_t *config)
{
assert(config);
uint32_t reg;
CLOCK_EnableClock(kCLOCK_Rtc0);
/* Issue a software reset if timer is invalid */
if (RTC_GetStatusFlags(RTC) & kRTC_TimeInvalidFlag)
{
RTC_Reset(RTC);
}
reg = base->CR;
/* Setup the update mode and supervisor access mode */
reg &= ~(RTC_CR_UM_MASK | RTC_CR_SUP_MASK);
reg |= RTC_CR_UM(config->updateMode) | RTC_CR_SUP(config->supervisorAccess);
#if defined(FSL_FEATURE_RTC_HAS_WAKEUP_PIN_SELECTION) && FSL_FEATURE_RTC_HAS_WAKEUP_PIN_SELECTION
/* Setup the wakeup pin select */
reg &= ~(RTC_CR_WPS_MASK);
reg |= RTC_CR_WPS(config->wakeupSelect);
#endif /* FSL_FEATURE_RTC_HAS_WAKEUP_PIN */
base->CR = reg;
/* Configure the RTC time compensation register */
base->TCR = (RTC_TCR_CIR(config->compensationInterval) | RTC_TCR_TCR(config->compensationTime));
}
void RTC_GetDefaultConfig(rtc_config_t *config)
{
assert(config);
/* Wakeup pin will assert if the RTC interrupt asserts or if the wakeup pin is turned on */
config->wakeupSelect = false;
/* Registers cannot be written when locked */
config->updateMode = false;
/* Non-supervisor mode write accesses are not supported and will generate a bus error */
config->supervisorAccess = false;
/* Compensation interval used by the crystal compensation logic */
config->compensationInterval = 0;
/* Compensation time used by the crystal compensation logic */
config->compensationTime = 0;
}
status_t RTC_SetDatetime(RTC_Type *base, const rtc_datetime_t *datetime)
{
assert(datetime);
/* Return error if the time provided is not valid */
if (!(RTC_CheckDatetimeFormat(datetime)))
{
return kStatus_InvalidArgument;
}
/* Set time in seconds */
base->TSR = RTC_ConvertDatetimeToSeconds(datetime);
return kStatus_Success;
}
void RTC_GetDatetime(RTC_Type *base, rtc_datetime_t *datetime)
{
assert(datetime);
uint32_t seconds = 0;
seconds = base->TSR;
RTC_ConvertSecondsToDatetime(seconds, datetime);
}
status_t RTC_SetAlarm(RTC_Type *base, const rtc_datetime_t *alarmTime)
{
assert(alarmTime);
uint32_t alarmSeconds = 0;
uint32_t currSeconds = 0;
/* Return error if the alarm time provided is not valid */
if (!(RTC_CheckDatetimeFormat(alarmTime)))
{
return kStatus_InvalidArgument;
}
alarmSeconds = RTC_ConvertDatetimeToSeconds(alarmTime);
/* Get the current time */
currSeconds = base->TSR;
/* Return error if the alarm time has passed */
if (alarmSeconds < currSeconds)
{
return kStatus_Fail;
}
/* Set alarm in seconds*/
base->TAR = alarmSeconds;
return kStatus_Success;
}
void RTC_GetAlarm(RTC_Type *base, rtc_datetime_t *datetime)
{
assert(datetime);
uint32_t alarmSeconds = 0;
/* Get alarm in seconds */
alarmSeconds = base->TAR;
RTC_ConvertSecondsToDatetime(alarmSeconds, datetime);
}
void RTC_ClearStatusFlags(RTC_Type *base, uint32_t mask)
{
/* The alarm flag is cleared by writing to the TAR register */
if (mask & kRTC_AlarmFlag)
{
base->TAR = 0U;
}
/* The timer overflow flag is cleared by initializing the TSR register.
* The time counter should be disabled for this write to be successful
*/
if (mask & kRTC_TimeOverflowFlag)
{
base->TSR = 1U;
}
/* The timer overflow flag is cleared by initializing the TSR register.
* The time counter should be disabled for this write to be successful
*/
if (mask & kRTC_TimeInvalidFlag)
{
base->TSR = 1U;
}
}
#if defined(FSL_FEATURE_RTC_HAS_MONOTONIC) && (FSL_FEATURE_RTC_HAS_MONOTONIC)
void RTC_GetMonotonicCounter(RTC_Type *base, uint64_t *counter)
{
assert(counter);
*counter = (((uint64_t)base->MCHR << 32) | ((uint64_t)base->MCLR));
}
void RTC_SetMonotonicCounter(RTC_Type *base, uint64_t counter)
{
/* Prepare to initialize the register with the new value written */
base->MER &= ~RTC_MER_MCE_MASK;
base->MCHR = (uint32_t)((counter) >> 32);
base->MCLR = (uint32_t)(counter);
}
status_t RTC_IncrementMonotonicCounter(RTC_Type *base)
{
if (base->SR & (RTC_SR_MOF_MASK | RTC_SR_TIF_MASK))
{
return kStatus_Fail;
}
/* Prepare to switch to increment mode */
base->MER |= RTC_MER_MCE_MASK;
/* Write anything so the counter increments*/
base->MCLR = 1U;
return kStatus_Success;
}
#endif /* FSL_FEATURE_RTC_HAS_MONOTONIC */

View File

@ -0,0 +1,412 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _FSL_RTC_H_
#define _FSL_RTC_H_
#include "fsl_common.h"
/*!
* @addtogroup rtc
* @{
*/
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @name Driver version */
/*@{*/
#define FSL_RTC_DRIVER_VERSION (MAKE_VERSION(2, 0, 0)) /*!< Version 2.0.0 */
/*@}*/
/*! @brief List of RTC interrupts */
typedef enum _rtc_interrupt_enable
{
kRTC_TimeInvalidInterruptEnable = RTC_IER_TIIE_MASK, /*!< Time invalid interrupt.*/
kRTC_TimeOverflowInterruptEnable = RTC_IER_TOIE_MASK, /*!< Time overflow interrupt.*/
kRTC_AlarmInterruptEnable = RTC_IER_TAIE_MASK, /*!< Alarm interrupt.*/
kRTC_SecondsInterruptEnable = RTC_IER_TSIE_MASK /*!< Seconds interrupt.*/
} rtc_interrupt_enable_t;
/*! @brief List of RTC flags */
typedef enum _rtc_status_flags
{
kRTC_TimeInvalidFlag = RTC_SR_TIF_MASK, /*!< Time invalid flag */
kRTC_TimeOverflowFlag = RTC_SR_TOF_MASK, /*!< Time overflow flag */
kRTC_AlarmFlag = RTC_SR_TAF_MASK /*!< Alarm flag*/
} rtc_status_flags_t;
#if (defined(FSL_FEATURE_RTC_HAS_OSC_SCXP) && FSL_FEATURE_RTC_HAS_OSC_SCXP)
/*! @brief List of RTC Oscillator capacitor load settings */
typedef enum _rtc_osc_cap_load
{
kRTC_Capacitor_2p = RTC_CR_SC2P_MASK, /*!< 2pF capacitor load */
kRTC_Capacitor_4p = RTC_CR_SC4P_MASK, /*!< 4pF capacitor load */
kRTC_Capacitor_8p = RTC_CR_SC8P_MASK, /*!< 8pF capacitor load */
kRTC_Capacitor_16p = RTC_CR_SC16P_MASK /*!< 16pF capacitor load */
} rtc_osc_cap_load_t;
#endif /* FSL_FEATURE_SCG_HAS_OSC_SCXP */
/*! @brief Structure is used to hold the date and time */
typedef struct _rtc_datetime
{
uint16_t year; /*!< Range from 1970 to 2099.*/
uint8_t month; /*!< Range from 1 to 12.*/
uint8_t day; /*!< Range from 1 to 31 (depending on month).*/
uint8_t hour; /*!< Range from 0 to 23.*/
uint8_t minute; /*!< Range from 0 to 59.*/
uint8_t second; /*!< Range from 0 to 59.*/
} rtc_datetime_t;
/*!
* @brief RTC config structure
*
* This structure holds the configuration settings for the RTC peripheral. To initialize this
* structure to reasonable defaults, call the RTC_GetDefaultConfig() function and pass a
* pointer to your config structure instance.
*
* The config struct can be made const so it resides in flash
*/
typedef struct _rtc_config
{
bool wakeupSelect; /*!< true: Wakeup pin outputs the 32KHz clock;
false:Wakeup pin used to wakeup the chip */
bool updateMode; /*!< true: Registers can be written even when locked under certain
conditions, false: No writes allowed when registers are locked */
bool supervisorAccess; /*!< true: Non-supervisor accesses are allowed;
false: Non-supervisor accesses are not supported */
uint32_t compensationInterval; /*!< Compensation interval that is written to the CIR field in RTC TCR Register */
uint32_t compensationTime; /*!< Compensation time that is written to the TCR field in RTC TCR Register */
} rtc_config_t;
/*******************************************************************************
* API
******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif
/*!
* @name Initialization and deinitialization
* @{
*/
/*!
* @brief Ungates the RTC clock and configures the peripheral for basic operation.
*
* This function will issue a software reset if the timer invalid flag is set.
*
* @note This API should be called at the beginning of the application using the RTC driver.
*
* @param base RTC peripheral base address
* @param config Pointer to user's RTC config structure.
*/
void RTC_Init(RTC_Type *base, const rtc_config_t *config);
/*!
* @brief Stop the timer and gate the RTC clock
*
* @param base RTC peripheral base address
*/
static inline void RTC_Deinit(RTC_Type *base)
{
/* Stop the RTC timer */
base->SR &= ~RTC_SR_TCE_MASK;
/* Gate the module clock */
CLOCK_DisableClock(kCLOCK_Rtc0);
}
/*!
* @brief Fill in the RTC config struct with the default settings
*
* The default values are:
* @code
* config->wakeupSelect = false;
* config->updateMode = false;
* config->supervisorAccess = false;
* config->compensationInterval = 0;
* config->compensationTime = 0;
* @endcode
* @param config Pointer to user's RTC config structure.
*/
void RTC_GetDefaultConfig(rtc_config_t *config);
/*! @}*/
/*!
* @name Current Time & Alarm
* @{
*/
/*!
* @brief Sets the RTC date and time according to the given time structure.
*
* The RTC counter must be stopped prior to calling this function as writes to the RTC
* seconds register will fail if the RTC counter is running.
*
* @param base RTC peripheral base address
* @param datetime Pointer to structure where the date and time details to set are stored
*
* @return kStatus_Success: Success in setting the time and starting the RTC
* kStatus_InvalidArgument: Error because the datetime format is incorrect
*/
status_t RTC_SetDatetime(RTC_Type *base, const rtc_datetime_t *datetime);
/*!
* @brief Gets the RTC time and stores it in the given time structure.
*
* @param base RTC peripheral base address
* @param datetime Pointer to structure where the date and time details are stored.
*/
void RTC_GetDatetime(RTC_Type *base, rtc_datetime_t *datetime);
/*!
* @brief Sets the RTC alarm time
*
* The function checks whether the specified alarm time is greater than the present
* time. If not, the function does not set the alarm and returns an error.
*
* @param base RTC peripheral base address
* @param alarmTime Pointer to structure where the alarm time is stored.
*
* @return kStatus_Success: success in setting the RTC alarm
* kStatus_InvalidArgument: Error because the alarm datetime format is incorrect
* kStatus_Fail: Error because the alarm time has already passed
*/
status_t RTC_SetAlarm(RTC_Type *base, const rtc_datetime_t *alarmTime);
/*!
* @brief Returns the RTC alarm time.
*
* @param base RTC peripheral base address
* @param datetime Pointer to structure where the alarm date and time details are stored.
*/
void RTC_GetAlarm(RTC_Type *base, rtc_datetime_t *datetime);
/*! @}*/
/*!
* @name Interrupt Interface
* @{
*/
/*!
* @brief Enables the selected RTC interrupts.
*
* @param base RTC peripheral base address
* @param mask The interrupts to enable. This is a logical OR of members of the
* enumeration ::rtc_interrupt_enable_t
*/
static inline void RTC_EnableInterrupts(RTC_Type *base, uint32_t mask)
{
base->IER |= mask;
}
/*!
* @brief Disables the selected RTC interrupts.
*
* @param base RTC peripheral base address
* @param mask The interrupts to enable. This is a logical OR of members of the
* enumeration ::rtc_interrupt_enable_t
*/
static inline void RTC_DisableInterrupts(RTC_Type *base, uint32_t mask)
{
base->IER &= ~mask;
}
/*!
* @brief Gets the enabled RTC interrupts.
*
* @param base RTC peripheral base address
*
* @return The enabled interrupts. This is the logical OR of members of the
* enumeration ::rtc_interrupt_enable_t
*/
static inline uint32_t RTC_GetEnabledInterrupts(RTC_Type *base)
{
return (base->IER & (RTC_IER_TIIE_MASK | RTC_IER_TOIE_MASK | RTC_IER_TAIE_MASK | RTC_IER_TSIE_MASK));
}
/*! @}*/
/*!
* @name Status Interface
* @{
*/
/*!
* @brief Gets the RTC status flags
*
* @param base RTC peripheral base address
*
* @return The status flags. This is the logical OR of members of the
* enumeration ::rtc_status_flags_t
*/
static inline uint32_t RTC_GetStatusFlags(RTC_Type *base)
{
return (base->SR & (RTC_SR_TIF_MASK | RTC_SR_TOF_MASK | RTC_SR_TAF_MASK));
}
/*!
* @brief Clears the RTC status flags.
*
* @param base RTC peripheral base address
* @param mask The status flags to clear. This is a logical OR of members of the
* enumeration ::rtc_status_flags_t
*/
void RTC_ClearStatusFlags(RTC_Type *base, uint32_t mask);
/*! @}*/
/*!
* @name Timer Start and Stop
* @{
*/
/*!
* @brief Starts the RTC time counter.
*
* After calling this function, the timer counter increments once a second provided SR[TOF] or
* SR[TIF] are not set.
*
* @param base RTC peripheral base address
*/
static inline void RTC_StartTimer(RTC_Type *base)
{
base->SR |= RTC_SR_TCE_MASK;
}
/*!
* @brief Stops the RTC time counter.
*
* RTC's seconds register can be written to only when the timer is stopped.
*
* @param base RTC peripheral base address
*/
static inline void RTC_StopTimer(RTC_Type *base)
{
base->SR &= ~RTC_SR_TCE_MASK;
}
/*! @}*/
#if (defined(FSL_FEATURE_RTC_HAS_OSC_SCXP) && FSL_FEATURE_RTC_HAS_OSC_SCXP)
/*!
* @brief This function sets the specified capacitor configuration for the RTC oscillator.
*
* @param base RTC peripheral base address
* @param capLoad Oscillator loads to enable. This is a logical OR of members of the
* enumeration ::rtc_osc_cap_load_t
*/
static inline void RTC_SetOscCapLoad(RTC_Type *base, uint32_t capLoad)
{
uint32_t reg = base->CR;
reg &= ~(RTC_CR_SC2P_MASK | RTC_CR_SC4P_MASK | RTC_CR_SC8P_MASK | RTC_CR_SC16P_MASK);
reg |= capLoad;
base->CR = reg;
}
#endif /* FSL_FEATURE_SCG_HAS_OSC_SCXP */
/*!
* @brief Performs a software reset on the RTC module.
*
* This resets all RTC registers except for the SWR bit and the RTC_WAR and RTC_RAR
* registers. The SWR bit is cleared by software explicitly clearing it.
*
* @param base RTC peripheral base address
*/
static inline void RTC_Reset(RTC_Type *base)
{
base->CR |= RTC_CR_SWR_MASK;
base->CR &= ~RTC_CR_SWR_MASK;
/* Set TSR register to 0x1 to avoid the timer invalid (TIF) bit being set in the SR register */
base->TSR = 1U;
}
#if defined(FSL_FEATURE_RTC_HAS_MONOTONIC) && (FSL_FEATURE_RTC_HAS_MONOTONIC)
/*!
* @name Monotonic counter functions
* @{
*/
/*!
* @brief Reads the values of the Monotonic Counter High and Monotonic Counter Low and returns
* them as a single value.
*
* @param base RTC peripheral base address
* @param counter Pointer to variable where the value is stored.
*/
void RTC_GetMonotonicCounter(RTC_Type *base, uint64_t *counter);
/*!
* @brief Writes values Monotonic Counter High and Monotonic Counter Low by decomposing
* the given single value.
*
* @param base RTC peripheral base address
* @param counter Counter value
*/
void RTC_SetMonotonicCounter(RTC_Type *base, uint64_t counter);
/*!
* @brief Increments the Monotonic Counter by one.
*
* Increments the Monotonic Counter (registers RTC_MCLR and RTC_MCHR accordingly) by setting
* the monotonic counter enable (MER[MCE]) and then writing to the RTC_MCLR register. A write to the
* monotonic counter low that causes it to overflow also increments the monotonic counter high.
*
* @param base RTC peripheral base address
*
* @return kStatus_Success: success
* kStatus_Fail: error occurred, either time invalid or monotonic overflow flag was found
*/
status_t RTC_IncrementMonotonicCounter(RTC_Type *base);
/*! @}*/
#endif /* FSL_FEATURE_RTC_HAS_MONOTONIC */
#if defined(__cplusplus)
}
#endif
/*! @}*/
#endif /* _FSL_RTC_H_ */

View File

@ -0,0 +1,53 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include "fsl_sim.h"
/*******************************************************************************
* Codes
******************************************************************************/
#if (defined(FSL_FEATURE_SIM_OPT_HAS_USB_VOLTAGE_REGULATOR) && FSL_FEATURE_SIM_OPT_HAS_USB_VOLTAGE_REGULATOR)
void SIM_SetUsbVoltRegulatorEnableMode(uint32_t mask)
{
SIM->SOPT1CFG |= (SIM_SOPT1CFG_URWE_MASK | SIM_SOPT1CFG_UVSWE_MASK | SIM_SOPT1CFG_USSWE_MASK);
SIM->SOPT1 = (SIM->SOPT1 & ~kSIM_UsbVoltRegEnableInAllModes) | mask;
}
#endif /* FSL_FEATURE_SIM_OPT_HAS_USB_VOLTAGE_REGULATOR */
void SIM_GetUniqueId(sim_uid_t *uid)
{
#if defined(SIM_UIDH)
uid->H = SIM->UIDH;
#endif
uid->MH = SIM->UIDMH;
uid->ML = SIM->UIDML;
uid->L = SIM->UIDL;
}

View File

@ -0,0 +1,127 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _FSL_SIM_H_
#define _FSL_SIM_H_
#include "fsl_common.h"
/*! @addtogroup sim */
/*! @{*/
/*******************************************************************************
* Definitions
*******************************************************************************/
/*! @name Driver version */
/*@{*/
#define FSL_SIM_DRIVER_VERSION (MAKE_VERSION(2, 0, 0)) /*!< Driver version 2.0.0 */
/*@}*/
#if (defined(FSL_FEATURE_SIM_OPT_HAS_USB_VOLTAGE_REGULATOR) && FSL_FEATURE_SIM_OPT_HAS_USB_VOLTAGE_REGULATOR)
/*!@brief USB voltage regulator enable setting. */
enum _sim_usb_volt_reg_enable_mode
{
kSIM_UsbVoltRegEnable = SIM_SOPT1_USBREGEN_MASK, /*!< Enable voltage regulator. */
kSIM_UsbVoltRegEnableInLowPower = SIM_SOPT1_USBVSTBY_MASK, /*!< Enable voltage regulator in VLPR/VLPW modes. */
kSIM_UsbVoltRegEnableInStop = SIM_SOPT1_USBSSTBY_MASK, /*!< Enable voltage regulator in STOP/VLPS/LLS/VLLS modes. */
kSIM_UsbVoltRegEnableInAllModes = SIM_SOPT1_USBREGEN_MASK | SIM_SOPT1_USBSSTBY_MASK |
SIM_SOPT1_USBVSTBY_MASK /*!< Enable voltage regulator in all power modes. */
};
#endif /* (defined(FSL_FEATURE_SIM_OPT_HAS_USB_VOLTAGE_REGULATOR) && FSL_FEATURE_SIM_OPT_HAS_USB_VOLTAGE_REGULATOR) */
/*!@brief Unique ID. */
typedef struct _sim_uid
{
#if defined(SIM_UIDH)
uint32_t H; /*!< UIDH. */
#endif
uint32_t MH; /*!< UIDMH. */
uint32_t ML; /*!< UIDML. */
uint32_t L; /*!< UIDL. */
} sim_uid_t;
/*!@brief Flash enable mode. */
enum _sim_flash_mode
{
kSIM_FlashDisableInWait = SIM_FCFG1_FLASHDOZE_MASK, /*!< Disable flash in wait mode. */
kSIM_FlashDisable = SIM_FCFG1_FLASHDIS_MASK /*!< Disable flash in normal mode. */
};
/*******************************************************************************
* API
******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif /* __cplusplus*/
#if (defined(FSL_FEATURE_SIM_OPT_HAS_USB_VOLTAGE_REGULATOR) && FSL_FEATURE_SIM_OPT_HAS_USB_VOLTAGE_REGULATOR)
/*!
* @brief Sets the USB voltage regulator setting.
*
* This function configures whether the USB voltage regulator is enabled in
* normal RUN mode, STOP/VLPS/LLS/VLLS modes and VLPR/VLPW modes. The configurations
* are passed in as mask value of \ref _sim_usb_volt_reg_enable_mode. For example, enable
* USB voltage regulator in RUN/VLPR/VLPW modes and disable in STOP/VLPS/LLS/VLLS mode,
* please use:
*
* SIM_SetUsbVoltRegulatorEnableMode(kSIM_UsbVoltRegEnable | kSIM_UsbVoltRegEnableInLowPower);
*
* @param mask USB voltage regulator enable setting.
*/
void SIM_SetUsbVoltRegulatorEnableMode(uint32_t mask);
#endif /* FSL_FEATURE_SIM_OPT_HAS_USB_VOLTAGE_REGULATOR */
/*!
* @brief Get the unique identification register value.
*
* @param uid Pointer to the structure to save the UID value.
*/
void SIM_GetUniqueId(sim_uid_t *uid);
/*!
* @brief Set the flash enable mode.
*
* @param mode The mode to set, see \ref _sim_flash_mode for mode details.
*/
static inline void SIM_SetFlashMode(uint8_t mode)
{
SIM->FCFG1 = mode;
}
#if defined(__cplusplus)
}
#endif /* __cplusplus*/
/*! @}*/
#endif /* _FSL_SIM_H_ */

View File

@ -0,0 +1,366 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include "fsl_smc.h"
#if (defined(FSL_FEATURE_SMC_HAS_PARAM) && FSL_FEATURE_SMC_HAS_PARAM)
void SMC_GetParam(SMC_Type *base, smc_param_t *param)
{
uint32_t reg = base->PARAM;
param->hsrunEnable = (bool)(reg & SMC_PARAM_EHSRUN_MASK);
param->llsEnable = (bool)(reg & SMC_PARAM_ELLS_MASK);
param->lls2Enable = (bool)(reg & SMC_PARAM_ELLS2_MASK);
param->vlls0Enable = (bool)(reg & SMC_PARAM_EVLLS0_MASK);
}
#endif /* FSL_FEATURE_SMC_HAS_PARAM */
status_t SMC_SetPowerModeRun(SMC_Type *base)
{
uint8_t reg;
reg = base->PMCTRL;
/* configure Normal RUN mode */
reg &= ~SMC_PMCTRL_RUNM_MASK;
reg |= (kSMC_RunNormal << SMC_PMCTRL_RUNM_SHIFT);
base->PMCTRL = reg;
return kStatus_Success;
}
#if (defined(FSL_FEATURE_SMC_HAS_HIGH_SPEED_RUN_MODE) && FSL_FEATURE_SMC_HAS_HIGH_SPEED_RUN_MODE)
status_t SMC_SetPowerModeHsrun(SMC_Type *base)
{
uint8_t reg;
reg = base->PMCTRL;
/* configure High Speed RUN mode */
reg &= ~SMC_PMCTRL_RUNM_MASK;
reg |= (kSMC_Hsrun << SMC_PMCTRL_RUNM_SHIFT);
base->PMCTRL = reg;
return kStatus_Success;
}
#endif /* FSL_FEATURE_SMC_HAS_HIGH_SPEED_RUN_MODE */
status_t SMC_SetPowerModeWait(SMC_Type *base)
{
/* configure Normal Wait mode */
SCB->SCR &= ~SCB_SCR_SLEEPDEEP_Msk;
__DSB();
__WFI();
__ISB();
return kStatus_Success;
}
status_t SMC_SetPowerModeStop(SMC_Type *base, smc_partial_stop_option_t option)
{
uint8_t reg;
#if (defined(FSL_FEATURE_SMC_HAS_PSTOPO) && FSL_FEATURE_SMC_HAS_PSTOPO)
/* configure the Partial Stop mode in Noraml Stop mode */
reg = base->STOPCTRL;
reg &= ~SMC_STOPCTRL_PSTOPO_MASK;
reg |= ((uint32_t)option << SMC_STOPCTRL_PSTOPO_SHIFT);
base->STOPCTRL = reg;
#endif
/* configure Normal Stop mode */
reg = base->PMCTRL;
reg &= ~SMC_PMCTRL_STOPM_MASK;
reg |= (kSMC_StopNormal << SMC_PMCTRL_STOPM_SHIFT);
base->PMCTRL = reg;
/* Set the SLEEPDEEP bit to enable deep sleep mode (stop mode) */
SCB->SCR |= SCB_SCR_SLEEPDEEP_Msk;
/* read back to make sure the configuration valid before enter stop mode */
(void)base->PMCTRL;
__DSB();
__WFI();
__ISB();
/* check whether the power mode enter Stop mode succeed */
if (base->PMCTRL & SMC_PMCTRL_STOPA_MASK)
{
return kStatus_SMC_StopAbort;
}
else
{
return kStatus_Success;
}
}
status_t SMC_SetPowerModeVlpr(SMC_Type *base
#if (defined(FSL_FEATURE_SMC_HAS_LPWUI) && FSL_FEATURE_SMC_HAS_LPWUI)
,
bool wakeupMode
#endif
)
{
uint8_t reg;
reg = base->PMCTRL;
#if (defined(FSL_FEATURE_SMC_HAS_LPWUI) && FSL_FEATURE_SMC_HAS_LPWUI)
/* configure whether the system remains in VLP mode on an interrupt */
if (wakeupMode)
{
/* exits to RUN mode on an interrupt */
reg |= SMC_PMCTRL_LPWUI_MASK;
}
else
{
/* remains in VLP mode on an interrupt */
reg &= ~SMC_PMCTRL_LPWUI_MASK;
}
#endif /* FSL_FEATURE_SMC_HAS_LPWUI */
/* configure VLPR mode */
reg &= ~SMC_PMCTRL_RUNM_MASK;
reg |= (kSMC_RunVlpr << SMC_PMCTRL_RUNM_SHIFT);
base->PMCTRL = reg;
return kStatus_Success;
}
status_t SMC_SetPowerModeVlpw(SMC_Type *base)
{
/* configure VLPW mode */
/* Set the SLEEPDEEP bit to enable deep sleep mode */
SCB->SCR &= ~SCB_SCR_SLEEPDEEP_Msk;
__DSB();
__WFI();
__ISB();
return kStatus_Success;
}
status_t SMC_SetPowerModeVlps(SMC_Type *base)
{
uint8_t reg;
/* configure VLPS mode */
reg = base->PMCTRL;
reg &= ~SMC_PMCTRL_STOPM_MASK;
reg |= (kSMC_StopVlps << SMC_PMCTRL_STOPM_SHIFT);
base->PMCTRL = reg;
/* Set the SLEEPDEEP bit to enable deep sleep mode */
SCB->SCR |= SCB_SCR_SLEEPDEEP_Msk;
/* read back to make sure the configuration valid before enter stop mode */
(void)base->PMCTRL;
__DSB();
__WFI();
__ISB();
/* check whether the power mode enter VLPS mode succeed */
if (base->PMCTRL & SMC_PMCTRL_STOPA_MASK)
{
return kStatus_SMC_StopAbort;
}
else
{
return kStatus_Success;
}
}
#if (defined(FSL_FEATURE_SMC_HAS_LOW_LEAKAGE_STOP_MODE) && FSL_FEATURE_SMC_HAS_LOW_LEAKAGE_STOP_MODE)
status_t SMC_SetPowerModeLls(SMC_Type *base
#if ((defined(FSL_FEATURE_SMC_HAS_LLS_SUBMODE) && FSL_FEATURE_SMC_HAS_LLS_SUBMODE) || \
(defined(FSL_FEATURE_SMC_HAS_LPOPO) && FSL_FEATURE_SMC_HAS_LPOPO))
,
const smc_power_mode_lls_config_t *config
#endif
)
{
uint8_t reg;
/* configure to LLS mode */
reg = base->PMCTRL;
reg &= ~SMC_PMCTRL_STOPM_MASK;
reg |= (kSMC_StopLls << SMC_PMCTRL_STOPM_SHIFT);
base->PMCTRL = reg;
/* configure LLS sub-mode*/
#if (defined(FSL_FEATURE_SMC_HAS_LLS_SUBMODE) && FSL_FEATURE_SMC_HAS_LLS_SUBMODE)
reg = base->STOPCTRL;
reg &= ~SMC_STOPCTRL_LLSM_MASK;
reg |= ((uint32_t)config->subMode << SMC_STOPCTRL_LLSM_SHIFT);
base->STOPCTRL = reg;
#endif /* FSL_FEATURE_SMC_HAS_LLS_SUBMODE */
#if (defined(FSL_FEATURE_SMC_HAS_LPOPO) && FSL_FEATURE_SMC_HAS_LPOPO)
if (config->enableLpoClock)
{
base->STOPCTRL &= ~SMC_STOPCTRL_LPOPO_MASK;
}
else
{
base->STOPCTRL |= SMC_STOPCTRL_LPOPO_MASK;
}
#endif /* FSL_FEATURE_SMC_HAS_LPOPO */
/* Set the SLEEPDEEP bit to enable deep sleep mode */
SCB->SCR |= SCB_SCR_SLEEPDEEP_Msk;
/* read back to make sure the configuration valid before enter stop mode */
(void)base->PMCTRL;
__DSB();
__WFI();
__ISB();
/* check whether the power mode enter LLS mode succeed */
if (base->PMCTRL & SMC_PMCTRL_STOPA_MASK)
{
return kStatus_SMC_StopAbort;
}
else
{
return kStatus_Success;
}
}
#endif /* FSL_FEATURE_SMC_HAS_LOW_LEAKAGE_STOP_MODE */
#if (defined(FSL_FEATURE_SMC_HAS_VERY_LOW_LEAKAGE_STOP_MODE) && FSL_FEATURE_SMC_HAS_VERY_LOW_LEAKAGE_STOP_MODE)
status_t SMC_SetPowerModeVlls(SMC_Type *base, const smc_power_mode_vlls_config_t *config)
{
uint8_t reg;
#if (defined(FSL_FEATURE_SMC_HAS_PORPO) && FSL_FEATURE_SMC_HAS_PORPO)
#if (defined(FSL_FEATURE_SMC_USE_VLLSCTRL_REG) && FSL_FEATURE_SMC_USE_VLLSCTRL_REG) || \
(defined(FSL_FEATURE_SMC_USE_STOPCTRL_VLLSM) && FSL_FEATURE_SMC_USE_STOPCTRL_VLLSM) || \
(defined(FSL_FEATURE_SMC_HAS_LLS_SUBMODE) && FSL_FEATURE_SMC_HAS_LLS_SUBMODE)
if (config->subMode == kSMC_StopSub0)
#endif
{
/* configure whether the Por Detect work in Vlls0 mode */
if (config->enablePorDetectInVlls0)
{
#if (defined(FSL_FEATURE_SMC_USE_VLLSCTRL_REG) && FSL_FEATURE_SMC_USE_VLLSCTRL_REG)
base->VLLSCTRL &= ~SMC_VLLSCTRL_PORPO_MASK;
#else
base->STOPCTRL &= ~SMC_STOPCTRL_PORPO_MASK;
#endif
}
else
{
#if (defined(FSL_FEATURE_SMC_USE_VLLSCTRL_REG) && FSL_FEATURE_SMC_USE_VLLSCTRL_REG)
base->VLLSCTRL |= SMC_VLLSCTRL_PORPO_MASK;
#else
base->STOPCTRL |= SMC_STOPCTRL_PORPO_MASK;
#endif
}
}
#endif /* FSL_FEATURE_SMC_HAS_PORPO */
#if (defined(FSL_FEATURE_SMC_HAS_RAM2_POWER_OPTION) && FSL_FEATURE_SMC_HAS_RAM2_POWER_OPTION)
else if (config->subMode == kSMC_StopSub2)
{
/* configure whether the Por Detect work in Vlls0 mode */
if (config->enableRam2InVlls2)
{
#if (defined(FSL_FEATURE_SMC_USE_VLLSCTRL_REG) && FSL_FEATURE_SMC_USE_VLLSCTRL_REG)
base->VLLSCTRL |= SMC_VLLSCTRL_RAM2PO_MASK;
#else
base->STOPCTRL |= SMC_STOPCTRL_RAM2PO_MASK;
#endif
}
else
{
#if (defined(FSL_FEATURE_SMC_USE_VLLSCTRL_REG) && FSL_FEATURE_SMC_USE_VLLSCTRL_REG)
base->VLLSCTRL &= ~SMC_VLLSCTRL_RAM2PO_MASK;
#else
base->STOPCTRL &= ~SMC_STOPCTRL_RAM2PO_MASK;
#endif
}
}
else
{
}
#endif /* FSL_FEATURE_SMC_HAS_RAM2_POWER_OPTION */
/* configure to VLLS mode */
reg = base->PMCTRL;
reg &= ~SMC_PMCTRL_STOPM_MASK;
reg |= (kSMC_StopVlls << SMC_PMCTRL_STOPM_SHIFT);
base->PMCTRL = reg;
/* configure the VLLS sub-mode */
#if (defined(FSL_FEATURE_SMC_USE_VLLSCTRL_REG) && FSL_FEATURE_SMC_USE_VLLSCTRL_REG)
reg = base->VLLSCTRL;
reg &= ~SMC_VLLSCTRL_VLLSM_MASK;
reg |= ((uint32_t)config->subMode << SMC_VLLSCTRL_VLLSM_SHIFT);
base->VLLSCTRL = reg;
#else
#if (defined(FSL_FEATURE_SMC_HAS_LLS_SUBMODE) && FSL_FEATURE_SMC_HAS_LLS_SUBMODE)
reg = base->STOPCTRL;
reg &= ~SMC_STOPCTRL_LLSM_MASK;
reg |= ((uint32_t)config->subMode << SMC_STOPCTRL_LLSM_SHIFT);
base->STOPCTRL = reg;
#else
reg = base->STOPCTRL;
reg &= ~SMC_STOPCTRL_VLLSM_MASK;
reg |= ((uint32_t)config->subMode << SMC_STOPCTRL_VLLSM_SHIFT);
base->STOPCTRL = reg;
#endif /* FSL_FEATURE_SMC_HAS_LLS_SUBMODE */
#endif
#if (defined(FSL_FEATURE_SMC_HAS_LPOPO) && FSL_FEATURE_SMC_HAS_LPOPO)
if (config->enableLpoClock)
{
base->STOPCTRL &= ~SMC_STOPCTRL_LPOPO_MASK;
}
else
{
base->STOPCTRL |= SMC_STOPCTRL_LPOPO_MASK;
}
#endif /* FSL_FEATURE_SMC_HAS_LPOPO */
/* Set the SLEEPDEEP bit to enable deep sleep mode */
SCB->SCR |= SCB_SCR_SLEEPDEEP_Msk;
/* read back to make sure the configuration valid before enter stop mode */
(void)base->PMCTRL;
__DSB();
__WFI();
__ISB();
/* check whether the power mode enter LLS mode succeed */
if (base->PMCTRL & SMC_PMCTRL_STOPA_MASK)
{
return kStatus_SMC_StopAbort;
}
else
{
return kStatus_Success;
}
}
#endif /* FSL_FEATURE_SMC_HAS_VERY_LOW_LEAKAGE_STOP_MODE */

View File

@ -0,0 +1,418 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _FSL_SMC_H_
#define _FSL_SMC_H_
#include "fsl_common.h"
/*! @addtogroup smc */
/*! @{ */
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @name Driver version */
/*@{*/
/*! @brief SMC driver version 2.0.2. */
#define FSL_SMC_DRIVER_VERSION (MAKE_VERSION(2, 0, 2))
/*@}*/
/*!
* @brief Power Modes Protection
*/
typedef enum _smc_power_mode_protection
{
#if (defined(FSL_FEATURE_SMC_HAS_VERY_LOW_LEAKAGE_STOP_MODE) && FSL_FEATURE_SMC_HAS_VERY_LOW_LEAKAGE_STOP_MODE)
kSMC_AllowPowerModeVlls = SMC_PMPROT_AVLLS_MASK, /*!< Allow Very-Low-Leakage Stop Mode. */
#endif
#if (defined(FSL_FEATURE_SMC_HAS_LOW_LEAKAGE_STOP_MODE) && FSL_FEATURE_SMC_HAS_LOW_LEAKAGE_STOP_MODE)
kSMC_AllowPowerModeLls = SMC_PMPROT_ALLS_MASK, /*!< Allow Low-Leakage Stop Mode. */
#endif /* FSL_FEATURE_SMC_HAS_LOW_LEAKAGE_STOP_MODE */
kSMC_AllowPowerModeVlp = SMC_PMPROT_AVLP_MASK, /*!< Allow Very-Low-Power Mode. */
#if (defined(FSL_FEATURE_SMC_HAS_HIGH_SPEED_RUN_MODE) && FSL_FEATURE_SMC_HAS_HIGH_SPEED_RUN_MODE)
kSMC_AllowPowerModeHsrun = SMC_PMPROT_AHSRUN_MASK, /*!< Allow High Speed Run mode. */
#endif /* FSL_FEATURE_SMC_HAS_HIGH_SPEED_RUN_MODE */
kSMC_AllowPowerModeAll = (0U
#if (defined(FSL_FEATURE_SMC_HAS_VERY_LOW_LEAKAGE_STOP_MODE) && FSL_FEATURE_SMC_HAS_VERY_LOW_LEAKAGE_STOP_MODE)
|
SMC_PMPROT_AVLLS_MASK
#endif
#if (defined(FSL_FEATURE_SMC_HAS_LOW_LEAKAGE_STOP_MODE) && FSL_FEATURE_SMC_HAS_LOW_LEAKAGE_STOP_MODE)
|
SMC_PMPROT_ALLS_MASK
#endif /* FSL_FEATURE_SMC_HAS_LOW_LEAKAGE_STOP_MODE */
|
SMC_PMPROT_AVLP_MASK
#if (defined(FSL_FEATURE_SMC_HAS_HIGH_SPEED_RUN_MODE) && FSL_FEATURE_SMC_HAS_HIGH_SPEED_RUN_MODE)
|
kSMC_AllowPowerModeHsrun
#endif /* FSL_FEATURE_SMC_HAS_HIGH_SPEED_RUN_MODE */
) /*!< Allow all power mode. */
} smc_power_mode_protection_t;
/*!
* @brief Power Modes in PMSTAT
*/
typedef enum _smc_power_state
{
kSMC_PowerStateRun = 0x01U << 0U, /*!< 0000_0001 - Current power mode is RUN */
kSMC_PowerStateStop = 0x01U << 1U, /*!< 0000_0010 - Current power mode is STOP */
kSMC_PowerStateVlpr = 0x01U << 2U, /*!< 0000_0100 - Current power mode is VLPR */
kSMC_PowerStateVlpw = 0x01U << 3U, /*!< 0000_1000 - Current power mode is VLPW */
kSMC_PowerStateVlps = 0x01U << 4U, /*!< 0001_0000 - Current power mode is VLPS */
#if (defined(FSL_FEATURE_SMC_HAS_LOW_LEAKAGE_STOP_MODE) && FSL_FEATURE_SMC_HAS_LOW_LEAKAGE_STOP_MODE)
kSMC_PowerStateLls = 0x01U << 5U, /*!< 0010_0000 - Current power mode is LLS */
#endif /* FSL_FEATURE_SMC_HAS_LOW_LEAKAGE_STOP_MODE */
#if (defined(FSL_FEATURE_SMC_HAS_VERY_LOW_LEAKAGE_STOP_MODE) && FSL_FEATURE_SMC_HAS_VERY_LOW_LEAKAGE_STOP_MODE)
kSMC_PowerStateVlls = 0x01U << 6U, /*!< 0100_0000 - Current power mode is VLLS */
#endif
#if (defined(FSL_FEATURE_SMC_HAS_HIGH_SPEED_RUN_MODE) && FSL_FEATURE_SMC_HAS_HIGH_SPEED_RUN_MODE)
kSMC_PowerStateHsrun = 0x01U << 7U /*!< 1000_0000 - Current power mode is HSRUN */
#endif /* FSL_FEATURE_SMC_HAS_HIGH_SPEED_RUN_MODE */
} smc_power_state_t;
/*!
* @brief Run mode definition
*/
typedef enum _smc_run_mode
{
kSMC_RunNormal = 0U, /*!< normal RUN mode. */
kSMC_RunVlpr = 2U, /*!< Very-Low-Power RUN mode. */
#if (defined(FSL_FEATURE_SMC_HAS_HIGH_SPEED_RUN_MODE) && FSL_FEATURE_SMC_HAS_HIGH_SPEED_RUN_MODE)
kSMC_Hsrun = 3U /*!< High Speed Run mode (HSRUN). */
#endif /* FSL_FEATURE_SMC_HAS_HIGH_SPEED_RUN_MODE */
} smc_run_mode_t;
/*!
* @brief Stop mode definition
*/
typedef enum _smc_stop_mode
{
kSMC_StopNormal = 0U, /*!< Normal STOP mode. */
kSMC_StopVlps = 2U, /*!< Very-Low-Power STOP mode. */
#if (defined(FSL_FEATURE_SMC_HAS_LOW_LEAKAGE_STOP_MODE) && FSL_FEATURE_SMC_HAS_LOW_LEAKAGE_STOP_MODE)
kSMC_StopLls = 3U, /*!< Low-Leakage Stop mode. */
#endif /* FSL_FEATURE_SMC_HAS_LOW_LEAKAGE_STOP_MODE */
#if (defined(FSL_FEATURE_SMC_HAS_VERY_LOW_LEAKAGE_STOP_MODE) && FSL_FEATURE_SMC_HAS_VERY_LOW_LEAKAGE_STOP_MODE)
kSMC_StopVlls = 4U /*!< Very-Low-Leakage Stop mode. */
#endif
} smc_stop_mode_t;
#if (defined(FSL_FEATURE_SMC_USE_VLLSCTRL_REG) && FSL_FEATURE_SMC_USE_VLLSCTRL_REG) || \
(defined(FSL_FEATURE_SMC_USE_STOPCTRL_VLLSM) && FSL_FEATURE_SMC_USE_STOPCTRL_VLLSM) || \
(defined(FSL_FEATURE_SMC_HAS_LLS_SUBMODE) && FSL_FEATURE_SMC_HAS_LLS_SUBMODE)
/*!
* @brief VLLS/LLS stop sub mode definition
*/
typedef enum _smc_stop_submode
{
kSMC_StopSub0 = 0U, /*!< Stop submode 0, for VLLS0/LLS0. */
kSMC_StopSub1 = 1U, /*!< Stop submode 1, for VLLS1/LLS1. */
kSMC_StopSub2 = 2U, /*!< Stop submode 2, for VLLS2/LLS2. */
kSMC_StopSub3 = 3U /*!< Stop submode 3, for VLLS3/LLS3. */
} smc_stop_submode_t;
#endif
/*!
* @brief Partial STOP option
*/
typedef enum _smc_partial_stop_mode
{
kSMC_PartialStop = 0U, /*!< STOP - Normal Stop mode*/
kSMC_PartialStop1 = 1U, /*!< Partial Stop with both system and bus clocks disabled*/
kSMC_PartialStop2 = 2U, /*!< Partial Stop with system clock disabled and bus clock enabled*/
} smc_partial_stop_option_t;
/*!
* @brief SMC configuration status
*/
enum _smc_status
{
kStatus_SMC_StopAbort = MAKE_STATUS(kStatusGroup_POWER, 0) /*!< Entering Stop mode is abort*/
};
#if (defined(FSL_FEATURE_SMC_HAS_VERID) && FSL_FEATURE_SMC_HAS_VERID)
/*!
* @brief IP version ID definition.
*/
typedef struct _smc_version_id
{
uint16_t feature; /*!< Feature Specification Number. */
uint8_t minor; /*!< Minor version number. */
uint8_t major; /*!< Major version number. */
} smc_version_id_t;
#endif /* FSL_FEATURE_SMC_HAS_VERID */
#if (defined(FSL_FEATURE_SMC_HAS_PARAM) && FSL_FEATURE_SMC_HAS_PARAM)
/*!
* @brief IP parameter definition.
*/
typedef struct _smc_param
{
bool hsrunEnable; /*!< HSRUN mode enable. */
bool llsEnable; /*!< LLS mode enable. */
bool lls2Enable; /*!< LLS2 mode enable. */
bool vlls0Enable; /*!< VLLS0 mode enable. */
} smc_param_t;
#endif /* FSL_FEATURE_SMC_HAS_PARAM */
#if (defined(FSL_FEATURE_SMC_HAS_LLS_SUBMODE) && FSL_FEATURE_SMC_HAS_LLS_SUBMODE) || \
(defined(FSL_FEATURE_SMC_HAS_LPOPO) && FSL_FEATURE_SMC_HAS_LPOPO)
/*!
* @brief SMC Low-Leakage Stop power mode config
*/
typedef struct _smc_power_mode_lls_config
{
#if (defined(FSL_FEATURE_SMC_HAS_LLS_SUBMODE) && FSL_FEATURE_SMC_HAS_LLS_SUBMODE)
smc_stop_submode_t subMode; /*!< Low-leakage Stop sub-mode */
#endif
#if (defined(FSL_FEATURE_SMC_HAS_LPOPO) && FSL_FEATURE_SMC_HAS_LPOPO)
bool enableLpoClock; /*!< Enable LPO clock in LLS mode */
#endif
} smc_power_mode_lls_config_t;
#endif /* (FSL_FEATURE_SMC_HAS_LLS_SUBMODE || FSL_FEATURE_SMC_HAS_LPOPO) */
#if (defined(FSL_FEATURE_SMC_HAS_VERY_LOW_LEAKAGE_STOP_MODE) && FSL_FEATURE_SMC_HAS_VERY_LOW_LEAKAGE_STOP_MODE)
/*!
* @brief SMC Very Low-Leakage Stop power mode config
*/
typedef struct _smc_power_mode_vlls_config
{
#if (defined(FSL_FEATURE_SMC_USE_VLLSCTRL_REG) && FSL_FEATURE_SMC_USE_VLLSCTRL_REG) || \
(defined(FSL_FEATURE_SMC_USE_STOPCTRL_VLLSM) && FSL_FEATURE_SMC_USE_STOPCTRL_VLLSM) || \
(defined(FSL_FEATURE_SMC_HAS_LLS_SUBMODE) && FSL_FEATURE_SMC_HAS_LLS_SUBMODE)
smc_stop_submode_t subMode; /*!< Very Low-leakage Stop sub-mode */
#endif
#if (defined(FSL_FEATURE_SMC_HAS_PORPO) && FSL_FEATURE_SMC_HAS_PORPO)
bool enablePorDetectInVlls0; /*!< Enable Power on reset detect in VLLS mode */
#endif
#if (defined(FSL_FEATURE_SMC_HAS_RAM2_POWER_OPTION) && FSL_FEATURE_SMC_HAS_RAM2_POWER_OPTION)
bool enableRam2InVlls2; /*!< Enable RAM2 power in VLLS2 */
#endif
#if (defined(FSL_FEATURE_SMC_HAS_LPOPO) && FSL_FEATURE_SMC_HAS_LPOPO)
bool enableLpoClock; /*!< Enable LPO clock in VLLS mode */
#endif
} smc_power_mode_vlls_config_t;
#endif
/*******************************************************************************
* API
******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif /* __cplusplus */
/*! @name System mode controller APIs*/
/*@{*/
#if (defined(FSL_FEATURE_SMC_HAS_VERID) && FSL_FEATURE_SMC_HAS_VERID)
/*!
* @brief Gets the SMC version ID.
*
* This function gets the SMC version ID, including major version number,
* minor version number and feature specification number.
*
* @param base SMC peripheral base address.
* @param versionId Pointer to version ID structure.
*/
static inline void SMC_GetVersionId(SMC_Type *base, smc_version_id_t *versionId)
{
*((uint32_t *)versionId) = base->VERID;
}
#endif /* FSL_FEATURE_SMC_HAS_VERID */
#if (defined(FSL_FEATURE_SMC_HAS_PARAM) && FSL_FEATURE_SMC_HAS_PARAM)
/*!
* @brief Gets the SMC parameter.
*
* This function gets the SMC parameter, including the enabled power mdoes.
*
* @param base SMC peripheral base address.
* @param param Pointer to SMC param structure.
*/
void SMC_GetParam(SMC_Type *base, smc_param_t *param);
#endif
/*!
* @brief Configures all power mode protection settings.
*
* This function configures the power mode protection settings for
* supported power modes in the specified chip family. The available power modes
* are defined in the smc_power_mode_protection_t. This should be done at an early
* system level initialization stage. See the reference manual for details.
* This register can only write once after the power reset.
*
* The allowed modes are passed as bit map, for example, to allow LLS and VLLS,
* use SMC_SetPowerModeProtection(kSMC_AllowPowerModeVlls | kSMC_AllowPowerModeVlps).
* To allow all modes, use SMC_SetPowerModeProtection(kSMC_AllowPowerModeAll).
*
* @param base SMC peripheral base address.
* @param allowedModes Bitmap of the allowed power modes.
*/
static inline void SMC_SetPowerModeProtection(SMC_Type *base, uint8_t allowedModes)
{
base->PMPROT = allowedModes;
}
/*!
* @brief Gets the current power mode status.
*
* This function returns the current power mode stat. Once application
* switches the power mode, it should always check the stat to check whether it
* runs into the specified mode or not. An application should check
* this mode before switching to a different mode. The system requires that
* only certain modes can switch to other specific modes. See the
* reference manual for details and the smc_power_state_t for information about
* the power stat.
*
* @param base SMC peripheral base address.
* @return Current power mode status.
*/
static inline smc_power_state_t SMC_GetPowerModeState(SMC_Type *base)
{
return (smc_power_state_t)base->PMSTAT;
}
/*!
* @brief Configure the system to RUN power mode.
*
* @param base SMC peripheral base address.
* @return SMC configuration error code.
*/
status_t SMC_SetPowerModeRun(SMC_Type *base);
#if (defined(FSL_FEATURE_SMC_HAS_HIGH_SPEED_RUN_MODE) && FSL_FEATURE_SMC_HAS_HIGH_SPEED_RUN_MODE)
/*!
* @brief Configure the system to HSRUN power mode.
*
* @param base SMC peripheral base address.
* @return SMC configuration error code.
*/
status_t SMC_SetPowerModeHsrun(SMC_Type *base);
#endif /* FSL_FEATURE_SMC_HAS_HIGH_SPEED_RUN_MODE */
/*!
* @brief Configure the system to WAIT power mode.
*
* @param base SMC peripheral base address.
* @return SMC configuration error code.
*/
status_t SMC_SetPowerModeWait(SMC_Type *base);
/*!
* @brief Configure the system to Stop power mode.
*
* @param base SMC peripheral base address.
* @param option Partial Stop mode option.
* @return SMC configuration error code.
*/
status_t SMC_SetPowerModeStop(SMC_Type *base, smc_partial_stop_option_t option);
#if (defined(FSL_FEATURE_SMC_HAS_LPWUI) && FSL_FEATURE_SMC_HAS_LPWUI)
/*!
* @brief Configure the system to VLPR power mode.
*
* @param base SMC peripheral base address.
* @param wakeupMode Enter Normal Run mode if true, else stay in VLPR mode.
* @return SMC configuration error code.
*/
status_t SMC_SetPowerModeVlpr(SMC_Type *base, bool wakeupMode);
#else
/*!
* @brief Configure the system to VLPR power mode.
*
* @param base SMC peripheral base address.
* @return SMC configuration error code.
*/
status_t SMC_SetPowerModeVlpr(SMC_Type *base);
#endif /* FSL_FEATURE_SMC_HAS_LPWUI */
/*!
* @brief Configure the system to VLPW power mode.
*
* @param base SMC peripheral base address.
* @return SMC configuration error code.
*/
status_t SMC_SetPowerModeVlpw(SMC_Type *base);
/*!
* @brief Configure the system to VLPS power mode.
*
* @param base SMC peripheral base address.
* @return SMC configuration error code.
*/
status_t SMC_SetPowerModeVlps(SMC_Type *base);
#if (defined(FSL_FEATURE_SMC_HAS_LOW_LEAKAGE_STOP_MODE) && FSL_FEATURE_SMC_HAS_LOW_LEAKAGE_STOP_MODE)
#if ((defined(FSL_FEATURE_SMC_HAS_LLS_SUBMODE) && FSL_FEATURE_SMC_HAS_LLS_SUBMODE) || \
(defined(FSL_FEATURE_SMC_HAS_LPOPO) && FSL_FEATURE_SMC_HAS_LPOPO))
/*!
* @brief Configure the system to LLS power mode.
*
* @param base SMC peripheral base address.
* @param config The LLS power mode configuration structure
* @return SMC configuration error code.
*/
status_t SMC_SetPowerModeLls(SMC_Type *base, const smc_power_mode_lls_config_t *config);
#else
/*!
* @brief Configure the system to LLS power mode.
*
* @param base SMC peripheral base address.
* @return SMC configuration error code.
*/
status_t SMC_SetPowerModeLls(SMC_Type *base);
#endif
#endif /* FSL_FEATURE_SMC_HAS_LOW_LEAKAGE_STOP_MODE */
#if (defined(FSL_FEATURE_SMC_HAS_VERY_LOW_LEAKAGE_STOP_MODE) && FSL_FEATURE_SMC_HAS_VERY_LOW_LEAKAGE_STOP_MODE)
/*!
* @brief Configure the system to VLLS power mode.
*
* @param base SMC peripheral base address.
* @param config The VLLS power mode configuration structure.
* @return SMC configuration error code.
*/
status_t SMC_SetPowerModeVlls(SMC_Type *base, const smc_power_mode_vlls_config_t *config);
#endif /* FSL_FEATURE_SMC_HAS_VERY_LOW_LEAKAGE_STOP_MODE */
/*@}*/
#if defined(__cplusplus)
}
#endif /* __cplusplus */
/*! @}*/
#endif /* _FSL_SMC_H_ */

View File

@ -0,0 +1,729 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include "fsl_tpm.h"
/*******************************************************************************
* Definitions
******************************************************************************/
#define TPM_COMBINE_SHIFT (8U)
/*******************************************************************************
* Prototypes
******************************************************************************/
/*!
* @brief Gets the instance from the base address
*
* @param base TPM peripheral base address
*
* @return The TPM instance
*/
static uint32_t TPM_GetInstance(TPM_Type *base);
/*******************************************************************************
* Variables
******************************************************************************/
/*! @brief Pointers to TPM bases for each instance. */
static TPM_Type *const s_tpmBases[] = TPM_BASE_PTRS;
/*! @brief Pointers to TPM clocks for each instance. */
static const clock_ip_name_t s_tpmClocks[] = TPM_CLOCKS;
/*******************************************************************************
* Code
******************************************************************************/
static uint32_t TPM_GetInstance(TPM_Type *base)
{
uint32_t instance;
uint32_t tpmArrayCount = (sizeof(s_tpmBases) / sizeof(s_tpmBases[0]));
/* Find the instance index from base address mappings. */
for (instance = 0; instance < tpmArrayCount; instance++)
{
if (s_tpmBases[instance] == base)
{
break;
}
}
assert(instance < tpmArrayCount);
return instance;
}
void TPM_Init(TPM_Type *base, const tpm_config_t *config)
{
assert(config);
/* Enable the module clock */
CLOCK_EnableClock(s_tpmClocks[TPM_GetInstance(base)]);
#if defined(FSL_FEATURE_TPM_HAS_GLOBAL) && FSL_FEATURE_TPM_HAS_GLOBAL
/* TPM reset is available on certain SoC's */
TPM_Reset(base);
#endif
/* Set the clock prescale factor */
base->SC = TPM_SC_PS(config->prescale);
/* Setup the counter operation */
base->CONF = TPM_CONF_DOZEEN(config->enableDoze) |
TPM_CONF_GTBEEN(config->useGlobalTimeBase) | TPM_CONF_CROT(config->enableReloadOnTrigger) |
TPM_CONF_CSOT(config->enableStartOnTrigger) | TPM_CONF_CSOO(config->enableStopOnOverflow) |
#if defined(FSL_FEATURE_TPM_HAS_PAUSE_COUNTER_ON_TRIGGER) && FSL_FEATURE_TPM_HAS_PAUSE_COUNTER_ON_TRIGGER
TPM_CONF_CPOT(config->enablePauseOnTrigger) |
#endif
#if defined(FSL_FEATURE_TPM_HAS_EXTERNAL_TRIGGER_SELECTION) && FSL_FEATURE_TPM_HAS_EXTERNAL_TRIGGER_SELECTION
TPM_CONF_TRGSRC(config->triggerSource) |
#endif
TPM_CONF_TRGSEL(config->triggerSelect);
if (config->enableDebugMode)
{
base->CONF |= TPM_CONF_DBGMODE_MASK;
}
else
{
base->CONF &= ~TPM_CONF_DBGMODE_MASK;
}
}
void TPM_Deinit(TPM_Type *base)
{
/* Stop the counter */
base->SC &= ~TPM_SC_CMOD_MASK;
/* Gate the TPM clock */
CLOCK_DisableClock(s_tpmClocks[TPM_GetInstance(base)]);
}
void TPM_GetDefaultConfig(tpm_config_t *config)
{
assert(config);
/* TPM clock divide by 1 */
config->prescale = kTPM_Prescale_Divide_1;
/* Use internal TPM counter as timebase */
config->useGlobalTimeBase = false;
/* TPM counter continues in doze mode */
config->enableDoze = false;
/* TPM counter pauses when in debug mode */
config->enableDebugMode = false;
/* TPM counter will not be reloaded on input trigger */
config->enableReloadOnTrigger = false;
/* TPM counter continues running after overflow */
config->enableStopOnOverflow = false;
/* TPM counter starts immediately once it is enabled */
config->enableStartOnTrigger = false;
#if defined(FSL_FEATURE_TPM_HAS_PAUSE_COUNTER_ON_TRIGGER) && FSL_FEATURE_TPM_HAS_PAUSE_COUNTER_ON_TRIGGER
config->enablePauseOnTrigger = false;
#endif
/* Choose trigger select 0 as input trigger for controlling counter operation */
config->triggerSelect = kTPM_Trigger_Select_0;
#if defined(FSL_FEATURE_TPM_HAS_EXTERNAL_TRIGGER_SELECTION) && FSL_FEATURE_TPM_HAS_EXTERNAL_TRIGGER_SELECTION
/* Choose external trigger source to control counter operation */
config->triggerSource = kTPM_TriggerSource_External;
#endif
}
status_t TPM_SetupPwm(TPM_Type *base,
const tpm_chnl_pwm_signal_param_t *chnlParams,
uint8_t numOfChnls,
tpm_pwm_mode_t mode,
uint32_t pwmFreq_Hz,
uint32_t srcClock_Hz)
{
assert(chnlParams);
assert(pwmFreq_Hz);
assert(numOfChnls);
assert(srcClock_Hz);
uint32_t mod;
uint32_t tpmClock = (srcClock_Hz / (1U << (base->SC & TPM_SC_PS_MASK)));
uint16_t cnv;
uint8_t i;
#if defined(FSL_FEATURE_TPM_HAS_QDCTRL) && FSL_FEATURE_TPM_HAS_QDCTRL
/* Clear quadrature Decoder mode because in quadrature Decoder mode PWM doesn't operate*/
base->QDCTRL &= ~TPM_QDCTRL_QUADEN_MASK;
#endif
switch (mode)
{
case kTPM_EdgeAlignedPwm:
#if defined(FSL_FEATURE_TPM_HAS_COMBINE) && FSL_FEATURE_TPM_HAS_COMBINE
case kTPM_CombinedPwm:
#endif
base->SC &= ~TPM_SC_CPWMS_MASK;
mod = (tpmClock / pwmFreq_Hz) - 1;
break;
case kTPM_CenterAlignedPwm:
base->SC |= TPM_SC_CPWMS_MASK;
mod = tpmClock / (pwmFreq_Hz * 2);
break;
default:
return kStatus_Fail;
}
/* Return an error in case we overflow the registers, probably would require changing
* clock source to get the desired frequency */
if (mod > 65535U)
{
return kStatus_Fail;
}
/* Set the PWM period */
base->MOD = mod;
/* Setup each TPM channel */
for (i = 0; i < numOfChnls; i++)
{
/* Return error if requested dutycycle is greater than the max allowed */
if (chnlParams->dutyCyclePercent > 100)
{
return kStatus_Fail;
}
#if defined(FSL_FEATURE_TPM_HAS_COMBINE) && FSL_FEATURE_TPM_HAS_COMBINE
if (mode == kTPM_CombinedPwm)
{
uint16_t cnvFirstEdge;
/* This check is added for combined mode as the channel number should be the pair number */
if (chnlParams->chnlNumber >= (FSL_FEATURE_TPM_CHANNEL_COUNTn(base) / 2))
{
return kStatus_Fail;
}
/* Return error if requested value is greater than the max allowed */
if (chnlParams->firstEdgeDelayPercent > 100)
{
return kStatus_Fail;
}
/* Configure delay of the first edge */
if (chnlParams->firstEdgeDelayPercent == 0)
{
/* No delay for the first edge */
cnvFirstEdge = 0;
}
else
{
cnvFirstEdge = (mod * chnlParams->firstEdgeDelayPercent) / 100;
}
/* Configure dutycycle */
if (chnlParams->dutyCyclePercent == 0)
{
/* Signal stays low */
cnv = 0;
cnvFirstEdge = 0;
}
else
{
cnv = (mod * chnlParams->dutyCyclePercent) / 100;
/* For 100% duty cycle */
if (cnv >= mod)
{
cnv = mod + 1;
}
}
/* Set the combine bit for the channel pair */
base->COMBINE |= (1U << (TPM_COMBINE_COMBINE0_SHIFT + (TPM_COMBINE_SHIFT * chnlParams->chnlNumber)));
/* When switching mode, disable channel n first */
base->CONTROLS[chnlParams->chnlNumber * 2].CnSC &=
~(TPM_CnSC_MSA_MASK | TPM_CnSC_MSB_MASK | TPM_CnSC_ELSA_MASK | TPM_CnSC_ELSB_MASK);
/* Wait till mode change to disable channel is acknowledged */
while ((base->CONTROLS[chnlParams->chnlNumber * 2].CnSC &
(TPM_CnSC_MSA_MASK | TPM_CnSC_MSB_MASK | TPM_CnSC_ELSA_MASK | TPM_CnSC_ELSB_MASK)))
{
}
/* Set the requested PWM mode for channel n, PWM output requires mode select to be set to 2 */
base->CONTROLS[chnlParams->chnlNumber * 2].CnSC |=
((chnlParams->level << TPM_CnSC_ELSA_SHIFT) | (2U << TPM_CnSC_MSA_SHIFT));
/* Wait till mode change is acknowledged */
while (!(base->CONTROLS[chnlParams->chnlNumber * 2].CnSC &
(TPM_CnSC_MSA_MASK | TPM_CnSC_MSB_MASK | TPM_CnSC_ELSA_MASK | TPM_CnSC_ELSB_MASK)))
{
}
/* Set the channel pair values */
base->CONTROLS[chnlParams->chnlNumber * 2].CnV = cnvFirstEdge;
/* When switching mode, disable channel n + 1 first */
base->CONTROLS[(chnlParams->chnlNumber * 2) + 1].CnSC &=
~(TPM_CnSC_MSA_MASK | TPM_CnSC_MSB_MASK | TPM_CnSC_ELSA_MASK | TPM_CnSC_ELSB_MASK);
/* Wait till mode change to disable channel is acknowledged */
while ((base->CONTROLS[(chnlParams->chnlNumber * 2) + 1].CnSC &
(TPM_CnSC_MSA_MASK | TPM_CnSC_MSB_MASK | TPM_CnSC_ELSA_MASK | TPM_CnSC_ELSB_MASK)))
{
}
/* Set the requested PWM mode for channel n + 1, PWM output requires mode select to be set to 2 */
base->CONTROLS[(chnlParams->chnlNumber * 2) + 1].CnSC |=
((chnlParams->level << TPM_CnSC_ELSA_SHIFT) | (2U << TPM_CnSC_MSA_SHIFT));
/* Wait till mode change is acknowledged */
while (!(base->CONTROLS[(chnlParams->chnlNumber * 2) + 1].CnSC &
(TPM_CnSC_MSA_MASK | TPM_CnSC_MSB_MASK | TPM_CnSC_ELSA_MASK | TPM_CnSC_ELSB_MASK)))
{
}
/* Set the channel pair values */
base->CONTROLS[(chnlParams->chnlNumber * 2) + 1].CnV = cnvFirstEdge + cnv;
}
else
{
#endif
if (chnlParams->dutyCyclePercent == 0)
{
/* Signal stays low */
cnv = 0;
}
else
{
cnv = (mod * chnlParams->dutyCyclePercent) / 100;
/* For 100% duty cycle */
if (cnv >= mod)
{
cnv = mod + 1;
}
}
/* When switching mode, disable channel first */
base->CONTROLS[chnlParams->chnlNumber].CnSC &=
~(TPM_CnSC_MSA_MASK | TPM_CnSC_MSB_MASK | TPM_CnSC_ELSA_MASK | TPM_CnSC_ELSB_MASK);
/* Wait till mode change to disable channel is acknowledged */
while ((base->CONTROLS[chnlParams->chnlNumber].CnSC &
(TPM_CnSC_MSA_MASK | TPM_CnSC_MSB_MASK | TPM_CnSC_ELSA_MASK | TPM_CnSC_ELSB_MASK)))
{
}
/* Set the requested PWM mode, PWM output requires mode select to be set to 2 */
base->CONTROLS[chnlParams->chnlNumber].CnSC |=
((chnlParams->level << TPM_CnSC_ELSA_SHIFT) | (2U << TPM_CnSC_MSA_SHIFT));
/* Wait till mode change is acknowledged */
while (!(base->CONTROLS[chnlParams->chnlNumber].CnSC &
(TPM_CnSC_MSA_MASK | TPM_CnSC_MSB_MASK | TPM_CnSC_ELSA_MASK | TPM_CnSC_ELSB_MASK)))
{
}
base->CONTROLS[chnlParams->chnlNumber].CnV = cnv;
#if defined(FSL_FEATURE_TPM_HAS_COMBINE) && FSL_FEATURE_TPM_HAS_COMBINE
}
#endif
chnlParams++;
}
return kStatus_Success;
}
void TPM_UpdatePwmDutycycle(TPM_Type *base,
tpm_chnl_t chnlNumber,
tpm_pwm_mode_t currentPwmMode,
uint8_t dutyCyclePercent)
{
assert(chnlNumber < FSL_FEATURE_TPM_CHANNEL_COUNTn(base));
uint16_t cnv, mod;
mod = base->MOD;
#if defined(FSL_FEATURE_TPM_HAS_COMBINE) && FSL_FEATURE_TPM_HAS_COMBINE
if (currentPwmMode == kTPM_CombinedPwm)
{
uint16_t cnvFirstEdge;
/* This check is added for combined mode as the channel number should be the pair number */
if (chnlNumber >= (FSL_FEATURE_TPM_CHANNEL_COUNTn(base) / 2))
{
return;
}
cnv = (mod * dutyCyclePercent) / 100;
cnvFirstEdge = base->CONTROLS[chnlNumber * 2].CnV;
/* For 100% duty cycle */
if (cnv >= mod)
{
cnv = mod + 1;
}
base->CONTROLS[(chnlNumber * 2) + 1].CnV = cnvFirstEdge + cnv;
}
else
{
#endif
cnv = (mod * dutyCyclePercent) / 100;
/* For 100% duty cycle */
if (cnv >= mod)
{
cnv = mod + 1;
}
base->CONTROLS[chnlNumber].CnV = cnv;
#if defined(FSL_FEATURE_TPM_HAS_COMBINE) && FSL_FEATURE_TPM_HAS_COMBINE
}
#endif
}
void TPM_UpdateChnlEdgeLevelSelect(TPM_Type *base, tpm_chnl_t chnlNumber, uint8_t level)
{
assert(chnlNumber < FSL_FEATURE_TPM_CHANNEL_COUNTn(base));
uint32_t reg = base->CONTROLS[chnlNumber].CnSC & ~(TPM_CnSC_CHF_MASK);
/* When switching mode, disable channel first */
base->CONTROLS[chnlNumber].CnSC &=
~(TPM_CnSC_MSA_MASK | TPM_CnSC_MSB_MASK | TPM_CnSC_ELSA_MASK | TPM_CnSC_ELSB_MASK);
/* Wait till mode change to disable channel is acknowledged */
while ((base->CONTROLS[chnlNumber].CnSC &
(TPM_CnSC_MSA_MASK | TPM_CnSC_MSB_MASK | TPM_CnSC_ELSA_MASK | TPM_CnSC_ELSB_MASK)))
{
}
/* Clear the field and write the new level value */
reg &= ~(TPM_CnSC_ELSA_MASK | TPM_CnSC_ELSB_MASK);
reg |= ((uint32_t)level << TPM_CnSC_ELSA_SHIFT) & (TPM_CnSC_ELSA_MASK | TPM_CnSC_ELSB_MASK);
base->CONTROLS[chnlNumber].CnSC = reg;
/* Wait till mode change is acknowledged */
reg &= (TPM_CnSC_MSA_MASK | TPM_CnSC_MSB_MASK | TPM_CnSC_ELSA_MASK | TPM_CnSC_ELSB_MASK);
while (reg != (base->CONTROLS[chnlNumber].CnSC &
(TPM_CnSC_MSA_MASK | TPM_CnSC_MSB_MASK | TPM_CnSC_ELSA_MASK | TPM_CnSC_ELSB_MASK)))
{
}
}
void TPM_SetupInputCapture(TPM_Type *base, tpm_chnl_t chnlNumber, tpm_input_capture_edge_t captureMode)
{
assert(chnlNumber < FSL_FEATURE_TPM_CHANNEL_COUNTn(base));
#if defined(FSL_FEATURE_TPM_HAS_QDCTRL) && FSL_FEATURE_TPM_HAS_QDCTRL
/* Clear quadrature Decoder mode for channel 0 or 1*/
if (chnlNumber == 0 || chnlNumber == 1)
{
base->QDCTRL &= ~TPM_QDCTRL_QUADEN_MASK;
}
#endif
#if defined(FSL_FEATURE_TPM_HAS_COMBINE) && FSL_FEATURE_TPM_HAS_COMBINE
/* Clear the combine bit for chnlNumber */
base->COMBINE &= ~(1U << TPM_COMBINE_COMBINE1_SHIFT *(chnlNumber/2));
#endif
/* When switching mode, disable channel first */
base->CONTROLS[chnlNumber].CnSC &=
~(TPM_CnSC_MSA_MASK | TPM_CnSC_MSB_MASK | TPM_CnSC_ELSA_MASK | TPM_CnSC_ELSB_MASK);
/* Wait till mode change to disable channel is acknowledged */
while ((base->CONTROLS[chnlNumber].CnSC &
(TPM_CnSC_MSA_MASK | TPM_CnSC_MSB_MASK | TPM_CnSC_ELSA_MASK | TPM_CnSC_ELSB_MASK)))
{
}
/* Set the requested input capture mode */
base->CONTROLS[chnlNumber].CnSC |= captureMode;
/* Wait till mode change is acknowledged */
while (!(base->CONTROLS[chnlNumber].CnSC &
(TPM_CnSC_MSA_MASK | TPM_CnSC_MSB_MASK | TPM_CnSC_ELSA_MASK | TPM_CnSC_ELSB_MASK)))
{
}
}
void TPM_SetupOutputCompare(TPM_Type *base,
tpm_chnl_t chnlNumber,
tpm_output_compare_mode_t compareMode,
uint32_t compareValue)
{
assert(chnlNumber < FSL_FEATURE_TPM_CHANNEL_COUNTn(base));
#if defined(FSL_FEATURE_TPM_HAS_QDCTRL) && FSL_FEATURE_TPM_HAS_QDCTRL
/* Clear quadrature Decoder mode for channel 0 or 1 */
if (chnlNumber == 0 || chnlNumber == 1)
{
base->QDCTRL &= ~TPM_QDCTRL_QUADEN_MASK;
}
#endif
/* When switching mode, disable channel first */
base->CONTROLS[chnlNumber].CnSC &=
~(TPM_CnSC_MSA_MASK | TPM_CnSC_MSB_MASK | TPM_CnSC_ELSA_MASK | TPM_CnSC_ELSB_MASK);
/* Wait till mode change to disable channel is acknowledged */
while ((base->CONTROLS[chnlNumber].CnSC &
(TPM_CnSC_MSA_MASK | TPM_CnSC_MSB_MASK | TPM_CnSC_ELSA_MASK | TPM_CnSC_ELSB_MASK)))
{
}
/* Setup the channel output behaviour when a match occurs with the compare value */
base->CONTROLS[chnlNumber].CnSC |= compareMode;
/* Setup the compare value */
base->CONTROLS[chnlNumber].CnV = compareValue;
/* Wait till mode change is acknowledged */
while (!(base->CONTROLS[chnlNumber].CnSC &
(TPM_CnSC_MSA_MASK | TPM_CnSC_MSB_MASK | TPM_CnSC_ELSA_MASK | TPM_CnSC_ELSB_MASK)))
{
}
}
#if defined(FSL_FEATURE_TPM_HAS_COMBINE) && FSL_FEATURE_TPM_HAS_COMBINE
void TPM_SetupDualEdgeCapture(TPM_Type *base,
tpm_chnl_t chnlPairNumber,
const tpm_dual_edge_capture_param_t *edgeParam,
uint32_t filterValue)
{
assert(edgeParam);
assert(chnlPairNumber < FSL_FEATURE_TPM_CHANNEL_COUNTn(base)/2);
uint32_t reg;
/* Clear quadrature Decoder mode for channel 0 or 1*/
#if defined(FSL_FEATURE_TPM_HAS_QDCTRL) && FSL_FEATURE_TPM_HAS_QDCTRL
if (chnlPairNumber == 0)
{
base->QDCTRL &= ~TPM_QDCTRL_QUADEN_MASK;
}
#endif
/* Unlock: When switching mode, disable channel first */
base->CONTROLS[chnlPairNumber * 2].CnSC &=
~(TPM_CnSC_MSA_MASK | TPM_CnSC_MSB_MASK | TPM_CnSC_ELSA_MASK | TPM_CnSC_ELSB_MASK);
/* Wait till mode change to disable channel is acknowledged */
while ((base->CONTROLS[chnlPairNumber * 2].CnSC &
(TPM_CnSC_MSA_MASK | TPM_CnSC_MSB_MASK | TPM_CnSC_ELSA_MASK | TPM_CnSC_ELSB_MASK)))
{
}
base->CONTROLS[chnlPairNumber * 2 + 1].CnSC &=
~(TPM_CnSC_MSA_MASK | TPM_CnSC_MSB_MASK | TPM_CnSC_ELSA_MASK | TPM_CnSC_ELSB_MASK);
/* Wait till mode change to disable channel is acknowledged */
while ((base->CONTROLS[chnlPairNumber * 2 + 1].CnSC &
(TPM_CnSC_MSA_MASK | TPM_CnSC_MSB_MASK | TPM_CnSC_ELSA_MASK | TPM_CnSC_ELSB_MASK)))
{
}
/* Now, the registers for input mode can be operated. */
if (edgeParam->enableSwap)
{
/* Set the combine and swap bits for the channel pair */
base->COMBINE |= (TPM_COMBINE_COMBINE0_MASK | TPM_COMBINE_COMSWAP0_MASK)
<< (TPM_COMBINE_SHIFT * chnlPairNumber);
/* Input filter setup for channel n+1 input */
reg = base->FILTER;
reg &= ~(TPM_FILTER_CH0FVAL_MASK << (TPM_FILTER_CH1FVAL_SHIFT * (chnlPairNumber + 1)));
reg |= (filterValue << (TPM_FILTER_CH1FVAL_SHIFT * (chnlPairNumber + 1)));
base->FILTER = reg;
}
else
{
reg = base->COMBINE;
/* Clear the swap bit for the channel pair */
reg &= ~(TPM_COMBINE_COMSWAP0_MASK << (TPM_COMBINE_COMSWAP0_SHIFT * chnlPairNumber));
/* Set the combine bit for the channel pair */
reg |= TPM_COMBINE_COMBINE0_MASK << (TPM_COMBINE_SHIFT * chnlPairNumber);
base->COMBINE = reg;
/* Input filter setup for channel n input */
reg = base->FILTER;
reg &= ~(TPM_FILTER_CH0FVAL_MASK << (TPM_FILTER_CH1FVAL_SHIFT * chnlPairNumber));
reg |= (filterValue << (TPM_FILTER_CH1FVAL_SHIFT * chnlPairNumber));
base->FILTER = reg;
}
/* Setup the edge detection from channel n */
base->CONTROLS[chnlPairNumber * 2].CnSC |= edgeParam->currChanEdgeMode;
/* Wait till mode change is acknowledged */
while (!(base->CONTROLS[chnlPairNumber * 2].CnSC &
(TPM_CnSC_MSA_MASK | TPM_CnSC_MSB_MASK | TPM_CnSC_ELSA_MASK | TPM_CnSC_ELSB_MASK)))
{
}
/* Setup the edge detection from channel n+1 */
base->CONTROLS[(chnlPairNumber * 2) + 1].CnSC |= edgeParam->nextChanEdgeMode;
/* Wait till mode change is acknowledged */
while (!(base->CONTROLS[(chnlPairNumber * 2) + 1].CnSC &
(TPM_CnSC_MSA_MASK | TPM_CnSC_MSB_MASK | TPM_CnSC_ELSA_MASK | TPM_CnSC_ELSB_MASK)))
{
}
}
#endif
#if defined(FSL_FEATURE_TPM_HAS_QDCTRL) && FSL_FEATURE_TPM_HAS_QDCTRL
void TPM_SetupQuadDecode(TPM_Type *base,
const tpm_phase_params_t *phaseAParams,
const tpm_phase_params_t *phaseBParams,
tpm_quad_decode_mode_t quadMode)
{
assert(phaseAParams);
assert(phaseBParams);
base->CONTROLS[0].CnSC &=
~(TPM_CnSC_MSA_MASK | TPM_CnSC_MSB_MASK | TPM_CnSC_ELSA_MASK | TPM_CnSC_ELSB_MASK);
/* Wait till mode change to disable channel is acknowledged */
while ((base->CONTROLS[0].CnSC &
(TPM_CnSC_MSA_MASK | TPM_CnSC_MSB_MASK | TPM_CnSC_ELSA_MASK | TPM_CnSC_ELSB_MASK)))
{
}
uint32_t reg;
/* Set Phase A filter value */
reg = base->FILTER;
reg &= ~(TPM_FILTER_CH0FVAL_MASK);
reg |= TPM_FILTER_CH0FVAL(phaseAParams->phaseFilterVal);
base->FILTER = reg;
#if defined(FSL_FEATURE_TPM_HAS_POL) && FSL_FEATURE_TPM_HAS_POL
/* Set Phase A polarity */
if (phaseAParams->phasePolarity)
{
base->POL |= TPM_POL_POL0_MASK;
}
else
{
base->POL &= ~TPM_POL_POL0_MASK;
}
#endif
base->CONTROLS[1].CnSC &=
~(TPM_CnSC_MSA_MASK | TPM_CnSC_MSB_MASK | TPM_CnSC_ELSA_MASK | TPM_CnSC_ELSB_MASK);
/* Wait till mode change to disable channel is acknowledged */
while ((base->CONTROLS[1].CnSC &
(TPM_CnSC_MSA_MASK | TPM_CnSC_MSB_MASK | TPM_CnSC_ELSA_MASK | TPM_CnSC_ELSB_MASK)))
{
}
/* Set Phase B filter value */
reg = base->FILTER;
reg &= ~(TPM_FILTER_CH1FVAL_MASK);
reg |= TPM_FILTER_CH1FVAL(phaseBParams->phaseFilterVal);
base->FILTER = reg;
#if defined(FSL_FEATURE_TPM_HAS_POL) && FSL_FEATURE_TPM_HAS_POL
/* Set Phase B polarity */
if (phaseBParams->phasePolarity)
{
base->POL |= TPM_POL_POL1_MASK;
}
else
{
base->POL &= ~TPM_POL_POL1_MASK;
}
#endif
/* Set Quadrature mode */
reg = base->QDCTRL;
reg &= ~(TPM_QDCTRL_QUADMODE_MASK);
reg |= TPM_QDCTRL_QUADMODE(quadMode);
base->QDCTRL = reg;
/* Enable Quad decode */
base->QDCTRL |= TPM_QDCTRL_QUADEN_MASK;
}
#endif
void TPM_EnableInterrupts(TPM_Type *base, uint32_t mask)
{
uint32_t chnlInterrupts = (mask & 0xFF);
uint8_t chnlNumber = 0;
/* Enable the timer overflow interrupt */
if (mask & kTPM_TimeOverflowInterruptEnable)
{
base->SC |= TPM_SC_TOIE_MASK;
}
/* Enable the channel interrupts */
while (chnlInterrupts)
{
if (chnlInterrupts & 0x1)
{
base->CONTROLS[chnlNumber].CnSC |= TPM_CnSC_CHIE_MASK;
}
chnlNumber++;
chnlInterrupts = chnlInterrupts >> 1U;
}
}
void TPM_DisableInterrupts(TPM_Type *base, uint32_t mask)
{
uint32_t chnlInterrupts = (mask & 0xFF);
uint8_t chnlNumber = 0;
/* Disable the timer overflow interrupt */
if (mask & kTPM_TimeOverflowInterruptEnable)
{
base->SC &= ~TPM_SC_TOIE_MASK;
}
/* Disable the channel interrupts */
while (chnlInterrupts)
{
if (chnlInterrupts & 0x1)
{
base->CONTROLS[chnlNumber].CnSC &= ~TPM_CnSC_CHIE_MASK;
}
chnlNumber++;
chnlInterrupts = chnlInterrupts >> 1U;
}
}
uint32_t TPM_GetEnabledInterrupts(TPM_Type *base)
{
uint32_t enabledInterrupts = 0;
int8_t chnlCount = FSL_FEATURE_TPM_CHANNEL_COUNTn(base);
/* The CHANNEL_COUNT macro returns -1 if it cannot match the TPM instance */
assert(chnlCount != -1);
/* Check if timer overflow interrupt is enabled */
if (base->SC & TPM_SC_TOIE_MASK)
{
enabledInterrupts |= kTPM_TimeOverflowInterruptEnable;
}
/* Check if the channel interrupts are enabled */
while (chnlCount > 0)
{
chnlCount--;
if (base->CONTROLS[chnlCount].CnSC & TPM_CnSC_CHIE_MASK)
{
enabledInterrupts |= (1U << chnlCount);
}
}
return enabledInterrupts;
}

View File

@ -0,0 +1,589 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _FSL_TPM_H_
#define _FSL_TPM_H_
#include "fsl_common.h"
/*!
* @addtogroup tpm
* @{
*/
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @name Driver version */
/*@{*/
#define FSL_TPM_DRIVER_VERSION (MAKE_VERSION(2, 0, 2)) /*!< Version 2.0.2 */
/*@}*/
/*!
* @brief List of TPM channels.
* @note Actual number of available channels is SoC dependent
*/
typedef enum _tpm_chnl
{
kTPM_Chnl_0 = 0U, /*!< TPM channel number 0*/
kTPM_Chnl_1, /*!< TPM channel number 1 */
kTPM_Chnl_2, /*!< TPM channel number 2 */
kTPM_Chnl_3, /*!< TPM channel number 3 */
kTPM_Chnl_4, /*!< TPM channel number 4 */
kTPM_Chnl_5, /*!< TPM channel number 5 */
kTPM_Chnl_6, /*!< TPM channel number 6 */
kTPM_Chnl_7 /*!< TPM channel number 7 */
} tpm_chnl_t;
/*! @brief TPM PWM operation modes */
typedef enum _tpm_pwm_mode
{
kTPM_EdgeAlignedPwm = 0U, /*!< Edge aligned PWM */
kTPM_CenterAlignedPwm, /*!< Center aligned PWM */
#if defined(FSL_FEATURE_TPM_HAS_COMBINE) && FSL_FEATURE_TPM_HAS_COMBINE
kTPM_CombinedPwm /*!< Combined PWM */
#endif
} tpm_pwm_mode_t;
/*! @brief TPM PWM output pulse mode: high-true, low-true or no output */
typedef enum _tpm_pwm_level_select
{
kTPM_NoPwmSignal = 0U, /*!< No PWM output on pin */
kTPM_LowTrue, /*!< Low true pulses */
kTPM_HighTrue /*!< High true pulses */
} tpm_pwm_level_select_t;
/*! @brief Options to configure a TPM channel's PWM signal */
typedef struct _tpm_chnl_pwm_signal_param
{
tpm_chnl_t chnlNumber; /*!< TPM channel to configure.
In combined mode (available in some SoC's, this represents the
channel pair number */
tpm_pwm_level_select_t level; /*!< PWM output active level select */
uint8_t dutyCyclePercent; /*!< PWM pulse width, value should be between 0 to 100
0=inactive signal(0% duty cycle)...
100=always active signal (100% duty cycle)*/
#if defined(FSL_FEATURE_TPM_HAS_COMBINE) && FSL_FEATURE_TPM_HAS_COMBINE
uint8_t firstEdgeDelayPercent; /*!< Used only in combined PWM mode to generate asymmetrical PWM.
Specifies the delay to the first edge in a PWM period.
If unsure, leave as 0; Should be specified as
percentage of the PWM period */
#endif
} tpm_chnl_pwm_signal_param_t;
/*!
* @brief Trigger options available.
*
* This is used for both internal & external trigger sources (external option available in certain SoC's)
*
* @note The actual trigger options available is SoC-specific.
*/
typedef enum _tpm_trigger_select
{
kTPM_Trigger_Select_0 = 0U,
kTPM_Trigger_Select_1,
kTPM_Trigger_Select_2,
kTPM_Trigger_Select_3,
kTPM_Trigger_Select_4,
kTPM_Trigger_Select_5,
kTPM_Trigger_Select_6,
kTPM_Trigger_Select_7,
kTPM_Trigger_Select_8,
kTPM_Trigger_Select_9,
kTPM_Trigger_Select_10,
kTPM_Trigger_Select_11,
kTPM_Trigger_Select_12,
kTPM_Trigger_Select_13,
kTPM_Trigger_Select_14,
kTPM_Trigger_Select_15
} tpm_trigger_select_t;
#if defined(FSL_FEATURE_TPM_HAS_EXTERNAL_TRIGGER_SELECTION) && FSL_FEATURE_TPM_HAS_EXTERNAL_TRIGGER_SELECTION
/*!
* @brief Trigger source options available
*
* @note This selection is available only on some SoC's. For SoC's without this selection, the only
* trigger source available is internal triger.
*/
typedef enum _tpm_trigger_source
{
kTPM_TriggerSource_External = 0U, /*!< Use external trigger input */
kTPM_TriggerSource_Internal /*!< Use internal trigger */
} tpm_trigger_source_t;
#endif
/*! @brief TPM output compare modes */
typedef enum _tpm_output_compare_mode
{
kTPM_NoOutputSignal = (1U << TPM_CnSC_MSA_SHIFT), /*!< No channel output when counter reaches CnV */
kTPM_ToggleOnMatch = ((1U << TPM_CnSC_MSA_SHIFT) | (1U << TPM_CnSC_ELSA_SHIFT)), /*!< Toggle output */
kTPM_ClearOnMatch = ((1U << TPM_CnSC_MSA_SHIFT) | (2U << TPM_CnSC_ELSA_SHIFT)), /*!< Clear output */
kTPM_SetOnMatch = ((1U << TPM_CnSC_MSA_SHIFT) | (3U << TPM_CnSC_ELSA_SHIFT)), /*!< Set output */
kTPM_HighPulseOutput = ((3U << TPM_CnSC_MSA_SHIFT) | (1U << TPM_CnSC_ELSA_SHIFT)), /*!< Pulse output high */
kTPM_LowPulseOutput = ((3U << TPM_CnSC_MSA_SHIFT) | (2U << TPM_CnSC_ELSA_SHIFT)) /*!< Pulse output low */
} tpm_output_compare_mode_t;
/*! @brief TPM input capture edge */
typedef enum _tpm_input_capture_edge
{
kTPM_RisingEdge = (1U << TPM_CnSC_ELSA_SHIFT), /*!< Capture on rising edge only */
kTPM_FallingEdge = (2U << TPM_CnSC_ELSA_SHIFT), /*!< Capture on falling edge only */
kTPM_RiseAndFallEdge = (3U << TPM_CnSC_ELSA_SHIFT) /*!< Capture on rising or falling edge */
} tpm_input_capture_edge_t;
#if defined(FSL_FEATURE_TPM_HAS_COMBINE) && FSL_FEATURE_TPM_HAS_COMBINE
/*!
* @brief TPM dual edge capture parameters
*
* @note This mode is available only on some SoC's.
*/
typedef struct _tpm_dual_edge_capture_param
{
bool enableSwap; /*!< true: Use channel n+1 input, channel n input is ignored;
false: Use channel n input, channel n+1 input is ignored */
tpm_input_capture_edge_t currChanEdgeMode; /*!< Input capture edge select for channel n */
tpm_input_capture_edge_t nextChanEdgeMode; /*!< Input capture edge select for channel n+1 */
} tpm_dual_edge_capture_param_t;
#endif
#if defined(FSL_FEATURE_TPM_HAS_QDCTRL) && FSL_FEATURE_TPM_HAS_QDCTRL
/*!
* @brief TPM quadrature decode modes
*
* @note This mode is available only on some SoC's.
*/
typedef enum _tpm_quad_decode_mode
{
kTPM_QuadPhaseEncode = 0U, /*!< Phase A and Phase B encoding mode */
kTPM_QuadCountAndDir /*!< Count and direction encoding mode */
} tpm_quad_decode_mode_t;
/*! @brief TPM quadrature phase polarities */
typedef enum _tpm_phase_polarity
{
kTPM_QuadPhaseNormal = 0U, /*!< Phase input signal is not inverted */
kTPM_QuadPhaseInvert /*!< Phase input signal is inverted */
} tpm_phase_polarity_t;
/*! @brief TPM quadrature decode phase parameters */
typedef struct _tpm_phase_param
{
uint32_t phaseFilterVal; /*!< Filter value, filter is disabled when the value is zero */
tpm_phase_polarity_t phasePolarity; /*!< Phase polarity */
} tpm_phase_params_t;
#endif
/*! @brief TPM clock source selection*/
typedef enum _tpm_clock_source
{
kTPM_SystemClock = 1U, /*!< System clock */
kTPM_ExternalClock /*!< External clock */
} tpm_clock_source_t;
/*! @brief TPM prescale value selection for the clock source*/
typedef enum _tpm_clock_prescale
{
kTPM_Prescale_Divide_1 = 0U, /*!< Divide by 1 */
kTPM_Prescale_Divide_2, /*!< Divide by 2 */
kTPM_Prescale_Divide_4, /*!< Divide by 4 */
kTPM_Prescale_Divide_8, /*!< Divide by 8 */
kTPM_Prescale_Divide_16, /*!< Divide by 16 */
kTPM_Prescale_Divide_32, /*!< Divide by 32 */
kTPM_Prescale_Divide_64, /*!< Divide by 64 */
kTPM_Prescale_Divide_128 /*!< Divide by 128 */
} tpm_clock_prescale_t;
/*!
* @brief TPM config structure
*
* This structure holds the configuration settings for the TPM peripheral. To initialize this
* structure to reasonable defaults, call the TPM_GetDefaultConfig() function and pass a
* pointer to your config structure instance.
*
* The config struct can be made const so it resides in flash
*/
typedef struct _tpm_config
{
tpm_clock_prescale_t prescale; /*!< Select TPM clock prescale value */
bool useGlobalTimeBase; /*!< true: Use of an external global time base is enabled;
false: disabled */
tpm_trigger_select_t triggerSelect; /*!< Input trigger to use for controlling the counter operation */
#if defined(FSL_FEATURE_TPM_HAS_EXTERNAL_TRIGGER_SELECTION) && FSL_FEATURE_TPM_HAS_EXTERNAL_TRIGGER_SELECTION
tpm_trigger_source_t triggerSource; /*!< Decides if we use external or internal trigger. */
#endif
bool enableDoze; /*!< true: TPM counter is paused in doze mode;
false: TPM counter continues in doze mode */
bool enableDebugMode; /*!< true: TPM counter continues in debug mode;
false: TPM counter is paused in debug mode */
bool enableReloadOnTrigger; /*!< true: TPM counter is reloaded on trigger;
false: TPM counter not reloaded */
bool enableStopOnOverflow; /*!< true: TPM counter stops after overflow;
false: TPM counter continues running after overflow */
bool enableStartOnTrigger; /*!< true: TPM counter only starts when a trigger is detected;
false: TPM counter starts immediately */
#if defined(FSL_FEATURE_TPM_HAS_PAUSE_COUNTER_ON_TRIGGER) && FSL_FEATURE_TPM_HAS_PAUSE_COUNTER_ON_TRIGGER
bool enablePauseOnTrigger; /*!< true: TPM counter will pause while trigger remains asserted;
false: TPM counter continues running */
#endif
} tpm_config_t;
/*! @brief List of TPM interrupts */
typedef enum _tpm_interrupt_enable
{
kTPM_Chnl0InterruptEnable = (1U << 0), /*!< Channel 0 interrupt.*/
kTPM_Chnl1InterruptEnable = (1U << 1), /*!< Channel 1 interrupt.*/
kTPM_Chnl2InterruptEnable = (1U << 2), /*!< Channel 2 interrupt.*/
kTPM_Chnl3InterruptEnable = (1U << 3), /*!< Channel 3 interrupt.*/
kTPM_Chnl4InterruptEnable = (1U << 4), /*!< Channel 4 interrupt.*/
kTPM_Chnl5InterruptEnable = (1U << 5), /*!< Channel 5 interrupt.*/
kTPM_Chnl6InterruptEnable = (1U << 6), /*!< Channel 6 interrupt.*/
kTPM_Chnl7InterruptEnable = (1U << 7), /*!< Channel 7 interrupt.*/
kTPM_TimeOverflowInterruptEnable = (1U << 8) /*!< Time overflow interrupt.*/
} tpm_interrupt_enable_t;
/*! @brief List of TPM flags */
typedef enum _tpm_status_flags
{
kTPM_Chnl0Flag = (1U << 0), /*!< Channel 0 flag */
kTPM_Chnl1Flag = (1U << 1), /*!< Channel 1 flag */
kTPM_Chnl2Flag = (1U << 2), /*!< Channel 2 flag */
kTPM_Chnl3Flag = (1U << 3), /*!< Channel 3 flag */
kTPM_Chnl4Flag = (1U << 4), /*!< Channel 4 flag */
kTPM_Chnl5Flag = (1U << 5), /*!< Channel 5 flag */
kTPM_Chnl6Flag = (1U << 6), /*!< Channel 6 flag */
kTPM_Chnl7Flag = (1U << 7), /*!< Channel 7 flag */
kTPM_TimeOverflowFlag = (1U << 8) /*!< Time overflow flag */
} tpm_status_flags_t;
/*******************************************************************************
* API
******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif
/*!
* @name Initialization and deinitialization
* @{
*/
/*!
* @brief Ungates the TPM clock and configures the peripheral for basic operation.
*
* @note This API should be called at the beginning of the application using the TPM driver.
*
* @param base TPM peripheral base address
* @param config Pointer to user's TPM config structure.
*/
void TPM_Init(TPM_Type *base, const tpm_config_t *config);
/*!
* @brief Stops the counter and gates the TPM clock
*
* @param base TPM peripheral base address
*/
void TPM_Deinit(TPM_Type *base);
/*!
* @brief Fill in the TPM config struct with the default settings
*
* The default values are:
* @code
* config->prescale = kTPM_Prescale_Divide_1;
* config->useGlobalTimeBase = false;
* config->dozeEnable = false;
* config->dbgMode = false;
* config->enableReloadOnTrigger = false;
* config->enableStopOnOverflow = false;
* config->enableStartOnTrigger = false;
*#if FSL_FEATURE_TPM_HAS_PAUSE_COUNTER_ON_TRIGGER
* config->enablePauseOnTrigger = false;
*#endif
* config->triggerSelect = kTPM_Trigger_Select_0;
*#if FSL_FEATURE_TPM_HAS_EXTERNAL_TRIGGER_SELECTION
* config->triggerSource = kTPM_TriggerSource_External;
*#endif
* @endcode
* @param config Pointer to user's TPM config structure.
*/
void TPM_GetDefaultConfig(tpm_config_t *config);
/*! @}*/
/*!
* @name Channel mode operations
* @{
*/
/*!
* @brief Configures the PWM signal parameters
*
* User calls this function to configure the PWM signals period, mode, dutycycle and edge. Use this
* function to configure all the TPM channels that will be used to output a PWM signal
*
* @param base TPM peripheral base address
* @param chnlParams Array of PWM channel parameters to configure the channel(s)
* @param numOfChnls Number of channels to configure, this should be the size of the array passed in
* @param mode PWM operation mode, options available in enumeration ::tpm_pwm_mode_t
* @param pwmFreq_Hz PWM signal frequency in Hz
* @param srcClock_Hz TPM counter clock in Hz
*
* @return kStatus_Success if the PWM setup was successful,
* kStatus_Error on failure
*/
status_t TPM_SetupPwm(TPM_Type *base,
const tpm_chnl_pwm_signal_param_t *chnlParams,
uint8_t numOfChnls,
tpm_pwm_mode_t mode,
uint32_t pwmFreq_Hz,
uint32_t srcClock_Hz);
/*!
* @brief Update the duty cycle of an active PWM signal
*
* @param base TPM peripheral base address
* @param chnlNumber The channel number. In combined mode, this represents
* the channel pair number
* @param currentPwmMode The current PWM mode set during PWM setup
* @param dutyCyclePercent New PWM pulse width, value should be between 0 to 100
* 0=inactive signal(0% duty cycle)...
* 100=active signal (100% duty cycle)
*/
void TPM_UpdatePwmDutycycle(TPM_Type *base,
tpm_chnl_t chnlNumber,
tpm_pwm_mode_t currentPwmMode,
uint8_t dutyCyclePercent);
/*!
* @brief Update the edge level selection for a channel
*
* @param base TPM peripheral base address
* @param chnlNumber The channel number
* @param level The level to be set to the ELSnB:ELSnA field; valid values are 00, 01, 10, 11.
* See the appropriate SoC reference manual for details about this field.
*/
void TPM_UpdateChnlEdgeLevelSelect(TPM_Type *base, tpm_chnl_t chnlNumber, uint8_t level);
/*!
* @brief Enables capturing an input signal on the channel using the function parameters.
*
* When the edge specified in the captureMode argument occurs on the channel, the TPM counter is captured into
* the CnV register. The user has to read the CnV register separately to get this value.
*
* @param base TPM peripheral base address
* @param chnlNumber The channel number
* @param captureMode Specifies which edge to capture
*/
void TPM_SetupInputCapture(TPM_Type *base, tpm_chnl_t chnlNumber, tpm_input_capture_edge_t captureMode);
/*!
* @brief Configures the TPM to generate timed pulses.
*
* When the TPM counter matches the value of compareVal argument (this is written into CnV reg), the channel
* output is changed based on what is specified in the compareMode argument.
*
* @param base TPM peripheral base address
* @param chnlNumber The channel number
* @param compareMode Action to take on the channel output when the compare condition is met
* @param compareValue Value to be programmed in the CnV register.
*/
void TPM_SetupOutputCompare(TPM_Type *base,
tpm_chnl_t chnlNumber,
tpm_output_compare_mode_t compareMode,
uint32_t compareValue);
#if defined(FSL_FEATURE_TPM_HAS_COMBINE) && FSL_FEATURE_TPM_HAS_COMBINE
/*!
* @brief Configures the dual edge capture mode of the TPM.
*
* This function allows to measure a pulse width of the signal on the input of channel of a
* channel pair. The filter function is disabled if the filterVal argument passed is zero.
*
* @param base TPM peripheral base address
* @param chnlPairNumber The TPM channel pair number; options are 0, 1, 2, 3
* @param edgeParam Sets up the dual edge capture function
* @param filterValue Filter value, specify 0 to disable filter.
*/
void TPM_SetupDualEdgeCapture(TPM_Type *base,
tpm_chnl_t chnlPairNumber,
const tpm_dual_edge_capture_param_t *edgeParam,
uint32_t filterValue);
#endif
#if defined(FSL_FEATURE_TPM_HAS_QDCTRL) && FSL_FEATURE_TPM_HAS_QDCTRL
/*!
* @brief Configures the parameters and activates the quadrature decode mode.
*
* @param base TPM peripheral base address
* @param phaseAParams Phase A configuration parameters
* @param phaseBParams Phase B configuration parameters
* @param quadMode Selects encoding mode used in quadrature decoder mode
*/
void TPM_SetupQuadDecode(TPM_Type *base,
const tpm_phase_params_t *phaseAParams,
const tpm_phase_params_t *phaseBParams,
tpm_quad_decode_mode_t quadMode);
#endif
/*! @}*/
/*!
* @name Interrupt Interface
* @{
*/
/*!
* @brief Enables the selected TPM interrupts.
*
* @param base TPM peripheral base address
* @param mask The interrupts to enable. This is a logical OR of members of the
* enumeration ::tpm_interrupt_enable_t
*/
void TPM_EnableInterrupts(TPM_Type *base, uint32_t mask);
/*!
* @brief Disables the selected TPM interrupts.
*
* @param base TPM peripheral base address
* @param mask The interrupts to disable. This is a logical OR of members of the
* enumeration ::tpm_interrupt_enable_t
*/
void TPM_DisableInterrupts(TPM_Type *base, uint32_t mask);
/*!
* @brief Gets the enabled TPM interrupts.
*
* @param base TPM peripheral base address
*
* @return The enabled interrupts. This is the logical OR of members of the
* enumeration ::tpm_interrupt_enable_t
*/
uint32_t TPM_GetEnabledInterrupts(TPM_Type *base);
/*! @}*/
/*!
* @name Status Interface
* @{
*/
/*!
* @brief Gets the TPM status flags
*
* @param base TPM peripheral base address
*
* @return The status flags. This is the logical OR of members of the
* enumeration ::tpm_status_flags_t
*/
static inline uint32_t TPM_GetStatusFlags(TPM_Type *base)
{
return base->STATUS;
}
/*!
* @brief Clears the TPM status flags
*
* @param base TPM peripheral base address
* @param mask The status flags to clear. This is a logical OR of members of the
* enumeration ::tpm_status_flags_t
*/
static inline void TPM_ClearStatusFlags(TPM_Type *base, uint32_t mask)
{
/* Clear the status flags */
base->STATUS = mask;
}
/*! @}*/
/*!
* @name Timer Start and Stop
* @{
*/
/*!
* @brief Starts the TPM counter.
*
*
* @param base TPM peripheral base address
* @param clockSource TPM clock source; once clock source is set the counter will start running
*/
static inline void TPM_StartTimer(TPM_Type *base, tpm_clock_source_t clockSource)
{
uint32_t reg = base->SC;
reg &= ~(TPM_SC_CMOD_MASK);
reg |= TPM_SC_CMOD(clockSource);
base->SC = reg;
}
/*!
* @brief Stops the TPM counter.
*
* @param base TPM peripheral base address
*/
static inline void TPM_StopTimer(TPM_Type *base)
{
/* Set clock source to none to disable counter */
base->SC &= ~(TPM_SC_CMOD_MASK);
/* Wait till this reads as zero acknowledging the counter is disabled */
while (base->SC & TPM_SC_CMOD_MASK)
{
}
}
/*! @}*/
#if defined(FSL_FEATURE_TPM_HAS_GLOBAL) && FSL_FEATURE_TPM_HAS_GLOBAL
/*!
* @brief Performs a software reset on the TPM module.
*
* Reset all internal logic and registers, except the Global Register. Remains set until cleared by software..
*
* @note TPM software reset is available on certain SoC's only
*
* @param base TPM peripheral base address
*/
static inline void TPM_Reset(TPM_Type *base)
{
base->GLOBAL |= TPM_GLOBAL_RST_MASK;
base->GLOBAL &= ~TPM_GLOBAL_RST_MASK;
}
#endif
#if defined(__cplusplus)
}
#endif
/*! @}*/
#endif /* _FSL_TPM_H_ */

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,239 @@
/*
* Copyright (c) 2015-2016, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _FSL_TRNG_DRIVER_H_
#define _FSL_TRNG_DRIVER_H_
#include "fsl_common.h"
#if defined(FSL_FEATURE_SOC_TRNG_COUNT) && FSL_FEATURE_SOC_TRNG_COUNT
/*!
* @addtogroup trng_driver
* @{
*/
/*******************************************************************************
* Definitions
*******************************************************************************/
/*! @name Driver version */
/*@{*/
/*! @brief TRNG driver version 2.0.1.
*
* Current version: 2.0.1
*
* Change log:
* - Version 2.0.1
* - add support for KL8x and KL28Z
* - update default OSCDIV for K81 to divide by 2
*/
#define FSL_TRNG_DRIVER_VERSION (MAKE_VERSION(2, 0, 1))
/*@}*/
/*! @brief TRNG sample mode. Used by trng_config_t. */
typedef enum _trng_sample_mode
{
kTRNG_SampleModeVonNeumann = 0U, /*!< Use von Neumann data in both Entropy shifter and Statistical Checker. */
kTRNG_SampleModeRaw = 1U, /*!< Use raw data into both Entropy shifter and Statistical Checker. */
kTRNG_SampleModeVonNeumannRaw =
2U /*!< Use von Neumann data in Entropy shifter. Use raw data into Statistical Checker. */
} trng_sample_mode_t;
/*! @brief TRNG clock mode. Used by trng_config_t. */
typedef enum _trng_clock_mode
{
kTRNG_ClockModeRingOscillator = 0U, /*!< Ring oscillator is used to operate the TRNG (default). */
kTRNG_ClockModeSystem = 1U /*!< System clock is used to operate the TRNG. This is for test use only, and
indeterminate results may occur. */
} trng_clock_mode_t;
/*! @brief TRNG ring oscillator divide. Used by trng_config_t. */
typedef enum _trng_ring_osc_div
{
kTRNG_RingOscDiv0 = 0U, /*!< Ring oscillator with no divide */
kTRNG_RingOscDiv2 = 1U, /*!< Ring oscillator divided-by-2. */
kTRNG_RingOscDiv4 = 2U, /*!< Ring oscillator divided-by-4. */
kTRNG_RingOscDiv8 = 3U /*!< Ring oscillator divided-by-8. */
} trng_ring_osc_div_t;
/*! @brief Data structure for definition of statistical check limits. Used by trng_config_t. */
typedef struct _trng_statistical_check_limit
{
uint32_t maximum; /*!< Maximum limit.*/
uint32_t minimum; /*!< Minimum limit.*/
} trng_statistical_check_limit_t;
/*!
* @brief Data structure for the TRNG initialization
*
* This structure initializes the TRNG by calling the the TRNG_Init() function.
* It contains all TRNG configurations.
*/
typedef struct _trng_user_config
{
bool lock; /*!< @brief Disable programmability of TRNG registers. */
trng_clock_mode_t clockMode; /*!< @brief Clock mode used to operate TRNG.*/
trng_ring_osc_div_t ringOscDiv; /*!< @brief Ring oscillator divide used by TRNG. */
trng_sample_mode_t sampleMode; /*!< @brief Sample mode of the TRNG ring oscillator. */
/* Seed Control*/
uint16_t
entropyDelay; /*!< @brief Entropy Delay. Defines the length (in system clocks) of each Entropy sample taken. */
uint16_t sampleSize; /*!< @brief Sample Size. Defines the total number of Entropy samples that will be taken during
Entropy generation. */
uint16_t
sparseBitLimit; /*!< @brief Sparse Bit Limit which defines the maximum number of
* consecutive samples that may be discarded before an error is generated.
* This limit is used only for during von Neumann sampling (enabled by TRNG_HAL_SetSampleMode()).
* Samples are discarded if two consecutive raw samples are both 0 or both 1. If
* this discarding occurs for a long period of time, it indicates that there is
* insufficient Entropy. */
/* Statistical Check Parameters.*/
uint8_t retryCount; /*!< @brief Retry count. It defines the number of times a statistical check may fails
* during the TRNG Entropy Generation before generating an error. */
uint8_t longRunMaxLimit; /*!< @brief Largest allowable number of consecutive samples of all 1, or all 0,
* that is allowed during the Entropy generation. */
trng_statistical_check_limit_t
monobitLimit; /*!< @brief Maximum and minimum limits for statistical check of number of ones/zero detected
during entropy generation. */
trng_statistical_check_limit_t
runBit1Limit; /*!< @brief Maximum and minimum limits for statistical check of number of runs of length 1
detected during entropy generation. */
trng_statistical_check_limit_t
runBit2Limit; /*!< @brief Maximum and minimum limits for statistical check of number of runs of length 2
detected during entropy generation. */
trng_statistical_check_limit_t
runBit3Limit; /*!< @brief Maximum and minimum limits for statistical check of number of runs of length 3
detected during entropy generation. */
trng_statistical_check_limit_t
runBit4Limit; /*!< @brief Maximum and minimum limits for statistical check of number of runs of length 4
detected during entropy generation. */
trng_statistical_check_limit_t
runBit5Limit; /*!< @brief Maximum and minimum limits for statistical check of number of runs of length 5
detected during entropy generation. */
trng_statistical_check_limit_t runBit6PlusLimit; /*!< @brief Maximum and minimum limits for statistical check of
number of runs of length 6 or more detected during entropy
generation. */
trng_statistical_check_limit_t
pokerLimit; /*!< @brief Maximum and minimum limits for statistical check of "Poker Test". */
trng_statistical_check_limit_t
frequencyCountLimit; /*!< @brief Maximum and minimum limits for statistical check of entropy sample frequency
count. */
} trng_config_t;
/*******************************************************************************
* API
*******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif
/*!
* @brief Initializes user configuration structure to default.
*
* This function initializes the configure structure to default value. the default
* value are:
* @code
* user_config->lock = 0;
* user_config->clockMode = kTRNG_ClockModeRingOscillator;
* user_config->ringOscDiv = kTRNG_RingOscDiv0; Or to other kTRNG_RingOscDiv[2|8] depending on platform.
* user_config->sampleMode = kTRNG_SampleModeRaw;
* user_config->entropyDelay = 3200;
* user_config->sampleSize = 2500;
* user_config->sparseBitLimit = TRNG_USER_CONFIG_DEFAULT_SPARSE_BIT_LIMIT;
* user_config->retryCount = 63;
* user_config->longRunMaxLimit = 34;
* user_config->monobitLimit.maximum = 1384;
* user_config->monobitLimit.minimum = 1116;
* user_config->runBit1Limit.maximum = 405;
* user_config->runBit1Limit.minimum = 227;
* user_config->runBit2Limit.maximum = 220;
* user_config->runBit2Limit.minimum = 98;
* user_config->runBit3Limit.maximum = 125;
* user_config->runBit3Limit.minimum = 37;
* user_config->runBit4Limit.maximum = 75;
* user_config->runBit4Limit.minimum = 11;
* user_config->runBit5Limit.maximum = 47;
* user_config->runBit5Limit.minimum = 1;
* user_config->runBit6PlusLimit.maximum = 47;
* user_config->runBit6PlusLimit.minimum = 1;
* user_config->pokerLimit.maximum = 26912;
* user_config->pokerLimit.minimum = 24445;
* user_config->frequencyCountLimit.maximum = 25600;
* user_config->frequencyCountLimit.minimum = 1600;
* @endcode
*
* @param user_config User configuration structure.
* @return If successful, returns the kStatus_TRNG_Success. Otherwise, it returns an error.
*/
status_t TRNG_GetDefaultConfig(trng_config_t *userConfig);
/*!
* @brief Initializes the TRNG.
*
* This function initializes the TRNG.
* When called, the TRNG entropy generation starts immediately.
*
* @param base TRNG base address
* @param userConfig Pointer to initialize configuration structure.
* @return If successful, returns the kStatus_TRNG_Success. Otherwise, it returns an error.
*/
status_t TRNG_Init(TRNG_Type *base, const trng_config_t *userConfig);
/*!
* @brief Shuts down the TRNG.
*
* This function shuts down the TRNG.
*
* @param base TRNG base address
*/
void TRNG_Deinit(TRNG_Type *base);
/*!
* @brief Gets random data.
*
* This function gets random data from the TRNG.
*
* @param base TRNG base address
* @param data Pointer address used to store random data
* @param dataSize Size of the buffer pointed by the data parameter
* @return random data
*/
status_t TRNG_GetRandomData(TRNG_Type *base, void *data, size_t dataSize);
#if defined(__cplusplus)
}
#endif
/*! @}*/
#endif /* FSL_FEATURE_SOC_TRNG_COUNT */
#endif /*_FSL_TRNG_H_*/

View File

@ -0,0 +1,190 @@
/*
* Copyright (c) 2014 - 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include "fsl_tsi_v4.h"
void TSI_Init(TSI_Type *base, const tsi_config_t *config)
{
assert(config != NULL);
bool is_module_enabled = false;
bool is_int_enabled = false;
CLOCK_EnableClock(kCLOCK_Tsi0);
if (base->GENCS & TSI_GENCS_TSIEN_MASK)
{
is_module_enabled = true;
TSI_EnableModule(base, false);
}
if (base->GENCS & TSI_GENCS_TSIIEN_MASK)
{
is_int_enabled = true;
TSI_DisableInterrupts(base, kTSI_GlobalInterruptEnable);
}
TSI_SetHighThreshold(base, config->thresh);
TSI_SetLowThreshold(base, config->thresl);
TSI_SetElectrodeOSCPrescaler(base, config->prescaler);
TSI_SetReferenceChargeCurrent(base, config->refchrg);
TSI_SetElectrodeChargeCurrent(base, config->extchrg);
TSI_SetNumberOfScans(base, config->nscn);
TSI_SetAnalogMode(base, config->mode);
TSI_SetOscVoltageRails(base, config->dvolt);
TSI_SetElectrodeSeriesResistor(base, config->resistor);
TSI_SetFilterBits(base, config->filter);
if (is_module_enabled)
{
TSI_EnableModule(base, true);
}
if (is_int_enabled)
{
TSI_EnableInterrupts(base, kTSI_GlobalInterruptEnable);
}
}
void TSI_Deinit(TSI_Type *base)
{
base->GENCS = 0U;
base->DATA = 0U;
base->TSHD = 0U;
CLOCK_DisableClock(kCLOCK_Tsi0);
}
void TSI_GetNormalModeDefaultConfig(tsi_config_t *userConfig)
{
userConfig->thresh = 0U;
userConfig->thresl = 0U;
userConfig->prescaler = kTSI_ElecOscPrescaler_2div;
userConfig->extchrg = kTSI_ExtOscChargeCurrent_4uA;
userConfig->refchrg = kTSI_RefOscChargeCurrent_4uA;
userConfig->nscn = kTSI_ConsecutiveScansNumber_5time;
userConfig->mode = kTSI_AnalogModeSel_Capacitive;
userConfig->dvolt = kTSI_OscVolRailsOption_0;
userConfig->resistor = kTSI_SeriesResistance_32k;
userConfig->filter = kTSI_FilterBits_3;
}
void TSI_GetLowPowerModeDefaultConfig(tsi_config_t *userConfig)
{
userConfig->thresh = 400U;
userConfig->thresl = 0U;
userConfig->prescaler = kTSI_ElecOscPrescaler_2div;
userConfig->extchrg = kTSI_ExtOscChargeCurrent_4uA;
userConfig->refchrg = kTSI_RefOscChargeCurrent_4uA;
userConfig->nscn = kTSI_ConsecutiveScansNumber_5time;
userConfig->mode = kTSI_AnalogModeSel_Capacitive;
userConfig->dvolt = kTSI_OscVolRailsOption_0;
userConfig->resistor = kTSI_SeriesResistance_32k;
userConfig->filter = kTSI_FilterBits_3;
}
void TSI_Calibrate(TSI_Type *base, tsi_calibration_data_t *calBuff)
{
assert(calBuff != NULL);
uint8_t i = 0U;
bool is_int_enabled = false;
if (base->GENCS & TSI_GENCS_TSIIEN_MASK)
{
is_int_enabled = true;
TSI_DisableInterrupts(base, kTSI_GlobalInterruptEnable);
}
for (i = 0U; i < FSL_FEATURE_TSI_CHANNEL_COUNT; i++)
{
TSI_SetMeasuredChannelNumber(base, i);
TSI_StartSoftwareTrigger(base);
while (!(TSI_GetStatusFlags(base) & kTSI_EndOfScanFlag))
{
}
calBuff->calibratedData[i] = TSI_GetCounter(base);
TSI_ClearStatusFlags(base, kTSI_EndOfScanFlag);
}
if (is_int_enabled)
{
TSI_EnableInterrupts(base, kTSI_GlobalInterruptEnable);
}
}
void TSI_EnableInterrupts(TSI_Type *base, uint32_t mask)
{
uint32_t regValue = base->GENCS & (~ALL_FLAGS_MASK);
if (mask & kTSI_GlobalInterruptEnable)
{
regValue |= TSI_GENCS_TSIIEN_MASK;
}
if (mask & kTSI_OutOfRangeInterruptEnable)
{
regValue &= (~TSI_GENCS_ESOR_MASK);
}
if (mask & kTSI_EndOfScanInterruptEnable)
{
regValue |= TSI_GENCS_ESOR_MASK;
}
base->GENCS = regValue; /* write value to register */
}
void TSI_DisableInterrupts(TSI_Type *base, uint32_t mask)
{
uint32_t regValue = base->GENCS & (~ALL_FLAGS_MASK);
if (mask & kTSI_GlobalInterruptEnable)
{
regValue &= (~TSI_GENCS_TSIIEN_MASK);
}
if (mask & kTSI_OutOfRangeInterruptEnable)
{
regValue |= TSI_GENCS_ESOR_MASK;
}
if (mask & kTSI_EndOfScanInterruptEnable)
{
regValue &= (~TSI_GENCS_ESOR_MASK);
}
base->GENCS = regValue; /* write value to register */
}
void TSI_ClearStatusFlags(TSI_Type *base, uint32_t mask)
{
uint32_t regValue = base->GENCS & (~ALL_FLAGS_MASK);
if (mask & kTSI_EndOfScanFlag)
{
regValue |= TSI_GENCS_EOSF_MASK;
}
if (mask & kTSI_OutOfRangeFlag)
{
regValue |= TSI_GENCS_OUTRGF_MASK;
}
base->GENCS = regValue; /* write value to register */
}

View File

@ -0,0 +1,710 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _FSL_TSI_V4_H_
#define _FSL_TSI_V4_H_
#include "fsl_common.h"
/*!
* @addtogroup tsi_v4_driver
* @{
*/
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @name Driver version */
/*@{*/
/*! @brief TSI driver version */
#define FSL_TSI_DRIVER_VERSION (MAKE_VERSION(2, 1, 2))
/*@}*/
/*! @brief TSI status flags macro collection */
#define ALL_FLAGS_MASK (TSI_GENCS_EOSF_MASK | TSI_GENCS_OUTRGF_MASK)
/*! @brief resistor bit shift in EXTCHRG bit-field */
#define TSI_V4_EXTCHRG_RESISTOR_BIT_SHIFT TSI_GENCS_EXTCHRG_SHIFT
/*! @brief filter bits shift in EXTCHRG bit-field */
#define TSI_V4_EXTCHRG_FILTER_BITS_SHIFT (1U + TSI_GENCS_EXTCHRG_SHIFT)
/*! @brief macro of clearing the resistor bit in EXTCHRG bit-field */
#define TSI_V4_EXTCHRG_RESISTOR_BIT_CLEAR \
((uint32_t)((~(ALL_FLAGS_MASK | TSI_GENCS_EXTCHRG_MASK)) | (3U << TSI_V4_EXTCHRG_FILTER_BITS_SHIFT)))
/*! @brief macro of clearing the filter bits in EXTCHRG bit-field */
#define TSI_V4_EXTCHRG_FILTER_BITS_CLEAR \
((uint32_t)((~(ALL_FLAGS_MASK | TSI_GENCS_EXTCHRG_MASK)) | (1U << TSI_V4_EXTCHRG_RESISTOR_BIT_SHIFT)))
/*!
* @brief TSI number of scan intervals for each electrode.
*
* These constants define the tsi number of consecutive scans in a TSI instance for each electrode.
*/
typedef enum _tsi_n_consecutive_scans
{
kTSI_ConsecutiveScansNumber_1time = 0U, /*!< Once per electrode */
kTSI_ConsecutiveScansNumber_2time = 1U, /*!< Twice per electrode */
kTSI_ConsecutiveScansNumber_3time = 2U, /*!< 3 times consecutive scan */
kTSI_ConsecutiveScansNumber_4time = 3U, /*!< 4 times consecutive scan */
kTSI_ConsecutiveScansNumber_5time = 4U, /*!< 5 times consecutive scan */
kTSI_ConsecutiveScansNumber_6time = 5U, /*!< 6 times consecutive scan */
kTSI_ConsecutiveScansNumber_7time = 6U, /*!< 7 times consecutive scan */
kTSI_ConsecutiveScansNumber_8time = 7U, /*!< 8 times consecutive scan */
kTSI_ConsecutiveScansNumber_9time = 8U, /*!< 9 times consecutive scan */
kTSI_ConsecutiveScansNumber_10time = 9U, /*!< 10 times consecutive scan */
kTSI_ConsecutiveScansNumber_11time = 10U, /*!< 11 times consecutive scan */
kTSI_ConsecutiveScansNumber_12time = 11U, /*!< 12 times consecutive scan */
kTSI_ConsecutiveScansNumber_13time = 12U, /*!< 13 times consecutive scan */
kTSI_ConsecutiveScansNumber_14time = 13U, /*!< 14 times consecutive scan */
kTSI_ConsecutiveScansNumber_15time = 14U, /*!< 15 times consecutive scan */
kTSI_ConsecutiveScansNumber_16time = 15U, /*!< 16 times consecutive scan */
kTSI_ConsecutiveScansNumber_17time = 16U, /*!< 17 times consecutive scan */
kTSI_ConsecutiveScansNumber_18time = 17U, /*!< 18 times consecutive scan */
kTSI_ConsecutiveScansNumber_19time = 18U, /*!< 19 times consecutive scan */
kTSI_ConsecutiveScansNumber_20time = 19U, /*!< 20 times consecutive scan */
kTSI_ConsecutiveScansNumber_21time = 20U, /*!< 21 times consecutive scan */
kTSI_ConsecutiveScansNumber_22time = 21U, /*!< 22 times consecutive scan */
kTSI_ConsecutiveScansNumber_23time = 22U, /*!< 23 times consecutive scan */
kTSI_ConsecutiveScansNumber_24time = 23U, /*!< 24 times consecutive scan */
kTSI_ConsecutiveScansNumber_25time = 24U, /*!< 25 times consecutive scan */
kTSI_ConsecutiveScansNumber_26time = 25U, /*!< 26 times consecutive scan */
kTSI_ConsecutiveScansNumber_27time = 26U, /*!< 27 times consecutive scan */
kTSI_ConsecutiveScansNumber_28time = 27U, /*!< 28 times consecutive scan */
kTSI_ConsecutiveScansNumber_29time = 28U, /*!< 29 times consecutive scan */
kTSI_ConsecutiveScansNumber_30time = 29U, /*!< 30 times consecutive scan */
kTSI_ConsecutiveScansNumber_31time = 30U, /*!< 31 times consecutive scan */
kTSI_ConsecutiveScansNumber_32time = 31U /*!< 32 times consecutive scan */
} tsi_n_consecutive_scans_t;
/*!
* @brief TSI electrode oscillator prescaler.
*
* These constants define the TSI electrode oscillator prescaler in a TSI instance.
*/
typedef enum _tsi_electrode_osc_prescaler
{
kTSI_ElecOscPrescaler_1div = 0U, /*!< Electrode oscillator frequency divided by 1 */
kTSI_ElecOscPrescaler_2div = 1U, /*!< Electrode oscillator frequency divided by 2 */
kTSI_ElecOscPrescaler_4div = 2U, /*!< Electrode oscillator frequency divided by 4 */
kTSI_ElecOscPrescaler_8div = 3U, /*!< Electrode oscillator frequency divided by 8 */
kTSI_ElecOscPrescaler_16div = 4U, /*!< Electrode oscillator frequency divided by 16 */
kTSI_ElecOscPrescaler_32div = 5U, /*!< Electrode oscillator frequency divided by 32 */
kTSI_ElecOscPrescaler_64div = 6U, /*!< Electrode oscillator frequency divided by 64 */
kTSI_ElecOscPrescaler_128div = 7U /*!< Electrode oscillator frequency divided by 128 */
} tsi_electrode_osc_prescaler_t;
/*!
* @brief TSI analog mode select.
*
* Set up TSI analog modes in a TSI instance.
*/
typedef enum _tsi_analog_mode
{
kTSI_AnalogModeSel_Capacitive = 0U, /*!< Active TSI capacitive sensing mode */
kTSI_AnalogModeSel_NoiseNoFreqLim = 4U, /*!< Single threshold noise detection mode with no freq. limitation. */
kTSI_AnalogModeSel_NoiseFreqLim = 8U, /*!< Single threshold noise detection mode with freq. limitation. */
kTSI_AnalogModeSel_AutoNoise = 12U /*!< Active TSI analog in automatic noise detection mode */
} tsi_analog_mode_t;
/*!
* @brief TSI Reference oscillator charge and discharge current select.
*
* These constants define the TSI Reference oscillator charge current select in a TSI (REFCHRG) instance.
*/
typedef enum _tsi_reference_osc_charge_current
{
kTSI_RefOscChargeCurrent_500nA = 0U, /*!< Reference oscillator charge current is 500 µA */
kTSI_RefOscChargeCurrent_1uA = 1U, /*!< Reference oscillator charge current is 1 µA */
kTSI_RefOscChargeCurrent_2uA = 2U, /*!< Reference oscillator charge current is 2 µA */
kTSI_RefOscChargeCurrent_4uA = 3U, /*!< Reference oscillator charge current is 4 µA */
kTSI_RefOscChargeCurrent_8uA = 4U, /*!< Reference oscillator charge current is 8 µA */
kTSI_RefOscChargeCurrent_16uA = 5U, /*!< Reference oscillator charge current is 16 µA */
kTSI_RefOscChargeCurrent_32uA = 6U, /*!< Reference oscillator charge current is 32 µA */
kTSI_RefOscChargeCurrent_64uA = 7U /*!< Reference oscillator charge current is 64 µA */
} tsi_reference_osc_charge_current_t;
/*!
* @brief TSI oscilator's voltage rails.
*
* These bits indicate the oscillator's voltage rails.
*/
typedef enum _tsi_osc_voltage_rails
{
kTSI_OscVolRailsOption_0 = 0U, /*!< DVOLT value option 0, the value may differ on different platforms */
kTSI_OscVolRailsOption_1 = 1U, /*!< DVOLT value option 1, the value may differ on different platforms */
kTSI_OscVolRailsOption_2 = 2U, /*!< DVOLT value option 2, the value may differ on different platforms */
kTSI_OscVolRailsOption_3 = 3U /*!< DVOLT value option 3, the value may differ on different platforms */
} tsi_osc_voltage_rails_t;
/*!
* @brief TSI External oscillator charge and discharge current select.
*
* These bits indicate the electrode oscillator charge and discharge current value
* in TSI (EXTCHRG) instance.
*/
typedef enum _tsi_external_osc_charge_current
{
kTSI_ExtOscChargeCurrent_500nA = 0U, /*!< External oscillator charge current is 500 µA */
kTSI_ExtOscChargeCurrent_1uA = 1U, /*!< External oscillator charge current is 1 µA */
kTSI_ExtOscChargeCurrent_2uA = 2U, /*!< External oscillator charge current is 2 µA */
kTSI_ExtOscChargeCurrent_4uA = 3U, /*!< External oscillator charge current is 4 µA */
kTSI_ExtOscChargeCurrent_8uA = 4U, /*!< External oscillator charge current is 8 µA */
kTSI_ExtOscChargeCurrent_16uA = 5U, /*!< External oscillator charge current is 16 µA */
kTSI_ExtOscChargeCurrent_32uA = 6U, /*!< External oscillator charge current is 32 µA */
kTSI_ExtOscChargeCurrent_64uA = 7U /*!< External oscillator charge current is 64 µA */
} tsi_external_osc_charge_current_t;
/*!
* @brief TSI series resistance RS value select.
*
* These bits indicate the electrode RS series resistance for the noise mode
* in TSI (EXTCHRG) instance.
*/
typedef enum _tsi_series_resistance
{
kTSI_SeriesResistance_32k = 0U, /*!< Series Resistance is 32 kilo ohms */
kTSI_SeriesResistance_187k = 1U /*!< Series Resistance is 18 7 kilo ohms */
} tsi_series_resistor_t;
/*!
* @brief TSI series filter bits select.
*
* These bits indicate the count of the filter bits
* in TSI noise mode EXTCHRG[2:1] bits
*/
typedef enum _tsi_filter_bits
{
kTSI_FilterBits_3 = 0U, /*!< 3 filter bits, 8 peaks increments the cnt+1 */
kTSI_FilterBits_2 = 1U, /*!< 2 filter bits, 4 peaks increments the cnt+1 */
kTSI_FilterBits_1 = 2U, /*!< 1 filter bits, 2 peaks increments the cnt+1 */
kTSI_FilterBits_0 = 3U /*!< no filter bits,1 peak increments the cnt+1 */
} tsi_filter_bits_t;
/*! @brief TSI status flags. */
typedef enum _tsi_status_flags
{
kTSI_EndOfScanFlag = TSI_GENCS_EOSF_MASK, /*!< End-Of-Scan flag */
kTSI_OutOfRangeFlag = TSI_GENCS_OUTRGF_MASK /*!< Out-Of-Range flag */
} tsi_status_flags_t;
/*! @brief TSI feature interrupt source.*/
typedef enum _tsi_interrupt_enable
{
kTSI_GlobalInterruptEnable = 1U, /*!< TSI module global interrupt */
kTSI_OutOfRangeInterruptEnable = 2U, /*!< Out-Of-Range interrupt */
kTSI_EndOfScanInterruptEnable = 4U /*!< End-Of-Scan interrupt */
} tsi_interrupt_enable_t;
/*! @brief TSI calibration data storage. */
typedef struct _tsi_calibration_data
{
uint16_t calibratedData[FSL_FEATURE_TSI_CHANNEL_COUNT]; /*!< TSI calibration data storage buffer */
} tsi_calibration_data_t;
/*!
* @brief TSI configuration structure.
*
* This structure contains the settings for the most common TSI configurations including
* the TSI module charge currents, number of scans, thresholds, and so on.
*/
typedef struct _tsi_config
{
uint16_t thresh; /*!< High threshold. */
uint16_t thresl; /*!< Low threshold. */
tsi_electrode_osc_prescaler_t prescaler; /*!< Prescaler */
tsi_external_osc_charge_current_t extchrg; /*!< Electrode charge current */
tsi_reference_osc_charge_current_t refchrg; /*!< Reference charge current */
tsi_n_consecutive_scans_t nscn; /*!< Number of scans. */
tsi_analog_mode_t mode; /*!< TSI mode of operation. */
tsi_osc_voltage_rails_t dvolt; /*!< Oscillator's voltage rails. */
tsi_series_resistor_t resistor; /*!< Series resistance value */
tsi_filter_bits_t filter; /*!< Noise mode filter bits */
} tsi_config_t;
/*******************************************************************************
* API
******************************************************************************/
#ifdef __cplusplus
extern "C" {
#endif
/*!
* @brief Initializes hardware.
*
* @details Initializes the peripheral to the targeted state specified by parameter configuration,
* such as sets prescalers, number of scans, clocks, delta voltage
* series resistor, filter bits, reference, and electrode charge current and threshold.
* @param base TSI peripheral base address.
* @param config Pointer to TSI module configuration structure.
* @return none
*/
void TSI_Init(TSI_Type *base, const tsi_config_t *config);
/*!
* @brief De-initializes hardware.
*
* @details De-initializes the peripheral to default state.
*
* @param base TSI peripheral base address.
* @return none
*/
void TSI_Deinit(TSI_Type *base);
/*!
* @brief Gets the TSI normal mode user configuration structure.
* This interface sets userConfig structure to a default value. The configuration structure only
* includes the settings for the whole TSI.
* The user configure is set to these values:
* @code
userConfig->prescaler = kTSI_ElecOscPrescaler_2div;
userConfig->extchrg = kTSI_ExtOscChargeCurrent_4uA;
userConfig->refchrg = kTSI_RefOscChargeCurrent_4uA;
userConfig->nscn = kTSI_ConsecutiveScansNumber_10time;
userConfig->mode = kTSI_AnalogModeSel_Capacitive;
userConfig->dvolt = kTSI_OscVolRailsOption_0;
userConfig->resistor = kTSI_SeriesResistance_32k;
userConfig->filter = kTSI_FilterBits_1;
userConfig->thresh = 0U;
userConfig->thresl = 0U;
@endcode
*
* @param userConfig Pointer to the TSI user configuration structure.
*/
void TSI_GetNormalModeDefaultConfig(tsi_config_t *userConfig);
/*!
* @brief Gets the TSI low power mode default user configuration structure.
* This interface sets userConfig structure to a default value. The configuration structure only
* includes the settings for the whole TSI.
* The user configure is set to these values:
* @code
userConfig->prescaler = kTSI_ElecOscPrescaler_2div;
userConfig->extchrg = kTSI_ExtOscChargeCurrent_4uA;
userConfig->refchrg = kTSI_RefOscChargeCurrent_4uA;
userConfig->nscn = kTSI_ConsecutiveScansNumber_10time;
userConfig->mode = kTSI_AnalogModeSel_Capacitive;
userConfig->dvolt = kTSI_OscVolRailsOption_0;
userConfig->resistor = kTSI_SeriesResistance_32k;
userConfig->filter = kTSI_FilterBits_1;
userConfig->thresh = 400U;
userConfig->thresl = 0U;
@endcode
*
* @param userConfig Pointer to the TSI user configuration structure.
*/
void TSI_GetLowPowerModeDefaultConfig(tsi_config_t *userConfig);
/*!
* @brief Hardware calibration.
*
* @details Calibrates the peripheral to fetch the initial counter value of
* the enabled electrodes.
* This API is mostly used at initial application setup. Call
* this function after the \ref TSI_Init API and use the calibrated
* counter values to set up applications (such as to determine
* under which counter value we can confirm a touch event occurs).
*
* @param base TSI peripheral base address.
* @param calBuff Data buffer that store the calibrated counter value.
* @return none
*
*/
void TSI_Calibrate(TSI_Type *base, tsi_calibration_data_t *calBuff);
/*!
* @brief Enables the TSI interrupt requests.
* @param base TSI peripheral base address.
* @param mask interrupt source
* The parameter can be combination of the following source if defined:
* @arg kTSI_GlobalInterruptEnable
* @arg kTSI_EndOfScanInterruptEnable
* @arg kTSI_OutOfRangeInterruptEnable
*/
void TSI_EnableInterrupts(TSI_Type *base, uint32_t mask);
/*!
* @brief Disables the TSI interrupt requests.
* @param base TSI peripheral base address.
* @param mask interrupt source
* The parameter can be combination of the following source if defined:
* @arg kTSI_GlobalInterruptEnable
* @arg kTSI_EndOfScanInterruptEnable
* @arg kTSI_OutOfRangeInterruptEnable
*/
void TSI_DisableInterrupts(TSI_Type *base, uint32_t mask);
/*!
* @brief Gets an interrupt flag.
* This function gets the TSI interrupt flags.
*
* @param base TSI peripheral base address.
* @return The mask of these status flags combination.
*/
static inline uint32_t TSI_GetStatusFlags(TSI_Type *base)
{
return (base->GENCS & (kTSI_EndOfScanFlag | kTSI_OutOfRangeFlag));
}
/*!
* @brief Clears the interrupt flag.
*
* This function clears the TSI interrupt flag,
* automatically cleared flags can't be cleared by this function.
*
* @param base TSI peripheral base address.
* @param mask The status flags to clear.
*/
void TSI_ClearStatusFlags(TSI_Type *base, uint32_t mask);
/*!
* @brief Gets the TSI scan trigger mode.
*
* @param base TSI peripheral base address.
* @return Scan trigger mode.
*/
static inline uint32_t TSI_GetScanTriggerMode(TSI_Type *base)
{
return (base->GENCS & TSI_GENCS_STM_MASK);
}
/*!
* @brief Gets the scan in progress flag.
*
* @param base TSI peripheral base address.
* @return True - scan is in progress.
* False - scan is not in progress.
*/
static inline bool TSI_IsScanInProgress(TSI_Type *base)
{
return (base->GENCS & TSI_GENCS_SCNIP_MASK);
}
/*!
* @brief Sets the prescaler.
*
* @param base TSI peripheral base address.
* @param prescaler Prescaler value.
* @return none.
*/
static inline void TSI_SetElectrodeOSCPrescaler(TSI_Type *base, tsi_electrode_osc_prescaler_t prescaler)
{
base->GENCS = (base->GENCS & ~(TSI_GENCS_PS_MASK | ALL_FLAGS_MASK)) | (TSI_GENCS_PS(prescaler));
}
/*!
* @brief Sets the number of scans (NSCN).
*
* @param base TSI peripheral base address.
* @param number Number of scans.
* @return none.
*/
static inline void TSI_SetNumberOfScans(TSI_Type *base, tsi_n_consecutive_scans_t number)
{
base->GENCS = (base->GENCS & ~(TSI_GENCS_NSCN_MASK | ALL_FLAGS_MASK)) | (TSI_GENCS_NSCN(number));
}
/*!
* @brief Enables/disables the TSI module.
*
* @param base TSI peripheral base address.
* @param enable Choose whether to enable or disable module;
* - true Enable TSI module;
* - false Disable TSI module;
* @return none.
*/
static inline void TSI_EnableModule(TSI_Type *base, bool enable)
{
if (enable)
{
base->GENCS = (base->GENCS & ~ALL_FLAGS_MASK) | TSI_GENCS_TSIEN_MASK; /* Enable module */
}
else
{
base->GENCS = (base->GENCS & ~ALL_FLAGS_MASK) & (~TSI_GENCS_TSIEN_MASK); /* Disable module */
}
}
/*!
* @brief Sets the TSI low power STOP mode as enabled or disabled.
* This enables the TSI module function in low power modes.
*
* @param base TSI peripheral base address.
* @param enable Choose to enable or disable STOP mode.
* - true Enable module in STOP mode;
* - false Disable module in STOP mode;
* @return none.
*/
static inline void TSI_EnableLowPower(TSI_Type *base, bool enable)
{
if (enable)
{
base->GENCS = (base->GENCS & ~ALL_FLAGS_MASK) | TSI_GENCS_STPE_MASK; /* Module enabled in low power stop modes */
}
else
{
base->GENCS = (base->GENCS & ~ALL_FLAGS_MASK) & (~TSI_GENCS_STPE_MASK); /* Module disabled in low power stop modes */
}
}
/*!
* @brief Enables/disables the hardware trigger scan.
*
* @param base TSI peripheral base address.
* @param enable Choose to enable hardware trigger or software trigger scan.
* - true Enable hardware trigger scan;
* - false Enable software trigger scan;
* @return none.
*/
static inline void TSI_EnableHardwareTriggerScan(TSI_Type *base, bool enable)
{
if (enable)
{
base->GENCS = (base->GENCS & ~ALL_FLAGS_MASK) | TSI_GENCS_STM_MASK; /* Enable hardware trigger scan */
}
else
{
base->GENCS = (base->GENCS & ~ALL_FLAGS_MASK) & (~TSI_GENCS_STM_MASK); /* Enable software trigger scan */
}
}
/*!
* @brief Starts a software trigger measurement (triggers a new measurement).
*
* @param base TSI peripheral base address.
* @return none.
*/
static inline void TSI_StartSoftwareTrigger(TSI_Type *base)
{
base->DATA |= TSI_DATA_SWTS_MASK;
}
/*!
* @brief Sets the the measured channel number.
*
* @param base TSI peripheral base address.
* @param channel Channel number 0 ... 15.
* @return none.
*/
static inline void TSI_SetMeasuredChannelNumber(TSI_Type *base, uint8_t channel)
{
assert(channel < FSL_FEATURE_TSI_CHANNEL_COUNT);
base->DATA = ((base->DATA) & ~TSI_DATA_TSICH_MASK) | (TSI_DATA_TSICH(channel));
}
/*!
* @brief Gets the current measured channel number.
*
* @param base TSI peripheral base address.
* @return uint8_t Channel number 0 ... 15.
*/
static inline uint8_t TSI_GetMeasuredChannelNumber(TSI_Type *base)
{
return (uint8_t)((base->DATA & TSI_DATA_TSICH_MASK) >> TSI_DATA_TSICH_SHIFT);
}
/*!
* @brief Enables/disables the DMA transfer.
*
* @param base TSI peripheral base address.
* @param enable Choose to enable DMA transfer or not.
* - true Enable DMA transfer;
* - false Disable DMA transfer;
* @return none.
*/
static inline void TSI_EnableDmaTransfer(TSI_Type *base, bool enable)
{
if (enable)
{
base->DATA |= TSI_DATA_DMAEN_MASK; /* Enable DMA transfer */
}
else
{
base->DATA &= ~TSI_DATA_DMAEN_MASK; /* Disable DMA transfer */
}
}
#if defined(FSL_FEATURE_TSI_HAS_END_OF_SCAN_DMA_ENABLE) && (FSL_FEATURE_TSI_HAS_END_OF_SCAN_DMA_ENABLE == 1)
/*!
* @brief Decides whether to enable end of scan DMA transfer request only.
*
* @param base TSI peripheral base address.
* @param enable Choose whether to enable End of Scan DMA transfer request only.
* - true Enable End of Scan DMA transfer request only;
* - false Both End-of-Scan and Out-of-Range can generate DMA transfer request.
* @return none.
*/
static inline void TSI_EnableEndOfScanDmaTransferOnly(TSI_Type *base, bool enable)
{
if (enable)
{
base->GENCS = (base->GENCS & ~ALL_FLAGS_MASK) | TSI_GENCS_EOSDMEO_MASK; /* Enable End of Scan DMA transfer request only; */
}
else
{
base->GENCS =
(base->GENCS & ~ALL_FLAGS_MASK) & (~TSI_GENCS_EOSDMEO_MASK); /* Both End-of-Scan and Out-of-Range can generate DMA transfer request. */
}
}
#endif /* End of (FSL_FEATURE_TSI_HAS_END_OF_SCAN_DMA_ENABLE == 1)*/
/*!
* @brief Gets the conversion counter value.
*
* @param base TSI peripheral base address.
* @return Accumulated scan counter value ticked by the reference clock.
*/
static inline uint16_t TSI_GetCounter(TSI_Type *base)
{
return (uint16_t)(base->DATA & TSI_DATA_TSICNT_MASK);
}
/*!
* @brief Sets the TSI wake-up channel low threshold.
*
* @param base TSI peripheral base address.
* @param low_threshold Low counter threshold.
* @return none.
*/
static inline void TSI_SetLowThreshold(TSI_Type *base, uint16_t low_threshold)
{
assert(low_threshold < 0xFFFFU);
base->TSHD = ((base->TSHD) & ~TSI_TSHD_THRESL_MASK) | (TSI_TSHD_THRESL(low_threshold));
}
/*!
* @brief Sets the TSI wake-up channel high threshold.
*
* @param base TSI peripheral base address.
* @param high_threshold High counter threshold.
* @return none.
*/
static inline void TSI_SetHighThreshold(TSI_Type *base, uint16_t high_threshold)
{
assert(high_threshold < 0xFFFFU);
base->TSHD = ((base->TSHD) & ~TSI_TSHD_THRESH_MASK) | (TSI_TSHD_THRESH(high_threshold));
}
/*!
* @brief Sets the analog mode of the TSI module.
*
* @param base TSI peripheral base address.
* @param mode Mode value.
* @return none.
*/
static inline void TSI_SetAnalogMode(TSI_Type *base, tsi_analog_mode_t mode)
{
base->GENCS = (base->GENCS & ~(TSI_GENCS_MODE_MASK | ALL_FLAGS_MASK)) | (TSI_GENCS_MODE(mode));
}
/*!
* @brief Gets the noise mode result of the TSI module.
*
* @param base TSI peripheral base address.
* @return Value of the GENCS[MODE] bit-fields.
*/
static inline uint8_t TSI_GetNoiseModeResult(TSI_Type *base)
{
return (base->GENCS & TSI_GENCS_MODE_MASK) >> TSI_GENCS_MODE_SHIFT;
}
/*!
* @brief Sets the reference oscillator charge current.
*
* @param base TSI peripheral base address.
* @param current The reference oscillator charge current.
* @return none.
*/
static inline void TSI_SetReferenceChargeCurrent(TSI_Type *base, tsi_reference_osc_charge_current_t current)
{
base->GENCS = (base->GENCS & ~(TSI_GENCS_REFCHRG_MASK | ALL_FLAGS_MASK)) | (TSI_GENCS_REFCHRG(current));
}
/*!
* @brief Sets the external electrode charge current.
*
* @param base TSI peripheral base address.
* @param current External electrode charge current.
* @return none.
*/
static inline void TSI_SetElectrodeChargeCurrent(TSI_Type *base, tsi_external_osc_charge_current_t current)
{
base->GENCS = (base->GENCS & ~(TSI_GENCS_EXTCHRG_MASK | ALL_FLAGS_MASK)) | (TSI_GENCS_EXTCHRG(current));
}
/*!
* @brief Sets the oscillator's voltage rails.
*
* @param base TSI peripheral base address.
* @param dvolt The voltage rails.
* @return none.
*/
static inline void TSI_SetOscVoltageRails(TSI_Type *base, tsi_osc_voltage_rails_t dvolt)
{
base->GENCS = (base->GENCS & ~(TSI_GENCS_DVOLT_MASK | ALL_FLAGS_MASK)) | (TSI_GENCS_DVOLT(dvolt));
}
/*!
* @brief Sets the electrode series resistance value in EXTCHRG[0] bit.
*
* @param base TSI peripheral base address.
* @param resistor Series resistance.
* @return none.
*/
static inline void TSI_SetElectrodeSeriesResistor(TSI_Type *base, tsi_series_resistor_t resistor)
{
base->GENCS = (base->GENCS & TSI_V4_EXTCHRG_RESISTOR_BIT_CLEAR) | TSI_GENCS_EXTCHRG(resistor);
}
/*!
* @brief Sets the electrode filter bits value in EXTCHRG[2:1] bits.
*
* @param base TSI peripheral base address.
* @param filter Series resistance.
* @return none.
*/
static inline void TSI_SetFilterBits(TSI_Type *base, tsi_filter_bits_t filter)
{
base->GENCS = (base->GENCS & TSI_V4_EXTCHRG_FILTER_BITS_CLEAR) | (filter << TSI_V4_EXTCHRG_FILTER_BITS_SHIFT);
}
#ifdef __cplusplus
}
#endif /* __cplusplus */
/*! @}*/
#endif /* _FSL_TSI_V4_H_ */

View File

@ -0,0 +1,224 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include "fsl_vref.h"
/*******************************************************************************
* Prototypes
******************************************************************************/
/*!
* @brief Gets the instance from the base address
*
* @param base VREF peripheral base address
*
* @return The VREF instance
*/
static uint32_t VREF_GetInstance(VREF_Type *base);
/*******************************************************************************
* Variables
******************************************************************************/
/*! @brief Pointers to VREF bases for each instance. */
static VREF_Type *const s_vrefBases[] = VREF_BASE_PTRS;
/*! @brief Pointers to VREF clocks for each instance. */
static const clock_ip_name_t s_vrefClocks[] = VREF_CLOCKS;
/*******************************************************************************
* Code
******************************************************************************/
static uint32_t VREF_GetInstance(VREF_Type *base)
{
uint32_t instance;
/* Find the instance index from base address mappings. */
for (instance = 0; instance < FSL_FEATURE_SOC_VREF_COUNT; instance++)
{
if (s_vrefBases[instance] == base)
{
break;
}
}
assert(instance < FSL_FEATURE_SOC_VREF_COUNT);
return instance;
}
void VREF_Init(VREF_Type *base, const vref_config_t *config)
{
assert(config != NULL);
uint8_t reg = 0U;
/* Ungate clock for VREF */
CLOCK_EnableClock(s_vrefClocks[VREF_GetInstance(base)]);
/* Configure VREF to a known state */
#if defined(FSL_FEATURE_VREF_HAS_CHOP_OSC) && FSL_FEATURE_VREF_HAS_CHOP_OSC
/* Set chop oscillator bit */
base->TRM |= VREF_TRM_CHOPEN_MASK;
#endif /* FSL_FEATURE_VREF_HAS_CHOP_OSC */
/* Get current SC register */
#if defined(FSL_FEATURE_VREF_HAS_LOW_REFERENCE) && FSL_FEATURE_VREF_HAS_LOW_REFERENCE
reg = base->VREFH_SC;
#else
reg = base->SC;
#endif/* FSL_FEATURE_VREF_HAS_LOW_REFERENCE */
/* Clear old buffer mode selection bits */
reg &= ~VREF_SC_MODE_LV_MASK;
/* Set buffer Mode selection and Regulator enable bit */
reg |= VREF_SC_MODE_LV(config->bufferMode) | VREF_SC_REGEN(1U);
#if defined(FSL_FEATURE_VREF_HAS_COMPENSATION) && FSL_FEATURE_VREF_HAS_COMPENSATION
/* Set second order curvature compensation enable bit */
reg |= VREF_SC_ICOMPEN(1U);
#endif /* FSL_FEATURE_VREF_HAS_COMPENSATION */
/* Enable VREF module */
reg |= VREF_SC_VREFEN(1U);
/* Update bit-field from value to Status and Control register */
#if defined(FSL_FEATURE_VREF_HAS_LOW_REFERENCE) && FSL_FEATURE_VREF_HAS_LOW_REFERENCE
base->VREFH_SC = reg;
#else
base->SC = reg;
#endif/* FSL_FEATURE_VREF_HAS_LOW_REFERENCE */
#if defined(FSL_FEATURE_VREF_HAS_LOW_REFERENCE) && FSL_FEATURE_VREF_HAS_LOW_REFERENCE
reg = base->VREFL_TRM;
/* Clear old select external voltage reference and VREFL (0.4 V) reference buffer enable bits */
reg &= ~(VREF_VREFL_TRM_VREFL_EN_MASK | VREF_VREFL_TRM_VREFL_SEL_MASK);
/* Select external voltage reference and set VREFL (0.4 V) reference buffer enable */
reg |= VREF_VREFL_TRM_VREFL_SEL(config->enableExternalVoltRef) | VREF_VREFL_TRM_VREFL_EN(config->enableLowRef);
base->VREFL_TRM = reg;
#endif /* FSL_FEATURE_VREF_HAS_LOW_REFERENCE */
#if defined(FSL_FEATURE_VREF_HAS_TRM4) && FSL_FEATURE_VREF_HAS_TRM4
reg = base->TRM4;
/* Clear old select internal voltage reference bit (2.1V) */
reg &= ~VREF_TRM4_VREF2V1_EN_MASK;
/* Select internal voltage reference (2.1V) */
reg |= VREF_TRM4_VREF2V1_EN(config->enable2V1VoltRef);
base->TRM4 = reg;
#endif /* FSL_FEATURE_VREF_HAS_TRM4 */
/* Wait until internal voltage stable */
#if defined(FSL_FEATURE_VREF_HAS_LOW_REFERENCE) && FSL_FEATURE_VREF_HAS_LOW_REFERENCE
while ((base->VREFH_SC & VREF_SC_VREFST_MASK) == 0)
#else
while ((base->SC & VREF_SC_VREFST_MASK) == 0)
#endif/* FSL_FEATURE_VREF_HAS_LOW_REFERENCE */
{
}
}
void VREF_Deinit(VREF_Type *base)
{
/* Gate clock for VREF */
CLOCK_DisableClock(s_vrefClocks[VREF_GetInstance(base)]);
}
void VREF_GetDefaultConfig(vref_config_t *config)
{
assert(config);
/* Set High power buffer mode in */
#if defined(FSL_FEATURE_VREF_MODE_LV_TYPE) && FSL_FEATURE_VREF_MODE_LV_TYPE
config->bufferMode = kVREF_ModeHighPowerBuffer;
#else
config->bufferMode = kVREF_ModeTightRegulationBuffer;
#endif /* FSL_FEATURE_VREF_MODE_LV_TYPE */
#if defined(FSL_FEATURE_VREF_HAS_LOW_REFERENCE) && FSL_FEATURE_VREF_HAS_LOW_REFERENCE
/* Select internal voltage reference */
config->enableExternalVoltRef = false;
/* Set VREFL (0.4 V) reference buffer disable */
config->enableLowRef = false;
#endif /* FSL_FEATURE_VREF_HAS_LOW_REFERENCE */
#if defined(FSL_FEATURE_VREF_HAS_TRM4) && FSL_FEATURE_VREF_HAS_TRM4
/* Disable internal voltage reference (2.1V) */
config->enable2V1VoltRef = false;
#endif /* FSL_FEATURE_VREF_HAS_TRM4 */
}
void VREF_SetTrimVal(VREF_Type *base, uint8_t trimValue)
{
uint8_t reg = 0U;
/* Set TRIM bits value in voltage reference */
reg = base->TRM;
reg = ((reg & ~VREF_TRM_TRIM_MASK) | VREF_TRM_TRIM(trimValue));
base->TRM = reg;
/* Wait until internal voltage stable */
#if defined(FSL_FEATURE_VREF_HAS_LOW_REFERENCE) && FSL_FEATURE_VREF_HAS_LOW_REFERENCE
while ((base->VREFH_SC & VREF_SC_VREFST_MASK) == 0)
#else
while ((base->SC & VREF_SC_VREFST_MASK) == 0)
#endif/* FSL_FEATURE_VREF_HAS_LOW_REFERENCE */
{
}
}
#if defined(FSL_FEATURE_VREF_HAS_TRM4) && FSL_FEATURE_VREF_HAS_TRM4
void VREF_SetTrim2V1Val(VREF_Type *base, uint8_t trimValue)
{
uint8_t reg = 0U;
/* Set TRIM bits value in voltage reference (2V1) */
reg = base->TRM4;
reg = ((reg & ~VREF_TRM4_TRIM2V1_MASK) | VREF_TRM4_TRIM2V1(trimValue));
base->TRM4 = reg;
/* Wait until internal voltage stable */
while ((base->SC & VREF_SC_VREFST_MASK) == 0)
{
}
}
#endif /* FSL_FEATURE_VREF_HAS_TRM4 */
#if defined(FSL_FEATURE_VREF_HAS_LOW_REFERENCE) && FSL_FEATURE_VREF_HAS_LOW_REFERENCE
void VREF_SetLowReferenceTrimVal(VREF_Type *base, uint8_t trimValue)
{
/* The values 111b and 110b are NOT valid/allowed */
assert((trimValue != 0x7U) && (trimValue != 0x6U));
uint8_t reg = 0U;
/* Set TRIM bits value in low voltage reference */
reg = base->VREFL_TRM;
reg = ((reg & ~VREF_VREFL_TRM_VREFL_TRIM_MASK) | VREF_VREFL_TRM_VREFL_TRIM(trimValue));
base->VREFL_TRM = reg;
/* Wait until internal voltage stable */
while ((base->VREFH_SC & VREF_SC_VREFST_MASK) == 0)
{
}
}
#endif /* FSL_FEATURE_VREF_HAS_LOW_REFERENCE */

View File

@ -0,0 +1,256 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _FSL_VREF_H_
#define _FSL_VREF_H_
#include "fsl_common.h"
/*!
* @addtogroup vref
* @{
*/
/******************************************************************************
* Definitions
******************************************************************************/
/*! @name Driver version */
/*@{*/
#define FSL_VREF_DRIVER_VERSION (MAKE_VERSION(2, 1, 0)) /*!< Version 2.1.0. */
/*@}*/
/* Those macros below defined to support SoC family which have VREFL (0.4V) reference */
#if defined(FSL_FEATURE_VREF_HAS_LOW_REFERENCE) && FSL_FEATURE_VREF_HAS_LOW_REFERENCE
#define VREF_SC_MODE_LV VREF_VREFH_SC_MODE_LV
#define VREF_SC_REGEN VREF_VREFH_SC_REGEN
#define VREF_SC_VREFEN VREF_VREFH_SC_VREFEN
#define VREF_SC_ICOMPEN VREF_VREFH_SC_ICOMPEN
#define VREF_SC_REGEN_MASK VREF_VREFH_SC_REGEN_MASK
#define VREF_SC_VREFST_MASK VREF_VREFH_SC_VREFST_MASK
#define VREF_SC_VREFEN_MASK VREF_VREFH_SC_VREFEN_MASK
#define VREF_SC_MODE_LV_MASK VREF_VREFH_SC_MODE_LV_MASK
#define VREF_SC_ICOMPEN_MASK VREF_VREFH_SC_ICOMPEN_MASK
#define TRM VREFH_TRM
#define VREF_TRM_TRIM VREF_VREFH_TRM_TRIM
#define VREF_TRM_CHOPEN_MASK VREF_VREFH_TRM_CHOPEN_MASK
#define VREF_TRM_TRIM_MASK VREF_VREFH_TRM_TRIM_MASK
#define VREF_TRM_CHOPEN_SHIFT VREF_VREFH_TRM_CHOPEN_SHIFT
#define VREF_TRM_TRIM_SHIFT VREF_VREFH_TRM_TRIM_SHIFT
#define VREF_SC_MODE_LV_SHIFT VREF_VREFH_SC_MODE_LV_SHIFT
#define VREF_SC_REGEN_SHIFT VREF_VREFH_SC_REGEN_SHIFT
#define VREF_SC_VREFST_SHIFT VREF_VREFH_SC_VREFST_SHIFT
#define VREF_SC_ICOMPEN_SHIFT VREF_VREFH_SC_ICOMPEN_SHIFT
#endif /* FSL_FEATURE_VREF_HAS_LOW_REFERENCE */
/*!
* @brief VREF modes.
*/
typedef enum _vref_buffer_mode
{
kVREF_ModeBandgapOnly = 0U, /*!< Bandgap on only, for stabilization and startup */
#if defined(FSL_FEATURE_VREF_MODE_LV_TYPE) && FSL_FEATURE_VREF_MODE_LV_TYPE
kVREF_ModeHighPowerBuffer = 1U, /*!< High power buffer mode enabled */
kVREF_ModeLowPowerBuffer = 2U /*!< Low power buffer mode enabled */
#else
kVREF_ModeTightRegulationBuffer = 2U /*!< Tight regulation buffer enabled */
#endif /* FSL_FEATURE_VREF_MODE_LV_TYPE */
} vref_buffer_mode_t;
/*!
* @brief The description structure for the VREF module.
*/
typedef struct _vref_config
{
vref_buffer_mode_t bufferMode; /*!< Buffer mode selection */
#if defined(FSL_FEATURE_VREF_HAS_LOW_REFERENCE) && FSL_FEATURE_VREF_HAS_LOW_REFERENCE
bool enableLowRef; /*!< Set VREFL (0.4 V) reference buffer enable or disable */
bool enableExternalVoltRef; /*!< Select external voltage reference or not (internal) */
#endif /* FSL_FEATURE_VREF_HAS_LOW_REFERENCE */
#if defined(FSL_FEATURE_VREF_HAS_TRM4) && FSL_FEATURE_VREF_HAS_TRM4
bool enable2V1VoltRef; /*!< Enable Internal Voltage Reference (2.1V) */
#endif /* FSL_FEATURE_VREF_HAS_TRM4 */
} vref_config_t;
/******************************************************************************
* API
******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif /* __cplusplus */
/*!
* @name VREF functional operation
* @{
*/
/*!
* @brief Enables the clock gate and configures the VREF module according to the configuration structure.
*
* This function must be called before calling all the other VREF driver functions,
* read/write registers, and configurations with user-defined settings.
* The example below shows how to set up vref_config_t parameters and
* how to call the VREF_Init function by passing in these parameters:
* Example:
* @code
* vref_config_t vrefConfig;
* vrefConfig.bufferMode = kVREF_ModeHighPowerBuffer;
* vrefConfig.enableExternalVoltRef = false;
* vrefConfig.enableLowRef = false;
* VREF_Init(VREF, &vrefConfig);
* @endcode
*
* @param base VREF peripheral address.
* @param config Pointer to the configuration structure.
*/
void VREF_Init(VREF_Type *base, const vref_config_t *config);
/*!
* @brief Stops and disables the clock for the VREF module.
*
* This function should be called to shut down the module.
* Example:
* @code
* vref_config_t vrefUserConfig;
* VREF_Init(VREF);
* VREF_GetDefaultConfig(&vrefUserConfig);
* ...
* VREF_Deinit(VREF);
* @endcode
*
* @param base VREF peripheral address.
*/
void VREF_Deinit(VREF_Type *base);
/*!
* @brief Initializes the VREF configuration structure.
*
* This function initializes the VREF configuration structure to a default value.
* Example:
* @code
* vrefConfig->bufferMode = kVREF_ModeHighPowerBuffer;
* vrefConfig->enableExternalVoltRef = false;
* vrefConfig->enableLowRef = false;
* @endcode
*
* @param config Pointer to the initialization structure.
*/
void VREF_GetDefaultConfig(vref_config_t *config);
/*!
* @brief Sets a TRIM value for reference voltage.
*
* This function sets a TRIM value for reference voltage.
* Note that the TRIM value maximum is 0x3F.
*
* @param base VREF peripheral address.
* @param trimValue Value of the trim register to set the output reference voltage (maximum 0x3F (6-bit)).
*/
void VREF_SetTrimVal(VREF_Type *base, uint8_t trimValue);
/*!
* @brief Reads the value of the TRIM meaning output voltage.
*
* This function gets the TRIM value from the TRM register.
*
* @param base VREF peripheral address.
* @return Six-bit value of trim setting.
*/
static inline uint8_t VREF_GetTrimVal(VREF_Type *base)
{
return (base->TRM & VREF_TRM_TRIM_MASK);
}
#if defined(FSL_FEATURE_VREF_HAS_TRM4) && FSL_FEATURE_VREF_HAS_TRM4
/*!
* @brief Sets a TRIM value for reference voltage (2V1).
*
* This function sets a TRIM value for reference voltage (2V1).
* Note that the TRIM value maximum is 0x3F.
*
* @param base VREF peripheral address.
* @param trimValue Value of the trim register to set the output reference voltage (maximum 0x3F (6-bit)).
*/
void VREF_SetTrim2V1Val(VREF_Type *base, uint8_t trimValue);
/*!
* @brief Reads the value of the TRIM meaning output voltage (2V1).
*
* This function gets the TRIM value from the VREF_TRM4 register.
*
* @param base VREF peripheral address.
* @return Six-bit value of trim setting.
*/
static inline uint8_t VREF_GetTrim2V1Val(VREF_Type *base)
{
return (base->TRM4 & VREF_TRM4_TRIM2V1_MASK);
}
#endif /* FSL_FEATURE_VREF_HAS_TRM4 */
#if defined(FSL_FEATURE_VREF_HAS_LOW_REFERENCE) && FSL_FEATURE_VREF_HAS_LOW_REFERENCE
/*!
* @brief Sets the TRIM value for low voltage reference.
*
* This function sets the TRIM value for low reference voltage.
* NOTE:
* - The TRIM value maximum is 0x05U
* - The values 111b and 110b are not valid/allowed.
*
* @param base VREF peripheral address.
* @param trimValue Value of the trim register to set output low reference voltage (maximum 0x05U (3-bit)).
*/
void VREF_SetLowReferenceTrimVal(VREF_Type *base, uint8_t trimValue);
/*!
* @brief Reads the value of the TRIM meaning output voltage.
*
* This function gets the TRIM value from the VREFL_TRM register.
*
* @param base VREF peripheral address.
* @return Three-bit value of the trim setting.
*/
static inline uint8_t VREF_GetLowReferenceTrimVal(VREF_Type *base)
{
return (base->VREFL_TRM & VREF_VREFL_TRM_VREFL_TRIM_MASK);
}
#endif /* FSL_FEATURE_VREF_HAS_LOW_REFERENCE */
/*@}*/
#if defined(__cplusplus)
}
#endif /* __cplusplus */
/*! @}*/
#endif /* _FSL_VREF_H_ */

View File

@ -0,0 +1,54 @@
/*
* Copyright (c) 2016, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of Freescale Semiconductor, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _FSL_PERIPHERAL_CLOCK_H_
#define _FSL_PERIPHERAL_CLOCK_H_
#include "fsl_clock.h"
/* Array for LPUART module clocks */
#define LPUART_CLOCK_FREQS \
{ \
kCLOCK_Osc0ErClk \
}
/* Array for I2C module clocks */
#define I2C_CLOCK_FREQS \
{ \
I2C0_CLK_SRC, I2C1_CLK_SRC \
}
/* Array for DSPI module clocks */
#define SPI_CLOCK_FREQS \
{ \
DSPI0_CLK_SRC, DSPI1_CLK_SRC \
}
#endif /* _FSL_PERIPHERAL_CLOCK_H_ */

View File

@ -0,0 +1,149 @@
/* mbed Microcontroller Library
* Copyright (c) 2006-2013 ARM Limited
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#include "mbed_assert.h"
#include "pwmout_api.h"
#if DEVICE_PWMOUT
#include "cmsis.h"
#include "pinmap.h"
#include "fsl_tpm.h"
#include "PeripheralPins.h"
static float pwm_clock_mhz;
/* Array of TPM peripheral base address. */
static TPM_Type *const tpm_addrs[] = TPM_BASE_PTRS;
void pwmout_init(pwmout_t* obj, PinName pin)
{
PWMName pwm = (PWMName)pinmap_peripheral(pin, PinMap_PWM);
MBED_ASSERT(pwm != (PWMName)NC);
obj->pwm_name = pwm;
uint32_t pwm_base_clock;
/* Set the TPM clock source to be MCG FLL clock */
CLOCK_SetTpmClock(1U);
pwm_base_clock = CLOCK_GetFreq(kCLOCK_McgFllClk);
float clkval = (float)pwm_base_clock / 1000000.0f;
uint32_t clkdiv = 0;
while (clkval > 1) {
clkdiv++;
clkval /= 2.0f;
if (clkdiv == 7) {
break;
}
}
pwm_clock_mhz = clkval;
uint32_t channel = pwm & 0xF;
uint32_t instance = pwm >> TPM_SHIFT;
tpm_config_t tpmInfo;
TPM_GetDefaultConfig(&tpmInfo);
tpmInfo.prescale = (tpm_clock_prescale_t)clkdiv;
/* Initialize TPM module */
TPM_Init(tpm_addrs[instance], &tpmInfo);
tpm_chnl_pwm_signal_param_t config = {
.chnlNumber = (tpm_chnl_t)channel,
.level = kTPM_HighTrue,
.dutyCyclePercent = 0,
};
// default to 20ms: standard for servos, and fine for e.g. brightness control
TPM_SetupPwm(tpm_addrs[instance], &config, 1, kTPM_EdgeAlignedPwm, 50, pwm_base_clock);
TPM_StartTimer(tpm_addrs[instance], kTPM_SystemClock);
// Wire pinout
pinmap_pinout(pin, PinMap_PWM);
}
void pwmout_free(pwmout_t* obj)
{
TPM_Deinit(tpm_addrs[obj->pwm_name >> TPM_SHIFT]);
}
void pwmout_write(pwmout_t* obj, float value)
{
if (value < 0.0f) {
value = 0.0f;
} else if (value > 1.0f) {
value = 1.0f;
}
TPM_Type *base = tpm_addrs[obj->pwm_name >> TPM_SHIFT];
uint16_t mod = base->MOD & TPM_MOD_MOD_MASK;
uint32_t new_count = (uint32_t)((float)(mod) * value);
// Update of CnV register
base->CONTROLS[obj->pwm_name & 0xF].CnV = new_count;
base->CNT = 0;
}
float pwmout_read(pwmout_t* obj)
{
TPM_Type *base = tpm_addrs[obj->pwm_name >> TPM_SHIFT];
uint16_t count = (base->CONTROLS[obj->pwm_name & 0xF].CnV) & TPM_CnV_VAL_MASK;
uint16_t mod = base->MOD & TPM_MOD_MOD_MASK;
if (mod == 0)
return 0.0;
float v = (float)(count) / (float)(mod);
return (v > 1.0f) ? (1.0f) : (v);
}
void pwmout_period(pwmout_t* obj, float seconds)
{
pwmout_period_us(obj, seconds * 1000000.0f);
}
void pwmout_period_ms(pwmout_t* obj, int ms)
{
pwmout_period_us(obj, ms * 1000);
}
// Set the PWM period, keeping the duty cycle the same.
void pwmout_period_us(pwmout_t* obj, int us)
{
TPM_Type *base = tpm_addrs[obj->pwm_name >> TPM_SHIFT];
float dc = pwmout_read(obj);
// Stop TPM clock to ensure instant update of MOD register
base->MOD = TPM_MOD_MOD((pwm_clock_mhz * (float)us) - 1);
pwmout_write(obj, dc);
}
void pwmout_pulsewidth(pwmout_t* obj, float seconds)
{
pwmout_pulsewidth_us(obj, seconds * 1000000.0f);
}
void pwmout_pulsewidth_ms(pwmout_t* obj, int ms)
{
pwmout_pulsewidth_us(obj, ms * 1000);
}
void pwmout_pulsewidth_us(pwmout_t* obj, int us)
{
TPM_Type *base = tpm_addrs[obj->pwm_name >> TPM_SHIFT];
uint32_t value = (uint32_t)(pwm_clock_mhz * (float)us);
// Update of CnV register
base->CONTROLS[obj->pwm_name & 0xF].CnV = value;
}
#endif

View File

@ -0,0 +1,253 @@
/* mbed Microcontroller Library
* Copyright (c) 2006-2013 ARM Limited
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#include "serial_api.h"
#if DEVICE_SERIAL
// math.h required for floating point operations for baud rate calculation
#include <math.h>
#include "mbed_assert.h"
#include <string.h>
#include "cmsis.h"
#include "pinmap.h"
#include "fsl_lpuart.h"
#include "peripheral_clock_defines.h"
#include "PeripheralPins.h"
#include "fsl_clock_config.h"
static uint32_t serial_irq_ids[FSL_FEATURE_SOC_LPUART_COUNT] = {0};
static uart_irq_handler irq_handler;
/* Array of UART peripheral base address. */
static LPUART_Type *const uart_addrs[] = LPUART_BASE_PTRS;
/* Array of LPUART bus clock frequencies */
static clock_name_t const uart_clocks[] = LPUART_CLOCK_FREQS;
int stdio_uart_inited = 0;
serial_t stdio_uart;
void serial_init(serial_t *obj, PinName tx, PinName rx)
{
uint32_t uart_tx = pinmap_peripheral(tx, PinMap_UART_TX);
uint32_t uart_rx = pinmap_peripheral(rx, PinMap_UART_RX);
obj->index = pinmap_merge(uart_tx, uart_rx);
MBED_ASSERT((int)obj->index != NC);
/* Set the LPUART clock source */
CLOCK_SetLpuartClock(2U);
lpuart_config_t config;
LPUART_GetDefaultConfig(&config);
config.baudRate_Bps = 9600;
config.enableTx = false;
config.enableRx = false;
LPUART_Init(uart_addrs[obj->index], &config, CLOCK_GetFreq(uart_clocks[obj->index]));
pinmap_pinout(tx, PinMap_UART_TX);
pinmap_pinout(rx, PinMap_UART_RX);
if (tx != NC) {
LPUART_EnableTx(uart_addrs[obj->index], true);
pin_mode(tx, PullUp);
}
if (rx != NC) {
LPUART_EnableRx(uart_addrs[obj->index], true);
pin_mode(rx, PullUp);
}
if (obj->index == STDIO_UART) {
stdio_uart_inited = 1;
memcpy(&stdio_uart, obj, sizeof(serial_t));
}
}
void serial_free(serial_t *obj)
{
LPUART_Deinit(uart_addrs[obj->index]);
serial_irq_ids[obj->index] = 0;
}
void serial_baud(serial_t *obj, int baudrate)
{
LPUART_SetBaudRate(uart_addrs[obj->index], (uint32_t)baudrate, CLOCK_GetFreq(uart_clocks[obj->index]));
}
void serial_format(serial_t *obj, int data_bits, SerialParity parity, int stop_bits)
{
LPUART_Type *base = uart_addrs[obj->index];
uint8_t temp;
/* Set bit count and parity mode. */
temp = base->CTRL & ~(LPUART_CTRL_PE_MASK | LPUART_CTRL_PT_MASK | LPUART_CTRL_M_MASK);
if (parity != ParityNone)
{
/* Enable Parity */
temp |= (LPUART_CTRL_PE_MASK | LPUART_CTRL_M_MASK);
if (parity == ParityOdd) {
temp |= LPUART_CTRL_PT_MASK;
} else if (parity == ParityEven) {
// PT=0 so nothing more to do
} else {
// Hardware does not support forced parity
MBED_ASSERT(0);
}
}
base->CTRL = temp;
#if defined(FSL_FEATURE_LPUART_HAS_STOP_BIT_CONFIG_SUPPORT) && FSL_FEATURE_LPUART_HAS_STOP_BIT_CONFIG_SUPPORT
/* set stop bit per char */
temp = base->BAUD & ~LPUART_BAUD_SBNS_MASK;
base->BAUD = temp | LPUART_BAUD_SBNS((uint8_t)--stop_bits);
#endif
}
/******************************************************************************
* INTERRUPTS HANDLING
******************************************************************************/
static inline void uart_irq(uint32_t transmit_empty, uint32_t receive_full, uint32_t index)
{
LPUART_Type *base = uart_addrs[index];
/* If RX overrun. */
if (LPUART_STAT_OR_MASK & base->STAT)
{
/* Read base->D, otherwise the RX does not work. */
(void)base->DATA;
LPUART_ClearStatusFlags(base, kLPUART_RxOverrunFlag);
}
if (serial_irq_ids[index] != 0) {
if (transmit_empty)
irq_handler(serial_irq_ids[index], TxIrq);
if (receive_full)
irq_handler(serial_irq_ids[index], RxIrq);
}
}
void uart0_irq()
{
uint32_t status_flags = LPUART0->STAT;
uart_irq((status_flags & kLPUART_TxDataRegEmptyFlag), (status_flags & kLPUART_RxDataRegFullFlag), 0);
}
void serial_irq_handler(serial_t *obj, uart_irq_handler handler, uint32_t id)
{
irq_handler = handler;
serial_irq_ids[obj->index] = id;
}
void serial_irq_set(serial_t *obj, SerialIrq irq, uint32_t enable)
{
IRQn_Type uart_irqs[] = LPUART_RX_TX_IRQS;
uint32_t vector = 0;
vector = (uint32_t)&uart0_irq;
if (enable) {
switch (irq) {
case RxIrq:
LPUART_EnableInterrupts(uart_addrs[obj->index], kLPUART_RxDataRegFullInterruptEnable);
break;
case TxIrq:
LPUART_EnableInterrupts(uart_addrs[obj->index], kLPUART_TxDataRegEmptyInterruptEnable);
break;
default:
break;
}
NVIC_SetVector(uart_irqs[obj->index], vector);
NVIC_EnableIRQ(uart_irqs[obj->index]);
} else { // disable
int all_disabled = 0;
SerialIrq other_irq = (irq == RxIrq) ? (TxIrq) : (RxIrq);
switch (irq) {
case RxIrq:
LPUART_DisableInterrupts(uart_addrs[obj->index], kLPUART_RxDataRegFullInterruptEnable);
break;
case TxIrq:
LPUART_DisableInterrupts(uart_addrs[obj->index], kLPUART_TxDataRegEmptyInterruptEnable);
break;
default:
break;
}
switch (other_irq) {
case RxIrq:
all_disabled = ((LPUART_GetEnabledInterrupts(uart_addrs[obj->index]) & kLPUART_RxDataRegFullInterruptEnable) == 0);
break;
case TxIrq:
all_disabled = ((LPUART_GetEnabledInterrupts(uart_addrs[obj->index]) & kLPUART_TxDataRegEmptyInterruptEnable) == 0);
break;
default:
break;
}
if (all_disabled)
NVIC_DisableIRQ(uart_irqs[obj->index]);
}
}
int serial_getc(serial_t *obj)
{
uint8_t data;
LPUART_ReadBlocking(uart_addrs[obj->index], &data, 1);
return data;
}
void serial_putc(serial_t *obj, int c)
{
while (!serial_writable(obj));
LPUART_WriteByte(uart_addrs[obj->index], (uint8_t)c);
}
int serial_readable(serial_t *obj)
{
uint32_t status_flags = LPUART_GetStatusFlags(uart_addrs[obj->index]);
if (status_flags & kLPUART_RxOverrunFlag)
LPUART_ClearStatusFlags(uart_addrs[obj->index], kLPUART_RxOverrunFlag);
return (status_flags & kLPUART_RxDataRegFullFlag);
}
int serial_writable(serial_t *obj)
{
uint32_t status_flags = LPUART_GetStatusFlags(uart_addrs[obj->index]);
if (status_flags & kLPUART_RxOverrunFlag)
LPUART_ClearStatusFlags(uart_addrs[obj->index], kLPUART_RxOverrunFlag);
return (status_flags & kLPUART_TxDataRegEmptyFlag);
}
void serial_clear(serial_t *obj)
{
}
void serial_pinout_tx(PinName tx)
{
pinmap_pinout(tx, PinMap_UART_TX);
}
void serial_break_set(serial_t *obj)
{
uart_addrs[obj->index]->CTRL |= LPUART_CTRL_SBK_MASK;
}
void serial_break_clear(serial_t *obj)
{
uart_addrs[obj->index]->CTRL &= ~LPUART_CTRL_SBK_MASK;
}
#endif

View File

@ -0,0 +1,140 @@
/* mbed Microcontroller Library
* Copyright (c) 2013 ARM Limited
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#include <math.h>
#include "mbed_assert.h"
#include "spi_api.h"
#if DEVICE_SPI
#include "cmsis.h"
#include "pinmap.h"
#include "mbed_error.h"
#include "fsl_dspi.h"
#include "peripheral_clock_defines.h"
#include "PeripheralPins.h"
/* Array of SPI peripheral base address. */
static SPI_Type *const spi_address[] = SPI_BASE_PTRS;
/* Array of SPI bus clock frequencies */
static clock_name_t const spi_clocks[] = SPI_CLOCK_FREQS;
void spi_init(spi_t *obj, PinName mosi, PinName miso, PinName sclk, PinName ssel)
{
// determine the SPI to use
uint32_t spi_mosi = pinmap_peripheral(mosi, PinMap_SPI_MOSI);
uint32_t spi_miso = pinmap_peripheral(miso, PinMap_SPI_MISO);
uint32_t spi_sclk = pinmap_peripheral(sclk, PinMap_SPI_SCLK);
uint32_t spi_ssel = pinmap_peripheral(ssel, PinMap_SPI_SSEL);
uint32_t spi_data = pinmap_merge(spi_mosi, spi_miso);
uint32_t spi_cntl = pinmap_merge(spi_sclk, spi_ssel);
obj->instance = pinmap_merge(spi_data, spi_cntl);
MBED_ASSERT((int)obj->instance != NC);
// pin out the spi pins
pinmap_pinout(mosi, PinMap_SPI_MOSI);
pinmap_pinout(miso, PinMap_SPI_MISO);
pinmap_pinout(sclk, PinMap_SPI_SCLK);
if (ssel != NC) {
pinmap_pinout(ssel, PinMap_SPI_SSEL);
}
}
void spi_free(spi_t *obj)
{
DSPI_Deinit(spi_address[obj->instance]);
}
void spi_format(spi_t *obj, int bits, int mode, int slave)
{
dspi_master_config_t master_config;
dspi_slave_config_t slave_config;
if (slave) {
/* Slave config */
DSPI_SlaveGetDefaultConfig(&slave_config);
slave_config.whichCtar = kDSPI_Ctar0;
slave_config.ctarConfig.bitsPerFrame = (uint32_t)bits;;
slave_config.ctarConfig.cpol = (mode & 0x2) ? kDSPI_ClockPolarityActiveLow : kDSPI_ClockPolarityActiveHigh;
slave_config.ctarConfig.cpha = (mode & 0x1) ? kDSPI_ClockPhaseSecondEdge : kDSPI_ClockPhaseFirstEdge;
DSPI_SlaveInit(spi_address[obj->instance], &slave_config);
} else {
/* Master config */
DSPI_MasterGetDefaultConfig(&master_config);
master_config.ctarConfig.bitsPerFrame = (uint32_t)bits;;
master_config.ctarConfig.cpol = (mode & 0x2) ? kDSPI_ClockPolarityActiveLow : kDSPI_ClockPolarityActiveHigh;
master_config.ctarConfig.cpha = (mode & 0x1) ? kDSPI_ClockPhaseSecondEdge : kDSPI_ClockPhaseFirstEdge;
master_config.ctarConfig.direction = kDSPI_MsbFirst;
master_config.ctarConfig.pcsToSckDelayInNanoSec = 0;
DSPI_MasterInit(spi_address[obj->instance], &master_config, CLOCK_GetFreq(spi_clocks[obj->instance]));
}
}
void spi_frequency(spi_t *obj, int hz)
{
uint32_t busClock = CLOCK_GetFreq(spi_clocks[obj->instance]);
DSPI_MasterSetBaudRate(spi_address[obj->instance], kDSPI_Ctar0, (uint32_t)hz, busClock);
//Half clock period delay after SPI transfer
DSPI_MasterSetDelayTimes(spi_address[obj->instance], kDSPI_Ctar0, kDSPI_LastSckToPcs, busClock, 500000000 / hz);
}
static inline int spi_readable(spi_t * obj)
{
return (DSPI_GetStatusFlags(spi_address[obj->instance]) & kDSPI_RxFifoDrainRequestFlag);
}
int spi_master_write(spi_t *obj, int value)
{
dspi_command_data_config_t command;
uint32_t rx_data;
DSPI_GetDefaultDataCommandConfig(&command);
command.isEndOfQueue = true;
DSPI_MasterWriteDataBlocking(spi_address[obj->instance], &command, (uint16_t)value);
DSPI_ClearStatusFlags(spi_address[obj->instance], kDSPI_TxFifoFillRequestFlag);
// wait rx buffer full
while (!spi_readable(obj));
rx_data = DSPI_ReadData(spi_address[obj->instance]);
DSPI_ClearStatusFlags(spi_address[obj->instance], kDSPI_RxFifoDrainRequestFlag | kDSPI_EndOfQueueFlag);
return rx_data & 0xffff;
}
int spi_slave_receive(spi_t *obj)
{
return spi_readable(obj);
}
int spi_slave_read(spi_t *obj)
{
uint32_t rx_data;
while (!spi_readable(obj));
rx_data = DSPI_ReadData(spi_address[obj->instance]);
DSPI_ClearStatusFlags(spi_address[obj->instance], kDSPI_RxFifoDrainRequestFlag);
return rx_data & 0xffff;
}
void spi_slave_write(spi_t *obj, int value)
{
DSPI_SlaveWriteDataBlocking(spi_address[obj->instance], (uint32_t)value);
}
#endif

View File

@ -0,0 +1,94 @@
/* mbed Microcontroller Library
* Copyright (c) 2006-2013 ARM Limited
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#include <stddef.h>
#include "us_ticker_api.h"
#include "PeripheralNames.h"
#include "fsl_pit.h"
#include "fsl_lptmr.h"
#include "fsl_clock_config.h"
static int us_ticker_inited = 0;
void us_ticker_init(void) {
if (us_ticker_inited) {
return;
}
us_ticker_inited = 1;
//Timer uses PIT
//Common for ticker/timer
uint32_t busClock;
// Structure to initialize PIT
pit_config_t pitConfig;
PIT_GetDefaultConfig(&pitConfig);
PIT_Init(PIT, &pitConfig);
busClock = CLOCK_GetFreq(kCLOCK_BusClk);
PIT_SetTimerPeriod(PIT, kPIT_Chnl_0, busClock / 1000000 - 1);
PIT_SetTimerPeriod(PIT, kPIT_Chnl_1, 0xFFFFFFFF);
PIT_SetTimerChainMode(PIT, kPIT_Chnl_1, true);
PIT_StartTimer(PIT, kPIT_Chnl_0);
PIT_StartTimer(PIT, kPIT_Chnl_1);
//Ticker uses LPTMR
lptmr_config_t lptmrConfig;
LPTMR_GetDefaultConfig(&lptmrConfig);
lptmrConfig.prescalerClockSource = kLPTMR_PrescalerClock_0;
LPTMR_Init(LPTMR0, &lptmrConfig);
busClock = CLOCK_GetFreq(kCLOCK_McgInternalRefClk);
LPTMR_SetTimerPeriod(LPTMR0, busClock / 1000000 - 1);
/* Set interrupt handler */
NVIC_SetVector(LPTMR0_IRQn, (uint32_t)us_ticker_irq_handler);
NVIC_EnableIRQ(LPTMR0_IRQn);
}
uint32_t us_ticker_read() {
if (!us_ticker_inited) {
us_ticker_init();
}
return ~(PIT_GetCurrentTimerCount(PIT, kPIT_Chnl_1));
}
void us_ticker_disable_interrupt(void) {
LPTMR_DisableInterrupts(LPTMR0, kLPTMR_TimerInterruptEnable);
}
void us_ticker_clear_interrupt(void) {
LPTMR_ClearStatusFlags(LPTMR0, kLPTMR_TimerCompareFlag);
}
void us_ticker_set_interrupt(timestamp_t timestamp) {
int delta = (int)(timestamp - us_ticker_read());
if (delta <= 0) {
// This event was in the past.
// Set the interrupt as pending, but don't process it here.
// This prevents a recurive loop under heavy load
// which can lead to a stack overflow.
NVIC_SetPendingIRQ(LPTMR0_IRQn);
return;
}
LPTMR_StopTimer(LPTMR0);
LPTMR_SetTimerPeriod(LPTMR0, (uint32_t)delta);
LPTMR_EnableInterrupts(LPTMR0, kLPTMR_TimerInterruptEnable);
LPTMR_StartTimer(LPTMR0);
}

View File

@ -37,8 +37,10 @@ void deepsleep(void) {
* If enter stop modes when MCG in PEE mode, then after wakeup, the MCG is in PBE mode,
* need to enter PEE mode manually.
*/
#if defined(kMCG_ModePEE)
if (mode == kMCG_ModePEE) {
BOARD_BootClockRUN();
}
#endif
#endif
}

View File

@ -217,6 +217,21 @@
#define OS_CLOCK 48000000
#endif
#elif defined(TARGET_KW41Z)
#ifndef INITIAL_SP
#define INITIAL_SP (0x20018000UL)
#endif
#ifndef OS_TASKCNT
#define OS_TASKCNT 14
#endif
#ifndef OS_MAINSTKSIZE
#define OS_MAINSTKSIZE 256
#endif
#ifndef OS_CLOCK
#define OS_CLOCK 40000000
#endif
#elif defined(TARGET_K82F)
#ifndef INITIAL_SP

View File

@ -554,6 +554,19 @@
"release_versions": ["2", "5"],
"device_name": "MKW24D512xxx5"
},
"KW41Z": {
"supported_form_factors": ["ARDUINO"],
"core": "Cortex-M0+",
"supported_toolchains": ["ARM", "GCC_ARM", "IAR"],
"extra_labels": ["Freescale", "KSDK2_MCUS", "FRDM"],
"is_disk_virtual": true,
"macros": ["CPU_MKW41Z512VHT4", "FSL_RTOS_MBED"],
"inherits": ["Target"],
"detect_code": ["0201"],
"device_has": ["ANALOGIN", "ANALOGOUT", "ERROR_RED", "I2C", "I2CSLAVE", "INTERRUPTIN", "PORTIN", "PORTINOUT", "PORTOUT", "PWMOUT", "RTC", "SERIAL", "SLEEP", "SPI", "SPISLAVE", "STDIO_MESSAGES"],
"release_versions": ["2", "5"],
"device_name": "MKW41Z512xxx4"
},
"K64F": {
"supported_form_factors": ["ARDUINO"],
"core": "Cortex-M4F",