NXP: Add support for MIMXRT1050_EVK

Signed-off-by: Mahesh Mahadevan <mahesh.mahadevan@nxp.com>
pull/5826/head
Mahesh Mahadevan 2017-12-19 15:18:05 -06:00
parent a0d16076c1
commit 060daa99c9
176 changed files with 108048 additions and 2 deletions

View File

@ -0,0 +1,50 @@
/* 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_PERIPHERALPINS_H
#define MBED_PERIPHERALPINS_H
#include "pinmap.h"
#include "PeripheralNames.h"
/************RTC***************/
extern const PinMap PinMap_RTC[];
/************ADC***************/
extern const PinMap PinMap_ADC[];
/************DAC***************/
extern const PinMap PinMap_DAC[];
/************I2C***************/
extern const PinMap PinMap_I2C_SDA[];
extern const PinMap PinMap_I2C_SCL[];
/************UART***************/
extern const PinMap PinMap_UART_TX[];
extern const PinMap PinMap_UART_RX[];
extern const PinMap PinMap_UART_CTS[];
extern const PinMap PinMap_UART_RTS[];
/************SPI***************/
extern const PinMap PinMap_SPI_SCLK[];
extern const PinMap PinMap_SPI_MOSI[];
extern const PinMap PinMap_SPI_MISO[];
extern const PinMap PinMap_SPI_SSEL[];
/************PWM***************/
extern const PinMap PinMap_PWM[];
#endif

View File

@ -0,0 +1,35 @@
/* 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_PORTNAMES_H
#define MBED_PORTNAMES_H
#ifdef __cplusplus
extern "C" {
#endif
typedef enum {
Gpio1 = 1,
Gpio2 = 2,
Gpio3 = 3,
Gpio4 = 4,
Gpio5 = 5
} PortName;
#ifdef __cplusplus
}
#endif
#endif

View File

@ -0,0 +1,77 @@
/* 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 "analogin_api.h"
#if DEVICE_ANALOGIN
#include "cmsis.h"
#include "pinmap.h"
#include "PeripheralNames.h"
#include "fsl_adc.h"
#include "PeripheralPins.h"
/* Array of ADC peripheral base address. */
static ADC_Type *const adc_addrs[] = ADC_BASE_PTRS;
void analogin_init(analogin_t *obj, PinName pin)
{
obj->adc = (ADCName)pinmap_peripheral(pin, PinMap_ADC);
MBED_ASSERT(obj->adc != (ADCName)NC);
uint32_t instance = obj->adc >> ADC_INSTANCE_SHIFT;
adc_config_t adc_config;
ADC_GetDefaultConfig(&adc_config);
ADC_Init(adc_addrs[instance], &adc_config);
#if !(defined(FSL_FEATURE_ADC_SUPPORT_HARDWARE_TRIGGER_REMOVE) && FSL_FEATURE_ADC_SUPPORT_HARDWARE_TRIGGER_REMOVE)
ADC_EnableHardwareTrigger(adc_addrs[instance], false);
#endif
ADC_DoAutoCalibration(adc_addrs[instance]);
}
uint16_t analogin_read_u16(analogin_t *obj)
{
uint32_t instance = obj->adc >> ADC_INSTANCE_SHIFT;
adc_channel_config_t adc_channel_config;
adc_channel_config.channelNumber = obj->adc & 0xF;
adc_channel_config.enableInterruptOnConversionCompleted = false;
/*
When in software trigger mode, each conversion would be launched once calling the "ADC_ChannelConfigure()"
function, which works like writing a conversion command and executing it. For another channel's conversion,
just to change the "channelNumber" field in channel configuration structure, and call the function
"ADC_ChannelConfigure()"" again.
Also, the "enableInterruptOnConversionCompleted" inside the channel configuration structure is a parameter
for the conversion command. It takes affect just for the current conversion. If the interrupt is still required
for the following conversion, it is necessary to assert the "enableInterruptOnConversionCompleted" every
time for each command.
*/
ADC_SetChannelConfig(adc_addrs[instance], 0, &adc_channel_config);
while (0U == ADC_GetChannelStatusFlags(adc_addrs[instance], 0))
{
}
return ADC_GetChannelConversionValue(adc_addrs[instance], 0);
}
float analogin_read(analogin_t *obj)
{
uint16_t value = analogin_read_u16(obj);
return (float)value * (1.0f / (float)0xFFFF);
}
#endif

View File

@ -0,0 +1,83 @@
/* 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 "gpio_api.h"
#include "pinmap.h"
#include "fsl_gpio.h"
static GPIO_Type * const gpio_addrs[] = GPIO_BASE_PTRS;
uint32_t gpio_set(PinName pin)
{
MBED_ASSERT(pin != (PinName)NC);
uint32_t pin_num = pin & 0xFF;
pin_function(pin, GPIO_MUX_PORT);
return 1 << pin_num;
}
void gpio_init(gpio_t *obj, PinName pin)
{
clock_ip_name_t gpio_clocks[] = GPIO_CLOCKS;
CLOCK_EnableClock(gpio_clocks[pin >> GPIO_PORT_SHIFT]);
obj->pin = pin;
if (pin == (PinName)NC)
return;
pin_function(pin, GPIO_MUX_PORT);
}
void gpio_mode(gpio_t *obj, PinMode mode)
{
pin_mode(obj->pin, mode);
}
void gpio_dir(gpio_t *obj, PinDirection direction)
{
MBED_ASSERT(obj->pin != (PinName)NC);
uint32_t port = (obj->pin >> GPIO_PORT_SHIFT) & 0xF;
uint32_t gpio_pin_num = obj->pin & 0xFF;
GPIO_Type *base = gpio_addrs[port];
switch (direction) {
case PIN_INPUT:
base->GDIR &= ~(1U << gpio_pin_num);
break;
case PIN_OUTPUT:
base->GDIR |= (1U << gpio_pin_num);
break;
}
}
void gpio_write(gpio_t *obj, int value)
{
MBED_ASSERT(obj->pin != (PinName)NC);
uint32_t port = (obj->pin >> GPIO_PORT_SHIFT) & 0xF;
uint32_t gpio_pin_num = obj->pin & 0xFF;
GPIO_WritePinOutput(gpio_addrs[port], gpio_pin_num, value);
}
int gpio_read(gpio_t *obj)
{
MBED_ASSERT(obj->pin != (PinName)NC);
uint32_t port = (obj->pin >> GPIO_PORT_SHIFT) & 0xF;
uint32_t gpio_pin_num = obj->pin & 0xFF;
return (int)GPIO_ReadPinInput(gpio_addrs[port], gpio_pin_num);
}

View File

@ -0,0 +1,246 @@
/* 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 "cmsis.h"
#include "gpio_irq_api.h"
#if DEVICE_INTERRUPTIN
#include "gpio_api.h"
#include "fsl_gpio.h"
#include "mbed_error.h"
#define CHANNEL_NUM 160
#define IRQ_DISABLED (0)
#define IRQ_RISING_EDGE (2)
#define IRQ_FALLING_EDGE (3)
#define IRQ_EITHER_EDGE (4)
static uint32_t channel_ids[CHANNEL_NUM] = {0};
static gpio_irq_handler irq_handler;
static GPIO_Type * const gpio_addrs[] = GPIO_BASE_PTRS;
/* Array of PORT IRQ number. */
static const IRQn_Type gpio_irqs[] = GPIO_IRQS;
static void handle_interrupt_in(PortName port, int ch_base)
{
uint32_t i;
uint32_t interrupt_flags;
GPIO_Type *port_base = gpio_addrs[port];
interrupt_flags = GPIO_GetPinsInterruptFlags(port_base);
for (i = 0; i < 32; i++) {
if (interrupt_flags & (1 << i)) {
uint32_t id = channel_ids[ch_base + i];
if (id == 0) {
continue;
}
gpio_irq_event event = IRQ_NONE;
if (port_base->EDGE_SEL & (1U << i)) {
/* Either edge was selected, find the edge that triggered the interrupt */
event = (GPIO_ReadPinInput(port_base, i)) ? (IRQ_RISE) : (IRQ_FALL);
} else {
/* Detect if falling or rising edge */
uint32_t icr;
uint32_t icrShift;
icrShift = i;
if (i < 16) {
icr = port_base->ICR1;
} else {
icr = port_base->ICR2;
icrShift -= 16;
}
if (((icr >> (2 * icrShift)) & 0x3) == IRQ_RISING_EDGE) {
event = IRQ_RISE;
}
if (((icr >> (2 * icrShift)) & 0x3) == IRQ_FALLING_EDGE) {
event = IRQ_FALL;
}
}
if (event != IRQ_NONE) {
irq_handler(id, event);
}
}
}
GPIO_ClearPinsInterruptFlags(port_base, interrupt_flags);
}
void gpio1_irq(void)
{
handle_interrupt_in(Gpio1, 0);
}
void gpio2_irq(void)
{
handle_interrupt_in(Gpio2, 32);
}
void gpio3_irq(void)
{
handle_interrupt_in(Gpio3, 64);
}
void gpio4_irq(void)
{
handle_interrupt_in(Gpio4, 96);
}
void gpio5_irq(void)
{
handle_interrupt_in(Gpio5, 128);
}
int gpio_irq_init(gpio_irq_t *obj, PinName pin, gpio_irq_handler handler, uint32_t id)
{
if (pin == NC) {
return -1;
}
irq_handler = handler;
obj->port = (pin >> GPIO_PORT_SHIFT) & 0xF;
obj->pin = (pin & 0xFF);
uint32_t ch_base = 0;
uint32_t vector = (uint32_t)gpio1_irq;
switch (obj->port) {
case Gpio1:
ch_base = 0;
vector = (uint32_t)gpio1_irq;
break;
case Gpio2:
ch_base = 32;
vector = (uint32_t)gpio2_irq;
break;
case Gpio3:
ch_base = 64;
vector = (uint32_t)gpio3_irq;
break;
case Gpio4:
ch_base = 96;
vector = (uint32_t)gpio4_irq;
break;
case Gpio5:
ch_base = 128;
vector = (uint32_t)gpio5_irq;
break;
default:
error("gpio_irq only supported on port A-E.");
break;
}
NVIC_SetVector(gpio_irqs[obj->port], vector);
NVIC_EnableIRQ(gpio_irqs[obj->port]);
obj->ch = ch_base + obj->pin;
channel_ids[obj->ch] = id;
return 0;
}
void gpio_irq_free(gpio_irq_t *obj)
{
channel_ids[obj->ch] = 0;
}
void gpio_irq_set(gpio_irq_t *obj, gpio_irq_event event, uint32_t enable)
{
GPIO_Type *base = gpio_addrs[obj->port];
gpio_interrupt_mode_t irq_settings = kGPIO_NoIntmode;
uint32_t icr;
uint32_t icrShift;
uint32_t irq_curr_settings = IRQ_DISABLED;
icrShift = obj->pin;
if (obj->pin < 16) {
icr = base->ICR1;
} else {
icr = base->ICR2;
icrShift -= 16;
}
if (base->EDGE_SEL & (1U << obj->pin)) {
irq_curr_settings = IRQ_EITHER_EDGE;
} else {
if (((icr >> (2 * icrShift)) & 0x3) == IRQ_RISING_EDGE) {
irq_curr_settings = IRQ_RISING_EDGE;
}
if (((icr >> (2 * icrShift)) & 0x3) == IRQ_FALLING_EDGE) {
irq_curr_settings = IRQ_FALLING_EDGE;
}
}
switch (irq_curr_settings) {
case IRQ_DISABLED:
if (enable)
irq_settings = (event == IRQ_RISE) ? (kGPIO_IntRisingEdge) : (kGPIO_IntFallingEdge);
break;
case IRQ_RISING_EDGE:
if (enable) {
irq_settings = (event == IRQ_RISE) ? (kGPIO_IntRisingEdge) : (kGPIO_IntRisingOrFallingEdge);
} else {
if (event == IRQ_FALL)
irq_settings = kGPIO_IntRisingEdge;
}
break;
case IRQ_FALLING_EDGE:
if (enable) {
irq_settings = (event == IRQ_FALL) ? (kGPIO_IntFallingEdge) : (kGPIO_IntRisingOrFallingEdge);
} else {
if (event == IRQ_RISE)
irq_settings = kGPIO_IntFallingEdge;
}
break;
case IRQ_EITHER_EDGE:
if (enable) {
irq_settings = kGPIO_IntRisingOrFallingEdge;
} else {
irq_settings = (event == IRQ_RISE) ? (kGPIO_IntFallingEdge) : (kGPIO_IntRisingEdge);
}
break;
}
if (irq_settings == kGPIO_NoIntmode) {
GPIO_DisableInterrupts(base, 1U << obj->pin);
} else {
GPIO_SetPinInterruptConfig(base, obj->pin, irq_settings);
GPIO_EnableInterrupts(base, 1U << obj->pin);
}
}
void gpio_irq_enable(gpio_irq_t *obj)
{
NVIC_EnableIRQ(gpio_irqs[obj->port]);
}
void gpio_irq_disable(gpio_irq_t *obj)
{
NVIC_DisableIRQ(gpio_irqs[obj->port]);
}
#endif

View File

@ -0,0 +1,256 @@
/* 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 "i2c_api.h"
#if DEVICE_I2C
#include "cmsis.h"
#include "pinmap.h"
#include "fsl_lpi2c.h"
#include "PeripheralPins.h"
/* 7 bit IIC addr - R/W flag not included */
static int i2c_address = 0;
/* Array of I2C peripheral base address. */
static LPI2C_Type *const i2c_addrs[] = LPI2C_BASE_PTRS;
extern void i2c_setup_clock();
extern uint32_t i2c_get_clock();
void pin_mode_opendrain(PinName pin, bool enable);
void i2c_init(i2c_t *obj, PinName sda, PinName scl)
{
uint32_t i2c_sda = pinmap_peripheral(sda, PinMap_I2C_SDA);
uint32_t i2c_scl = pinmap_peripheral(scl, PinMap_I2C_SCL);
obj->instance = pinmap_merge(i2c_sda, i2c_scl);
obj->next_repeated_start = 0;
MBED_ASSERT((int)obj->instance != NC);
lpi2c_master_config_t master_config;
i2c_setup_clock();
LPI2C_MasterGetDefaultConfig(&master_config);
LPI2C_MasterInit(i2c_addrs[obj->instance], &master_config, i2c_get_clock());
pinmap_pinout(sda, PinMap_I2C_SDA);
pinmap_pinout(scl, PinMap_I2C_SCL);
pin_mode_opendrain(sda, true);
pin_mode_opendrain(scl, true);
}
int i2c_start(i2c_t *obj)
{
if (LPI2C_MasterStart(i2c_addrs[obj->instance], 0, kLPI2C_Write) != kStatus_Success) {
return 1;
}
return 0;
}
int i2c_stop(i2c_t *obj)
{
obj->next_repeated_start = 0;
if (LPI2C_MasterStop(i2c_addrs[obj->instance]) != kStatus_Success) {
return 1;
}
return 0;
}
void i2c_frequency(i2c_t *obj, int hz)
{
uint32_t busClock;
busClock = i2c_get_clock();
LPI2C_MasterSetBaudRate(i2c_addrs[obj->instance], hz, busClock);
}
int i2c_read(i2c_t *obj, int address, char *data, int length, int stop)
{
LPI2C_Type *base = i2c_addrs[obj->instance];
lpi2c_master_transfer_t master_xfer;
i2c_address = address >> 1;
memset(&master_xfer, 0, sizeof(master_xfer));
master_xfer.slaveAddress = address >> 1;
master_xfer.direction = kLPI2C_Read;
master_xfer.data = (uint8_t *)data;
master_xfer.dataSize = length;
if (obj->next_repeated_start) {
master_xfer.flags |= kLPI2C_TransferRepeatedStartFlag;
}
if (!stop) {
master_xfer.flags |= kLPI2C_TransferNoStopFlag;
}
obj->next_repeated_start = master_xfer.flags & kLPI2C_TransferNoStopFlag ? 1 : 0;
/* The below function will issue a STOP signal at the end of the transfer.
* This is required by the hardware in order to receive the last byte
*/
if (LPI2C_MasterTransferBlocking(base, &master_xfer) != kStatus_Success) {
return I2C_ERROR_NO_SLAVE;
}
return length;
}
int i2c_write(i2c_t *obj, int address, const char *data, int length, int stop)
{
LPI2C_Type *base = i2c_addrs[obj->instance];
lpi2c_master_transfer_t master_xfer;
if (length == 0) {
if (LPI2C_MasterStart(base, address >> 1, kLPI2C_Write) != kStatus_Success) {
return I2C_ERROR_NO_SLAVE;
}
if (base->MSR & kLPI2C_MasterNackDetectFlag) {
i2c_stop(obj);
return I2C_ERROR_NO_SLAVE;
} else {
i2c_stop(obj);
return length;
}
}
memset(&master_xfer, 0, sizeof(master_xfer));
master_xfer.slaveAddress = address >> 1;
master_xfer.direction = kLPI2C_Write;
master_xfer.data = (uint8_t *)data;
master_xfer.dataSize = length;
if (obj->next_repeated_start) {
master_xfer.flags |= kLPI2C_TransferRepeatedStartFlag;
}
if (!stop) {
master_xfer.flags |= kLPI2C_TransferNoStopFlag;
}
obj->next_repeated_start = master_xfer.flags & kLPI2C_TransferNoStopFlag ? 1 : 0;
if (LPI2C_MasterTransferBlocking(base, &master_xfer) != kStatus_Success) {
return I2C_ERROR_NO_SLAVE;
}
return length;
}
void i2c_reset(i2c_t *obj)
{
i2c_stop(obj);
}
int i2c_byte_read(i2c_t *obj, int last)
{
uint8_t data;
LPI2C_Type *base = i2c_addrs[obj->instance];
lpi2c_master_transfer_t master_xfer;
memset(&master_xfer, 0, sizeof(master_xfer));
master_xfer.slaveAddress = i2c_address;
master_xfer.direction = kLPI2C_Read;
master_xfer.data = &data;
master_xfer.dataSize = 1;
master_xfer.flags = kLPI2C_TransferNoStopFlag;
if (LPI2C_MasterTransferBlocking(base, &master_xfer) != kStatus_Success) {
return I2C_ERROR_NO_SLAVE;
}
return data;
}
int i2c_byte_write(i2c_t *obj, int data)
{
LPI2C_Type *base = i2c_addrs[obj->instance];
lpi2c_master_transfer_t master_xfer;
status_t ret_value;
memset(&master_xfer, 0, sizeof(master_xfer));
master_xfer.slaveAddress = i2c_address;
master_xfer.direction = kLPI2C_Write;
master_xfer.data = &data;
master_xfer.dataSize = 1;
master_xfer.flags = kLPI2C_TransferNoStopFlag;
ret_value = LPI2C_MasterTransferBlocking(base, &master_xfer);
if (ret_value == kStatus_Success) {
return 1;
} else if (ret_value == kStatus_LPI2C_Nak) {
return 0;
} else {
return 2;
}
}
#if DEVICE_I2CSLAVE
void i2c_slave_mode(i2c_t *obj, int enable_slave)
{
lpi2c_slave_config_t slave_config;
LPI2C_SlaveGetDefaultConfig(&slave_config);
slave_config.enableSlave = (bool)enable_slave;
LPI2C_SlaveInit(i2c_addrs[obj->instance], &slave_config, i2c_get_clock());
}
int i2c_slave_receive(i2c_t *obj)
{
LPI2C_Type *base = i2c_addrs[obj->instance];
uint32_t status_flags = LPI2C_SlaveGetStatusFlags(base);
if (status_flags & kLPI2C_SlaveAddressValidFlag) {
if (base->SASR & kLPI2C_Read) {
// read addressed
return 1;
} else {
// write addressed
return 3;
}
} else {
// slave not addressed
return 0;
}
}
int i2c_slave_read(i2c_t *obj, char *data, int length)
{
LPI2C_Type *base = i2c_addrs[obj->instance];
int actual_rx;
LPI2C_SlaveReceive(base, (uint8_t *)data, length, (size_t *)&actual_rx);
return actual_rx;
}
int i2c_slave_write(i2c_t *obj, const char *data, int length)
{
LPI2C_Type *base = i2c_addrs[obj->instance];
int actual_rx;
LPI2C_SlaveSend(base, (uint8_t *)data, length, (size_t *)&actual_rx);
return actual_rx;
}
void i2c_slave_address(i2c_t *obj, int idx, uint32_t address, uint32_t mask)
{
i2c_addrs[obj->instance]->SAMR = LPI2C_SAMR_ADDR0(address & 0xfe);
}
#endif
#endif

View File

@ -0,0 +1,134 @@
/* mbed Microcontroller Library
* Copyright (c) 2016 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.
*/
#if DEVICE_LOWPOWERTIMER
#include "lp_ticker_api.h"
#include "fsl_snvs_hp.h"
#include "fsl_gpt.h"
#include "cmsis.h"
#include "rtc_api.h"
#define LOWFREQ_REF_CLK_HZ (32768)
static bool lp_ticker_inited = false;
static void gpt_isr(void)
{
GPT_ClearStatusFlags(GPT2, kGPT_OutputCompare1Flag);
GPT_StopTimer(GPT2);
lp_ticker_irq_handler();
}
/** Initialize the low power ticker
*
*/
void lp_ticker_init(void)
{
gpt_config_t gptConfig;
if (lp_ticker_inited) {
return;
}
lp_ticker_inited = true;
/* Setup low resolution clock - RTC */
if (!rtc_isenabled()) {
rtc_init();
}
/* Setup GPT */
GPT_GetDefaultConfig(&gptConfig);
/* Use 32kHz drive */
gptConfig.clockSource = kGPT_ClockSource_LowFreq;
GPT_Init(GPT2, &gptConfig);
GPT_EnableInterrupts(GPT2, kGPT_OutputCompare1InterruptEnable);
NVIC_ClearPendingIRQ(GPT2_IRQn);
NVIC_SetVector(GPT2_IRQn, (uint32_t)gpt_isr);
EnableIRQ(GPT2_IRQn);
}
/** Read the current counter
*
* @return The current timer's counter value in microseconds
*/
uint32_t lp_ticker_read(void)
{
uint32_t ticks = 0;
uint64_t tmp = 0;
if (!lp_ticker_inited) {
lp_ticker_init();
}
/* Do consecutive reads until value is correct */
do
{
ticks = tmp;
tmp = SNVS->HPRTCLR;
} while (tmp != ticks);
return COUNT_TO_USEC(ticks, LOWFREQ_REF_CLK_HZ);;
}
/** Set interrupt for specified timestamp
*
* @param timestamp The time in microseconds to be set
*/
void lp_ticker_set_interrupt(timestamp_t timestamp)
{
uint32_t now_us, delta_us, delta_ticks;
if (!lp_ticker_inited) {
lp_ticker_init();
}
now_us = lp_ticker_read();
delta_us = timestamp > now_us ? timestamp - now_us : (uint32_t)((uint64_t)timestamp + 0xFFFFFFFF - now_us);
delta_ticks = USEC_TO_COUNT(delta_us, LOWFREQ_REF_CLK_HZ);
if (delta_ticks == 0) {
delta_ticks = 1;
}
GPT_SetOutputCompareValue(GPT2, kGPT_OutputCompare_Channel1, delta_ticks);
GPT_EnableInterrupts(GPT2, kGPT_OutputCompare1InterruptEnable);
GPT_StartTimer(GPT2);
}
void lp_ticker_fire_interrupt(void)
{
NVIC_SetPendingIRQ(GPT2_IRQn);
}
/** Disable low power ticker interrupt
*
*/
void lp_ticker_disable_interrupt(void)
{
GPT_DisableInterrupts(GPT2, kGPT_OutputCompare1InterruptEnable);
}
/** Clear the low power ticker interrupt
*
*/
void lp_ticker_clear_interrupt(void)
{
GPT_ClearStatusFlags(GPT2, kGPT_OutputCompare1Flag);
}
#endif /* DEVICE_LOWPOWERTIMER */

View File

@ -0,0 +1,75 @@
/* 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_OBJECTS_H
#define MBED_OBJECTS_H
#include "cmsis.h"
#include "PortNames.h"
#include "PeripheralNames.h"
#include "PinNames.h"
#ifdef __cplusplus
extern "C" {
#endif
struct gpio_irq_s {
uint32_t port;
uint32_t pin;
uint32_t ch;
};
struct port_s {
PortName port;
uint32_t mask;
};
struct pwmout_s {
PWMName pwm_name;
};
struct serial_s {
int index;
};
struct analogin_s {
ADCName adc;
};
struct i2c_s {
uint32_t instance;
uint8_t next_repeated_start;
};
struct spi_s {
uint32_t instance;
uint8_t bits;
};
struct dac_s {
DACName dac;
};
struct trng_s {
uint8_t dummy;
};
#include "gpio_object.h"
#ifdef __cplusplus
}
#endif
#endif

View File

@ -0,0 +1,157 @@
/* 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 "PeripheralPins.h"
#include "mbed_error.h"
#include "fsl_clock.h"
/* Array of IOMUX base address. */
static uint32_t iomux_base_addrs[FSL_FEATURE_SOC_IGPIO_COUNT] = { 0x401F80BC, 0x401F813C, 0u, 0x401F8014, 0x400A8000 };
/* Get the IOMUX register address from the GPIO3 pin number */
static uint32_t get_iomux_reg_base(PinName pin)
{
int32_t gpio_pin = pin & 0xFF;
uint32_t retval = 0;
if ((gpio_pin >= 0) && (gpio_pin < 12)) {
retval = 0x401F81D4 + (gpio_pin * 4);
} else if ((gpio_pin >= 12) && (gpio_pin < 18)) {
retval = 0x401F81BC + ((gpio_pin - 12) * 4);
} else if ((gpio_pin >= 18) && (gpio_pin < 28)) {
retval = 0x401F8094 + ((gpio_pin - 18) * 4);
}
return retval;
}
void pin_function(PinName pin, int function)
{
MBED_ASSERT(pin != (PinName)NC);
uint32_t muxregister = iomux_base_addrs[(pin >> GPIO_PORT_SHIFT) - 1];
uint32_t daisyregister;
CLOCK_EnableClock(kCLOCK_Iomuxc);
/* Get mux register address */
if (muxregister == 0) {
muxregister = get_iomux_reg_base(pin);
} else {
muxregister = muxregister + ((pin & 0xFF) * 4);
}
/* Write to the mux register */
*((volatile uint32_t *)muxregister) = IOMUXC_SW_MUX_CTL_PAD_MUX_MODE(function);
/* If required write to the input daisy register */
daisyregister = (function >> DAISY_REG_SHIFT) & 0xFFF;
if (daisyregister != 0) {
daisyregister = daisyregister + 0x401F8000;
*((volatile uint32_t *)daisyregister) = IOMUXC_SELECT_INPUT_DAISY(((function >> DAISY_REG_VALUE_SHIFT) & 0xF));
}
}
void pin_mode(PinName pin, PinMode mode)
{
MBED_ASSERT(pin != (PinName)NC);
uint32_t instance = pin >> GPIO_PORT_SHIFT;
uint32_t reg;
uint32_t muxregister = iomux_base_addrs[instance - 1];
uint32_t configregister;
if (muxregister == 0) {
muxregister = get_iomux_reg_base(pin);
} else {
muxregister = muxregister + ((pin & 0xFF) * 4);
}
/* Get pad register address */
if (instance == 5) {
configregister = muxregister + 0x10;
} else {
configregister = muxregister + 0x1F0;
}
reg = *((volatile uint32_t *)configregister);
switch (mode) {
case PullNone:
/* Write 0 to the PUE bit & 1 to the PKE bit to set the pad to keeper mode */
reg &= ~(IOMUXC_SW_PAD_CTL_PAD_PUE_MASK);
reg |= (IOMUXC_SW_PAD_CTL_PAD_PKE_MASK);
break;
case PullDown:
/* Write 1 to PKE & PUE bit to enable the pull configuration and 0 to PUS bit for 100K pull down */
reg &= ~(IOMUXC_SW_PAD_CTL_PAD_PUS_MASK);
reg |= (IOMUXC_SW_PAD_CTL_PAD_PKE_MASK | IOMUXC_SW_PAD_CTL_PAD_PUE_MASK);
break;
case PullUp_47K:
/* Write 1 to PKE & PUE bit to enable the pull configuration and 1 to PUS bit for 47K pull up*/
reg &= ~(IOMUXC_SW_PAD_CTL_PAD_PUS_MASK);
reg |= IOMUXC_SW_PAD_CTL_PAD_PUS(1);
reg |= (IOMUXC_SW_PAD_CTL_PAD_PKE_MASK | IOMUXC_SW_PAD_CTL_PAD_PUE_MASK);
break;
case PullUp_100K:
/* Write 1 to PKE & PUE bit to enable the pull configuration and 2 to PUS bit for 100K pull up*/
reg &= ~(IOMUXC_SW_PAD_CTL_PAD_PUS_MASK);
reg |= IOMUXC_SW_PAD_CTL_PAD_PUS(2);
reg |= (IOMUXC_SW_PAD_CTL_PAD_PKE_MASK | IOMUXC_SW_PAD_CTL_PAD_PUE_MASK);
break;
case PullUp_22K:
/* Write 1 to PKE & PUE bit to enable the pull configuration and 3 to PUS bit for 22K pull up*/
reg &= ~(IOMUXC_SW_PAD_CTL_PAD_PUS_MASK);
reg |= IOMUXC_SW_PAD_CTL_PAD_PUS(3);
reg |= (IOMUXC_SW_PAD_CTL_PAD_PKE_MASK | IOMUXC_SW_PAD_CTL_PAD_PUE_MASK);
break;
default:
break;
}
/* Below settings for DSE and SPEED fields per test results */
reg = (reg & ~(IOMUXC_SW_PAD_CTL_PAD_DSE_MASK | IOMUXC_SW_PAD_CTL_PAD_SPEED_MASK)) |
IOMUXC_SW_PAD_CTL_PAD_DSE(6) | IOMUXC_SW_PAD_CTL_PAD_SPEED(2);
/* Write value to the pad register */
*((volatile uint32_t *)configregister) = reg;
}
void pin_mode_opendrain(PinName pin, bool enable)
{
MBED_ASSERT(pin != (PinName)NC);
uint32_t instance = pin >> GPIO_PORT_SHIFT;
uint32_t muxregister = iomux_base_addrs[instance - 1];
uint32_t configregister;
if (muxregister == 0) {
muxregister = get_iomux_reg_base(pin);
} else {
muxregister = muxregister + ((pin & 0xFF) * 4);
}
/* Get pad register address */
if (instance == 5) {
configregister = muxregister + 0x10;
} else {
configregister = muxregister + 0x1F0;
}
if (enable) {
*((volatile uint32_t *)configregister) |= IOMUXC_SW_PAD_CTL_PAD_ODE_MASK;
} else {
*((volatile uint32_t *)configregister) &= ~IOMUXC_SW_PAD_CTL_PAD_ODE_MASK;
}
}

View File

@ -0,0 +1,87 @@
/* 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 "port_api.h"
#if DEVICE_PORTIN || DEVICE_PORTOUT
#include "pinmap.h"
#include "gpio_api.h"
/* Array of GPIO peripheral base address. */
static GPIO_Type *const port_addrs[] = GPIO_BASE_PTRS;
PinName port_pin(PortName port, int pin_n)
{
return (PinName)((port << GPIO_PORT_SHIFT) | pin_n);
}
void port_init(port_t *obj, PortName port, int mask, PinDirection dir)
{
obj->port = port;
obj->mask = mask;
// The function is set per pin: reuse gpio logic
for (uint32_t i = 0; i < 32; i++) {
if (obj->mask & (1 << i)) {
gpio_set(port_pin(obj->port, i));
}
}
port_dir(obj, dir);
}
void port_mode(port_t *obj, PinMode mode)
{
// The mode is set per pin: reuse pinmap logic
for (uint32_t i = 0; i < 32; i++) {
if (obj->mask & (1 << i)) {
pin_mode(port_pin(obj->port, i), mode);
}
}
}
void port_dir(port_t *obj, PinDirection dir)
{
GPIO_Type *base = port_addrs[obj->port];
uint32_t direction = base->GDIR;
switch (dir) {
case PIN_INPUT :
direction &= ~obj->mask;
break;
case PIN_OUTPUT:
direction |= obj->mask;
break;
}
base->GDIR = direction;
}
void port_write(port_t *obj, int value)
{
GPIO_Type *base = port_addrs[obj->port];
uint32_t input = base->DR & ~obj->mask;
base->DR = (input | (uint32_t)(value & obj->mask));
}
int port_read(port_t *obj)
{
GPIO_Type *base = port_addrs[obj->port];
return (int)(base->DR & obj->mask);
}
#endif

View File

@ -0,0 +1,199 @@
/* 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_pwm.h"
#include "PeripheralPins.h"
static float pwm_clock_mhz;
/* Array of PWM peripheral base address. */
static PWM_Type *const pwm_addrs[] = PWM_BASE_PTRS;
extern void pwm_setup_clock();
extern uint32_t pwm_get_clock();
void pwmout_init(pwmout_t* obj, PinName pin)
{
PWMName pwm = (PWMName)pinmap_peripheral(pin, PinMap_PWM);
MBED_ASSERT(pwm != (PWMName)NC);
pwm_setup_clock();
obj->pwm_name = pwm;
uint32_t pwm_base_clock;
pwm_base_clock = pwm_get_clock();
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 instance = (pwm >> PWM_SHIFT) & 0x3;
uint32_t module = pwm >> PWM_MODULE_SHIFT;
uint8_t pwmchannel = pwm & 0x1;
pwm_config_t pwmInfo;
PWM_GetDefaultConfig(&pwmInfo);
pwmInfo.prescale = (pwm_clock_prescale_t)clkdiv;
/* Initialize PWM module */
PWM_Init(pwm_addrs[instance], (pwm_submodule_t)module, &pwmInfo);
pwm_signal_param_t config = {
.level = kPWM_HighTrue,
.dutyCyclePercent = 0,
.deadtimeValue = 0
};
if (pwmchannel == 0) {
config.pwmChannel = kPWM_PwmA;
} else {
config.pwmChannel = kPWM_PwmB;
}
// default to 20ms: standard for servos, and fine for e.g. brightness control
PWM_SetupPwm(pwm_addrs[instance], (pwm_submodule_t)module, &config, 1, kPWM_EdgeAligned, 50, pwm_base_clock);
PWM_StartTimer(pwm_addrs[instance], module);
// Wire pinout
pinmap_pinout(pin, PinMap_PWM);
}
void pwmout_free(pwmout_t* obj)
{
uint32_t instance = (obj->pwm_name >> PWM_SHIFT) & 0x3;
uint32_t module = obj->pwm_name >> PWM_MODULE_SHIFT;
PWM_Deinit(pwm_addrs[instance], (pwm_submodule_t)module);
}
void pwmout_write(pwmout_t* obj, float value)
{
if (value < 0.0f) {
value = 0.0f;
} else if (value > 1.0f) {
value = 1.0f;
}
PWM_Type *base = pwm_addrs[(obj->pwm_name >> PWM_SHIFT) & 0x3];
uint32_t module = obj->pwm_name >> PWM_MODULE_SHIFT;
uint32_t pwmchannel = obj->pwm_name & 0xF;
uint16_t pulseCnt = 0;
pulseCnt = base->SM[module].VAL1;
uint32_t new_count = (uint32_t)((float)(pulseCnt) * value);
/* Setup the PWM dutycycle */
if (pwmchannel == 0) {
base->SM[module].VAL2 = 0;
base->SM[module].VAL3 = new_count;
} else {
base->SM[module].VAL4 = 0;
base->SM[module].VAL5 = new_count;
}
/* Set the load okay bit */
PWM_SetPwmLdok(base, module, true);
}
float pwmout_read(pwmout_t* obj)
{
PWM_Type *base = pwm_addrs[(obj->pwm_name >> PWM_SHIFT) & 0x3];
uint32_t module = obj->pwm_name >> PWM_MODULE_SHIFT;
uint32_t pwmchannel = obj->pwm_name & 0xF;
uint16_t count;
uint16_t mod = (base->SM[module].VAL1) & PWM_VAL1_VAL1_MASK;
if (pwmchannel == 0) {
count = (base->SM[module].VAL3) & PWM_VAL3_VAL3_MASK;
} else {
count = (base->SM[module].VAL5) & PWM_VAL5_VAL5_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)
{
PWM_Type *base = pwm_addrs[(obj->pwm_name >> PWM_SHIFT) & 0x3];
uint32_t module = obj->pwm_name >> PWM_MODULE_SHIFT;
float dc = pwmout_read(obj);
/* Indicates the end of the PWM period */
base->SM[module].VAL1 = PWM_VAL1_VAL1((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)
{
PWM_Type *base = pwm_addrs[(obj->pwm_name >> PWM_SHIFT) & 0x3];
uint32_t module = obj->pwm_name >> PWM_MODULE_SHIFT;
uint32_t pwmchannel = obj->pwm_name & 0xF;
uint32_t value = (uint32_t)(pwm_clock_mhz * (float)us);
/* Setup the PWM dutycycle */
if (pwmchannel == 0) {
base->SM[module].VAL2 = 0;
base->SM[module].VAL3 = value;
} else {
base->SM[module].VAL4 = 0;
base->SM[module].VAL5 = value;
}
/* Set the load okay bit */
PWM_SetPwmLdok(base, module, true);
}
#endif

View File

@ -0,0 +1,73 @@
/* 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 "rtc_api.h"
#if DEVICE_RTC
#include "fsl_snvs_hp.h"
void rtc_init(void)
{
snvs_hp_rtc_config_t snvsRtcConfig;
SNVS_HP_RTC_GetDefaultConfig(&snvsRtcConfig);
SNVS_HP_RTC_Init(SNVS, &snvsRtcConfig);
SNVS_HP_RTC_StartTimer(SNVS);
}
void rtc_free(void)
{
SNVS_HP_RTC_Deinit(SNVS);
}
/*
* Little check routine to see if the RTC has been enabled
* 0 = Disabled, 1 = Enabled
*/
int rtc_isenabled(void)
{
return (int)((SNVS->HPCR & SNVS_HPCR_RTC_EN_MASK) >> SNVS_HPCR_RTC_EN_SHIFT);
}
time_t rtc_read(void)
{
uint64_t seconds = 0;
uint64_t tmp = 0;
/* Do consecutive reads until value is correct */
do
{
seconds = tmp;
tmp = SNVS->HPRTCLR;
} while (tmp != seconds);
return (time_t)seconds;
}
void rtc_write(time_t t)
{
if (t == 0) {
t = 1;
}
SNVS_HP_RTC_StopTimer(SNVS);
SNVS->HPRTCLR = (uint32_t)t;
SNVS_HP_RTC_StartTimer(SNVS);
}
#endif

View File

@ -0,0 +1,287 @@
/* 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 "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;
int stdio_uart_inited = 0;
serial_t stdio_uart;
extern void serial_setup_clock(void);
extern uint32_t serial_get_clock(void);
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);
serial_setup_clock();
lpuart_config_t config;
LPUART_GetDefaultConfig(&config);
config.baudRate_Bps = 9600;
config.enableTx = false;
config.enableRx = false;
LPUART_Init(uart_addrs[obj->index], &config, serial_get_clock());
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, PullDefault);
}
if (rx != NC) {
LPUART_EnableRx(uart_addrs[obj->index], true);
pin_mode(rx, PullDefault);
}
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, serial_get_clock());
}
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 uart1_irq()
{
uint32_t status_flags = LPUART1->STAT;
uart_irq((status_flags & kLPUART_TxDataRegEmptyFlag), (status_flags & kLPUART_RxDataRegFullFlag), 1);
}
void uart2_irq()
{
uint32_t status_flags = LPUART2->STAT;
uart_irq((status_flags & kLPUART_TxDataRegEmptyFlag), (status_flags & kLPUART_RxDataRegFullFlag), 2);
}
void uart3_irq()
{
uint32_t status_flags = LPUART3->STAT;
uart_irq((status_flags & kLPUART_TxDataRegEmptyFlag), (status_flags & kLPUART_RxDataRegFullFlag), 3);
}
void uart4_irq()
{
uint32_t status_flags = LPUART4->STAT;
uart_irq((status_flags & kLPUART_TxDataRegEmptyFlag), (status_flags & kLPUART_RxDataRegFullFlag), 4);
}
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;
switch (obj->index) {
case 1:
vector = (uint32_t)&uart1_irq;
break;
case 2:
vector = (uint32_t)&uart2_irq;
break;
case 3:
vector = (uint32_t)&uart3_irq;
break;
case 4:
vector = (uint32_t)&uart4_irq;
break;
default:
break;
}
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,39 @@
/* 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 "sleep_api.h"
#include "cmsis.h"
#include "fsl_clock.h"
static void stop(void)
{
SCB->SCR |= SCB_SCR_SLEEPDEEP_Msk;
__asm("WFI");
}
void hal_sleep(void)
{
CLOCK_SetMode(kCLOCK_ModeWait);
stop();
}
void hal_deepsleep(void)
{
CLOCK_SetMode(kCLOCK_ModeStop);
stop();
}

View File

@ -0,0 +1,174 @@
/* 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_lpspi.h"
#include "PeripheralPins.h"
/* Array of SPI peripheral base address. */
static LPSPI_Type *const spi_address[] = LPSPI_BASE_PTRS;
extern uint32_t spi_get_clock(void);
extern void spi_setup_clock();
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);
}
spi_setup_clock();
}
void spi_free(spi_t *obj)
{
LPSPI_Deinit(spi_address[obj->instance]);
}
void spi_format(spi_t *obj, int bits, int mode, int slave)
{
lpspi_master_config_t master_config;
lpspi_slave_config_t slave_config;
if (slave) {
/* Slave config */
LPSPI_SlaveGetDefaultConfig(&slave_config);
slave_config.bitsPerFrame = (uint32_t)bits;;
slave_config.cpol = (mode & 0x2) ? kLPSPI_ClockPolarityActiveLow : kLPSPI_ClockPolarityActiveHigh;
slave_config.cpha = (mode & 0x1) ? kLPSPI_ClockPhaseSecondEdge : kLPSPI_ClockPhaseFirstEdge;
LPSPI_SlaveInit(spi_address[obj->instance], &slave_config);
} else {
/* Master config */
LPSPI_MasterGetDefaultConfig(&master_config);
master_config.bitsPerFrame = (uint32_t)bits;;
master_config.cpol = (mode & 0x2) ? kLPSPI_ClockPolarityActiveLow : kLPSPI_ClockPolarityActiveHigh;
master_config.cpha = (mode & 0x1) ? kLPSPI_ClockPhaseSecondEdge : kLPSPI_ClockPhaseFirstEdge;
master_config.direction = kLPSPI_MsbFirst;
LPSPI_MasterInit(spi_address[obj->instance], &master_config, spi_get_clock());
}
}
void spi_frequency(spi_t *obj, int hz)
{
uint32_t busClock = spi_get_clock();
uint32_t tcrPrescaleValue = 0;
LPSPI_Type *spibase = spi_address[obj->instance];
/* Disable the LPSPI module before setting the baudrate */
LPSPI_Enable(spibase, false);
LPSPI_MasterSetBaudRate(spibase, (uint32_t)hz, busClock, &tcrPrescaleValue);
spibase->TCR = (spibase->TCR & ~LPSPI_TCR_PRESCALE_MASK) | LPSPI_TCR_PRESCALE(tcrPrescaleValue);
/* Enable the LPSPI module */
LPSPI_Enable(spibase, true);
}
static inline int spi_readable(spi_t * obj)
{
return (LPSPI_GetStatusFlags(spi_address[obj->instance]) & kLPSPI_RxDataReadyFlag);
}
int spi_master_write(spi_t *obj, int value)
{
lpspi_transfer_t masterXfer;
uint32_t rx_data;
masterXfer.txData = (uint8_t *)&value;
masterXfer.rxData = NULL;
masterXfer.dataSize = 1;
masterXfer.configFlags = kLPSPI_MasterPcs0 | kLPSPI_MasterPcsContinuous | kLPSPI_SlaveByteSwap;
LPSPI_MasterTransferBlocking(spi_address[obj->instance], &masterXfer);
// wait rx buffer full
while (!spi_readable(obj));
rx_data = LPSPI_ReadData(spi_address[obj->instance]);
LPSPI_ClearStatusFlags(spi_address[obj->instance], kLPSPI_TransferCompleteFlag);
return rx_data & 0xffff;
}
int spi_master_block_write(spi_t *obj, const char *tx_buffer, int tx_length,
char *rx_buffer, int rx_length, char write_fill) {
int total = (tx_length > rx_length) ? tx_length : rx_length;
// Default write is done in each and every call, in future can create HAL API instead
LPSPI_SetDummyData(spi_address[obj->instance], write_fill);
LPSPI_MasterTransferBlocking(spi_address[obj->instance], &(lpspi_transfer_t){
.txData = (uint8_t *)tx_buffer,
.rxData = (uint8_t *)rx_buffer,
.dataSize = total,
.configFlags = kLPSPI_MasterPcs0 | kLPSPI_MasterPcsContinuous | kLPSPI_SlaveByteSwap,
});
return total;
}
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 = LPSPI_ReadData(spi_address[obj->instance]);
return rx_data & 0xffff;
}
void spi_slave_write(spi_t *obj, int value)
{
/*Write the word to TX register*/
LPSPI_WriteData(spi_address[obj->instance], (uint32_t)value);
/* Transfer is not complete until transfer complete flag sets */
while (!(LPSPI_GetStatusFlags(spi_address[obj->instance]) & kLPSPI_FrameCompleteFlag))
{
}
LPSPI_ClearStatusFlags(spi_address[obj->instance], kLPSPI_FrameCompleteFlag);
}
#endif

View File

@ -0,0 +1,102 @@
/* 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 "fsl_pit.h"
#include "fsl_clock_config.h"
static int us_ticker_inited = 0;
extern void us_ticker_setup_clock();
extern uint32_t us_ticker_get_clock();
static void pit_isr(void)
{
PIT_ClearStatusFlags(PIT, kPIT_Chnl_3, PIT_TFLG_TIF_MASK);
PIT_ClearStatusFlags(PIT, kPIT_Chnl_2, PIT_TFLG_TIF_MASK);
PIT_StopTimer(PIT, kPIT_Chnl_2);
PIT_StopTimer(PIT, kPIT_Chnl_3);
us_ticker_irq_handler();
}
void us_ticker_init(void)
{
if (us_ticker_inited) {
return;
}
us_ticker_inited = 1;
//Common for ticker/timer
uint32_t busClock;
// Structure to initialize PIT
pit_config_t pitConfig;
us_ticker_setup_clock();
PIT_GetDefaultConfig(&pitConfig);
PIT_Init(PIT, &pitConfig);
busClock = us_ticker_get_clock();
//Timer
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
PIT_SetTimerPeriod(PIT, kPIT_Chnl_2, busClock / 1000000 - 1);
PIT_SetTimerChainMode(PIT, kPIT_Chnl_3, true);
NVIC_SetVector(PIT_IRQn, (uint32_t)pit_isr);
NVIC_EnableIRQ(PIT_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)
{
PIT_DisableInterrupts(PIT, kPIT_Chnl_3, kPIT_TimerInterruptEnable);
}
void us_ticker_clear_interrupt(void)
{
PIT_ClearStatusFlags(PIT, kPIT_Chnl_3, PIT_TFLG_TIF_MASK);
}
void us_ticker_set_interrupt(timestamp_t timestamp)
{
uint32_t delta = timestamp - us_ticker_read();
PIT_StopTimer(PIT, kPIT_Chnl_3);
PIT_StopTimer(PIT, kPIT_Chnl_2);
PIT_SetTimerPeriod(PIT, kPIT_Chnl_3, (uint32_t)delta);
PIT_EnableInterrupts(PIT, kPIT_Chnl_3, kPIT_TimerInterruptEnable);
PIT_StartTimer(PIT, kPIT_Chnl_3);
PIT_StartTimer(PIT, kPIT_Chnl_2);
}
void us_ticker_fire_interrupt(void)
{
NVIC_SetPendingIRQ(PIT_IRQn);
}

View File

@ -0,0 +1,36 @@
/* 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_GPIO_OBJECT_H
#define MBED_GPIO_OBJECT_H
#ifdef __cplusplus
extern "C" {
#endif
typedef struct {
PinName pin;
} gpio_t;
static inline int gpio_is_connected(const gpio_t *obj)
{
return obj->pin != (PinName)NC;
}
#ifdef __cplusplus
}
#endif
#endif

View File

@ -0,0 +1,115 @@
/* 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 {
UART_1 = 1,
UART_2 = 2,
UART_3 = 3,
UART_4 = 4,
} UARTName;
#define STDIO_UART_TX USBTX
#define STDIO_UART_RX USBRX
#define STDIO_UART UART_1
#define DAISY_REG_SHIFT (4)
#define DAISY_REG_VALUE_SHIFT (16)
typedef enum {
I2C_1 = 1,
I2C_2 = 2,
I2C_3 = 3,
I2C_4 = 4,
} I2CName;
#define PWM_MODULE_SHIFT 2
#define PWM_SHIFT 8
typedef enum {
PWM_1 = (0 << PWM_SHIFT) | (0 << PWM_MODULE_SHIFT) | (0), // PWM1 Submodule 0 PWMA
PWM_2 = (0 << PWM_SHIFT) | (0 << PWM_MODULE_SHIFT) | (1), // PWM1 Submodule 0 PWMB
PWM_3 = (0 << PWM_SHIFT) | (1 << PWM_MODULE_SHIFT) | (0), // PWM1 Submodule 1 PWMA
PWM_4 = (0 << PWM_SHIFT) | (1 << PWM_MODULE_SHIFT) | (1), // PWM1 Submodule 1 PWMB
PWM_5 = (0 << PWM_SHIFT) | (2 << PWM_MODULE_SHIFT) | (0), // PWM1 Submodule 2 PWMA
PWM_6 = (0 << PWM_SHIFT) | (2 << PWM_MODULE_SHIFT) | (1), // PWM1 Submodule 2 PWMB
PWM_7 = (0 << PWM_SHIFT) | (3 << PWM_MODULE_SHIFT) | (0), // PWM1 Submodule 3 PWMA
PWM_8 = (0 << PWM_SHIFT) | (3 << PWM_MODULE_SHIFT) | (1), // PWM1 Submodule 3 PWMB
} PWMName;
#define ADC_INSTANCE_SHIFT 8
typedef enum {
ADC1_0 = (1 << ADC_INSTANCE_SHIFT | 0),
ADC1_1 = (1 << ADC_INSTANCE_SHIFT | 1),
ADC1_2 = (1 << ADC_INSTANCE_SHIFT | 2),
ADC1_3 = (1 << ADC_INSTANCE_SHIFT | 3),
ADC1_4 = (1 << ADC_INSTANCE_SHIFT | 4),
ADC1_5 = (1 << ADC_INSTANCE_SHIFT | 5),
ADC1_6 = (1 << ADC_INSTANCE_SHIFT | 6),
ADC1_7 = (1 << ADC_INSTANCE_SHIFT | 7),
ADC1_8 = (1 << ADC_INSTANCE_SHIFT | 8),
ADC1_9 = (1 << ADC_INSTANCE_SHIFT | 9),
ADC1_10 = (1 << ADC_INSTANCE_SHIFT | 10),
ADC1_11 = (1 << ADC_INSTANCE_SHIFT | 11),
ADC1_12 = (1 << ADC_INSTANCE_SHIFT | 12),
ADC1_13 = (1 << ADC_INSTANCE_SHIFT | 13),
ADC1_14 = (1 << ADC_INSTANCE_SHIFT | 14),
ADC1_15 = (1 << ADC_INSTANCE_SHIFT | 15),
ADC2_0 = (2 << ADC_INSTANCE_SHIFT | 0),
ADC2_1 = (2 << ADC_INSTANCE_SHIFT | 1),
ADC2_2 = (2 << ADC_INSTANCE_SHIFT | 2),
ADC2_3 = (2 << ADC_INSTANCE_SHIFT | 3),
ADC2_4 = (2 << ADC_INSTANCE_SHIFT | 4),
ADC2_5 = (2 << ADC_INSTANCE_SHIFT | 5),
ADC2_6 = (2 << ADC_INSTANCE_SHIFT | 6),
ADC2_7 = (2 << ADC_INSTANCE_SHIFT | 7),
ADC2_8 = (2 << ADC_INSTANCE_SHIFT | 8),
ADC2_9 = (2 << ADC_INSTANCE_SHIFT | 9),
ADC2_10 = (2 << ADC_INSTANCE_SHIFT | 10),
ADC2_11 = (2 << ADC_INSTANCE_SHIFT | 11),
ADC2_12 = (2 << ADC_INSTANCE_SHIFT | 12),
ADC2_13 = (2 << ADC_INSTANCE_SHIFT | 13),
ADC2_14 = (2 << ADC_INSTANCE_SHIFT | 14),
ADC2_15 = (2 << ADC_INSTANCE_SHIFT | 15),
} ADCName;
typedef enum {
DAC_0 = 0
} DACName;
typedef enum {
SPI_1 = 1,
SPI_2 = 2,
SPI_3 = 3,
} SPIName;
#ifdef __cplusplus
}
#endif
#endif

View File

@ -0,0 +1,89 @@
/* 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[] = {
{GPIO_AD_B1_11, ADC1_0, 0},
{GPIO_AD_B1_04, ADC1_9, 0},
{NC , NC , 0}
};
/************DAC***************/
const PinMap PinMap_DAC[] = {
{NC , NC , 0}
};
/************I2C***************/
const PinMap PinMap_I2C_SDA[] = {
{GPIO_AD_B1_01, I2C_1, ((1U << DAISY_REG_VALUE_SHIFT) | (0x4D0 << DAISY_REG_SHIFT) | 3)},
{NC , NC , 0}
};
const PinMap PinMap_I2C_SCL[] = {
{GPIO_AD_B1_00, I2C_1, ((1U << DAISY_REG_VALUE_SHIFT) | (0x4CC << DAISY_REG_SHIFT) | 3)},
{NC , NC , 0}
};
/************UART***************/
const PinMap PinMap_UART_TX[] = {
{GPIO_AD_B0_12, UART_1, 2},
{NC , NC , 0}
};
const PinMap PinMap_UART_RX[] = {
{GPIO_AD_B0_13, UART_1, 2},
{NC , NC , 0}
};
/************SPI***************/
const PinMap PinMap_SPI_SCLK[] = {
{GPIO_SD_B0_00, SPI_1, ((1U << DAISY_REG_VALUE_SHIFT) | (0x4F0 << DAISY_REG_SHIFT) | 4)},
{GPIO_AD_B0_00, SPI_3, ((0U << DAISY_REG_VALUE_SHIFT) | (0x510 << DAISY_REG_SHIFT) | 7)},
{NC , NC , 0}
};
const PinMap PinMap_SPI_MOSI[] = {
{GPIO_SD_B0_02, SPI_1, ((1U << DAISY_REG_VALUE_SHIFT) | (0x4F8 << DAISY_REG_SHIFT) | 4)},
{GPIO_AD_B0_01, SPI_3, ((0U << DAISY_REG_VALUE_SHIFT) | (0x518 << DAISY_REG_SHIFT) | 7)},
{NC , NC , 0}
};
const PinMap PinMap_SPI_MISO[] = {
{GPIO_SD_B0_03, SPI_1, ((1U << DAISY_REG_VALUE_SHIFT) | (0x4F4 << DAISY_REG_SHIFT) | 4)},
{GPIO_AD_B0_02, SPI_3, ((0U << DAISY_REG_VALUE_SHIFT) | (0x514 << DAISY_REG_SHIFT) | 7)},
{NC , NC , 0}
};
const PinMap PinMap_SPI_SSEL[] = {
{GPIO_SD_B0_01, SPI_1, ((0U << DAISY_REG_VALUE_SHIFT) | (0x4EC << DAISY_REG_SHIFT) | 4)},
{GPIO_AD_B0_03, SPI_3, ((0U << DAISY_REG_VALUE_SHIFT) | (0x50C << DAISY_REG_SHIFT) | 7)},
{NC , NC , 0}
};
/************PWM***************/
const PinMap PinMap_PWM[] = {
{GPIO_AD_B0_10, PWM_7, ((3U << DAISY_REG_VALUE_SHIFT) | (0x454 << DAISY_REG_SHIFT) | 1)},
{GPIO_AD_B0_11, PWM_8, ((3U << DAISY_REG_VALUE_SHIFT) | (0x464 << DAISY_REG_SHIFT) | 1)},
{NC , NC , 0}
};

View File

@ -0,0 +1,227 @@
/* 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
#define GPIO_MUX_PORT 5
typedef enum {
WAKEUP = ((5 << GPIO_PORT_SHIFT) | 0),
PMIC_ON_REQ = ((5 << GPIO_PORT_SHIFT) | 1),
PMIC_STBY_REQ = ((5 << GPIO_PORT_SHIFT) | 2),
GPIO_EMC_00 = ((4 << GPIO_PORT_SHIFT) | 0),
GPIO_EMC_01 = ((4 << GPIO_PORT_SHIFT) | 1),
GPIO_EMC_02 = ((4 << GPIO_PORT_SHIFT) | 2),
GPIO_EMC_03 = ((4 << GPIO_PORT_SHIFT) | 3),
GPIO_EMC_04 = ((4 << GPIO_PORT_SHIFT) | 4),
GPIO_EMC_05 = ((4 << GPIO_PORT_SHIFT) | 5),
GPIO_EMC_06 = ((4 << GPIO_PORT_SHIFT) | 6),
GPIO_EMC_07 = ((4 << GPIO_PORT_SHIFT) | 7),
GPIO_EMC_08 = ((4 << GPIO_PORT_SHIFT) | 8),
GPIO_EMC_09 = ((4 << GPIO_PORT_SHIFT) | 9),
GPIO_EMC_10 = ((4 << GPIO_PORT_SHIFT) | 10),
GPIO_EMC_11 = ((4 << GPIO_PORT_SHIFT) | 11),
GPIO_EMC_12 = ((4 << GPIO_PORT_SHIFT) | 12),
GPIO_EMC_13 = ((4 << GPIO_PORT_SHIFT) | 13),
GPIO_EMC_14 = ((4 << GPIO_PORT_SHIFT) | 14),
GPIO_EMC_15 = ((4 << GPIO_PORT_SHIFT) | 15),
GPIO_EMC_16 = ((4 << GPIO_PORT_SHIFT) | 16),
GPIO_EMC_17 = ((4 << GPIO_PORT_SHIFT) | 17),
GPIO_EMC_18 = ((4 << GPIO_PORT_SHIFT) | 18),
GPIO_EMC_19 = ((4 << GPIO_PORT_SHIFT) | 19),
GPIO_EMC_20 = ((4 << GPIO_PORT_SHIFT) | 20),
GPIO_EMC_21 = ((4 << GPIO_PORT_SHIFT) | 21),
GPIO_EMC_22 = ((4 << GPIO_PORT_SHIFT) | 22),
GPIO_EMC_23 = ((4 << GPIO_PORT_SHIFT) | 23),
GPIO_EMC_24 = ((4 << GPIO_PORT_SHIFT) | 24),
GPIO_EMC_25 = ((4 << GPIO_PORT_SHIFT) | 25),
GPIO_EMC_26 = ((4 << GPIO_PORT_SHIFT) | 26),
GPIO_EMC_27 = ((4 << GPIO_PORT_SHIFT) | 27),
GPIO_EMC_28 = ((4 << GPIO_PORT_SHIFT) | 28),
GPIO_EMC_29 = ((4 << GPIO_PORT_SHIFT) | 29),
GPIO_EMC_30 = ((4 << GPIO_PORT_SHIFT) | 30),
GPIO_EMC_31 = ((4 << GPIO_PORT_SHIFT) | 31),
GPIO_EMC_32 = ((3 << GPIO_PORT_SHIFT) | 18),
GPIO_EMC_33 = ((3 << GPIO_PORT_SHIFT) | 19),
GPIO_EMC_34 = ((3 << GPIO_PORT_SHIFT) | 20),
GPIO_EMC_35 = ((3 << GPIO_PORT_SHIFT) | 21),
GPIO_EMC_36 = ((3 << GPIO_PORT_SHIFT) | 22),
GPIO_EMC_37 = ((3 << GPIO_PORT_SHIFT) | 23),
GPIO_EMC_38 = ((3 << GPIO_PORT_SHIFT) | 24),
GPIO_EMC_39 = ((3 << GPIO_PORT_SHIFT) | 25),
GPIO_EMC_40 = ((3 << GPIO_PORT_SHIFT) | 26),
GPIO_EMC_41 = ((3 << GPIO_PORT_SHIFT) | 27),
GPIO_AD_B0_00 = ((1 << GPIO_PORT_SHIFT) | 0),
GPIO_AD_B0_01 = ((1 << GPIO_PORT_SHIFT) | 1),
GPIO_AD_B0_02 = ((1 << GPIO_PORT_SHIFT) | 2),
GPIO_AD_B0_03 = ((1 << GPIO_PORT_SHIFT) | 3),
GPIO_AD_B0_04 = ((1 << GPIO_PORT_SHIFT) | 4),
GPIO_AD_B0_05 = ((1 << GPIO_PORT_SHIFT) | 5),
GPIO_AD_B0_06 = ((1 << GPIO_PORT_SHIFT) | 6),
GPIO_AD_B0_07 = ((1 << GPIO_PORT_SHIFT) | 7),
GPIO_AD_B0_08 = ((1 << GPIO_PORT_SHIFT) | 8),
GPIO_AD_B0_09 = ((1 << GPIO_PORT_SHIFT) | 9),
GPIO_AD_B0_10 = ((1 << GPIO_PORT_SHIFT) | 10),
GPIO_AD_B0_11 = ((1 << GPIO_PORT_SHIFT) | 11),
GPIO_AD_B0_12 = ((1 << GPIO_PORT_SHIFT) | 12),
GPIO_AD_B0_13 = ((1 << GPIO_PORT_SHIFT) | 13),
GPIO_AD_B0_14 = ((1 << GPIO_PORT_SHIFT) | 14),
GPIO_AD_B0_15 = ((1 << GPIO_PORT_SHIFT) | 15),
GPIO_AD_B1_00 = ((1 << GPIO_PORT_SHIFT) | 16),
GPIO_AD_B1_01 = ((1 << GPIO_PORT_SHIFT) | 17),
GPIO_AD_B1_02 = ((1 << GPIO_PORT_SHIFT) | 18),
GPIO_AD_B1_03 = ((1 << GPIO_PORT_SHIFT) | 19),
GPIO_AD_B1_04 = ((1 << GPIO_PORT_SHIFT) | 20),
GPIO_AD_B1_05 = ((1 << GPIO_PORT_SHIFT) | 21),
GPIO_AD_B1_06 = ((1 << GPIO_PORT_SHIFT) | 22),
GPIO_AD_B1_07 = ((1 << GPIO_PORT_SHIFT) | 23),
GPIO_AD_B1_08 = ((1 << GPIO_PORT_SHIFT) | 24),
GPIO_AD_B1_09 = ((1 << GPIO_PORT_SHIFT) | 25),
GPIO_AD_B1_10 = ((1 << GPIO_PORT_SHIFT) | 26),
GPIO_AD_B1_11 = ((1 << GPIO_PORT_SHIFT) | 27),
GPIO_AD_B1_12 = ((1 << GPIO_PORT_SHIFT) | 28),
GPIO_AD_B1_13 = ((1 << GPIO_PORT_SHIFT) | 29),
GPIO_AD_B1_14 = ((1 << GPIO_PORT_SHIFT) | 30),
GPIO_AD_B1_15 = ((1 << GPIO_PORT_SHIFT) | 31),
GPIO_B0_00 = ((2 << GPIO_PORT_SHIFT) | 0),
GPIO_B0_01 = ((2 << GPIO_PORT_SHIFT) | 1),
GPIO_B0_02 = ((2 << GPIO_PORT_SHIFT) | 2),
GPIO_B0_03 = ((2 << GPIO_PORT_SHIFT) | 3),
GPIO_B0_04 = ((2 << GPIO_PORT_SHIFT) | 4),
GPIO_B0_05 = ((2 << GPIO_PORT_SHIFT) | 5),
GPIO_B0_06 = ((2 << GPIO_PORT_SHIFT) | 6),
GPIO_B0_07 = ((2 << GPIO_PORT_SHIFT) | 7),
GPIO_B0_08 = ((2 << GPIO_PORT_SHIFT) | 8),
GPIO_B0_09 = ((2 << GPIO_PORT_SHIFT) | 9),
GPIO_B0_10 = ((2 << GPIO_PORT_SHIFT) | 10),
GPIO_B0_11 = ((2 << GPIO_PORT_SHIFT) | 11),
GPIO_B0_12 = ((2 << GPIO_PORT_SHIFT) | 12),
GPIO_B0_13 = ((2 << GPIO_PORT_SHIFT) | 13),
GPIO_B0_14 = ((2 << GPIO_PORT_SHIFT) | 14),
GPIO_B0_15 = ((2 << GPIO_PORT_SHIFT) | 15),
GPIO_B1_00 = ((2 << GPIO_PORT_SHIFT) | 16),
GPIO_B1_01 = ((2 << GPIO_PORT_SHIFT) | 17),
GPIO_B1_02 = ((2 << GPIO_PORT_SHIFT) | 18),
GPIO_B1_03 = ((2 << GPIO_PORT_SHIFT) | 19),
GPIO_B1_04 = ((2 << GPIO_PORT_SHIFT) | 20),
GPIO_B1_05 = ((2 << GPIO_PORT_SHIFT) | 21),
GPIO_B1_06 = ((2 << GPIO_PORT_SHIFT) | 22),
GPIO_B1_07 = ((2 << GPIO_PORT_SHIFT) | 23),
GPIO_B1_08 = ((2 << GPIO_PORT_SHIFT) | 24),
GPIO_B1_09 = ((2 << GPIO_PORT_SHIFT) | 25),
GPIO_B1_10 = ((2 << GPIO_PORT_SHIFT) | 26),
GPIO_B1_11 = ((2 << GPIO_PORT_SHIFT) | 27),
GPIO_B1_12 = ((2 << GPIO_PORT_SHIFT) | 28),
GPIO_B1_13 = ((2 << GPIO_PORT_SHIFT) | 29),
GPIO_B1_14 = ((2 << GPIO_PORT_SHIFT) | 30),
GPIO_B1_15 = ((2 << GPIO_PORT_SHIFT) | 31),
GPIO_SD_B0_00 = ((3 << GPIO_PORT_SHIFT) | 12),
GPIO_SD_B0_01 = ((3 << GPIO_PORT_SHIFT) | 13),
GPIO_SD_B0_02 = ((3 << GPIO_PORT_SHIFT) | 14),
GPIO_SD_B0_03 = ((3 << GPIO_PORT_SHIFT) | 15),
GPIO_SD_B0_04 = ((3 << GPIO_PORT_SHIFT) | 16),
GPIO_SD_B0_05 = ((3 << GPIO_PORT_SHIFT) | 17),
GPIO_SD_B1_00 = ((3 << GPIO_PORT_SHIFT) | 0),
GPIO_SD_B1_01 = ((3 << GPIO_PORT_SHIFT) | 1),
GPIO_SD_B1_02 = ((3 << GPIO_PORT_SHIFT) | 2),
GPIO_SD_B1_03 = ((3 << GPIO_PORT_SHIFT) | 3),
GPIO_SD_B1_04 = ((3 << GPIO_PORT_SHIFT) | 4),
GPIO_SD_B1_05 = ((3 << GPIO_PORT_SHIFT) | 5),
GPIO_SD_B1_06 = ((3 << GPIO_PORT_SHIFT) | 6),
GPIO_SD_B1_07 = ((3 << GPIO_PORT_SHIFT) | 7),
GPIO_SD_B1_08 = ((3 << GPIO_PORT_SHIFT) | 8),
GPIO_SD_B1_09 = ((3 << GPIO_PORT_SHIFT) | 9),
GPIO_SD_B1_10 = ((3 << GPIO_PORT_SHIFT) | 10),
GPIO_SD_B1_11 = ((3 << GPIO_PORT_SHIFT) | 11),
LED_GREEN = GPIO_AD_B0_09,
// mbed original LED naming
LED1 = LED_GREEN,
LED2 = LED_GREEN,
LED3 = LED_GREEN,
LED4 = LED_GREEN,
// USB Pins
USBTX = GPIO_AD_B0_12,
USBRX = GPIO_AD_B0_13,
// Arduino Headers
D0 = GPIO_AD_B1_07,
D1 = GPIO_AD_B1_06,
D2 = GPIO_AD_B0_11,
D3 = GPIO_AD_B1_08,
D4 = GPIO_AD_B0_09,
D5 = GPIO_AD_B0_10,
D6 = GPIO_AD_B1_02,
D7 = GPIO_AD_B1_03,
D8 = GPIO_AD_B0_03,
D9 = GPIO_AD_B0_02,
D10 = GPIO_SD_B0_01,
D11 = GPIO_SD_B0_02,
D12 = GPIO_SD_B0_03,
D13 = GPIO_SD_B0_00,
D14 = GPIO_AD_B0_01,
D15 = GPIO_AD_B0_00,
I2C_SCL = D15,
I2C_SDA = D14,
A0 = GPIO_AD_B1_10,
A1 = GPIO_AD_B1_11,
A2 = GPIO_AD_B1_04,
A3 = GPIO_AD_B1_05,
A4 = GPIO_AD_B1_01,
A5 = GPIO_AD_B1_00,
// Not connected
NC = (int)0xFFFFFFFF
} PinName;
typedef enum {
PullNone = 0,
PullDown = 1,
PullUp_47K = 2,
PullUp_100K = 3,
PullUp_22K = 4,
PullDefault = PullUp_47K
} PinMode;
#ifdef __cplusplus
}
#endif
#endif

View File

@ -0,0 +1,25 @@
// 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,107 @@
/*
* Copyright 2017 NXP
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include "fsl_common.h"
#include "fsl_clock_config.h"
/*******************************************************************************
* Definitions
******************************************************************************/
/* ARM PLL configuration for RUN mode */
const clock_arm_pll_config_t armPllConfig = {.loopDivider = 100U};
/* SYS PLL configuration for RUN mode */
const clock_sys_pll_config_t sysPllConfig = {.loopDivider = 1U};
/* USB1 PLL configuration for RUN mode */
const clock_usb_pll_config_t usb1PllConfig = {.loopDivider = 0U};
/*******************************************************************************
* Variables
******************************************************************************/
/* System clock frequency. */
extern uint32_t SystemCoreClock;
/*******************************************************************************
* Code
******************************************************************************/
static void BOARD_BootClockGate(void)
{
/* Disable all unused peripheral clock */
CCM->CCGR0 = 0x00C0000FU;
CCM->CCGR1 = 0x30000000U;
CCM->CCGR2 = 0xFF3F303FU;
CCM->CCGR3 = 0xF0000330U;
CCM->CCGR4 = 0x0000FF3CU;
CCM->CCGR5 = 0xF003330FU;
CCM->CCGR6 = 0x00FC0F00U;
}
void BOARD_BootClockRUN(void)
{
/* Boot ROM did initialize the XTAL, here we only sets external XTAL OSC freq */
CLOCK_SetXtalFreq(24000000U);
CLOCK_SetRtcXtalFreq(32768U);
CLOCK_SetMux(kCLOCK_PeriphClk2Mux, 0x1); /* Set PERIPH_CLK2 MUX to OSC */
CLOCK_SetMux(kCLOCK_PeriphMux, 0x1); /* Set PERIPH_CLK MUX to PERIPH_CLK2 */
/* Setting the VDD_SOC to 1.5V. It is necessary to config AHB to 600Mhz */
DCDC->REG3 = (DCDC->REG3 & (~DCDC_REG3_TRG_MASK)) | DCDC_REG3_TRG(0x12);
CLOCK_InitArmPll(&armPllConfig); /* Configure ARM PLL to 1200M */
#ifndef SKIP_SYSCLK_INIT
CLOCK_InitSysPll(&sysPllConfig); /* Configure SYS PLL to 528M */
#endif
#ifndef SKIP_USB_PLL_INIT
CLOCK_InitUsb1Pll(&usb1PllConfig); /* Configure USB1 PLL to 480M */
#endif
CLOCK_SetDiv(kCLOCK_ArmDiv, 0x1); /* Set ARM PODF to 0, divide by 2 */
CLOCK_SetDiv(kCLOCK_AhbDiv, 0x0); /* Set AHB PODF to 0, divide by 1 */
CLOCK_SetDiv(kCLOCK_IpgDiv, 0x3); /* Set IPG PODF to 3, divede by 4 */
CLOCK_SetMux(kCLOCK_PrePeriphMux, 0x3); /* Set PRE_PERIPH_CLK to PLL1, 1200M */
CLOCK_SetMux(kCLOCK_PeriphMux, 0x0); /* Set PERIPH_CLK MUX to PRE_PERIPH_CLK */
/* Disable unused clock */
BOARD_BootClockGate();
/* Power down all unused PLL */
CLOCK_DeinitAudioPll();
CLOCK_DeinitVideoPll();
CLOCK_DeinitEnetPll();
CLOCK_DeinitUsb2Pll();
/* Configure UART divider to default */
CLOCK_SetMux(kCLOCK_UartMux, 0); /* Set UART source to PLL3 80M */
CLOCK_SetDiv(kCLOCK_UartDiv, 0); /* Set UART divider to 1 */
/* Update core clock */
SystemCoreClockUpdate();
}

View File

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

View File

@ -0,0 +1,336 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* Copyright 2016-2017 NXP
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include "fsl_phy.h"
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @brief Defines the timeout macro. */
#define PHY_TIMEOUT_COUNT 0x3FFFFFFU
/*******************************************************************************
* Prototypes
******************************************************************************/
/*!
* @brief Get the ENET instance from peripheral base address.
*
* @param base ENET peripheral base address.
* @return ENET instance.
*/
extern uint32_t ENET_GetInstance(ENET_Type *base);
/*******************************************************************************
* Variables
******************************************************************************/
#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
/*! @brief Pointers to enet clocks for each instance. */
extern clock_ip_name_t s_enetClock[FSL_FEATURE_SOC_ENET_COUNT];
#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
/*******************************************************************************
* Code
******************************************************************************/
status_t PHY_Init(ENET_Type *base, uint32_t phyAddr, uint32_t srcClock_Hz)
{
uint32_t bssReg;
uint32_t counter = PHY_TIMEOUT_COUNT;
uint32_t idReg = 0;
status_t result = kStatus_Success;
uint32_t instance = ENET_GetInstance(base);
uint32_t timeDelay;
uint32_t ctlReg = 0;
#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
/* Set SMI first. */
CLOCK_EnableClock(s_enetClock[instance]);
#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
ENET_SetSMI(base, srcClock_Hz, false);
/* Initialization after PHY stars to work. */
while ((idReg != PHY_CONTROL_ID1) && (counter != 0))
{
PHY_Read(base, phyAddr, PHY_ID1_REG, &idReg);
counter --;
}
if (!counter)
{
return kStatus_Fail;
}
/* Reset PHY. */
counter = PHY_TIMEOUT_COUNT;
result = PHY_Write(base, phyAddr, PHY_BASICCONTROL_REG, PHY_BCTL_RESET_MASK);
if (result == kStatus_Success)
{
#if defined(FSL_FEATURE_PHYKSZ8081_USE_RMII50M_MODE)
uint32_t data = 0;
result = PHY_Read(base, phyAddr, PHY_CONTROL2_REG, &data);
if ( result != kStatus_Success)
{
return result;
}
result = PHY_Write(base, phyAddr, PHY_CONTROL2_REG, (data | PHY_CTL2_REFCLK_SELECT_MASK));
if (result != kStatus_Success)
{
return result;
}
#endif /* FSL_FEATURE_PHYKSZ8081_USE_RMII50M_MODE */
/* Set the negotiation. */
result = PHY_Write(base, phyAddr, PHY_AUTONEG_ADVERTISE_REG,
(PHY_100BASETX_FULLDUPLEX_MASK | PHY_100BASETX_HALFDUPLEX_MASK |
PHY_10BASETX_FULLDUPLEX_MASK | PHY_10BASETX_HALFDUPLEX_MASK | 0x1U));
if (result == kStatus_Success)
{
result = PHY_Write(base, phyAddr, PHY_BASICCONTROL_REG,
(PHY_BCTL_AUTONEG_MASK | PHY_BCTL_RESTART_AUTONEG_MASK));
if (result == kStatus_Success)
{
/* Check auto negotiation complete. */
while (counter --)
{
result = PHY_Read(base, phyAddr, PHY_BASICSTATUS_REG, &bssReg);
if ( result == kStatus_Success)
{
PHY_Read(base, phyAddr, PHY_CONTROL1_REG, &ctlReg);
if (((bssReg & PHY_BSTATUS_AUTONEGCOMP_MASK) != 0) && (ctlReg & PHY_LINK_READY_MASK))
{
/* Wait a moment for Phy status stable. */
for (timeDelay = 0; timeDelay < PHY_TIMEOUT_COUNT; timeDelay ++)
{
__ASM("nop");
}
break;
}
}
if (!counter)
{
return kStatus_PHY_AutoNegotiateFail;
}
}
}
}
}
return result;
}
status_t PHY_Write(ENET_Type *base, uint32_t phyAddr, uint32_t phyReg, uint32_t data)
{
uint32_t counter;
/* Clear the SMI interrupt event. */
ENET_ClearInterruptStatus(base, ENET_EIR_MII_MASK);
/* Starts a SMI write command. */
ENET_StartSMIWrite(base, phyAddr, phyReg, kENET_MiiWriteValidFrame, data);
/* Wait for SMI complete. */
for (counter = PHY_TIMEOUT_COUNT; counter > 0; counter--)
{
if (ENET_GetInterruptStatus(base) & ENET_EIR_MII_MASK)
{
break;
}
}
/* Check for timeout. */
if (!counter)
{
return kStatus_PHY_SMIVisitTimeout;
}
/* Clear MII interrupt event. */
ENET_ClearInterruptStatus(base, ENET_EIR_MII_MASK);
return kStatus_Success;
}
status_t PHY_Read(ENET_Type *base, uint32_t phyAddr, uint32_t phyReg, uint32_t *dataPtr)
{
assert(dataPtr);
uint32_t counter;
/* Clear the MII interrupt event. */
ENET_ClearInterruptStatus(base, ENET_EIR_MII_MASK);
/* Starts a SMI read command operation. */
ENET_StartSMIRead(base, phyAddr, phyReg, kENET_MiiReadValidFrame);
/* Wait for MII complete. */
for (counter = PHY_TIMEOUT_COUNT; counter > 0; counter--)
{
if (ENET_GetInterruptStatus(base) & ENET_EIR_MII_MASK)
{
break;
}
}
/* Check for timeout. */
if (!counter)
{
return kStatus_PHY_SMIVisitTimeout;
}
/* Get data from MII register. */
*dataPtr = ENET_ReadSMIData(base);
/* Clear MII interrupt event. */
ENET_ClearInterruptStatus(base, ENET_EIR_MII_MASK);
return kStatus_Success;
}
status_t PHY_EnableLoopback(ENET_Type *base, uint32_t phyAddr, phy_loop_t mode, phy_speed_t speed, bool enable)
{
status_t result;
uint32_t data = 0;
/* Set the loop mode. */
if (enable)
{
if (mode == kPHY_LocalLoop)
{
if (speed == kPHY_Speed100M)
{
data = PHY_BCTL_SPEED_100M_MASK | PHY_BCTL_DUPLEX_MASK | PHY_BCTL_LOOP_MASK;
}
else
{
data = PHY_BCTL_DUPLEX_MASK | PHY_BCTL_LOOP_MASK;
}
return PHY_Write(base, phyAddr, PHY_BASICCONTROL_REG, data);
}
else
{
/* First read the current status in control register. */
result = PHY_Read(base, phyAddr, PHY_CONTROL2_REG, &data);
if (result == kStatus_Success)
{
return PHY_Write(base, phyAddr, PHY_CONTROL2_REG, (data | PHY_CTL2_REMOTELOOP_MASK));
}
}
}
else
{
/* Disable the loop mode. */
if (mode == kPHY_LocalLoop)
{
/* First read the current status in control register. */
result = PHY_Read(base, phyAddr, PHY_BASICCONTROL_REG, &data);
if (result == kStatus_Success)
{
data &= ~PHY_BCTL_LOOP_MASK;
return PHY_Write(base, phyAddr, PHY_BASICCONTROL_REG, (data | PHY_BCTL_RESTART_AUTONEG_MASK));
}
}
else
{
/* First read the current status in control one register. */
result = PHY_Read(base, phyAddr, PHY_CONTROL2_REG, &data);
if (result == kStatus_Success)
{
return PHY_Write(base, phyAddr, PHY_CONTROL2_REG, (data & ~PHY_CTL2_REMOTELOOP_MASK));
}
}
}
return result;
}
status_t PHY_GetLinkStatus(ENET_Type *base, uint32_t phyAddr, bool *status)
{
assert(status);
status_t result = kStatus_Success;
uint32_t data;
/* Read the basic status register. */
result = PHY_Read(base, phyAddr, PHY_BASICSTATUS_REG, &data);
if (result == kStatus_Success)
{
if (!(PHY_BSTATUS_LINKSTATUS_MASK & data))
{
/* link down. */
*status = false;
}
else
{
/* link up. */
*status = true;
}
}
return result;
}
status_t PHY_GetLinkSpeedDuplex(ENET_Type *base, uint32_t phyAddr, phy_speed_t *speed, phy_duplex_t *duplex)
{
assert(duplex);
status_t result = kStatus_Success;
uint32_t data, ctlReg;
/* Read the control two register. */
result = PHY_Read(base, phyAddr, PHY_CONTROL1_REG, &ctlReg);
if (result == kStatus_Success)
{
data = ctlReg & PHY_CTL1_SPEEDUPLX_MASK;
if ((PHY_CTL1_10FULLDUPLEX_MASK == data) || (PHY_CTL1_100FULLDUPLEX_MASK == data))
{
/* Full duplex. */
*duplex = kPHY_FullDuplex;
}
else
{
/* Half duplex. */
*duplex = kPHY_HalfDuplex;
}
data = ctlReg & PHY_CTL1_SPEEDUPLX_MASK;
if ((PHY_CTL1_100HALFDUPLEX_MASK == data) || (PHY_CTL1_100FULLDUPLEX_MASK == data))
{
/* 100M speed. */
*speed = kPHY_Speed100M;
}
else
{ /* 10M speed. */
*speed = kPHY_Speed10M;
}
}
return result;
}

View File

@ -0,0 +1,222 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* Copyright 2016-2017 NXP
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _FSL_PHY_H_
#define _FSL_PHY_H_
#include "fsl_enet.h"
/*!
* @addtogroup phy_driver
* @{
*/
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @brief PHY driver version */
#define FSL_PHY_DRIVER_VERSION (MAKE_VERSION(2, 0, 0)) /*!< Version 2.0.0. */
/*! @brief Defines the PHY registers. */
#define PHY_BASICCONTROL_REG 0x00U /*!< The PHY basic control register. */
#define PHY_BASICSTATUS_REG 0x01U /*!< The PHY basic status register. */
#define PHY_ID1_REG 0x02U /*!< The PHY ID one register. */
#define PHY_ID2_REG 0x03U /*!< The PHY ID two register. */
#define PHY_AUTONEG_ADVERTISE_REG 0x04U /*!< The PHY auto-negotiate advertise register. */
#define PHY_CONTROL1_REG 0x1EU /*!< The PHY control one register. */
#define PHY_CONTROL2_REG 0x1FU /*!< The PHY control two register. */
#define PHY_CONTROL_ID1 0x22U /*!< The PHY ID1*/
/*! @brief Defines the mask flag in basic control register. */
#define PHY_BCTL_DUPLEX_MASK 0x0100U /*!< The PHY duplex bit mask. */
#define PHY_BCTL_RESTART_AUTONEG_MASK 0x0200U /*!< The PHY restart auto negotiation mask. */
#define PHY_BCTL_AUTONEG_MASK 0x1000U /*!< The PHY auto negotiation bit mask. */
#define PHY_BCTL_SPEED_MASK 0x2000U /*!< The PHY speed bit mask. */
#define PHY_BCTL_LOOP_MASK 0x4000U /*!< The PHY loop bit mask. */
#define PHY_BCTL_RESET_MASK 0x8000U /*!< The PHY reset bit mask. */
#define PHY_BCTL_SPEED_100M_MASK 0x2000U /*!< The PHY 100M speed mask. */
/*!@brief Defines the mask flag of operation mode in control two register*/
#define PHY_CTL2_REMOTELOOP_MASK 0x0004U /*!< The PHY remote loopback mask. */
#define PHY_CTL2_REFCLK_SELECT_MASK 0x0080U /*!< The PHY RMII reference clock select. */
#define PHY_CTL1_10HALFDUPLEX_MASK 0x0001U /*!< The PHY 10M half duplex mask. */
#define PHY_CTL1_100HALFDUPLEX_MASK 0x0002U /*!< The PHY 100M half duplex mask. */
#define PHY_CTL1_10FULLDUPLEX_MASK 0x0005U /*!< The PHY 10M full duplex mask. */
#define PHY_CTL1_100FULLDUPLEX_MASK 0x0006U /*!< The PHY 100M full duplex mask. */
#define PHY_CTL1_SPEEDUPLX_MASK 0x0007U /*!< The PHY speed and duplex mask. */
#define PHY_CTL1_ENERGYDETECT_MASK 0x10U /*!< The PHY signal present on rx differential pair. */
#define PHY_CTL1_LINKUP_MASK 0x100U /*!< The PHY link up. */
#define PHY_LINK_READY_MASK (PHY_CTL1_ENERGYDETECT_MASK | PHY_CTL1_LINKUP_MASK)
/*! @brief Defines the mask flag in basic status register. */
#define PHY_BSTATUS_LINKSTATUS_MASK 0x0004U /*!< The PHY link status mask. */
#define PHY_BSTATUS_AUTONEGABLE_MASK 0x0008U /*!< The PHY auto-negotiation ability mask. */
#define PHY_BSTATUS_AUTONEGCOMP_MASK 0x0020U /*!< The PHY auto-negotiation complete mask. */
/*! @brief Defines the mask flag in PHY auto-negotiation advertise register. */
#define PHY_100BaseT4_ABILITY_MASK 0x200U /*!< The PHY have the T4 ability. */
#define PHY_100BASETX_FULLDUPLEX_MASK 0x100U /*!< The PHY has the 100M full duplex ability.*/
#define PHY_100BASETX_HALFDUPLEX_MASK 0x080U /*!< The PHY has the 100M full duplex ability.*/
#define PHY_10BASETX_FULLDUPLEX_MASK 0x040U /*!< The PHY has the 10M full duplex ability.*/
#define PHY_10BASETX_HALFDUPLEX_MASK 0x020U /*!< The PHY has the 10M full duplex ability.*/
/*! @brief Defines the PHY status. */
enum _phy_status
{
kStatus_PHY_SMIVisitTimeout = MAKE_STATUS(kStatusGroup_PHY, 1), /*!< ENET PHY SMI visit timeout. */
kStatus_PHY_AutoNegotiateFail = MAKE_STATUS(kStatusGroup_PHY, 2) /*!< ENET PHY AutoNegotiate Fail. */
};
/*! @brief Defines the PHY link speed. This is align with the speed for ENET MAC. */
typedef enum _phy_speed
{
kPHY_Speed10M = 0U, /*!< ENET PHY 10M speed. */
kPHY_Speed100M /*!< ENET PHY 100M speed. */
} phy_speed_t;
/*! @brief Defines the PHY link duplex. */
typedef enum _phy_duplex
{
kPHY_HalfDuplex = 0U, /*!< ENET PHY half duplex. */
kPHY_FullDuplex /*!< ENET PHY full duplex. */
} phy_duplex_t;
/*! @brief Defines the PHY loopback mode. */
typedef enum _phy_loop
{
kPHY_LocalLoop = 0U, /*!< ENET PHY local loopback. */
kPHY_RemoteLoop /*!< ENET PHY remote loopback. */
} phy_loop_t;
/*******************************************************************************
* API
******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif
/*!
* @name PHY Driver
* @{
*/
/*!
* @brief Initializes PHY.
*
* This function initialize the SMI interface and initialize PHY.
* The SMI is the MII management interface between PHY and MAC, which should be
* firstly initialized before any other operation for PHY. The PHY initialize with auto-negotiation.
*
* @param base ENET peripheral base address.
* @param phyAddr The PHY address.
* @param srcClock_Hz The module clock frequency - system clock for MII management interface - SMI.
* @retval kStatus_Success PHY initialize success
* @retval kStatus_PHY_SMIVisitTimeout PHY SMI visit time out
* @retval kStatus_PHY_AutoNegotiateFail PHY auto negotiate fail
*/
status_t PHY_Init(ENET_Type *base, uint32_t phyAddr, uint32_t srcClock_Hz);
/*!
* @brief PHY Write function. This function write data over the SMI to
* the specified PHY register. This function is called by all PHY interfaces.
*
* @param base ENET peripheral base address.
* @param phyAddr The PHY address.
* @param phyReg The PHY register.
* @param data The data written to the PHY register.
* @retval kStatus_Success PHY write success
* @retval kStatus_PHY_SMIVisitTimeout PHY SMI visit time out
*/
status_t PHY_Write(ENET_Type *base, uint32_t phyAddr, uint32_t phyReg, uint32_t data);
/*!
* @brief PHY Read function. This interface read data over the SMI from the
* specified PHY register. This function is called by all PHY interfaces.
*
* @param base ENET peripheral base address.
* @param phyAddr The PHY address.
* @param phyReg The PHY register.
* @param dataPtr The address to store the data read from the PHY register.
* @retval kStatus_Success PHY read success
* @retval kStatus_PHY_SMIVisitTimeout PHY SMI visit time out
*/
status_t PHY_Read(ENET_Type *base, uint32_t phyAddr, uint32_t phyReg, uint32_t *dataPtr);
/*!
* @brief Enables/disables PHY loopback.
*
* @param base ENET peripheral base address.
* @param phyAddr The PHY address.
* @param mode The loopback mode to be enabled, please see "phy_loop_t".
* the two loopback mode should not be both set. when one loopback mode is set
* the other one should be disabled.
* @param speed PHY speed for loopback mode.
* @param enable True to enable, false to disable.
* @retval kStatus_Success PHY loopback success
* @retval kStatus_PHY_SMIVisitTimeout PHY SMI visit time out
*/
status_t PHY_EnableLoopback(ENET_Type *base, uint32_t phyAddr, phy_loop_t mode, phy_speed_t speed, bool enable);
/*!
* @brief Gets the PHY link status.
*
* @param base ENET peripheral base address.
* @param phyAddr The PHY address.
* @param status The link up or down status of the PHY.
* - true the link is up.
* - false the link is down.
* @retval kStatus_Success PHY get link status success
* @retval kStatus_PHY_SMIVisitTimeout PHY SMI visit time out
*/
status_t PHY_GetLinkStatus(ENET_Type *base, uint32_t phyAddr, bool *status);
/*!
* @brief Gets the PHY link speed and duplex.
*
* @param base ENET peripheral base address.
* @param phyAddr The PHY address.
* @param speed The address of PHY link speed.
* @param duplex The link duplex of PHY.
* @retval kStatus_Success PHY get link speed and duplex success
* @retval kStatus_PHY_SMIVisitTimeout PHY SMI visit time out
*/
status_t PHY_GetLinkSpeedDuplex(ENET_Type *base, uint32_t phyAddr, phy_speed_t *speed, phy_duplex_t *duplex);
/* @} */
#if defined(__cplusplus)
}
#endif
/*! @}*/
#endif /* _FSL_PHY_H_ */

View File

@ -0,0 +1,210 @@
/* 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 "pinmap.h"
#include "fsl_clock_config.h"
#include "fsl_clock.h"
#define LPSPI_CLOCK_SOURCE_DIVIDER (7U)
#define LPI2C_CLOCK_SOURCE_DIVIDER (5U)
uint8_t mbed_otp_mac_address(char *mac);
void mbed_default_mac_address(char *mac);
/* MPU configuration. */
void BOARD_ConfigMPU(void)
{
/* Disable I cache and D cache */
SCB_DisableICache();
SCB_DisableDCache();
/* Disable MPU */
ARM_MPU_Disable();
/* Region 0 setting */
MPU->RBAR = ARM_MPU_RBAR(0, 0xC0000000U);
MPU->RASR = ARM_MPU_RASR(0, ARM_MPU_AP_FULL, 2, 0, 0, 0, 0, ARM_MPU_REGION_SIZE_512MB);
/* Region 1 setting */
MPU->RBAR = ARM_MPU_RBAR(1, 0x80000000U);
MPU->RASR = ARM_MPU_RASR(0, ARM_MPU_AP_FULL, 2, 0, 0, 0, 0, ARM_MPU_REGION_SIZE_1GB);
/* Region 2 setting */
MPU->RBAR = ARM_MPU_RBAR(2, 0x60000000U);
MPU->RASR = ARM_MPU_RASR(0, ARM_MPU_AP_FULL, 0, 0, 1, 1, 0, ARM_MPU_REGION_SIZE_512MB);
/* Region 3 setting */
MPU->RBAR = ARM_MPU_RBAR(3, 0x00000000U);
MPU->RASR = ARM_MPU_RASR(0, ARM_MPU_AP_FULL, 2, 0, 0, 0, 0, ARM_MPU_REGION_SIZE_1GB);
/* Region 4 setting */
MPU->RBAR = ARM_MPU_RBAR(4, 0x00000000U);
MPU->RASR = ARM_MPU_RASR(0, ARM_MPU_AP_FULL, 0, 0, 1, 1, 0, ARM_MPU_REGION_SIZE_128KB);
/* Region 5 setting */
MPU->RBAR = ARM_MPU_RBAR(5, 0x20000000U);
MPU->RASR = ARM_MPU_RASR(0, ARM_MPU_AP_FULL, 0, 0, 1, 1, 0, ARM_MPU_REGION_SIZE_128KB);
/* Region 6 setting */
MPU->RBAR = ARM_MPU_RBAR(6, 0x20200000U);
MPU->RASR = ARM_MPU_RASR(0, ARM_MPU_AP_FULL, 0, 0, 1, 1, 0, ARM_MPU_REGION_SIZE_256KB);
#if defined(SDRAM_MPU_INIT)
/* Region 7 setting */
MPU->RBAR = ARM_MPU_RBAR(7, 0x80000000U);
MPU->RASR = ARM_MPU_RASR(0, ARM_MPU_AP_FULL, 0, 0, 1, 1, 0, ARM_MPU_REGION_SIZE_32MB);
/* Region 8 setting */
MPU->RBAR = ARM_MPU_RBAR(8, 0x81E00000U);
MPU->RASR = ARM_MPU_RASR(0, ARM_MPU_AP_FULL, 1, 0, 0, 0, 0, ARM_MPU_REGION_SIZE_2MB);
#endif
/* Enable MPU */
ARM_MPU_Enable(MPU_CTRL_PRIVDEFENA_Msk);
/* Enable I cache and D cache */
SCB_EnableDCache();
SCB_EnableICache();
}
// called before main
void mbed_sdk_init()
{
BOARD_ConfigMPU();
BOARD_BootClockRUN();
}
void spi_setup_clock()
{
/*Set clock source for LPSPI*/
CLOCK_SetMux(kCLOCK_LpspiMux, 1U);
CLOCK_SetDiv(kCLOCK_LpspiDiv, LPSPI_CLOCK_SOURCE_DIVIDER);
}
uint32_t spi_get_clock(void)
{
return (CLOCK_GetFreq(kCLOCK_Usb1PllPfd0Clk) / (LPSPI_CLOCK_SOURCE_DIVIDER + 1U));
}
void us_ticker_setup_clock()
{
/* Set PERCLK_CLK source to OSC_CLK*/
CLOCK_SetMux(kCLOCK_PerclkMux, 1U);
/* Set PERCLK_CLK divider to 1 */
CLOCK_SetDiv(kCLOCK_PerclkDiv, 0U);
}
uint32_t us_ticker_get_clock()
{
return CLOCK_GetFreq(kCLOCK_OscClk);
}
void serial_setup_clock(void)
{
/* We assume default PLL and divider settings */
}
uint32_t serial_get_clock(void)
{
uint32_t clock_freq;
/* We assume default PLL and divider settings, and the only variable
* from application is use PLL3 source or OSC source
*/
if (CLOCK_GetMux(kCLOCK_UartMux) == 0) /* PLL3 div6 80M */ {
clock_freq = (CLOCK_GetPllFreq(kCLOCK_PllUsb1) / 6U) / (CLOCK_GetDiv(kCLOCK_UartDiv) + 1U);
} else {
clock_freq = CLOCK_GetOscFreq() / (CLOCK_GetDiv(kCLOCK_UartDiv) + 1U);
}
return clock_freq;
}
void i2c_setup_clock()
{
/* Select USB1 PLL (480 MHz) as master lpi2c clock source */
CLOCK_SetMux(kCLOCK_Lpi2cMux, 0U);
CLOCK_SetDiv(kCLOCK_Lpi2cDiv, LPI2C_CLOCK_SOURCE_DIVIDER);
}
uint32_t i2c_get_clock()
{
return ((CLOCK_GetFreq(kCLOCK_Usb1PllClk) / 8) / (LPI2C_CLOCK_SOURCE_DIVIDER + 1U));
}
void pwm_setup_clock()
{
/* Use default settings */
}
uint32_t pwm_get_clock()
{
return CLOCK_GetFreq(kCLOCK_IpgClk);
}
// 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)
{
pin_function(WAKEUP, 7);
pin_mode(WAKEUP, PullDefault);
}
void mbed_mac_address(char *mac) {
if (mbed_otp_mac_address(mac)) {
return;
} else {
mbed_default_mac_address(mac);
}
return;
}
uint8_t mbed_otp_mac_address(char *mac) {
/* Check if a valid MAC address is programmed to the fuse bank */
if ((OCOTP->MAC0 != 0) &&
(OCOTP->MAC1 != 0) &&
(OCOTP->GP3 != 0)) {
uint16_t MAC[3]; // 3 16 bits words for the MAC
// Read the MAC address from the OCOTP MAC registers
MAC[0] = (uint16_t)OCOTP->MAC0; // most significant half-word
MAC[1] = (uint16_t)OCOTP->MAC1;
MAC[2] = (uint16_t)OCOTP->GP3; // least significant half word
// The network stack expects an array of 6 bytes
// so we copy, and shift and copy from the half-word array to the byte array
mac[0] = MAC[0] >> 8;
mac[1] = MAC[0];
mac[2] = MAC[1] >> 8;
mac[3] = MAC[1];
mac[4] = MAC[2] >> 8;
mac[5] = MAC[2];
} else {
return 0;
}
return 1;
}
void mbed_default_mac_address(char *mac) {
mac[0] = 0x00;
mac[1] = 0x02;
mac[2] = 0xF7;
mac[3] = 0xF0;
mac[4] = 0x00;
mac[5] = 0x00;
return;
}

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,993 @@
/*
** ###################################################################
** Version: rev. 0.1, 2017-01-10
** Build: b171017
**
** Abstract:
** Chip specific module features.
**
** Copyright 2016 Freescale Semiconductor, Inc.
** Copyright 2016-2017 NXP
** Redistribution and use in source and binary forms, with or without modification,
** are permitted provided that the following conditions are met:
**
** 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 the copyright holder nor the names of its
** contributors may be used to endorse or promote products derived from this
** software without specific prior written permission.
**
** THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
** ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
** WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
** DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
** ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
** (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
** LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
** ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
** (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
** SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
**
** http: www.nxp.com
** mail: support@nxp.com
**
** Revisions:
** - rev. 0.1 (2017-01-10)
** Initial version.
**
** ###################################################################
*/
#ifndef _MIMXRT1052_FEATURES_H_
#define _MIMXRT1052_FEATURES_H_
/* SOC module features */
/* @brief ACMP availability on the SoC. */
#define FSL_FEATURE_SOC_ACMP_COUNT (0)
/* @brief ADC availability on the SoC. */
#define FSL_FEATURE_SOC_ADC_COUNT (2)
/* @brief ADC12 availability on the SoC. */
#define FSL_FEATURE_SOC_ADC12_COUNT (0)
/* @brief ADC16 availability on the SoC. */
#define FSL_FEATURE_SOC_ADC16_COUNT (0)
/* @brief ADC_5HC availability on the SoC. */
#define FSL_FEATURE_SOC_ADC_5HC_COUNT (0)
/* @brief AES availability on the SoC. */
#define FSL_FEATURE_SOC_AES_COUNT (0)
/* @brief AFE availability on the SoC. */
#define FSL_FEATURE_SOC_AFE_COUNT (0)
/* @brief AGC availability on the SoC. */
#define FSL_FEATURE_SOC_AGC_COUNT (0)
/* @brief AIPS availability on the SoC. */
#define FSL_FEATURE_SOC_AIPS_COUNT (0)
/* @brief AIPSTZ availability on the SoC. */
#define FSL_FEATURE_SOC_AIPSTZ_COUNT (4)
/* @brief ANATOP availability on the SoC. */
#define FSL_FEATURE_SOC_ANATOP_COUNT (0)
/* @brief AOI availability on the SoC. */
#define FSL_FEATURE_SOC_AOI_COUNT (2)
/* @brief APBH availability on the SoC. */
#define FSL_FEATURE_SOC_APBH_COUNT (0)
/* @brief ASMC availability on the SoC. */
#define FSL_FEATURE_SOC_ASMC_COUNT (0)
/* @brief ASRC availability on the SoC. */
#define FSL_FEATURE_SOC_ASRC_COUNT (0)
/* @brief ASYNC_SYSCON availability on the SoC. */
#define FSL_FEATURE_SOC_ASYNC_SYSCON_COUNT (0)
/* @brief ATX availability on the SoC. */
#define FSL_FEATURE_SOC_ATX_COUNT (0)
/* @brief AXBS availability on the SoC. */
#define FSL_FEATURE_SOC_AXBS_COUNT (0)
/* @brief BCH availability on the SoC. */
#define FSL_FEATURE_SOC_BCH_COUNT (0)
/* @brief BLEDP availability on the SoC. */
#define FSL_FEATURE_SOC_BLEDP_COUNT (0)
/* @brief BOD availability on the SoC. */
#define FSL_FEATURE_SOC_BOD_COUNT (0)
/* @brief CAAM availability on the SoC. */
#define FSL_FEATURE_SOC_CAAM_COUNT (0)
/* @brief CADC availability on the SoC. */
#define FSL_FEATURE_SOC_CADC_COUNT (0)
/* @brief CALIB availability on the SoC. */
#define FSL_FEATURE_SOC_CALIB_COUNT (0)
/* @brief CAN availability on the SoC. */
#define FSL_FEATURE_SOC_CAN_COUNT (0)
/* @brief CAU availability on the SoC. */
#define FSL_FEATURE_SOC_CAU_COUNT (0)
/* @brief CAU3 availability on the SoC. */
#define FSL_FEATURE_SOC_CAU3_COUNT (0)
/* @brief CCM availability on the SoC. */
#define FSL_FEATURE_SOC_CCM_COUNT (1)
/* @brief CCM_ANALOG availability on the SoC. */
#define FSL_FEATURE_SOC_CCM_ANALOG_COUNT (1)
/* @brief CHRG availability on the SoC. */
#define FSL_FEATURE_SOC_CHRG_COUNT (0)
/* @brief CLKCTL0 availability on the SoC. */
#define FSL_FEATURE_SOC_CLKCTL0_COUNT (0)
/* @brief CLKCTL1 availability on the SoC. */
#define FSL_FEATURE_SOC_CLKCTL1_COUNT (0)
/* @brief CMP availability on the SoC. */
#define FSL_FEATURE_SOC_CMP_COUNT (4)
/* @brief CMT availability on the SoC. */
#define FSL_FEATURE_SOC_CMT_COUNT (0)
/* @brief CNC availability on the SoC. */
#define FSL_FEATURE_SOC_CNC_COUNT (0)
/* @brief COP availability on the SoC. */
#define FSL_FEATURE_SOC_COP_COUNT (0)
/* @brief CRC availability on the SoC. */
#define FSL_FEATURE_SOC_CRC_COUNT (0)
/* @brief CS availability on the SoC. */
#define FSL_FEATURE_SOC_CS_COUNT (0)
/* @brief CSI availability on the SoC. */
#define FSL_FEATURE_SOC_CSI_COUNT (1)
/* @brief CT32B availability on the SoC. */
#define FSL_FEATURE_SOC_CT32B_COUNT (0)
/* @brief CTI availability on the SoC. */
#define FSL_FEATURE_SOC_CTI_COUNT (0)
/* @brief CTIMER availability on the SoC. */
#define FSL_FEATURE_SOC_CTIMER_COUNT (0)
/* @brief DAC availability on the SoC. */
#define FSL_FEATURE_SOC_DAC_COUNT (0)
/* @brief DAC32 availability on the SoC. */
#define FSL_FEATURE_SOC_DAC32_COUNT (0)
/* @brief DCDC availability on the SoC. */
#define FSL_FEATURE_SOC_DCDC_COUNT (1)
/* @brief DCP availability on the SoC. */
#define FSL_FEATURE_SOC_DCP_COUNT (1)
/* @brief DDR availability on the SoC. */
#define FSL_FEATURE_SOC_DDR_COUNT (0)
/* @brief DDRC availability on the SoC. */
#define FSL_FEATURE_SOC_DDRC_COUNT (0)
/* @brief DDRC_MP availability on the SoC. */
#define FSL_FEATURE_SOC_DDRC_MP_COUNT (0)
/* @brief DDR_PHY availability on the SoC. */
#define FSL_FEATURE_SOC_DDR_PHY_COUNT (0)
/* @brief DMA availability on the SoC. */
#define FSL_FEATURE_SOC_DMA_COUNT (0)
/* @brief DMAMUX availability on the SoC. */
#define FSL_FEATURE_SOC_DMAMUX_COUNT (1)
/* @brief DMIC availability on the SoC. */
#define FSL_FEATURE_SOC_DMIC_COUNT (0)
/* @brief DRY availability on the SoC. */
#define FSL_FEATURE_SOC_DRY_COUNT (0)
/* @brief DSPI availability on the SoC. */
#define FSL_FEATURE_SOC_DSPI_COUNT (0)
/* @brief ECSPI availability on the SoC. */
#define FSL_FEATURE_SOC_ECSPI_COUNT (0)
/* @brief EDMA availability on the SoC. */
#define FSL_FEATURE_SOC_EDMA_COUNT (1)
/* @brief EEPROM availability on the SoC. */
#define FSL_FEATURE_SOC_EEPROM_COUNT (0)
/* @brief EIM availability on the SoC. */
#define FSL_FEATURE_SOC_EIM_COUNT (0)
/* @brief EMC availability on the SoC. */
#define FSL_FEATURE_SOC_EMC_COUNT (0)
/* @brief EMVSIM availability on the SoC. */
#define FSL_FEATURE_SOC_EMVSIM_COUNT (0)
/* @brief ENC availability on the SoC. */
#define FSL_FEATURE_SOC_ENC_COUNT (4)
/* @brief ENET availability on the SoC. */
#define FSL_FEATURE_SOC_ENET_COUNT (1)
/* @brief EPDC availability on the SoC. */
#define FSL_FEATURE_SOC_EPDC_COUNT (0)
/* @brief EPIT availability on the SoC. */
#define FSL_FEATURE_SOC_EPIT_COUNT (0)
/* @brief ESAI availability on the SoC. */
#define FSL_FEATURE_SOC_ESAI_COUNT (0)
/* @brief EWM availability on the SoC. */
#define FSL_FEATURE_SOC_EWM_COUNT (1)
/* @brief FB availability on the SoC. */
#define FSL_FEATURE_SOC_FB_COUNT (0)
/* @brief FGPIO availability on the SoC. */
#define FSL_FEATURE_SOC_FGPIO_COUNT (0)
/* @brief FLASH availability on the SoC. */
#define FSL_FEATURE_SOC_FLASH_COUNT (0)
/* @brief FLEXCAN availability on the SoC. */
#define FSL_FEATURE_SOC_FLEXCAN_COUNT (2)
/* @brief FLEXCOMM availability on the SoC. */
#define FSL_FEATURE_SOC_FLEXCOMM_COUNT (0)
/* @brief FLEXIO availability on the SoC. */
#define FSL_FEATURE_SOC_FLEXIO_COUNT (2)
/* @brief FLEXRAM availability on the SoC. */
#define FSL_FEATURE_SOC_FLEXRAM_COUNT (1)
/* @brief FLEXSPI availability on the SoC. */
#define FSL_FEATURE_SOC_FLEXSPI_COUNT (1)
/* @brief FMC availability on the SoC. */
#define FSL_FEATURE_SOC_FMC_COUNT (0)
/* @brief FREQME availability on the SoC. */
#define FSL_FEATURE_SOC_FREQME_COUNT (0)
/* @brief FSKDT availability on the SoC. */
#define FSL_FEATURE_SOC_FSKDT_COUNT (0)
/* @brief FSP availability on the SoC. */
#define FSL_FEATURE_SOC_FSP_COUNT (0)
/* @brief FTFA availability on the SoC. */
#define FSL_FEATURE_SOC_FTFA_COUNT (0)
/* @brief FTFE availability on the SoC. */
#define FSL_FEATURE_SOC_FTFE_COUNT (0)
/* @brief FTFL availability on the SoC. */
#define FSL_FEATURE_SOC_FTFL_COUNT (0)
/* @brief FTM availability on the SoC. */
#define FSL_FEATURE_SOC_FTM_COUNT (0)
/* @brief FTMRA availability on the SoC. */
#define FSL_FEATURE_SOC_FTMRA_COUNT (0)
/* @brief FTMRE availability on the SoC. */
#define FSL_FEATURE_SOC_FTMRE_COUNT (0)
/* @brief FTMRH availability on the SoC. */
#define FSL_FEATURE_SOC_FTMRH_COUNT (0)
/* @brief GINT availability on the SoC. */
#define FSL_FEATURE_SOC_GINT_COUNT (0)
/* @brief GPC availability on the SoC. */
#define FSL_FEATURE_SOC_GPC_COUNT (1)
/* @brief GPC_PGC availability on the SoC. */
#define FSL_FEATURE_SOC_GPC_PGC_COUNT (0)
/* @brief GPIO availability on the SoC. */
#define FSL_FEATURE_SOC_GPIO_COUNT (0)
/* @brief GPMI availability on the SoC. */
#define FSL_FEATURE_SOC_GPMI_COUNT (0)
/* @brief GPT availability on the SoC. */
#define FSL_FEATURE_SOC_GPT_COUNT (2)
/* @brief HASH availability on the SoC. */
#define FSL_FEATURE_SOC_HASH_COUNT (0)
/* @brief HSADC availability on the SoC. */
#define FSL_FEATURE_SOC_HSADC_COUNT (0)
/* @brief I2C availability on the SoC. */
#define FSL_FEATURE_SOC_I2C_COUNT (0)
/* @brief I2S availability on the SoC. */
#define FSL_FEATURE_SOC_I2S_COUNT (3)
/* @brief ICS availability on the SoC. */
#define FSL_FEATURE_SOC_ICS_COUNT (0)
/* @brief IEE availability on the SoC. */
#define FSL_FEATURE_SOC_IEE_COUNT (0)
/* @brief IEER availability on the SoC. */
#define FSL_FEATURE_SOC_IEER_COUNT (0)
/* @brief IGPIO availability on the SoC. */
#define FSL_FEATURE_SOC_IGPIO_COUNT (5)
/* @brief II2C availability on the SoC. */
#define FSL_FEATURE_SOC_II2C_COUNT (0)
/* @brief INPUTMUX availability on the SoC. */
#define FSL_FEATURE_SOC_INPUTMUX_COUNT (0)
/* @brief INTMUX availability on the SoC. */
#define FSL_FEATURE_SOC_INTMUX_COUNT (0)
/* @brief IOCON availability on the SoC. */
#define FSL_FEATURE_SOC_IOCON_COUNT (0)
/* @brief IOMUXC availability on the SoC. */
#define FSL_FEATURE_SOC_IOMUXC_COUNT (1)
/* @brief IOMUXC_GPR availability on the SoC. */
#define FSL_FEATURE_SOC_IOMUXC_GPR_COUNT (1)
/* @brief IOMUXC_LPSR availability on the SoC. */
#define FSL_FEATURE_SOC_IOMUXC_LPSR_COUNT (0)
/* @brief IOMUXC_LPSR_GPR availability on the SoC. */
#define FSL_FEATURE_SOC_IOMUXC_LPSR_GPR_COUNT (0)
/* @brief IOMUXC_SNVS availability on the SoC. */
#define FSL_FEATURE_SOC_IOMUXC_SNVS_COUNT (1)
/* @brief IOPCTL availability on the SoC. */
#define FSL_FEATURE_SOC_IOPCTL_COUNT (0)
/* @brief IPWM availability on the SoC. */
#define FSL_FEATURE_SOC_IPWM_COUNT (0)
/* @brief IRQ availability on the SoC. */
#define FSL_FEATURE_SOC_IRQ_COUNT (0)
/* @brief IUART availability on the SoC. */
#define FSL_FEATURE_SOC_IUART_COUNT (0)
/* @brief KBI availability on the SoC. */
#define FSL_FEATURE_SOC_KBI_COUNT (0)
/* @brief KPP availability on the SoC. */
#define FSL_FEATURE_SOC_KPP_COUNT (1)
/* @brief L2CACHEC availability on the SoC. */
#define FSL_FEATURE_SOC_L2CACHEC_COUNT (0)
/* @brief LCD availability on the SoC. */
#define FSL_FEATURE_SOC_LCD_COUNT (0)
/* @brief LCDC availability on the SoC. */
#define FSL_FEATURE_SOC_LCDC_COUNT (0)
/* @brief LCDIF availability on the SoC. */
#define FSL_FEATURE_SOC_LCDIF_COUNT (1)
/* @brief LDO availability on the SoC. */
#define FSL_FEATURE_SOC_LDO_COUNT (0)
/* @brief LLWU availability on the SoC. */
#define FSL_FEATURE_SOC_LLWU_COUNT (0)
/* @brief LMEM availability on the SoC. */
#define FSL_FEATURE_SOC_LMEM_COUNT (0)
/* @brief LPADC availability on the SoC. */
#define FSL_FEATURE_SOC_LPADC_COUNT (0)
/* @brief LPCMP availability on the SoC. */
#define FSL_FEATURE_SOC_LPCMP_COUNT (0)
/* @brief LPDAC availability on the SoC. */
#define FSL_FEATURE_SOC_LPDAC_COUNT (0)
/* @brief LPI2C availability on the SoC. */
#define FSL_FEATURE_SOC_LPI2C_COUNT (4)
/* @brief LPIT availability on the SoC. */
#define FSL_FEATURE_SOC_LPIT_COUNT (0)
/* @brief LPSCI availability on the SoC. */
#define FSL_FEATURE_SOC_LPSCI_COUNT (0)
/* @brief LPSPI availability on the SoC. */
#define FSL_FEATURE_SOC_LPSPI_COUNT (4)
/* @brief LPTMR availability on the SoC. */
#define FSL_FEATURE_SOC_LPTMR_COUNT (0)
/* @brief LPTPM availability on the SoC. */
#define FSL_FEATURE_SOC_LPTPM_COUNT (0)
/* @brief LPUART availability on the SoC. */
#define FSL_FEATURE_SOC_LPUART_COUNT (8)
/* @brief LTC availability on the SoC. */
#define FSL_FEATURE_SOC_LTC_COUNT (0)
/* @brief MAILBOX availability on the SoC. */
#define FSL_FEATURE_SOC_MAILBOX_COUNT (0)
/* @brief MC availability on the SoC. */
#define FSL_FEATURE_SOC_MC_COUNT (0)
/* @brief MCG availability on the SoC. */
#define FSL_FEATURE_SOC_MCG_COUNT (0)
/* @brief MCGLITE availability on the SoC. */
#define FSL_FEATURE_SOC_MCGLITE_COUNT (0)
/* @brief MCM availability on the SoC. */
#define FSL_FEATURE_SOC_MCM_COUNT (0)
/* @brief MIPI_CSI2 availability on the SoC. */
#define FSL_FEATURE_SOC_MIPI_CSI2_COUNT (0)
/* @brief MIPI_CSI2RX availability on the SoC. */
#define FSL_FEATURE_SOC_MIPI_CSI2RX_COUNT (0)
/* @brief MIPI_DSI availability on the SoC. */
#define FSL_FEATURE_SOC_MIPI_DSI_COUNT (0)
/* @brief MIPI_DSI_HOST availability on the SoC. */
#define FSL_FEATURE_SOC_MIPI_DSI_HOST_COUNT (0)
/* @brief MMAU availability on the SoC. */
#define FSL_FEATURE_SOC_MMAU_COUNT (0)
/* @brief MMCAU availability on the SoC. */
#define FSL_FEATURE_SOC_MMCAU_COUNT (0)
/* @brief MMDC availability on the SoC. */
#define FSL_FEATURE_SOC_MMDC_COUNT (0)
/* @brief MMDVSQ availability on the SoC. */
#define FSL_FEATURE_SOC_MMDVSQ_COUNT (0)
/* @brief MPU availability on the SoC. */
#define FSL_FEATURE_SOC_MPU_COUNT (0)
/* @brief MRT availability on the SoC. */
#define FSL_FEATURE_SOC_MRT_COUNT (0)
/* @brief MSCAN availability on the SoC. */
#define FSL_FEATURE_SOC_MSCAN_COUNT (0)
/* @brief MSCM availability on the SoC. */
#define FSL_FEATURE_SOC_MSCM_COUNT (0)
/* @brief MTB availability on the SoC. */
#define FSL_FEATURE_SOC_MTB_COUNT (0)
/* @brief MTBDWT availability on the SoC. */
#define FSL_FEATURE_SOC_MTBDWT_COUNT (0)
/* @brief MU availability on the SoC. */
#define FSL_FEATURE_SOC_MU_COUNT (0)
/* @brief NFC availability on the SoC. */
#define FSL_FEATURE_SOC_NFC_COUNT (0)
/* @brief OCOTP availability on the SoC. */
#define FSL_FEATURE_SOC_OCOTP_COUNT (1)
/* @brief OPAMP availability on the SoC. */
#define FSL_FEATURE_SOC_OPAMP_COUNT (0)
/* @brief OTPC availability on the SoC. */
#define FSL_FEATURE_SOC_OTPC_COUNT (0)
/* @brief OSC availability on the SoC. */
#define FSL_FEATURE_SOC_OSC_COUNT (0)
/* @brief OSC32 availability on the SoC. */
#define FSL_FEATURE_SOC_OSC32_COUNT (0)
/* @brief OTFAD availability on the SoC. */
#define FSL_FEATURE_SOC_OTFAD_COUNT (0)
/* @brief PCC availability on the SoC. */
#define FSL_FEATURE_SOC_PCC_COUNT (0)
/* @brief PCIE_PHY_CMN availability on the SoC. */
#define FSL_FEATURE_SOC_PCIE_PHY_CMN_COUNT (0)
/* @brief PCIE_PHY_TRSV availability on the SoC. */
#define FSL_FEATURE_SOC_PCIE_PHY_TRSV_COUNT (0)
/* @brief PDB availability on the SoC. */
#define FSL_FEATURE_SOC_PDB_COUNT (0)
/* @brief PGA availability on the SoC. */
#define FSL_FEATURE_SOC_PGA_COUNT (0)
/* @brief PIMCTL availability on the SoC. */
#define FSL_FEATURE_SOC_PIMCTL_COUNT (0)
/* @brief PINT availability on the SoC. */
#define FSL_FEATURE_SOC_PINT_COUNT (0)
/* @brief PIT availability on the SoC. */
#define FSL_FEATURE_SOC_PIT_COUNT (1)
/* @brief PMC availability on the SoC. */
#define FSL_FEATURE_SOC_PMC_COUNT (0)
/* @brief PMU availability on the SoC. */
#define FSL_FEATURE_SOC_PMU_COUNT (1)
/* @brief POWERQUAD availability on the SoC. */
#define FSL_FEATURE_SOC_POWERQUAD_COUNT (0)
/* @brief PORT availability on the SoC. */
#define FSL_FEATURE_SOC_PORT_COUNT (0)
/* @brief PROP availability on the SoC. */
#define FSL_FEATURE_SOC_PROP_COUNT (0)
/* @brief PWM availability on the SoC. */
#define FSL_FEATURE_SOC_PWM_COUNT (4)
/* @brief PWT availability on the SoC. */
#define FSL_FEATURE_SOC_PWT_COUNT (0)
/* @brief PXP availability on the SoC. */
#define FSL_FEATURE_SOC_PXP_COUNT (1)
/* @brief QDDKEY availability on the SoC. */
#define FSL_FEATURE_SOC_QDDKEY_COUNT (0)
/* @brief QDEC availability on the SoC. */
#define FSL_FEATURE_SOC_QDEC_COUNT (0)
/* @brief QuadSPI availability on the SoC. */
#define FSL_FEATURE_SOC_QuadSPI_COUNT (0)
/* @brief RCM availability on the SoC. */
#define FSL_FEATURE_SOC_RCM_COUNT (0)
/* @brief RDC availability on the SoC. */
#define FSL_FEATURE_SOC_RDC_COUNT (0)
/* @brief RDC_SEMAPHORE availability on the SoC. */
#define FSL_FEATURE_SOC_RDC_SEMAPHORE_COUNT (0)
/* @brief RFSYS availability on the SoC. */
#define FSL_FEATURE_SOC_RFSYS_COUNT (0)
/* @brief RFVBAT availability on the SoC. */
#define FSL_FEATURE_SOC_RFVBAT_COUNT (0)
/* @brief RIT availability on the SoC. */
#define FSL_FEATURE_SOC_RIT_COUNT (0)
/* @brief RNG availability on the SoC. */
#define FSL_FEATURE_SOC_RNG_COUNT (0)
/* @brief RNGB availability on the SoC. */
#define FSL_FEATURE_SOC_RNGB_COUNT (0)
/* @brief ROM availability on the SoC. */
#define FSL_FEATURE_SOC_ROM_COUNT (0)
/* @brief ROMC availability on the SoC. */
#define FSL_FEATURE_SOC_ROMC_COUNT (1)
/* @brief RSIM availability on the SoC. */
#define FSL_FEATURE_SOC_RSIM_COUNT (0)
/* @brief RSTCTL0 availability on the SoC. */
#define FSL_FEATURE_SOC_RSTCTL0_COUNT (0)
/* @brief RSTCTL1 availability on the SoC. */
#define FSL_FEATURE_SOC_RSTCTL1_COUNT (0)
/* @brief RTC availability on the SoC. */
#define FSL_FEATURE_SOC_RTC_COUNT (0)
/* @brief SCG availability on the SoC. */
#define FSL_FEATURE_SOC_SCG_COUNT (0)
/* @brief SCI availability on the SoC. */
#define FSL_FEATURE_SOC_SCI_COUNT (0)
/* @brief SCT availability on the SoC. */
#define FSL_FEATURE_SOC_SCT_COUNT (0)
/* @brief SDHC availability on the SoC. */
#define FSL_FEATURE_SOC_SDHC_COUNT (0)
/* @brief SDIF availability on the SoC. */
#define FSL_FEATURE_SOC_SDIF_COUNT (0)
/* @brief SDIO availability on the SoC. */
#define FSL_FEATURE_SOC_SDIO_COUNT (0)
/* @brief SDMA availability on the SoC. */
#define FSL_FEATURE_SOC_SDMA_COUNT (0)
/* @brief SDMAARM availability on the SoC. */
#define FSL_FEATURE_SOC_SDMAARM_COUNT (0)
/* @brief SDMABP availability on the SoC. */
#define FSL_FEATURE_SOC_SDMABP_COUNT (0)
/* @brief SDMACORE availability on the SoC. */
#define FSL_FEATURE_SOC_SDMACORE_COUNT (0)
/* @brief SDMCORE availability on the SoC. */
#define FSL_FEATURE_SOC_SDMCORE_COUNT (0)
/* @brief SDRAM availability on the SoC. */
#define FSL_FEATURE_SOC_SDRAM_COUNT (0)
/* @brief SEMA4 availability on the SoC. */
#define FSL_FEATURE_SOC_SEMA4_COUNT (0)
/* @brief SEMA42 availability on the SoC. */
#define FSL_FEATURE_SOC_SEMA42_COUNT (0)
/* @brief SEMC availability on the SoC. */
#define FSL_FEATURE_SOC_SEMC_COUNT (1)
/* @brief SHA availability on the SoC. */
#define FSL_FEATURE_SOC_SHA_COUNT (0)
/* @brief SIM availability on the SoC. */
#define FSL_FEATURE_SOC_SIM_COUNT (0)
/* @brief SJC availability on the SoC. */
#define FSL_FEATURE_SOC_SJC_COUNT (0)
/* @brief SLCD availability on the SoC. */
#define FSL_FEATURE_SOC_SLCD_COUNT (0)
/* @brief SMARTCARD availability on the SoC. */
#define FSL_FEATURE_SOC_SMARTCARD_COUNT (0)
/* @brief SMC availability on the SoC. */
#define FSL_FEATURE_SOC_SMC_COUNT (0)
/* @brief SNVS availability on the SoC. */
#define FSL_FEATURE_SOC_SNVS_COUNT (1)
/* @brief SPBA availability on the SoC. */
#define FSL_FEATURE_SOC_SPBA_COUNT (0)
/* @brief SPDIF availability on the SoC. */
#define FSL_FEATURE_SOC_SPDIF_COUNT (1)
/* @brief SPI availability on the SoC. */
#define FSL_FEATURE_SOC_SPI_COUNT (0)
/* @brief SPIFI availability on the SoC. */
#define FSL_FEATURE_SOC_SPIFI_COUNT (0)
/* @brief SPM availability on the SoC. */
#define FSL_FEATURE_SOC_SPM_COUNT (0)
/* @brief SRC availability on the SoC. */
#define FSL_FEATURE_SOC_SRC_COUNT (1)
/* @brief SYSCON availability on the SoC. */
#define FSL_FEATURE_SOC_SYSCON_COUNT (0)
/* @brief SYSCTL0 availability on the SoC. */
#define FSL_FEATURE_SOC_SYSCTL0_COUNT (0)
/* @brief SYSCTL1 availability on the SoC. */
#define FSL_FEATURE_SOC_SYSCTL1_COUNT (0)
/* @brief TEMPMON availability on the SoC. */
#define FSL_FEATURE_SOC_TEMPMON_COUNT (1)
/* @brief TMR availability on the SoC. */
#define FSL_FEATURE_SOC_TMR_COUNT (4)
/* @brief TPM availability on the SoC. */
#define FSL_FEATURE_SOC_TPM_COUNT (0)
/* @brief TRGMUX availability on the SoC. */
#define FSL_FEATURE_SOC_TRGMUX_COUNT (0)
/* @brief TRIAMP availability on the SoC. */
#define FSL_FEATURE_SOC_TRIAMP_COUNT (0)
/* @brief TRNG availability on the SoC. */
#define FSL_FEATURE_SOC_TRNG_COUNT (1)
/* @brief TSC availability on the SoC. */
#define FSL_FEATURE_SOC_TSC_COUNT (1)
/* @brief TSI availability on the SoC. */
#define FSL_FEATURE_SOC_TSI_COUNT (0)
/* @brief TSTMR availability on the SoC. */
#define FSL_FEATURE_SOC_TSTMR_COUNT (0)
/* @brief UART availability on the SoC. */
#define FSL_FEATURE_SOC_UART_COUNT (0)
/* @brief USART availability on the SoC. */
#define FSL_FEATURE_SOC_USART_COUNT (0)
/* @brief USB availability on the SoC. */
#define FSL_FEATURE_SOC_USB_COUNT (0)
/* @brief USBHS availability on the SoC. */
#define FSL_FEATURE_SOC_USBHS_COUNT (2)
/* @brief USBDCD availability on the SoC. */
#define FSL_FEATURE_SOC_USBDCD_COUNT (0)
/* @brief USBFSH availability on the SoC. */
#define FSL_FEATURE_SOC_USBFSH_COUNT (0)
/* @brief USBHSD availability on the SoC. */
#define FSL_FEATURE_SOC_USBHSD_COUNT (0)
/* @brief USBHSDCD availability on the SoC. */
#define FSL_FEATURE_SOC_USBHSDCD_COUNT (0)
/* @brief USBHSH availability on the SoC. */
#define FSL_FEATURE_SOC_USBHSH_COUNT (0)
/* @brief USBNC availability on the SoC. */
#define FSL_FEATURE_SOC_USBNC_COUNT (2)
/* @brief USBPHY availability on the SoC. */
#define FSL_FEATURE_SOC_USBPHY_COUNT (2)
/* @brief USB_HSIC availability on the SoC. */
#define FSL_FEATURE_SOC_USB_HSIC_COUNT (0)
/* @brief USB_OTG availability on the SoC. */
#define FSL_FEATURE_SOC_USB_OTG_COUNT (0)
/* @brief USBVREG availability on the SoC. */
#define FSL_FEATURE_SOC_USBVREG_COUNT (0)
/* @brief USDHC availability on the SoC. */
#define FSL_FEATURE_SOC_USDHC_COUNT (2)
/* @brief UTICK availability on the SoC. */
#define FSL_FEATURE_SOC_UTICK_COUNT (0)
/* @brief VIU availability on the SoC. */
#define FSL_FEATURE_SOC_VIU_COUNT (0)
/* @brief VREF availability on the SoC. */
#define FSL_FEATURE_SOC_VREF_COUNT (0)
/* @brief VFIFO availability on the SoC. */
#define FSL_FEATURE_SOC_VFIFO_COUNT (0)
/* @brief WDOG availability on the SoC. */
#define FSL_FEATURE_SOC_WDOG_COUNT (2)
/* @brief WKPU availability on the SoC. */
#define FSL_FEATURE_SOC_WKPU_COUNT (0)
/* @brief WWDT availability on the SoC. */
#define FSL_FEATURE_SOC_WWDT_COUNT (0)
/* @brief XBAR availability on the SoC. */
#define FSL_FEATURE_SOC_XBAR_COUNT (0)
/* @brief XBARA availability on the SoC. */
#define FSL_FEATURE_SOC_XBARA_COUNT (1)
/* @brief XBARB availability on the SoC. */
#define FSL_FEATURE_SOC_XBARB_COUNT (2)
/* @brief XCVR availability on the SoC. */
#define FSL_FEATURE_SOC_XCVR_COUNT (0)
/* @brief XRDC availability on the SoC. */
#define FSL_FEATURE_SOC_XRDC_COUNT (0)
/* @brief XTALOSC availability on the SoC. */
#define FSL_FEATURE_SOC_XTALOSC_COUNT (0)
/* @brief XTALOSC24M availability on the SoC. */
#define FSL_FEATURE_SOC_XTALOSC24M_COUNT (1)
/* @brief ZLL availability on the SoC. */
#define FSL_FEATURE_SOC_ZLL_COUNT (0)
/* ADC module features */
/* @brief Remove Hardware Trigger feature. */
#define FSL_FEATURE_ADC_SUPPORT_HARDWARE_TRIGGER_REMOVE (0)
/* @brief Remove ALT Clock selection feature. */
#define FSL_FEATURE_ADC_SUPPORT_ALTCLK_REMOVE (1)
/* AOI module features */
/* @brief Maximum value of input mux. */
#define FSL_FEATURE_AOI_MODULE_INPUTS (4)
/* @brief Number of events related to number of registers AOIx_BFCRT01n/AOIx_BFCRT23n. */
#define FSL_FEATURE_AOI_EVENT_COUNT (4)
/* FLEXCAN module features */
/* @brief Message buffer size */
#define FSL_FEATURE_FLEXCAN_HAS_MESSAGE_BUFFER_MAX_NUMBERn(x) (64)
/* @brief Has doze mode support (register bit field MCR[DOZE]). */
#define FSL_FEATURE_FLEXCAN_HAS_DOZE_MODE_SUPPORT (0)
/* @brief Has a glitch filter on the receive pin (register bit field MCR[WAKSRC]). */
#define FSL_FEATURE_FLEXCAN_HAS_GLITCH_FILTER (1)
/* @brief Has extended interrupt mask and flag register (register IMASK2, IFLAG2). */
#define FSL_FEATURE_FLEXCAN_HAS_EXTENDED_FLAG_REGISTER (1)
/* @brief Has extended bit timing register (register CBT). */
#define FSL_FEATURE_FLEXCAN_HAS_EXTENDED_TIMING_REGISTER (0)
/* @brief Has a receive FIFO DMA feature (register bit field MCR[DMA]). */
#define FSL_FEATURE_FLEXCAN_HAS_RX_FIFO_DMA (0)
/* @brief Remove CAN Engine Clock Source Selection from unsupported part. */
#define FSL_FEATURE_FLEXCAN_SUPPORT_ENGINE_CLK_SEL_REMOVE (1)
/* @brief Is affected by errata with ID 5641 (Module does not transmit a message that is enabled to be transmitted at a specific moment during the arbitration process). */
#define FSL_FEATURE_FLEXCAN_HAS_ERRATA_5641 (0)
/* @brief Has CAN with Flexible Data rate (CAN FD) protocol. */
#define FSL_FEATURE_FLEXCAN_HAS_FLEXIBLE_DATA_RATE (0)
/* @brief Has extra MB interrupt or common one. */
#define FSL_FEATURE_FLEXCAN_HAS_EXTRA_MB_INT (1)
/* CMP module features */
/* @brief Has Trigger mode in CMP (register bit field CR1[TRIGM]). */
#define FSL_FEATURE_CMP_HAS_TRIGGER_MODE (0)
/* @brief Has Window mode in CMP (register bit field CR1[WE]). */
#define FSL_FEATURE_CMP_HAS_WINDOW_MODE (1)
/* @brief Has External sample supported in CMP (register bit field CR1[SE]). */
#define FSL_FEATURE_CMP_HAS_EXTERNAL_SAMPLE_SUPPORT (1)
/* @brief Has DMA support in CMP (register bit field SCR[DMAEN]). */
#define FSL_FEATURE_CMP_HAS_DMA (1)
/* @brief Has Pass Through mode in CMP (register bit field MUXCR[PSTM]). */
#define FSL_FEATURE_CMP_HAS_PASS_THROUGH_MODE (0)
/* @brief Has DAC Test function in CMP (register DACTEST). */
#define FSL_FEATURE_CMP_HAS_DAC_TEST (0)
/* EDMA module features */
/* @brief Number of DMA channels (related to number of registers TCD, DCHPRI, bit fields ERQ[ERQn], EEI[EEIn], INT[INTn], ERR[ERRn], HRS[HRSn] and bit field widths ES[ERRCHN], CEEI[CEEI], SEEI[SEEI], CERQ[CERQ], SERQ[SERQ], CDNE[CDNE], SSRT[SSRT], CERR[CERR], CINT[CINT], TCDn_CITER_ELINKYES[LINKCH], TCDn_CSR[MAJORLINKCH], TCDn_BITER_ELINKYES[LINKCH]). (Valid only for eDMA modules.) */
#define FSL_FEATURE_EDMA_MODULE_CHANNEL (32)
/* @brief Total number of DMA channels on all modules. */
#define FSL_FEATURE_EDMA_DMAMUX_CHANNELS (32)
/* @brief Number of DMA channel groups (register bit fields CR[ERGA], CR[GRPnPRI], ES[GPE], DCHPRIn[GRPPRI]). (Valid only for eDMA modules.) */
#define FSL_FEATURE_EDMA_CHANNEL_GROUP_COUNT (1)
/* @brief Has DMA_Error interrupt vector. */
#define FSL_FEATURE_EDMA_HAS_ERROR_IRQ (1)
/* @brief Number of DMA channels with asynchronous request capability (register EARS). (Valid only for eDMA modules.) */
#define FSL_FEATURE_EDMA_ASYNCHRO_REQUEST_CHANNEL_COUNT (32)
/* DMAMUX module features */
/* @brief Number of DMA channels (related to number of register CHCFGn). */
#define FSL_FEATURE_DMAMUX_MODULE_CHANNEL (32)
/* @brief Total number of DMA channels on all modules. */
#define FSL_FEATURE_DMAMUX_DMAMUX_CHANNELS (FSL_FEATURE_SOC_DMAMUX_COUNT * 32)
/* @brief Has the periodic trigger capability for the triggered DMA channel (register bit CHCFG0[TRIG]). */
#define FSL_FEATURE_DMAMUX_HAS_TRIG (1)
/* @brief Has DMA Channel Always ON function (register bit CHCFG0[A_ON]). */
#define FSL_FEATURE_DMAMUX_HAS_A_ON (1)
/* ENET module features */
/* @brief Support Interrupt Coalesce */
#define FSL_FEATURE_ENET_HAS_INTERRUPT_COALESCE (1)
/* @brief Queue Size. */
#define FSL_FEATURE_ENET_QUEUE (1)
/* @brief Has AVB Support. */
#define FSL_FEATURE_ENET_HAS_AVB (0)
/* @brief Has Timer Pulse Width control. */
#define FSL_FEATURE_ENET_HAS_TIMER_PWCONTROL (1)
/* @brief Has Extend MDIO Support. */
#define FSL_FEATURE_ENET_HAS_EXTEND_MDIO (1)
/* @brief Has Additional 1588 Timer Channel Interrupt. */
#define FSL_FEATURE_ENET_HAS_ADD_1588_TIMER_CHN_INT (0)
/* FLEXRAM module features */
/* @brief Bank size */
#define FSL_FEATURE_FLEXRAM_INTERNAL_RAM_BANK_SIZE (32 * 1024)
/* @brief Total Bank numbers */
#define FSL_FEATURE_FLEXRAM_INTERNAL_RAM_TOTAL_BANK_NUMBERS (16)
/* FLEXSPI module features */
/* @brief FlexSPI AHB buffer count */
#define FSL_FEATURE_FLEXSPI_AHB_BUFFER_COUNTn(x) (4)
/* @brief FlexSPI has no data learn. */
#define FSL_FEATURE_FLEXSPI_HAS_NO_DATA_LEARN (1)
/* GPC module features */
/* @brief Has DVFS0 Change Request. */
#define FSL_FEATURE_GPC_HAS_CNTR_DVFS0CR (0)
/* @brief Has GPC interrupt/event masking. */
#define FSL_FEATURE_GPC_HAS_CNTR_GPCIRQM (0)
/* @brief Has L2 cache power control. */
#define FSL_FEATURE_GPC_HAS_CNTR_L2PGE (0)
/* @brief Has FLEXRAM PDRAM0(bank1-7) power control. */
#define FSL_FEATURE_GPC_HAS_CNTR_PDRAM0PGE (1)
/* @brief Has VADC power control. */
#define FSL_FEATURE_GPC_HAS_CNTR_VADC (0)
/* @brief Has Display power control. */
#define FSL_FEATURE_GPC_HAS_CNTR_DISPLAY (0)
/* @brief Supports IRQ 0-31. */
#define FSL_FEATURE_GPC_HAS_IRQ_0_31 (1)
/* LCDIF module features */
/* @brief LCDIF does not support alpha support. */
#define FSL_FEATURE_LCDIF_HAS_NO_AS (1)
/* @brief LCDIF does not support output reset pin to LCD panel. */
#define FSL_FEATURE_LCDIF_HAS_NO_RESET_PIN (1)
/* @brief LCDIF supports LUT. */
#define FSL_FEATURE_LCDIF_HAS_LUT (1)
/* LPI2C module features */
/* @brief Has separate DMA RX and TX requests. */
#define FSL_FEATURE_LPI2C_HAS_SEPARATE_DMA_RX_TX_REQn(x) (0)
/* @brief Capacity (number of entries) of the transmit/receive FIFO (or zero if no FIFO is available). */
#define FSL_FEATURE_LPI2C_FIFO_SIZEn(x) (4)
/* LPSPI module features */
/* @brief Capacity (number of entries) of the transmit/receive FIFO (or zero if no FIFO is available). */
#define FSL_FEATURE_LPSPI_FIFO_SIZEn(x) (16)
/* @brief Has separate DMA RX and TX requests. */
#define FSL_FEATURE_LPSPI_HAS_SEPARATE_DMA_RX_TX_REQn(x) (1)
/* LPUART module features */
/* @brief Has receive FIFO overflow detection (bit field CFIFO[RXOFE]). */
#define FSL_FEATURE_LPUART_HAS_IRQ_EXTENDED_FUNCTIONS (0)
/* @brief Has low power features (can be enabled in wait mode via register bit C1[DOZEEN] or CTRL[DOZEEN] if the registers are 32-bit wide). */
#define FSL_FEATURE_LPUART_HAS_LOW_POWER_UART_SUPPORT (1)
/* @brief Has extended data register ED (or extra flags in the DATA register if the registers are 32-bit wide). */
#define FSL_FEATURE_LPUART_HAS_EXTENDED_DATA_REGISTER_FLAGS (1)
/* @brief Capacity (number of entries) of the transmit/receive FIFO (or zero if no FIFO is available). */
#define FSL_FEATURE_LPUART_HAS_FIFO (1)
/* @brief Has 32-bit register MODIR */
#define FSL_FEATURE_LPUART_HAS_MODIR (1)
/* @brief Hardware flow control (RTS, CTS) is supported. */
#define FSL_FEATURE_LPUART_HAS_MODEM_SUPPORT (1)
/* @brief Infrared (modulation) is supported. */
#define FSL_FEATURE_LPUART_HAS_IR_SUPPORT (1)
/* @brief 2 bits long stop bit is available. */
#define FSL_FEATURE_LPUART_HAS_STOP_BIT_CONFIG_SUPPORT (1)
/* @brief If 10-bit mode is supported. */
#define FSL_FEATURE_LPUART_HAS_10BIT_DATA_SUPPORT (1)
/* @brief If 7-bit mode is supported. */
#define FSL_FEATURE_LPUART_HAS_7BIT_DATA_SUPPORT (1)
/* @brief Baud rate fine adjustment is available. */
#define FSL_FEATURE_LPUART_HAS_BAUD_RATE_FINE_ADJUST_SUPPORT (0)
/* @brief Baud rate oversampling is available (has bit fields C4[OSR], C5[BOTHEDGE], C5[RESYNCDIS] or BAUD[OSR], BAUD[BOTHEDGE], BAUD[RESYNCDIS] if the registers are 32-bit wide). */
#define FSL_FEATURE_LPUART_HAS_BAUD_RATE_OVER_SAMPLING_SUPPORT (1)
/* @brief Baud rate oversampling is available. */
#define FSL_FEATURE_LPUART_HAS_RX_RESYNC_SUPPORT (1)
/* @brief Baud rate oversampling is available. */
#define FSL_FEATURE_LPUART_HAS_BOTH_EDGE_SAMPLING_SUPPORT (1)
/* @brief Peripheral type. */
#define FSL_FEATURE_LPUART_IS_SCI (1)
/* @brief Capacity (number of entries) of the transmit/receive FIFO (or zero if no FIFO is available). */
#define FSL_FEATURE_LPUART_FIFO_SIZEn(x) (4)
/* @brief Maximal data width without parity bit. */
#define FSL_FEATURE_LPUART_MAX_DATA_WIDTH_WITH_NO_PARITY (10)
/* @brief Maximal data width with parity bit. */
#define FSL_FEATURE_LPUART_MAX_DATA_WIDTH_WITH_PARITY (9)
/* @brief Supports two match addresses to filter incoming frames. */
#define FSL_FEATURE_LPUART_HAS_ADDRESS_MATCHING (1)
/* @brief Has transmitter/receiver DMA enable bits C5[TDMAE]/C5[RDMAE] (or BAUD[TDMAE]/BAUD[RDMAE] if the registers are 32-bit wide). */
#define FSL_FEATURE_LPUART_HAS_DMA_ENABLE (1)
/* @brief Has transmitter/receiver DMA select bits C4[TDMAS]/C4[RDMAS], resp. C5[TDMAS]/C5[RDMAS] if IS_SCI = 0. */
#define FSL_FEATURE_LPUART_HAS_DMA_SELECT (0)
/* @brief Data character bit order selection is supported (bit field S2[MSBF] or STAT[MSBF] if the registers are 32-bit wide). */
#define FSL_FEATURE_LPUART_HAS_BIT_ORDER_SELECT (1)
/* @brief Has smart card (ISO7816 protocol) support and no improved smart card support. */
#define FSL_FEATURE_LPUART_HAS_SMART_CARD_SUPPORT (0)
/* @brief Has improved smart card (ISO7816 protocol) support. */
#define FSL_FEATURE_LPUART_HAS_IMPROVED_SMART_CARD_SUPPORT (0)
/* @brief Has local operation network (CEA709.1-B protocol) support. */
#define FSL_FEATURE_LPUART_HAS_LOCAL_OPERATION_NETWORK_SUPPORT (0)
/* @brief Has 32-bit registers (BAUD, STAT, CTRL, DATA, MATCH, MODIR) instead of 8-bit (BDH, BDL, C1, S1, D, etc.). */
#define FSL_FEATURE_LPUART_HAS_32BIT_REGISTERS (1)
/* @brief Lin break detect available (has bit BAUD[LBKDIE]). */
#define FSL_FEATURE_LPUART_HAS_LIN_BREAK_DETECT (1)
/* @brief UART stops in Wait mode available (has bit C1[UARTSWAI]). */
#define FSL_FEATURE_LPUART_HAS_WAIT_MODE_OPERATION (0)
/* @brief Has separate DMA RX and TX requests. */
#define FSL_FEATURE_LPUART_HAS_SEPARATE_DMA_RX_TX_REQn(x) (1)
/* @brief Has separate RX and TX interrupts. */
#define FSL_FEATURE_LPUART_HAS_SEPARATE_RX_TX_IRQ (0)
/* @brief Has LPAURT_PARAM. */
#define FSL_FEATURE_LPUART_HAS_PARAM (1)
/* @brief Has LPUART_VERID. */
#define FSL_FEATURE_LPUART_HAS_VERID (1)
/* @brief Has LPUART_GLOBAL. */
#define FSL_FEATURE_LPUART_HAS_GLOBAL (1)
/* @brief Has LPUART_PINCFG. */
#define FSL_FEATURE_LPUART_HAS_PINCFG (1)
/* interrupt module features */
/* @brief Lowest interrupt request number. */
#define FSL_FEATURE_INTERRUPT_IRQ_MIN (-14)
/* @brief Highest interrupt request number. */
#define FSL_FEATURE_INTERRUPT_IRQ_MAX (159)
/* OCOTP module features */
/* No feature definitions */
/* PIT module features */
/* @brief Number of channels (related to number of registers LDVALn, CVALn, TCTRLn, TFLGn). */
#define FSL_FEATURE_PIT_TIMER_COUNT (4)
/* @brief Has lifetime timer (related to existence of registers LTMR64L and LTMR64H). */
#define FSL_FEATURE_PIT_HAS_LIFETIME_TIMER (1)
/* @brief Has chain mode (related to existence of register bit field TCTRLn[CHN]). */
#define FSL_FEATURE_PIT_HAS_CHAIN_MODE (1)
/* @brief Has shared interrupt handler (has not individual interrupt handler for each channel). */
#define FSL_FEATURE_PIT_HAS_SHARED_IRQ_HANDLER (1)
/* @brief Has timer enable control. */
#define FSL_FEATURE_PIT_HAS_MDIS (1)
/* PMU module features */
/* @brief PMU supports lower power control. */
#define FSL_FEATURE_PMU_HAS_LOWPWR_CTRL (0)
/* PWM module features */
/* @brief Number of each EflexPWM module channels (outputs). */
#define FSL_FEATURE_PWM_CHANNEL_COUNT (12U)
/* @brief Number of EflexPWM module A channels (outputs). */
#define FSL_FEATURE_PWM_CHANNELA_COUNT (4U)
/* @brief Number of EflexPWM module B channels (outputs). */
#define FSL_FEATURE_PWM_CHANNELB_COUNT (4U)
/* @brief Number of EflexPWM module X channels (outputs). */
#define FSL_FEATURE_PWM_CHANNELX_COUNT (4U)
/* @brief Number of each EflexPWM module compare channels interrupts. */
#define FSL_FEATURE_PWM_CMP_INT_HANDLER_COUNT (4U)
/* @brief Number of each EflexPWM module reload channels interrupts. */
#define FSL_FEATURE_PWM_RELOAD_INT_HANDLER_COUNT (4U)
/* @brief Number of each EflexPWM module capture channels interrupts. */
#define FSL_FEATURE_PWM_CAP_INT_HANDLER_COUNT (1U)
/* @brief Number of each EflexPWM module reload error channels interrupts. */
#define FSL_FEATURE_PWM_RERR_INT_HANDLER_COUNT (1U)
/* @brief Number of each EflexPWM module fault channels interrupts. */
#define FSL_FEATURE_PWM_FAULT_INT_HANDLER_COUNT (1U)
/* @brief Number of submodules in each EflexPWM module. */
#define FSL_FEATURE_PWM_SUBMODULE_COUNT (4U)
/* PXP module features */
/* @brief PXP module has dither engine. */
#define FSL_FEATURE_PXP_HAS_DITHER (0)
/* @brief PXP module supports repeat run */
#define FSL_FEATURE_PXP_HAS_EN_REPEAT (1)
/* @brief PXP doesn't have CSC */
#define FSL_FEATURE_PXP_HAS_NO_CSC2 (1)
/* @brief PXP doesn't have LUT */
#define FSL_FEATURE_PXP_HAS_NO_LUT (1)
/* RTWDOG module features */
/* @brief Watchdog is available. */
#define FSL_FEATURE_RTWDOG_HAS_WATCHDOG (1)
/* @brief RTWDOG_CNT can be 32-bit written. */
#define FSL_FEATURE_RTWDOG_HAS_32BIT_ACCESS (1)
/* SAI module features */
/* @brief Receive/transmit FIFO size in item count (register bit fields TCSR[FRDE], TCSR[FRIE], TCSR[FRF], TCR1[TFW], RCSR[FRDE], RCSR[FRIE], RCSR[FRF], RCR1[RFW], registers TFRn, RFRn). */
#define FSL_FEATURE_SAI_FIFO_COUNT (32)
/* @brief Receive/transmit channel number (register bit fields TCR3[TCE], RCR3[RCE], registers TDRn and RDRn). */
#define FSL_FEATURE_SAI_CHANNEL_COUNT (4)
/* @brief Maximum words per frame (register bit fields TCR3[WDFL], TCR4[FRSZ], TMR[TWM], RCR3[WDFL], RCR4[FRSZ], RMR[RWM]). */
#define FSL_FEATURE_SAI_MAX_WORDS_PER_FRAME (32)
/* @brief Has support of combining multiple data channel FIFOs into single channel FIFO (register bit fields TCR3[CFR], TCR4[FCOMB], TFR0[WCP], TFR1[WCP], RCR3[CFR], RCR4[FCOMB], RFR0[RCP], RFR1[RCP]). */
#define FSL_FEATURE_SAI_HAS_FIFO_COMBINE_MODE (1)
/* @brief Has packing of 8-bit and 16-bit data into each 32-bit FIFO word (register bit fields TCR4[FPACK], RCR4[FPACK]). */
#define FSL_FEATURE_SAI_HAS_FIFO_PACKING (1)
/* @brief Configures when the SAI will continue transmitting after a FIFO error has been detected (register bit fields TCR4[FCONT], RCR4[FCONT]). */
#define FSL_FEATURE_SAI_HAS_FIFO_FUNCTION_AFTER_ERROR (1)
/* @brief Configures if the frame sync is generated internally, a frame sync is only generated when the FIFO warning flag is clear or continuously (register bit fields TCR4[ONDEM], RCR4[ONDEM]). */
#define FSL_FEATURE_SAI_HAS_ON_DEMAND_MODE (1)
/* @brief Simplified bit clock source and asynchronous/synchronous mode selection (register bit fields TCR2[CLKMODE], RCR2[CLKMODE]), in comparison with the exclusively implemented TCR2[SYNC,BCS,BCI,MSEL], RCR2[SYNC,BCS,BCI,MSEL]. */
#define FSL_FEATURE_SAI_HAS_CLOCKING_MODE (0)
/* @brief Has register for configuration of the MCLK divide ratio (register bit fields MDR[FRACT], MDR[DIVIDE]). */
#define FSL_FEATURE_SAI_HAS_MCLKDIV_REGISTER (0)
/* @brief Interrupt source number */
#define FSL_FEATURE_SAI_INT_SOURCE_NUM (2)
/* @brief Has register of MCR. */
#define FSL_FEATURE_SAI_HAS_MCR (0)
/* @brief Has register of MDR */
#define FSL_FEATURE_SAI_HAS_MDR (0)
/* SNVS module features */
/* @brief Has Secure Real Time Counter Enabled and Valid (bit field LPCR[SRTC_ENV]). */
#define FSL_FEATURE_SNVS_HAS_SRTC (1)
/* SRC module features */
/* @brief There is MASK_WDOG3_RST bit in SCR register. */
#define FSL_FEATURE_SRC_HAS_SCR_MASK_WDOG3_RST (1)
/* @brief There is MIX_RST_STRCH bit in SCR register. */
#define FSL_FEATURE_SRC_HAS_SCR_MIX_RST_STRCH (0)
/* @brief There is DBG_RST_MSK_PG bit in SCR register. */
#define FSL_FEATURE_SRC_HAS_SCR_DBG_RST_MSK_PG (1)
/* @brief There is WDOG3_RST_OPTN bit in SCR register. */
#define FSL_FEATURE_SRC_HAS_SCR_WDOG3_RST_OPTN (0)
/* @brief There is CORES_DBG_RST bit in SCR register. */
#define FSL_FEATURE_SRC_HAS_SCR_CORES_DBG_RST (0)
/* @brief There is MTSR bit in SCR register. */
#define FSL_FEATURE_SRC_HAS_SCR_MTSR (0)
/* @brief There is CORE0_DBG_RST bit in SCR register. */
#define FSL_FEATURE_SRC_HAS_SCR_CORE0_DBG_RST (1)
/* @brief There is CORE0_RST bit in SCR register. */
#define FSL_FEATURE_SRC_HAS_SCR_CORE0_RST (1)
/* @brief There is LOCKUP_RST bit in SCR register. */
#define FSL_FEATURE_SRC_HAS_SCR_LOCKUP_RST (1)
/* @brief There is SWRC bit in SCR register. */
#define FSL_FEATURE_SRC_HAS_SCR_SWRC (0)
/* @brief There is EIM_RST bit in SCR register. */
#define FSL_FEATURE_SRC_HAS_SCR_EIM_RST (0)
/* @brief There is LUEN bit in SCR register. */
#define FSL_FEATURE_SRC_HAS_SCR_LUEN (0)
/* @brief There is no WRBC bit in SCR register. */
#define FSL_FEATURE_SRC_HAS_NO_SCR_WRBC (1)
/* @brief There is no WRE bit in SCR register. */
#define FSL_FEATURE_SRC_HAS_NO_SCR_WRE (1)
/* @brief There is SISR register. */
#define FSL_FEATURE_SRC_HAS_SISR (0)
/* @brief There is RESET_OUT bit in SRSR register. */
#define FSL_FEATURE_SRC_HAS_SRSR_RESET_OUT (0)
/* @brief There is WDOG3_RST_B bit in SRSR register. */
#define FSL_FEATURE_SRC_HAS_SRSR_WDOG3_RST_B (1)
/* @brief There is SW bit in SRSR register. */
#define FSL_FEATURE_SRC_HAS_SRSR_SW (0)
/* @brief There is IPP_USER_RESET_B bit in SRSR register. */
#define FSL_FEATURE_SRC_HAS_SRSR_IPP_USER_RESET_B (1)
/* @brief There is SNVS bit in SRSR register. */
#define FSL_FEATURE_SRC_HAS_SRSR_SNVS (0)
/* @brief There is CSU_RESET_B bit in SRSR register. */
#define FSL_FEATURE_SRC_HAS_SRSR_CSU_RESET_B (1)
/* @brief There is LOCKUP bit in SRSR register. */
#define FSL_FEATURE_SRC_HAS_SRSR_LOCKUP (0)
/* @brief There is LOCKUP_SYSRESETREQ bit in SRSR register. */
#define FSL_FEATURE_SRC_HAS_SRSR_LOCKUP_SYSRESETREQ (1)
/* @brief There is POR bit in SRSR register. */
#define FSL_FEATURE_SRC_HAS_SRSR_POR (0)
/* @brief There is IPP_RESET_B bit in SRSR register. */
#define FSL_FEATURE_SRC_HAS_SRSR_IPP_RESET_B (1)
/* @brief There is no WBI bit in SCR register. */
#define FSL_FEATURE_SRC_HAS_NO_SRSR_WBI (1)
/* SCB module features */
/* @brief L1 ICACHE line size in byte. */
#define FSL_FEATURE_L1ICACHE_LINESIZE_BYTE (32)
/* @brief L1 DCACHE line size in byte. */
#define FSL_FEATURE_L1DCACHE_LINESIZE_BYTE (32)
/* TRNG module features */
/* @brief TRNG has no TRNG_ACC bitfield. */
#define FSL_FEATURE_TRNG_HAS_NO_TRNG_ACC (1)
/* USBHS module features */
/* @brief EHCI module instance count */
#define FSL_FEATURE_USBHS_EHCI_COUNT (2)
/* @brief Number of endpoints supported */
#define FSL_FEATURE_USBHS_ENDPT_COUNT (8)
/* USDHC module features */
/* @brief Has external DMA support (VEND_SPEC[EXT_DMA_EN]) */
#define FSL_FEATURE_USDHC_HAS_EXT_DMA (0)
/* @brief Has HS400 mode (MIX_CTRL[HS400_MODE]) */
#define FSL_FEATURE_USDHC_HAS_HS400_MODE (0)
/* @brief Has SDR50 support (HOST_CTRL_CAP[SDR50_SUPPORT]) */
#define FSL_FEATURE_USDHC_HAS_SDR50_MODE (1)
/* @brief Has SDR104 support (HOST_CTRL_CAP[SDR104_SUPPORT]) */
#define FSL_FEATURE_USDHC_HAS_SDR104_MODE (1)
/* XBARA module features */
/* @brief DMA_CH_MUX_REQ_30. */
#define FSL_FEATURE_XBARA_OUTPUT_DMA_CH_MUX_REQ_30 (1)
/* @brief DMA_CH_MUX_REQ_31. */
#define FSL_FEATURE_XBARA_OUTPUT_DMA_CH_MUX_REQ_31 (1)
/* @brief DMA_CH_MUX_REQ_94. */
#define FSL_FEATURE_XBARA_OUTPUT_DMA_CH_MUX_REQ_94 (1)
/* @brief DMA_CH_MUX_REQ_95. */
#define FSL_FEATURE_XBARA_OUTPUT_DMA_CH_MUX_REQ_95 (1)
#endif /* _MIMXRT1052_FEATURES_H_ */

View File

@ -0,0 +1,109 @@
#! armcc -E
/*
** ###################################################################
** Processors: MIMXRT1052CVL5A
** MIMXRT1052DVL6A
**
** Compiler: Keil ARM C/C++ Compiler
** Reference manual: IMXRT1050RM Rev.C, 08/2017
** Version: rev. 0.1, 2017-01-10
** Build: b171109
**
** Abstract:
** Linker file for the Keil ARM C/C++ Compiler
**
** Copyright 2016 Freescale Semiconductor, Inc.
** Copyright 2016-2017 NXP
** Redistribution and use in source and binary forms, with or without modification,
** are permitted provided that the following conditions are met:
**
** 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 the copyright holder nor the names of its
** contributors may be used to endorse or promote products derived from this
** software without specific prior written permission.
**
** THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
** ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
** WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
** DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
** ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
** (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
** LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
** ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
** (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
** SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
**
** http: www.nxp.com
** mail: support@nxp.com
**
** ###################################################################
*/
#define __ram_vector_table__ 1
#if (defined(__ram_vector_table__))
#define __ram_vector_table_size__ 0x00000400
#else
#define __ram_vector_table_size__ 0x00000000
#endif
#define m_interrupts_start 0x60002000
#define m_interrupts_size 0x00000400
#define m_text_start 0x60002400
#define m_text_size 0x03FFDC00
#define m_interrupts_ram_start 0x20000000
#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)
#define m_data2_start 0x20200000
#define m_data2_size 0x00040000
/* 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_size { ; load region size_region
VECTOR_ROM m_interrupts_start m_interrupts_size { ; load address = execution address
* (RESET,+FIRST)
}
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)
* (NonCacheable.init)
* (NonCacheable)
}
RW_IRAM1 +0 EMPTY Heap_Size { ; Heap region growing up
}
ARM_LIB_STACK m_data_start+m_data_size EMPTY -Stack_Size { ; Stack region growing down
}
}

View File

@ -0,0 +1,265 @@
/*
** ###################################################################
** Processors: MIMXRT1052CVL5A
** MIMXRT1052DVL6A
**
** Compiler: GNU C Compiler
** Reference manual: IMXRT1050RM Rev.C, 08/2017
** Version: rev. 0.1, 2017-01-10
** Build: b171108
**
** Abstract:
** Linker file for the GNU C Compiler
**
** Copyright 2016 Freescale Semiconductor, Inc.
** Copyright 2016-2017 NXP
** Redistribution and use in source and binary forms, with or without modification,
** are permitted provided that the following conditions are met:
**
** 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 the copyright holder nor the names of its
** contributors may be used to endorse or promote products derived from this
** software without specific prior written permission.
**
** THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
** ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
** WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
** DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
** ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
** (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
** LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
** ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
** (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
** SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
**
** http: www.nxp.com
** mail: support@nxp.com
**
** ###################################################################
*/
/* Entry Point */
ENTRY(Reset_Handler)
__ram_vector_table__ = 1;
/* With the RTOS in use, this does not affect the main stack size. The size of
* the stack where main runs is determined via the RTOS. */
__stack_size__ = 0x400;
/* This is the guaranteed minimum available heap size for an application. When
* uVisor is enabled, this is also the maximum available heap size. The
* HEAP_SIZE value is set by uVisor porters to balance the size of the legacy
* heap and the page heap in uVisor applications. */
__heap_size__ = 0x1000;
HEAP_SIZE = DEFINED(__heap_size__) ? __heap_size__ : 0x0400;
STACK_SIZE = DEFINED(__stack_size__) ? __stack_size__ : 0x0400;
M_VECTOR_RAM_SIZE = DEFINED(__ram_vector_table__) ? 0x0400 : 0x0;
/* Specify the memory areas */
MEMORY
{
m_interrupts (RX) : ORIGIN = 0x60002000, LENGTH = 0x00000400
m_text (RX) : ORIGIN = 0x60002400, LENGTH = 0x03FFDC00
m_data (RW) : ORIGIN = 0x20000000, LENGTH = 0x00020000
m_data2 (RW) : ORIGIN = 0x20200000, LENGTH = 0x00040000
}
/* Define output sections */
SECTIONS
{
/* The startup code goes first into internal RAM */
.interrupts :
{
__VECTOR_TABLE = .;
. = ALIGN(4);
KEEP(*(.isr_vector)) /* Startup code */
. = ALIGN(4);
} > m_interrupts
/* The program code and other data goes into internal RAM */
.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 */
.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 */
*(m_usb_dma_init_data)
*(.data) /* .data sections */
*(.data*) /* .data* sections */
KEEP(*(.jcr*))
. = ALIGN(4);
__data_end__ = .; /* define a global symbol at data end */
} > m_data
__NDATA_ROM = __DATA_ROM + (__data_end__ - __data_start__);
.ncache.init : AT(__NDATA_ROM)
{
__noncachedata_start__ = .; /* create a global symbol at ncache data start */
*(NonCacheable.init)
. = ALIGN(4);
__noncachedata_init_end__ = .; /* create a global symbol at initialized ncache data end */
} > m_data
. = __noncachedata_init_end__;
.ncache :
{
*(NonCacheable)
. = ALIGN(4);
__noncachedata_end__ = .; /* define a global symbol at ncache data end */
} > m_data
__DATA_END = __NDATA_ROM + (__noncachedata_init_end__ - __noncachedata_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__ = .;
*(m_usb_dma_noninit_data)
*(.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,113 @@
/*
** ###################################################################
** Processors: MIMXRT1052CVL5A
** MIMXRT1052DVL6A
**
** Compiler: IAR ANSI C/C++ Compiler for ARM
** Reference manual: IMXRT1050RM Rev.C, 08/2017
** Version: rev. 0.1, 2017-01-10
** Build: b170927
**
** Abstract:
** Linker file for the IAR ANSI C/C++ Compiler for ARM
**
** Copyright 2016 Freescale Semiconductor, Inc.
** Copyright 2016-2017 NXP
** Redistribution and use in source and binary forms, with or without modification,
** are permitted provided that the following conditions are met:
**
** 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 the copyright holder nor the names of its
** contributors may be used to endorse or promote products derived from this
** software without specific prior written permission.
**
** THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
** ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
** WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
** DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
** ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
** (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
** LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
** ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
** (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
** SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
**
** http: www.nxp.com
** mail: support@nxp.com
**
** ###################################################################
*/
define symbol __ram_vector_table__ = 1;
/* Heap 1/4 of ram and stack 1/8 */
define symbol __stack_size__=0x8000;
define symbol __heap_size__=0x10000;
define symbol __ram_vector_table_size__ = isdefinedsymbol(__ram_vector_table__) ? 0x00000400 : 0;
define symbol __ram_vector_table_offset__ = isdefinedsymbol(__ram_vector_table__) ? 0x000003FF : 0;
define symbol m_interrupts_start = 0x60002000;
define symbol m_interrupts_end = 0x600023FF;
define symbol m_text_start = 0x60002400;
define symbol m_text_end = 0x63FFFFFF;
define symbol m_interrupts_ram_start = 0x20000000;
define symbol m_interrupts_ram_end = 0x20000000 + __ram_vector_table_offset__;
define symbol m_data_start = m_interrupts_ram_start + __ram_vector_table_size__;
define symbol m_data_end = 0x2001FFFF;
define symbol m_data2_start = 0x20200000;
define symbol m_data2_end = 0x2023FFFF;
/* 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 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 DATA2_region = mem:[from m_data2_start to m_data2_end];
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 };
define block NCACHE_VAR { section NonCacheable , section NonCacheable.init };
initialize by copy { readwrite, section .textrw };
do not initialize { section .noinit };
place at address mem: m_interrupts_start { readonly section .intvec };
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 DATA_region { block NCACHE_VAR };
place in CSTACK_region { block CSTACK };
place in m_interrupts_ram_region { section m_interrupts_ram };

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,45 @@
/* mbed Microcontroller Library
*******************************************************************************
* 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
#if defined(__CC_ARM)
extern uint32_t Image$$VECTOR_RAM$$Base[];
#define __VECTOR_RAM Image$$VECTOR_RAM$$Base
#else
extern uint32_t __VECTOR_RAM[];
#endif
/* Symbols defined by the linker script */
#define NVIC_NUM_VECTORS (16 + 160) // CORE + MCU Peripherals
#define NVIC_RAM_VECTOR_ADDRESS (__VECTOR_RAM) // Vectors positioned at start of RAM
#endif

View File

@ -0,0 +1,56 @@
/*
* Copyright 2014-2016 Freescale Semiconductor, Inc.
* Copyright 2016-2017 NXP
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* 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 the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
*/
#ifndef __FSL_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_MIMXRT1052CVL5A) || defined(CPU_MIMXRT1052DVL6A))
#define MIMXRT1052_SERIES
/* CMSIS-style register definitions */
#include "MIMXRT1052.h"
/* CPU specific feature definitions */
#include "MIMXRT1052_features.h"
#else
#error "No valid CPU defined!"
#endif
#endif /* __FSL_DEVICE_REGISTERS_H__ */
/*******************************************************************************
* EOF
******************************************************************************/

View File

@ -0,0 +1,195 @@
/*
** ###################################################################
** Processors: MIMXRT1052CVL5A
** MIMXRT1052DVL6A
**
** Compilers: Keil ARM C/C++ Compiler
** Freescale C/C++ for Embedded ARM
** GNU C Compiler
** IAR ANSI C/C++ Compiler for ARM
** MCUXpresso Compiler
**
** Reference manual: IMXRT1050RM Rev.C, 08/2017
** Version: rev. 0.1, 2017-01-10
** Build: b170927
**
** 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 2016 Freescale Semiconductor, Inc.
** Copyright 2016-2017 NXP
** Redistribution and use in source and binary forms, with or without modification,
** are permitted provided that the following conditions are met:
**
** 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 the copyright holder nor the names of its
** contributors may be used to endorse or promote products derived from this
** software without specific prior written permission.
**
** THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
** ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
** WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
** DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
** ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
** (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
** LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
** ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
** (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
** SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
**
** http: www.nxp.com
** mail: support@nxp.com
**
** Revisions:
** - rev. 0.1 (2017-01-10)
** Initial version.
**
** ###################################################################
*/
/*!
* @file MIMXRT1052
* @version 0.1
* @date 2017-01-10
* @brief Device specific configuration file for MIMXRT1052 (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 ((__FPU_PRESENT == 1) && (__FPU_USED == 1))
SCB->CPACR |= ((3UL << 10*2) | (3UL << 11*2)); /* set CP10, CP11 Full Access */
#endif /* ((__FPU_PRESENT == 1) && (__FPU_USED == 1)) */
/* Watchdog disable */
#if (DISABLE_WDOG)
if (WDOG1->WCR & WDOG_WCR_WDE_MASK)
{
WDOG1->WCR &= ~WDOG_WCR_WDE_MASK;
}
if (WDOG2->WCR & WDOG_WCR_WDE_MASK)
{
WDOG2->WCR &= ~WDOG_WCR_WDE_MASK;
}
RTWDOG->CNT = 0xD928C520U; /* 0xD928C520U is the update key */
RTWDOG->TOVAL = 0xFFFF;
RTWDOG->CS = (uint32_t) ((RTWDOG->CS) & ~RTWDOG_CS_EN_MASK) | RTWDOG_CS_UPDATE_MASK;
#endif /* (DISABLE_WDOG) */
/* Disable Systick which might be enabled by bootrom */
if (SysTick->CTRL & SysTick_CTRL_ENABLE_Msk)
{
SysTick->CTRL &= ~SysTick_CTRL_ENABLE_Msk;
}
/* Enable instruction and data caches */
#if defined(__ICACHE_PRESENT) && __ICACHE_PRESENT
SCB_EnableICache();
#endif
#if defined(__DCACHE_PRESENT) && __DCACHE_PRESENT
SCB_EnableDCache();
#endif
}
/* ----------------------------------------------------------------------------
-- SystemCoreClockUpdate()
---------------------------------------------------------------------------- */
void SystemCoreClockUpdate (void) {
uint32_t freq;
uint32_t PLL1MainClock;
uint32_t PLL2MainClock;
/* Periph_clk2_clk ---> Periph_clk */
if (CCM->CBCDR & CCM_CBCDR_PERIPH_CLK_SEL_MASK)
{
switch (CCM->CBCMR & CCM_CBCMR_PERIPH_CLK2_SEL_MASK)
{
/* Pll3_sw_clk ---> Periph_clk2_clk ---> Periph_clk */
case CCM_CBCMR_PERIPH_CLK2_SEL(0U):
freq = (24000000UL * ((CCM_ANALOG->PLL_USB1 & CCM_ANALOG_PLL_USB1_DIV_SELECT_MASK) ? 22U : 20U));
break;
/* Osc_clk ---> Periph_clk2_clk ---> Periph_clk */
case CCM_CBCMR_PERIPH_CLK2_SEL(1U):
freq = 24000000UL;
break;
case CCM_CBCMR_PERIPH_CLK2_SEL(2U):
case CCM_CBCMR_PERIPH_CLK2_SEL(3U):
default:
freq = 0U;
break;
}
freq /= (((CCM->CBCDR & CCM_CBCDR_PERIPH_CLK2_PODF_MASK) >> CCM_CBCDR_PERIPH_CLK2_PODF_SHIFT) + 1U);
}
/* Pre_Periph_clk ---> Periph_clk */
else
{
PLL1MainClock = ((24000000UL * ((CCM_ANALOG->PLL_ARM & CCM_ANALOG_PLL_ARM_DIV_SELECT_MASK) >>
CCM_ANALOG_PLL_ARM_DIV_SELECT_SHIFT)) >> 1U);
PLL2MainClock = (24000000UL * ((CCM_ANALOG->PLL_SYS & CCM_ANALOG_PLL_SYS_DIV_SELECT_MASK) ? 22U : 20U));
PLL2MainClock += ((uint64_t)24000000UL * ((uint64_t)(CCM_ANALOG->PLL_SYS_NUM))) / ((uint64_t)(CCM_ANALOG->PLL_SYS_DENOM));
switch (CCM->CBCMR & CCM_CBCMR_PRE_PERIPH_CLK_SEL_MASK)
{
/* PLL2 ---> Pre_Periph_clk ---> Periph_clk */
case CCM_CBCMR_PRE_PERIPH_CLK_SEL(0U):
freq = PLL2MainClock;
break;
/* PLL2 PFD2 ---> Pre_Periph_clk ---> Periph_clk */
case CCM_CBCMR_PRE_PERIPH_CLK_SEL(1U):
freq = PLL2MainClock / ((CCM_ANALOG->PFD_528 & CCM_ANALOG_PFD_528_PFD2_FRAC_MASK) >> CCM_ANALOG_PFD_528_PFD2_FRAC_SHIFT) * 18U;
break;
/* PLL2 PFD0 ---> Pre_Periph_clk ---> Periph_clk */
case CCM_CBCMR_PRE_PERIPH_CLK_SEL(2U):
freq = PLL2MainClock / ((CCM_ANALOG->PFD_528 & CCM_ANALOG_PFD_528_PFD0_FRAC_MASK) >> CCM_ANALOG_PFD_528_PFD0_FRAC_SHIFT) * 18U;
break;
/* PLL1 divided(/2) ---> Pre_Periph_clk ---> Periph_clk */
case CCM_CBCMR_PRE_PERIPH_CLK_SEL(3U):
freq = PLL1MainClock / (((CCM->CACRR & CCM_CACRR_ARM_PODF_MASK) >> CCM_CACRR_ARM_PODF_SHIFT) + 1U);
break;
default:
freq = 0U;
break;
}
}
SystemCoreClock = (freq / (((CCM->CBCDR & CCM_CBCDR_AHB_PODF_MASK) >> CCM_CBCDR_AHB_PODF_SHIFT) + 1U));
}

View File

@ -0,0 +1,123 @@
/*
** ###################################################################
** Processors: MIMXRT1052CVL5A
** MIMXRT1052DVL6A
**
** Compilers: Keil ARM C/C++ Compiler
** Freescale C/C++ for Embedded ARM
** GNU C Compiler
** IAR ANSI C/C++ Compiler for ARM
** MCUXpresso Compiler
**
** Reference manual: IMXRT1050RM Rev.C, 08/2017
** Version: rev. 0.1, 2017-01-10
** Build: b170927
**
** 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 2016 Freescale Semiconductor, Inc.
** Copyright 2016-2017 NXP
** Redistribution and use in source and binary forms, with or without modification,
** are permitted provided that the following conditions are met:
**
** 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 the copyright holder nor the names of its
** contributors may be used to endorse or promote products derived from this
** software without specific prior written permission.
**
** THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
** ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
** WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
** DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
** ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
** (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
** LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
** ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
** (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
** SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
**
** http: www.nxp.com
** mail: support@nxp.com
**
** Revisions:
** - rev. 0.1 (2017-01-10)
** Initial version.
**
** ###################################################################
*/
/*!
* @file MIMXRT1052
* @version 0.1
* @date 2017-01-10
* @brief Device specific configuration file for MIMXRT1052 (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_MIMXRT1052_H_
#define _SYSTEM_MIMXRT1052_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 24000000UL /* Value of the external crystal or oscillator clock frequency in Hz */
#define DEFAULT_SYSTEM_CLOCK 528000000UL /* 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_MIMXRT1052_H_ */

View File

@ -0,0 +1,296 @@
/*
* Copyright (c) 2016, Freescale Semiconductor, Inc.
* Copyright 2016-2017 NXP
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include "fsl_adc.h"
/*******************************************************************************
* Prototypes
******************************************************************************/
/*!
* @brief Get instance number for ADC module.
*
* @param base ADC peripheral base address
*/
static uint32_t ADC_GetInstance(ADC_Type *base);
/*******************************************************************************
* Variables
******************************************************************************/
/*! @brief Pointers to ADC bases for each instance. */
static ADC_Type *const s_adcBases[] = ADC_BASE_PTRS;
/*! @brief Pointers to ADC clocks for each instance. */
static const clock_ip_name_t s_adcClocks[] = ADC_CLOCKS;
/*******************************************************************************
* Code
******************************************************************************/
static uint32_t ADC_GetInstance(ADC_Type *base)
{
uint32_t instance;
/* Find the instance index from base address mappings. */
for (instance = 0; instance < ARRAY_SIZE(s_adcBases); instance++)
{
if (s_adcBases[instance] == base)
{
break;
}
}
assert(instance < ARRAY_SIZE(s_adcBases));
return instance;
}
void ADC_Init(ADC_Type *base, const adc_config_t *config)
{
assert(NULL != config);
uint32_t tmp32;
/* Enable the clock. */
CLOCK_EnableClock(s_adcClocks[ADC_GetInstance(base)]);
/* ADCx_CFG */
tmp32 = base->CFG & (ADC_CFG_AVGS_MASK | ADC_CFG_ADTRG_MASK); /* Reserve AVGS and ADTRG bits. */
tmp32 |= ADC_CFG_REFSEL(config->referenceVoltageSource) | ADC_CFG_ADSTS(config->samplePeriodMode) |
ADC_CFG_ADICLK(config->clockSource) | ADC_CFG_ADIV(config->clockDriver) | ADC_CFG_MODE(config->resolution);
if (config->enableOverWrite)
{
tmp32 |= ADC_CFG_OVWREN_MASK;
}
if (config->enableLongSample)
{
tmp32 |= ADC_CFG_ADLSMP_MASK;
}
if (config->enableLowPower)
{
tmp32 |= ADC_CFG_ADLPC_MASK;
}
if (config->enableHighSpeed)
{
tmp32 |= ADC_CFG_ADHSC_MASK;
}
base->CFG = tmp32;
/* ADCx_GC */
tmp32 = base->GC & ~(ADC_GC_ADCO_MASK | ADC_GC_ADACKEN_MASK);
if (config->enableContinuousConversion)
{
tmp32 |= ADC_GC_ADCO_MASK;
}
if (config->enableAsynchronousClockOutput)
{
tmp32 |= ADC_GC_ADACKEN_MASK;
}
base->GC = tmp32;
}
void ADC_Deinit(ADC_Type *base)
{
/* Disable the clock. */
CLOCK_DisableClock(s_adcClocks[ADC_GetInstance(base)]);
}
void ADC_GetDefaultConfig(adc_config_t *config)
{
assert(NULL != config);
config->enableAsynchronousClockOutput = true;
config->enableOverWrite = false;
config->enableContinuousConversion = false;
config->enableHighSpeed = false;
config->enableLowPower = false;
config->enableLongSample = false;
config->referenceVoltageSource = kADC_ReferenceVoltageSourceAlt0;
config->samplePeriodMode = kADC_SamplePeriod2or12Clocks;
config->clockSource = kADC_ClockSourceAD;
config->clockDriver = kADC_ClockDriver1;
config->resolution = kADC_Resolution12Bit;
}
void ADC_SetChannelConfig(ADC_Type *base, uint32_t channelGroup, const adc_channel_config_t *config)
{
assert(NULL != config);
assert(channelGroup < ADC_HC_COUNT);
uint32_t tmp32;
tmp32 = ADC_HC_ADCH(config->channelNumber);
if (config->enableInterruptOnConversionCompleted)
{
tmp32 |= ADC_HC_AIEN_MASK;
}
base->HC[channelGroup] = tmp32;
}
/*
*To complete calibration, the user must follow the below procedure:
* 1. Configure ADC_CFG with actual operating values for maximum accuracy.
* 2. Configure the ADC_GC values along with CAL bit.
* 3. Check the status of CALF bit in ADC_GS and the CAL bit in ADC_GC.
* 4. When CAL bit becomes '0' then check the CALF status and COCO[0] bit status.
*/
status_t ADC_DoAutoCalibration(ADC_Type *base)
{
status_t status = kStatus_Success;
#if !(defined(FSL_FEATURE_ADC_SUPPORT_HARDWARE_TRIGGER_REMOVE) && FSL_FEATURE_ADC_SUPPORT_HARDWARE_TRIGGER_REMOVE)
bool bHWTrigger = false;
/* 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_CFG_ADTRG_MASK & base->CFG))
{
bHWTrigger = true;
ADC_EnableHardwareTrigger(base, false);
}
#endif
/* Clear the CALF and launch the calibration. */
base->GS = ADC_GS_CALF_MASK; /* Clear the CALF. */
base->GC |= ADC_GC_CAL_MASK; /* Launch the calibration. */
/* Check the status of CALF bit in ADC_GS and the CAL bit in ADC_GC. */
while (0U != (base->GC & ADC_GC_CAL_MASK))
{
/* Check the CALF when the calibration is active. */
if (0U != (ADC_GetStatusFlags(base) & kADC_CalibrationFailedFlag))
{
status = kStatus_Fail;
break;
}
}
/* When CAL bit becomes '0' then check the CALF status and COCO[0] bit status. */
if (0U == ADC_GetChannelStatusFlags(base, 0U)) /* Check the COCO[0] bit status. */
{
status = kStatus_Fail;
}
if (0U != (ADC_GetStatusFlags(base) & kADC_CalibrationFailedFlag)) /* Check the CALF status. */
{
status = kStatus_Fail;
}
/* Clear conversion done flag. */
ADC_GetChannelConversionValue(base, 0U);
#if !(defined(FSL_FEATURE_ADC_SUPPORT_HARDWARE_TRIGGER_REMOVE) && FSL_FEATURE_ADC_SUPPORT_HARDWARE_TRIGGER_REMOVE)
/* Restore original trigger mode. */
if (true == bHWTrigger)
{
ADC_EnableHardwareTrigger(base, true);
}
#endif
return status;
}
void ADC_SetOffsetConfig(ADC_Type *base, const adc_offest_config_t *config)
{
assert(NULL != config);
uint32_t tmp32;
tmp32 = ADC_OFS_OFS(config->offsetValue);
if (config->enableSigned)
{
tmp32 |= ADC_OFS_SIGN_MASK;
}
base->OFS = tmp32;
}
void ADC_SetHardwareCompareConfig(ADC_Type *base, const adc_hardware_compare_config_t *config)
{
uint32_t tmp32;
tmp32 = base->GC & ~(ADC_GC_ACFE_MASK | ADC_GC_ACFGT_MASK | ADC_GC_ACREN_MASK);
if (NULL == config) /* Pass "NULL" to disable the feature. */
{
base->GC = tmp32;
return;
}
/* Enable the feature. */
tmp32 |= ADC_GC_ACFE_MASK;
/* Select the hardware compare working mode. */
switch (config->hardwareCompareMode)
{
case kADC_HardwareCompareMode0:
break;
case kADC_HardwareCompareMode1:
tmp32 |= ADC_GC_ACFGT_MASK;
break;
case kADC_HardwareCompareMode2:
tmp32 |= ADC_GC_ACREN_MASK;
break;
case kADC_HardwareCompareMode3:
tmp32 |= ADC_GC_ACFGT_MASK | ADC_GC_ACREN_MASK;
break;
default:
break;
}
base->GC = tmp32;
/* Load the compare values. */
tmp32 = ADC_CV_CV1(config->value1) | ADC_CV_CV2(config->value2);
base->CV = tmp32;
}
void ADC_SetHardwareAverageConfig(ADC_Type *base, adc_hardware_average_mode_t mode)
{
uint32_t tmp32;
if (mode == kADC_HardwareAverageDiasable)
{
base->GC &= ~ADC_GC_AVGE_MASK;
}
else
{
tmp32 = base->CFG & ~ADC_CFG_AVGS_MASK;
tmp32 |= ADC_CFG_AVGS(mode);
base->CFG = tmp32;
base->GC |= ADC_GC_AVGE_MASK; /* Enable the hardware compare. */
}
}
void ADC_ClearStatusFlags(ADC_Type *base, uint32_t mask)
{
uint32_t tmp32 = 0;
if (0U != (mask & kADC_CalibrationFailedFlag))
{
tmp32 |= ADC_GS_CALF_MASK;
}
if (0U != (mask & kADC_ConversionActiveFlag))
{
tmp32 |= ADC_GS_ADACT_MASK;
}
base->GS = tmp32;
}

View File

@ -0,0 +1,442 @@
/*
* Copyright (c) 2016, Freescale Semiconductor, Inc.
* Copyright 2016-2017 NXP
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _FSL_ADC_H_
#define _FSL_ADC_H_
#include "fsl_common.h"
/*!
* @addtogroup adc_12b1msps_sar
* @{
*/
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @brief ADC driver version */
#define FSL_ADC_DRIVER_VERSION (MAKE_VERSION(2, 0, 0)) /*!< Version 2.0.0. */
/*!
* @brief Converter's status flags.
*/
typedef enum _adc_status_flags
{
kADC_ConversionActiveFlag = ADC_GS_ADACT_MASK, /*!< Conversion is active,not support w1c. */
kADC_CalibrationFailedFlag = ADC_GS_CALF_MASK, /*!< Calibration is failed,support w1c. */
kADC_AsynchronousWakeupInterruptFlag =
ADC_GS_AWKST_MASK, /*!< Asynchronous wakeup interrupt occured, support w1c. */
} adc_status_flags_t;
/*!
* @brief Reference voltage source.
*/
typedef enum _adc_reference_voltage_source
{
kADC_ReferenceVoltageSourceAlt0 = 0U, /*!< For external pins pair of VrefH and VrefL. */
} adc_reference_voltage_source_t;
/*!
* @brief Sample time duration.
*/
typedef enum _adc_sample_period_mode
{
/* This group of enumeration is for internal use which is related to register setting. */
kADC_SamplePeriod2or12Clocks = 0U, /*!< Long sample 12 clocks or short sample 2 clocks. */
kADC_SamplePeriod4or16Clocks = 1U, /*!< Long sample 16 clocks or short sample 4 clocks. */
kADC_SamplePeriod6or20Clocks = 2U, /*!< Long sample 20 clocks or short sample 6 clocks. */
kADC_SamplePeriod8or24Clocks = 3U, /*!< Long sample 24 clocks or short sample 8 clocks. */
/* This group of enumeration is for a public user. */
/* For long sample mode. */
kADC_SamplePeriodLong12Clcoks = kADC_SamplePeriod2or12Clocks, /*!< Long sample 12 clocks. */
kADC_SamplePeriodLong16Clcoks = kADC_SamplePeriod4or16Clocks, /*!< Long sample 16 clocks. */
kADC_SamplePeriodLong20Clcoks = kADC_SamplePeriod6or20Clocks, /*!< Long sample 20 clocks. */
kADC_SamplePeriodLong24Clcoks = kADC_SamplePeriod8or24Clocks, /*!< Long sample 24 clocks. */
/* For short sample mode. */
kADC_SamplePeriodShort2Clocks = kADC_SamplePeriod2or12Clocks, /*!< Short sample 2 clocks. */
kADC_SamplePeriodShort4Clocks = kADC_SamplePeriod4or16Clocks, /*!< Short sample 4 clocks. */
kADC_SamplePeriodShort6Clocks = kADC_SamplePeriod6or20Clocks, /*!< Short sample 6 clocks. */
kADC_SamplePeriodShort8Clocks = kADC_SamplePeriod8or24Clocks, /*!< Short sample 8 clocks. */
} adc_sample_period_mode_t;
/*!
* @brief Clock source.
*/
typedef enum _adc_clock_source
{
kADC_ClockSourceIPG = 0U, /*!< Select IPG clock to generate ADCK. */
kADC_ClockSourceIPGDiv2 = 1U, /*!< Select IPG clock divided by 2 to generate ADCK. */
#if !(defined(FSL_FEATURE_ADC_SUPPORT_ALTCLK_REMOVE) && FSL_FEATURE_ADC_SUPPORT_ALTCLK_REMOVE)
kADC_ClockSourceALT = 2U, /*!< Select alternate clock to generate ADCK. */
#endif
kADC_ClockSourceAD = 3U, /*!< Select Asynchronous clock to generate ADCK. */
} adc_clock_source_t;
/*!
* @brief Clock divider for the converter.
*/
typedef enum _adc_clock_drvier
{
kADC_ClockDriver1 = 0U, /*!< For divider 1 from the input clock to the module. */
kADC_ClockDriver2 = 1U, /*!< For divider 2 from the input clock to the module. */
kADC_ClockDriver4 = 2U, /*!< For divider 4 from the input clock to the module. */
kADC_ClockDriver8 = 3U, /*!< For divider 8 from the input clock to the module. */
} adc_clock_driver_t;
/*!
* @brief Converter's resolution.
*/
typedef enum _adc_resolution
{
kADC_Resolution8Bit = 0U, /*!< Single End 8-bit resolution. */
kADC_Resolution10Bit = 1U, /*!< Single End 10-bit resolution. */
kADC_Resolution12Bit = 2U, /*!< Single End 12-bit resolution. */
} adc_resolution_t;
/*!
* @brief Converter hardware compare mode.
*/
typedef enum _adc_hardware_compare_mode
{
kADC_HardwareCompareMode0 = 0U, /*!< Compare true if the result is less than the value1. */
kADC_HardwareCompareMode1 = 1U, /*!< Compare true if the result is greater than or equal to value1. */
kADC_HardwareCompareMode2 = 2U, /*!< Value1 <= Value2, compare true if the result is less than value1 Or
the result is Greater than value2.
Value1 > Value2, compare true if the result is less than value1 And the
result is greater than value2*/
kADC_HardwareCompareMode3 = 3U, /*!< Value1 <= Value2, compare true if the result is greater than or equal
to value1 And the result is less than or equal to value2.
Value1 > Value2, compare true if the result is greater than or equal to
value1 Or the result is less than or equal to value2. */
} adc_hardware_compare_mode_t;
/*!
* @brief Converter hardware average mode.
*/
typedef enum _adc_hardware_average_mode
{
kADC_HardwareAverageCount4 = 0U, /*!< For hardware average with 4 samples. */
kADC_HardwareAverageCount8 = 1U, /*!< For hardware average with 8 samples. */
kADC_HardwareAverageCount16 = 2U, /*!< For hardware average with 16 samples. */
kADC_HardwareAverageCount32 = 3U, /*!< For hardware average with 32 samples. */
kADC_HardwareAverageDiasable = 4U, /*!< Disable the hardware average function. */
} adc_hardware_average_mode_t;
/*!
* @brief Converter configuration.
*/
typedef struct _adc_config
{
bool enableOverWrite; /*!< Enable the overwriting. */
bool enableContinuousConversion; /*!< Enable the continuous conversion mode. */
bool enableHighSpeed; /*!< Enable the high-speed mode. */
bool enableLowPower; /*!< Enable the low power mode. */
bool enableLongSample; /*!< Enable the long sample mode. */
bool enableAsynchronousClockOutput; /*!< Enable the asynchronous clock output. */
adc_reference_voltage_source_t referenceVoltageSource; /*!< Select the reference voltage source. */
adc_sample_period_mode_t samplePeriodMode; /*!< Select the sample period in long sample mode or short mode. */
adc_clock_source_t clockSource; /*!< Select the input clock source to generate the internal clock ADCK. */
adc_clock_driver_t clockDriver; /*!< Select the divide ratio used by the ADC to generate the internal clock ADCK. */
adc_resolution_t resolution; /*!< Select the ADC resolution mode. */
} adc_config_t;
/*!
* @brief Converter Offset configuration.
*/
typedef struct _adc_offest_config
{
bool enableSigned; /*!< if false,The offset value is added with the raw result.
if true,The offset value is subtracted from the raw converted value. */
uint32_t offsetValue; /*!< User configurable offset value(0-4095). */
} adc_offest_config_t;
/*!
* @brief ADC hardware compare configuration.
*
* In kADC_HardwareCompareMode0, compare true if the result is less than the value1.
* In kADC_HardwareCompareMode1, compare true if the result is greater than or equal to value1.
* In kADC_HardwareCompareMode2, Value1 <= Value2, compare true if the result is less than value1 Or the result is
* Greater than value2.
* Value1 > Value2, compare true if the result is less than value1 And the result is
* Greater than value2.
* In kADC_HardwareCompareMode3, Value1 <= Value2, compare true if the result is greater than or equal to value1 And the
* result is less than or equal to value2.
* Value1 > Value2, compare true if the result is greater than or equal to value1 Or the
* result is less than or equal to value2.
*/
typedef struct _adc_hardware_compare_config
{
adc_hardware_compare_mode_t hardwareCompareMode; /*!< Select the hardware compare mode.
See "adc_hardware_compare_mode_t". */
uint16_t value1; /*!< Setting value1(0-4095) for hardware compare mode. */
uint16_t value2; /*!< Setting value2(0-4095) for hardware compare mode. */
} adc_hardware_compare_config_t;
/*!
* @brief ADC channel conversion configuration.
*/
typedef struct _adc_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. */
} adc_channel_config_t;
/*******************************************************************************
* API
******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif
/*!
* @name Initialization
* @{
*/
/*!
* @brief Initialize the ADC module.
*
* @param base ADC peripheral base address.
* @param config Pointer to "adc_config_t" structure.
*/
void ADC_Init(ADC_Type *base, const adc_config_t *config);
/*!
* @brief De-initializes the ADC module.
*
* @param base ADC peripheral base address.
*/
void ADC_Deinit(ADC_Type *base);
/*!
* @brief Gets an available pre-defined settings for the converter's configuration.
*
* This function initializes the converter configuration structure with available settings. The default values are:
* @code
* config->enableAsynchronousClockOutput = true;
* config->enableOverWrite = false;
* config->enableContinuousConversion = false;
* config->enableHighSpeed = false;
* config->enableLowPower = false;
* config->enableLongSample = false;
* config->referenceVoltageSource = kADC_ReferenceVoltageSourceAlt0;
* config->samplePeriodMode = kADC_SamplePeriod2or12Clocks;
* config->clockSource = kADC_ClockSourceAD;
* config->clockDriver = kADC_ClockDriver1;
* config->resolution = kADC_Resolution12Bit;
* @endcode
* @param base ADC peripheral base address.
* @param config Pointer to the configuration structure.
*/
void ADC_GetDefaultConfig(adc_config_t *config);
/*!
* @brief Configures the conversion channel.
*
* This operation triggers the conversion when in software trigger mode. When in hardware trigger mode, this API
* configures the channel while the external trigger source helps to trigger the conversion.
*
* Note that the "Channel Group" has a detailed description.
* To allow sequential conversions of the ADC to be triggered by internal peripherals, the ADC has more than one
* group of status and control registers, one for each conversion. The channel group parameter indicates which group of
* registers are used, for example channel group 0 is for Group A registers and channel group 1 is for Group B
* registers. The
* channel groups are used in a "ping-pong" approach to control the ADC operation. At any point, only one of
* the channel groups is actively controlling ADC conversions. The channel group 0 is used for both software and
* hardware
* trigger modes. Channel groups 1 and greater indicate potentially multiple channel group registers for
* use only in hardware trigger mode. See the chip configuration information in the appropriate 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. Therefore, writing to these channel groups does not initiate a new conversion.
* Updating the channel group 0 while a different channel group is actively controlling a conversion is allowed and
* vice versa. Writing any of the channel group registers while that specific channel group is actively controlling a
* conversion aborts the current conversion.
*
* @param base ADC peripheral base address.
* @param channelGroup Channel group index.
* @param config Pointer to the "adc_channel_config_t" structure for the conversion channel.
*/
void ADC_SetChannelConfig(ADC_Type *base, uint32_t channelGroup, const adc_channel_config_t *config);
/*!
* @brief Gets the conversion value.
*
* @param base ADC peripheral base address.
* @param channelGroup Channel group index.
*
* @return Conversion value.
*/
static inline uint32_t ADC_GetChannelConversionValue(ADC_Type *base, uint32_t channelGroup)
{
assert(channelGroup < ADC_R_COUNT);
return base->R[channelGroup];
}
/*!
* @brief Gets the status flags of channel.
*
* A conversion is completed when the result of the conversion is transferred into the data
* result registers. (provided the compare function & hardware averaging is disabled), this is
* indicated by the setting of COCOn. If hardware averaging is enabled, COCOn sets only,
* if the last of the selected number of conversions is complete. If the compare function is
* enabled, COCOn sets and conversion result data is transferred only if the compare
* condition is true. If both hardware averaging and compare functions are enabled, then
* COCOn sets only if the last of the selected number of conversions is complete and the
* compare condition is true.
*
* @param base ADC peripheral base address.
* @param channelGroup Channel group index.
*
* @return Status flags of channel.return 0 means COCO flag is 0,return 1 means COCOflag is 1.
*/
static inline uint32_t ADC_GetChannelStatusFlags(ADC_Type *base, uint32_t channelGroup)
{
assert(channelGroup < ADC_HC_COUNT);
/* If flag is set,return 1,otherwise, return 0. */
return (((base->HS) & (1U << channelGroup)) >> channelGroup);
}
/*!
* @brief Automates the hardware calibration.
*
* This auto calibration helps to adjust the plus/minus side gain automatically.
* Execute the calibration before using the converter. Note that the software trigger should be used
* during calibration.
*
* @param base ADC peripheral base address.
*
* @return Execution status.
* @retval kStatus_Success Calibration is done successfully.
* @retval kStatus_Fail Calibration has failed.
*/
status_t ADC_DoAutoCalibration(ADC_Type *base);
/*!
* @brief Set user defined offset.
*
* @param base ADC peripheral base address.
* @param config Pointer to "adc_offest_config_t" structure.
*/
void ADC_SetOffsetConfig(ADC_Type *base, const adc_offest_config_t *config);
/*!
* @brief Enables generating the DMA trigger when the conversion is complete.
*
* @param base ADC peripheral base address.
* @param enable Switcher of the DMA feature. "true" means enabled, "false" means not enabled.
*/
static inline void ADC_EnableDMA(ADC_Type *base, bool enable)
{
if (enable)
{
base->GC |= ADC_GC_DMAEN_MASK;
}
else
{
base->GC &= ~ADC_GC_DMAEN_MASK;
}
}
/*!
* @brief Enables the hardware trigger mode.
*
* @param base ADC peripheral base address.
* @param enable Switcher of the trigger mode. "true" means hardware tirgger mode,"false" means software mode.
*/
#if !(defined(FSL_FEATURE_ADC_SUPPORT_HARDWARE_TRIGGER_REMOVE) && FSL_FEATURE_ADC_SUPPORT_HARDWARE_TRIGGER_REMOVE)
static inline void ADC_EnableHardwareTrigger(ADC_Type *base, bool enable)
{
if (enable)
{
base->CFG |= ADC_CFG_ADTRG_MASK;
}
else
{
base->CFG &= ~ADC_CFG_ADTRG_MASK;
}
}
#endif
/*!
* @brief Configures the hardware compare mode.
*
* The hardware compare mode provides a way to process the conversion result automatically by using hardware. Only the
* result
* in the compare range is available. To compare the range, see "adc_hardware_compare_mode_t" or the appopriate
* reference
* manual for more information.
*
* @param base ADC peripheral base address.
* @param Pointer to "adc_hardware_compare_config_t" structure.
*
*/
void ADC_SetHardwareCompareConfig(ADC_Type *base, const adc_hardware_compare_config_t *config);
/*!
* @brief Configures the hardware average mode.
*
* The hardware average mode provides a way to process the conversion result automatically by using hardware. The
* multiple
* conversion results are accumulated and averaged internally making them easier to read.
*
* @param base ADC peripheral base address.
* @param mode Setting the hardware average mode. See "adc_hardware_average_mode_t".
*/
void ADC_SetHardwareAverageConfig(ADC_Type *base, adc_hardware_average_mode_t mode);
/*!
* @brief Gets the converter's status flags.
*
* @param base ADC peripheral base address.
*
* @return Flags' mask if indicated flags are asserted. See "adc_status_flags_t".
*/
static inline uint32_t ADC_GetStatusFlags(ADC_Type *base)
{
return base->GS;
}
/*!
* @brief Clears the converter's status falgs.
*
* @param base ADC peripheral base address.
* @param mask Mask value for the cleared flags. See "adc_status_flags_t".
*/
void ADC_ClearStatusFlags(ADC_Type *base, uint32_t mask);
#if defined(__cplusplus)
}
#endif
#endif /* _FSL_ADC_H_ */

View File

@ -0,0 +1,349 @@
/*
* Copyright (c) 2016, Freescale Semiconductor, Inc.
* Copyright 2016-2017 NXP
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include "fsl_adc_etc.h"
/*******************************************************************************
* Prototypes
******************************************************************************/
#if defined(ADC_ETC_CLOCKS)
/*!
* @brief Get instance number for ADC_ETC module.
*
* @param base ADC_ETC peripheral base address
*/
static uint32_t ADC_ETC_GetInstance(ADC_ETC_Type *base);
/*******************************************************************************
* Variables
******************************************************************************/
/*! @brief Pointers to ADC_ETC bases for each instance. */
static ADC_ETC_Type *const s_adcetcBases[] = ADC_ETC_BASE_PTRS;
/*! @brief Pointers to ADC_ETC clocks for each instance. */
static const clock_ip_name_t s_adcetcClocks[] = ADC_ETC_CLOCKS;
/*******************************************************************************
* Code
******************************************************************************/
static uint32_t ADC_ETC_GetInstance(ADC_ETC_Type *base)
{
uint32_t instance = 0U;
uint32_t adcetcArrayCount = (sizeof(s_adcetcBases) / sizeof(s_adcetcBases[0]));
/* Find the instance index from base address mappings. */
for (instance = 0; instance < adcetcArrayCount; instance++)
{
if (s_adcetcBases[instance] == base)
{
break;
}
}
return instance;
}
#endif /* ADC_ETC_CLOCKS */
void ADC_ETC_Init(ADC_ETC_Type *base, const adc_etc_config_t *config)
{
assert(NULL != config);
uint32_t tmp32;
#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
#if defined(ADC_ETC_CLOCKS)
/* Open clock gate. */
CLOCK_EnableClock(s_adcetcClocks[ADC_ETC_GetInstance(base)]);
#endif /* ADC_ETC_CLOCKS */
#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
/* Disable software reset. */
ADC_ETC_DoSoftwareReset(base, false);
/* Set ADC_ETC_CTRL register. */
tmp32 = ADC_ETC_CTRL_EXT0_TRIG_PRIORITY(config->TSC0triggerPriority) |
ADC_ETC_CTRL_EXT1_TRIG_PRIORITY(config->TSC1triggerPriority) |
ADC_ETC_CTRL_PRE_DIVIDER(config->clockPreDivider) | ADC_ETC_CTRL_TRIG_ENABLE(config->XBARtriggerMask);
if (config->enableTSCBypass)
{
tmp32 |= ADC_ETC_CTRL_TSC_BYPASS_MASK;
}
if (config->enableTSC0Trigger)
{
tmp32 |= ADC_ETC_CTRL_EXT0_TRIG_ENABLE_MASK;
}
if (config->enableTSC1Trigger)
{
tmp32 |= ADC_ETC_CTRL_EXT1_TRIG_ENABLE_MASK;
}
base->CTRL = tmp32;
}
void ADC_ETC_Deinit(ADC_ETC_Type *base)
{
/* Do software reset to clear all logical. */
ADC_ETC_DoSoftwareReset(base, true);
#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
#if defined(ADC_ETC_CLOCKS)
/* Close clock gate. */
CLOCK_DisableClock(s_adcetcClocks[ADC_ETC_GetInstance(base)]);
#endif /* ADC_ETC_CLOCKS */
#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
}
void ADC_ETC_GetDefaultConfig(adc_etc_config_t *config)
{
config->enableTSCBypass = true;
config->enableTSC0Trigger = false;
config->enableTSC1Trigger = false;
config->TSC0triggerPriority = 0U;
config->TSC1triggerPriority = 0U;
config->clockPreDivider = 0U;
config->XBARtriggerMask = 0U;
}
void ADC_ETC_SetTriggerConfig(ADC_ETC_Type *base, uint32_t triggerGroup, const adc_etc_trigger_config_t *config)
{
assert(triggerGroup < ADC_ETC_TRIGn_CTRL_COUNT);
assert(ADC_ETC_TRIGn_COUNTER_COUNT > triggerGroup);
uint32_t tmp32;
/* Set ADC_ETC_TRGn_CTRL register. */
tmp32 = ADC_ETC_TRIGn_CTRL_TRIG_CHAIN(config->triggerChainLength) |
ADC_ETC_TRIGn_CTRL_TRIG_PRIORITY(config->triggerPriority);
if (config->enableSyncMode)
{
tmp32 |= ADC_ETC_TRIGn_CTRL_SYNC_MODE_MASK;
}
if (config->enableSWTriggerMode)
{
tmp32 |= ADC_ETC_TRIGn_CTRL_TRIG_MODE_MASK;
}
base->TRIG[triggerGroup].TRIGn_CTRL = tmp32;
/* Set ADC_ETC_TRGn_COUNTER register. */
tmp32 = ADC_ETC_TRIGn_COUNTER_INIT_DELAY(config->initialDelay) |
ADC_ETC_TRIGn_COUNTER_SAMPLE_INTERVAL(config->sampleIntervalDelay);
base->TRIG[triggerGroup].TRIGn_COUNTER = tmp32;
}
void ADC_ETC_SetTriggerChainConfig(ADC_ETC_Type *base,
uint32_t triggerGroup,
uint32_t chainGroup,
const adc_etc_trigger_chain_config_t *config)
{
assert(triggerGroup < ADC_ETC_TRIGn_CTRL_COUNT);
uint32_t tmp;
uint32_t tmp32;
uint8_t mRemainder = chainGroup % 2U;
/* Set ADC_ETC_TRIGn_CHAINm register. */
tmp = ADC_ETC_TRIGn_CHAIN_1_0_HWTS0(config->ADCHCRegisterSelect) |
ADC_ETC_TRIGn_CHAIN_1_0_CSEL0(config->ADCChannelSelect) |
ADC_ETC_TRIGn_CHAIN_1_0_IE0(config->InterruptEnable);
if (config->enableB2BMode)
{
tmp |= ADC_ETC_TRIGn_CHAIN_1_0_B2B0_MASK;
}
switch (chainGroup / 2U)
{
case 0U: /* Configurate trigger chain0 and chain 1. */
tmp32 = base->TRIG[triggerGroup].TRIGn_CHAIN_1_0;
if (mRemainder == 0U) /* Chain 0. */
{
tmp32 &= ~(ADC_ETC_TRIGn_CHAIN_1_0_CSEL0_MASK | ADC_ETC_TRIGn_CHAIN_1_0_HWTS0_MASK |
ADC_ETC_TRIGn_CHAIN_1_0_B2B0_MASK | ADC_ETC_TRIGn_CHAIN_1_0_IE0_MASK);
tmp32 |= tmp;
}
else /* Chain 1. */
{
tmp32 &= ~(ADC_ETC_TRIGn_CHAIN_1_0_CSEL1_MASK | ADC_ETC_TRIGn_CHAIN_1_0_HWTS1_MASK |
ADC_ETC_TRIGn_CHAIN_1_0_B2B1_MASK | ADC_ETC_TRIGn_CHAIN_1_0_IE1_MASK);
tmp32 |= (tmp << ADC_ETC_TRIGn_CHAIN_1_0_CSEL1_SHIFT);
}
base->TRIG[triggerGroup].TRIGn_CHAIN_1_0 = tmp32;
break;
case 1U: /* Configurate trigger chain2 and chain 3. */
tmp32 = base->TRIG[triggerGroup].TRIGn_CHAIN_3_2;
if (mRemainder == 0U) /* Chain 2. */
{
tmp32 &= ~(ADC_ETC_TRIGn_CHAIN_3_2_CSEL2_MASK | ADC_ETC_TRIGn_CHAIN_3_2_HWTS2_MASK |
ADC_ETC_TRIGn_CHAIN_3_2_B2B2_MASK | ADC_ETC_TRIGn_CHAIN_3_2_IE2_MASK);
tmp32 |= tmp;
}
else /* Chain 3. */
{
tmp32 &= ~(ADC_ETC_TRIGn_CHAIN_3_2_CSEL3_MASK | ADC_ETC_TRIGn_CHAIN_3_2_HWTS3_MASK |
ADC_ETC_TRIGn_CHAIN_3_2_B2B3_MASK | ADC_ETC_TRIGn_CHAIN_3_2_IE3_MASK);
tmp32 |= (tmp << ADC_ETC_TRIGn_CHAIN_3_2_CSEL3_SHIFT);
}
base->TRIG[triggerGroup].TRIGn_CHAIN_3_2 = tmp32;
break;
case 2U: /* Configurate trigger chain4 and chain 5. */
tmp32 = base->TRIG[triggerGroup].TRIGn_CHAIN_5_4;
if (mRemainder == 0U) /* Chain 4. */
{
tmp32 &= ~(ADC_ETC_TRIGn_CHAIN_5_4_CSEL4_MASK | ADC_ETC_TRIGn_CHAIN_5_4_HWTS4_MASK |
ADC_ETC_TRIGn_CHAIN_5_4_B2B4_MASK | ADC_ETC_TRIGn_CHAIN_5_4_IE4_MASK);
tmp32 |= tmp;
}
else /* Chain 5. */
{
tmp32 &= ~(ADC_ETC_TRIGn_CHAIN_5_4_CSEL5_MASK | ADC_ETC_TRIGn_CHAIN_5_4_HWTS5_MASK |
ADC_ETC_TRIGn_CHAIN_5_4_B2B5_MASK | ADC_ETC_TRIGn_CHAIN_5_4_IE5_MASK);
tmp32 |= (tmp << ADC_ETC_TRIGn_CHAIN_5_4_CSEL5_SHIFT);
}
base->TRIG[triggerGroup].TRIGn_CHAIN_5_4 = tmp32;
break;
case 3U: /* Configurate trigger chain6 and chain 7. */
tmp32 = base->TRIG[triggerGroup].TRIGn_CHAIN_7_6;
if (mRemainder == 0U) /* Chain 6. */
{
tmp32 &= ~(ADC_ETC_TRIGn_CHAIN_7_6_CSEL6_MASK | ADC_ETC_TRIGn_CHAIN_7_6_HWTS6_MASK |
ADC_ETC_TRIGn_CHAIN_7_6_B2B6_MASK | ADC_ETC_TRIGn_CHAIN_7_6_IE6_MASK);
tmp32 |= tmp;
}
else /* Chain 7. */
{
tmp32 &= ~(ADC_ETC_TRIGn_CHAIN_7_6_CSEL7_MASK | ADC_ETC_TRIGn_CHAIN_7_6_HWTS7_MASK |
ADC_ETC_TRIGn_CHAIN_7_6_B2B7_MASK | ADC_ETC_TRIGn_CHAIN_7_6_IE7_MASK);
tmp32 |= (tmp << ADC_ETC_TRIGn_CHAIN_7_6_CSEL7_SHIFT);
}
base->TRIG[triggerGroup].TRIGn_CHAIN_7_6 = tmp32;
break;
default:
break;
}
}
uint32_t ADC_ETC_GetInterruptStatusFlags(ADC_ETC_Type *base, adc_etc_external_trigger_source_t sourceIndex)
{
uint32_t tmp32 = 0U;
if (((base->DONE0_1_IRQ) & (ADC_ETC_DONE0_1_IRQ_TRIG0_DONE0_MASK << sourceIndex)) != 0U)
{
tmp32 |= kADC_ETC_Done0StatusFlagMask; /* Customized DONE0 status flags mask, which is defined in fsl_adc_etc.h
file. */
}
if (((base->DONE0_1_IRQ) & (ADC_ETC_DONE0_1_IRQ_TRIG0_DONE1_MASK << sourceIndex)) != 0U)
{
tmp32 |= kADC_ETC_Done1StatusFlagMask; /* Customized DONE1 status flags mask, which is defined in fsl_adc_etc.h
file. */
}
if (((base->DONE2_ERR_IRQ) & (ADC_ETC_DONE2_ERR_IRQ_TRIG0_DONE2_MASK << sourceIndex)) != 0U)
{
tmp32 |= kADC_ETC_Done2StatusFlagMask; /* Customized DONE2 status flags mask, which is defined in fsl_adc_etc.h
file. */
}
if (((base->DONE2_ERR_IRQ) & (ADC_ETC_DONE2_ERR_IRQ_TRIG0_ERR_MASK << sourceIndex)) != 0U)
{
tmp32 |= kADC_ETC_ErrorStatusFlagMask; /* Customized ERROR status flags mask, which is defined in fsl_adc_etc.h
file. */
}
return tmp32;
}
void ADC_ETC_ClearInterruptStatusFlags(ADC_ETC_Type *base, adc_etc_external_trigger_source_t sourceIndex, uint32_t mask)
{
if (0U != (mask & kADC_ETC_Done0StatusFlagMask)) /* Write 1 to clear DONE0 status flags. */
{
base->DONE0_1_IRQ = (ADC_ETC_DONE0_1_IRQ_TRIG0_DONE0_MASK << sourceIndex);
}
if (0U != (mask & kADC_ETC_Done1StatusFlagMask)) /* Write 1 to clear DONE1 status flags. */
{
base->DONE0_1_IRQ = (ADC_ETC_DONE0_1_IRQ_TRIG0_DONE1_MASK << sourceIndex);
}
if (0U != (mask & kADC_ETC_Done2StatusFlagMask)) /* Write 1 to clear DONE2 status flags. */
{
base->DONE2_ERR_IRQ = (ADC_ETC_DONE2_ERR_IRQ_TRIG0_DONE2_MASK << sourceIndex);
}
if (0U != (mask & kADC_ETC_ErrorStatusFlagMask)) /* Write 1 to clear ERROR status flags. */
{
base->DONE2_ERR_IRQ = (ADC_ETC_DONE2_ERR_IRQ_TRIG0_ERR_MASK << sourceIndex);
}
}
uint32_t ADC_ETC_GetADCConversionValue(ADC_ETC_Type *base, uint32_t triggerGroup, uint32_t chainGroup)
{
assert(triggerGroup < ADC_ETC_TRIGn_RESULT_1_0_COUNT);
uint32_t mADCResult;
uint8_t mRemainder = chainGroup % 2U;
switch (chainGroup / 2U)
{
case 0U:
if (0U == mRemainder)
{
mADCResult = ADC_ETC_TRIGn_RESULT_1_0_DATA0_MASK & (base->TRIG[triggerGroup].TRIGn_RESULT_1_0);
}
else
{
mADCResult = (base->TRIG[triggerGroup].TRIGn_RESULT_1_0) >> ADC_ETC_TRIGn_RESULT_1_0_DATA1_SHIFT;
}
break;
case 1U:
if (0U == mRemainder)
{
mADCResult = ADC_ETC_TRIGn_RESULT_3_2_DATA2_MASK & (base->TRIG[triggerGroup].TRIGn_RESULT_3_2);
}
else
{
mADCResult = (base->TRIG[triggerGroup].TRIGn_RESULT_3_2) >> ADC_ETC_TRIGn_RESULT_3_2_DATA3_SHIFT;
}
break;
case 2U:
if (0U == mRemainder)
{
mADCResult = ADC_ETC_TRIGn_RESULT_5_4_DATA4_MASK & (base->TRIG[triggerGroup].TRIGn_RESULT_5_4);
}
else
{
mADCResult = (base->TRIG[triggerGroup].TRIGn_RESULT_5_4) >> ADC_ETC_TRIGn_RESULT_5_4_DATA5_SHIFT;
}
break;
case 3U:
if (0U == mRemainder)
{
mADCResult = ADC_ETC_TRIGn_RESULT_7_6_DATA6_MASK & (base->TRIG[triggerGroup].TRIGn_RESULT_7_6);
}
else
{
mADCResult = (base->TRIG[triggerGroup].TRIGn_RESULT_7_6) >> ADC_ETC_TRIGn_RESULT_7_6_DATA7_SHIFT;
}
break;
default:
return 0U;
}
return mADCResult;
}

View File

@ -0,0 +1,324 @@
/*
* Copyright (c) 2016, Freescale Semiconductor, Inc.
* Copyright 2016-2017 NXP
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _FSL_ADC_ETC_H_
#define _FSL_ADC_ETC_H_
#include "fsl_common.h"
/*!
* @addtogroup adc_etc
* @{
*/
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @brief ADC_ETC driver version */
#define FSL_ADC_ETC_DRIVER_VERSION (MAKE_VERSION(2, 0, 0)) /*!< Version 2.0.0. */
/*! @brief The mask of status flags cleared by writing 1. */
#define ADC_ETC_DMA_CTRL_TRGn_REQ_MASK 0xFF0000U
/*!
* @brief ADC_ETC customized status flags mask.
*/
enum _adc_etc_status_flag_mask
{
kADC_ETC_Done0StatusFlagMask = 1U,
kADC_ETC_Done1StatusFlagMask = 2U,
kADC_ETC_Done2StatusFlagMask = 4U,
kADC_ETC_ErrorStatusFlagMask = 8U,
};
/*!
* @brief External triggers sources.
*/
typedef enum _adc_etc_external_trigger_source
{
/* External XBAR sources. Support HW or SW mode. */
kADC_ETC_Trg0TriggerSource = 0U, /* External XBAR trigger0 source. */
kADC_ETC_Trg1TriggerSource = 1U, /* External XBAR trigger1 source. */
kADC_ETC_Trg2TriggerSource = 2U, /* External XBAR trigger2 source. */
kADC_ETC_Trg3TriggerSource = 3U, /* External XBAR trigger3 source. */
kADC_ETC_Trg4TriggerSource = 4U, /* External XBAR trigger4 source. */
kADC_ETC_Trg5TriggerSource = 5U, /* External XBAR trigger5 source. */
kADC_ETC_Trg6TriggerSource = 6U, /* External XBAR trigger6 source. */
kADC_ETC_Trg7TriggerSource = 7U, /* External XBAR trigger7 source. */
/* External TSC sources. Only support HW mode. */
kADC_ETC_TSC0TriggerSource = 8U, /* External TSC trigger0 source. */
kADC_ETC_TSC1TriggerSource = 9U, /* External TSC trigger1 source. */
} adc_etc_external_trigger_source_t;
/*!
* @brief Interrupt enable/disable mask.
*/
typedef enum _adc_etc_interrupt_enable
{
kADC_ETC_InterruptDisable = 0U, /* Disable the ADC_ETC interrupt. */
kADC_ETC_Done0InterruptEnable = 1U, /* Enable the DONE0 interrupt when ADC conversions complete. */
kADC_ETC_Done1InterruptEnable = 2U, /* Enable the DONE1 interrupt when ADC conversions complete. */
kADC_ETC_Done2InterruptEnable = 3U, /* Enable the DONE2 interrupt when ADC conversions complete. */
} adc_etc_interrupt_enable_t;
/*!
* @brief ADC_ETC configuration.
*/
typedef struct _adc_etc_config
{
bool enableTSCBypass; /* If bypass TSC, TSC would trigger ADC directly.
Otherwise TSC would trigger ADC through ADC_ETC. */
bool enableTSC0Trigger; /* Enable external TSC0 trigger. It is valid when enableTSCBypass = false. */
bool enableTSC1Trigger; /* Enable external TSC1 trigger. It is valid when enableTSCBypass = false.*/
uint32_t TSC0triggerPriority; /* External TSC0 trigger priority, 7 is highest, 0 is lowest. */
uint32_t TSC1triggerPriority; /* External TSC1 trigger priority, 7 is highest, 0 is lowest. */
uint32_t clockPreDivider; /* Pre-divider for trig delay and interval. Available range is 0-255.
Clock would be divided by (clockPreDivider+1). */
uint32_t XBARtriggerMask; /* Enable the corresponding trigger source. Available range is trigger0:0x01 to
trigger7:0x80
For example, XBARtriggerMask = 0x7U, which means trigger0, trigger1 and trigger2 is
enabled. */
} adc_etc_config_t;
/*!
* @brief ADC_ETC trigger chain configuration.
*/
typedef struct _adc_etc_trigger_chain_config
{
bool enableB2BMode; /* Enable ADC_ETC BackToBack mode. when not enabled B2B mode,
wait until interval delay is reached. */
uint32_t ADCHCRegisterSelect; /* Select relevant ADC_HCx register to trigger. 1U : HC0, 2U: HC1, 4U: HC2 ... */
uint32_t ADCChannelSelect; /* Select ADC sample channel. */
adc_etc_interrupt_enable_t InterruptEnable; /* Enable/disable Interrupt. */
} adc_etc_trigger_chain_config_t;
/*!
* @brief ADC_ETC trigger configuration.
*/
typedef struct _adc_etc_trigger_config
{
bool enableSyncMode; /* Enable the sync Mode, In SyncMode ADC1 and ADC2 are controlled by the same trigger source.
In AsyncMode ADC1 and ADC2 are controlled by separate trigger source. */
bool enableSWTriggerMode; /* Enable the sofware trigger mode. */
uint32_t triggerChainLength; /* TRIG chain length to the ADC. 0: Trig length is 1. ... 7: Trig length is 8. */
uint32_t triggerPriority; /* External trigger priority, 7 is highest, 0 is lowest. */
uint32_t sampleIntervalDelay; /* Set sampling interval delay. */
uint32_t initialDelay; /* Set trigger initial delay. */
} adc_etc_trigger_config_t;
/*******************************************************************************
* API
******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif
/*!
* @name Initialization
* @{
*/
/*!
* @brief Initialize the ADC_ETC module.
*
* @param base ADC_ETC peripheral base address.
* @param config Pointer to "adc_etc_config_t" structure.
*/
void ADC_ETC_Init(ADC_ETC_Type *base, const adc_etc_config_t *config);
/*!
* @brief De-Initialize the ADC_ETC module.
*
* @param base ADC_ETC peripheral base address.
*/
void ADC_ETC_Deinit(ADC_ETC_Type *base);
/*!
* @brief Gets an available pre-defined settings for the ADC_ETC's configuration.
* This function initializes the ADC_ETC's configuration structure with available settings. The default values are:
* @code
* config->enableTSCBypass = true;
* config->enableTSC0Trigger = false;
* config->enableTSC1Trigger = false;
* config->TSC0triggerPriority = 0U;
* config->TSC1triggerPriority = 0U;
* config->clockPreDivider = 0U;
* config->XBARtriggerMask = 0U;
* @endCode
*
* @param config Pointer to "adc_etc_config_t" structure.
*/
void ADC_ETC_GetDefaultConfig(adc_etc_config_t *config);
/*!
* @brief Set the external XBAR trigger configuration.
*
* @param base ADC_ETC peripheral base address.
* @param triggerGroup Trigger group index.
* @param config Pointer to "adc_etc_trigger_config_t" structure.
*/
void ADC_ETC_SetTriggerConfig(ADC_ETC_Type *base, uint32_t triggerGroup, const adc_etc_trigger_config_t *config);
/*!
* @brief Set the external XBAR trigger chain configuration.
* For example, if triggerGroup is set to 0U and chainGroup is set to 1U, which means Trigger0 source's chain1 would be
* configurated.
*
* @param base ADC_ETC peripheral base address.
* @param triggerGroup Trigger group index. Available number is 0~7.
* @param chainGroup Trigger chain group index. Available number is 0~7.
* @param config Pointer to "adc_etc_trigger_chain_config_t" structure.
*/
void ADC_ETC_SetTriggerChainConfig(ADC_ETC_Type *base,
uint32_t triggerGroup,
uint32_t chainGroup,
const adc_etc_trigger_chain_config_t *config);
/*!
* @brief Gets the interrupt status flags of external XBAR and TSC triggers.
*
* @param base ADC_ETC peripheral base address.
* @param sourceIndex trigger source index.
*
* @return Status flags mask of trigger. Refer to "_adc_etc_status_flag_mask".
*/
uint32_t ADC_ETC_GetInterruptStatusFlags(ADC_ETC_Type *base, adc_etc_external_trigger_source_t sourceIndex);
/*!
* @brief Clears the ADC_ETC's interrupt status falgs.
*
* @param base ADC_ETC peripheral base address.
* @param sourceIndex trigger source index.
* @param mask Status flags mask of trigger. Refer to "_adc_etc_status_flag_mask".
*/
void ADC_ETC_ClearInterruptStatusFlags(ADC_ETC_Type *base,
adc_etc_external_trigger_source_t sourceIndex,
uint32_t mask);
/*!
* @brief Enable the DMA corresponding to each trigger source.
*
* @param base ADC_ETC peripheral base address.
* @param triggerGroup Trigger group index. Available number is 0~7.
*/
static inline void ADC_ETC_EnableDMA(ADC_ETC_Type *base, uint32_t triggerGroup)
{
/* Avoid clearing status flags at the same time. */
base->DMA_CTRL =
(base->DMA_CTRL | (ADC_ETC_DMA_CTRL_TRIG0_ENABLE_MASK << triggerGroup)) & ~ADC_ETC_DMA_CTRL_TRGn_REQ_MASK;
}
/*!
* @brief Disable the DMA corresponding to each trigger sources.
*
* @param base ADC_ETC peripheral base address.
* @param triggerGroup Trigger group index. Available number is 0~7.
*/
static inline void ADC_ETC_DisableDMA(ADC_ETC_Type *base, uint32_t triggerGroup)
{
/* Avoid clearing status flags at the same time. */
base->DMA_CTRL =
(base->DMA_CTRL & ~(ADC_ETC_DMA_CTRL_TRIG0_ENABLE_MASK << triggerGroup)) & ~ADC_ETC_DMA_CTRL_TRGn_REQ_MASK;
}
/*!
* @brief Get the DMA request status falgs. Only external XBAR sources support DMA request.
*
* @param base ADC_ETC peripheral base address.
* @return Mask of external XBAR tirgger's DMA request asserted flags. Available range is trigger0:0x01 to
* trigger7:0x80.
*/
static inline uint32_t ADC_ETC_GetDMAStatusFlags(ADC_ETC_Type *base)
{
return (((base->DMA_CTRL) & ADC_ETC_DMA_CTRL_TRGn_REQ_MASK) >> ADC_ETC_DMA_CTRL_TRIG0_REQ_SHIFT);
}
/*!
* @brief Clear the DMA request status falgs. Only external XBAR sources support DMA request.
*
* @param base ADC_ETC peripheral base address.
* @param mask Mask of external XBAR tirgger's DMA request asserted flags. Available range is trigger0:0x01 to
* trigger7:0x80.
*/
static inline void ADC_ETC_ClearDMAStatusFlags(ADC_ETC_Type *base, uint32_t mask)
{
base->DMA_CTRL = ((base->DMA_CTRL) & ~ADC_ETC_DMA_CTRL_TRGn_REQ_MASK) | (mask << ADC_ETC_DMA_CTRL_TRIG0_REQ_SHIFT);
}
/*!
* @brief When enable ,all logical will be reset.
*
* @param base ADC_ETC peripheral base address.
* @param enable Enable/Disable the software reset.
*/
static inline void ADC_ETC_DoSoftwareReset(ADC_ETC_Type *base, bool enable)
{
if (enable)
{
base->CTRL |= ADC_ETC_CTRL_SOFTRST_MASK;
}
else
{
base->CTRL &= ~ADC_ETC_CTRL_SOFTRST_MASK;
}
}
/*!
* @brief Do software trigger corresponding to each XBAR trigger sources.
* Each XBAR trigger sources can be configured as HW or SW trigger mode. In hardware trigger mode,
* trigger source is from XBAR. In software mode, trigger source is from software tigger. TSC trigger sources
* can only work in hardware trigger mode.
*
* @param base ADC_ETC peripheral base address.
* @param triggerGroup Trigger group index. Available number is 0~7.
*/
static inline void ADC_ETC_DoSoftwareTrigger(ADC_ETC_Type *base, uint32_t triggerGroup)
{
assert(triggerGroup < ADC_ETC_TRIGn_CTRL_COUNT);
base->TRIG[triggerGroup].TRIGn_CTRL |= ADC_ETC_TRIGn_CTRL_SW_TRIG_MASK;
}
/*!
* @brief Get ADC conversion result from external XBAR sources.
* For example, if triggerGroup is set to 0U and chainGroup is set to 1U, which means the API would
* return Trigger0 source's chain1 conversion result.
*
* @param base ADC_ETC peripheral base address.
* @param triggerGroup Trigger group index. Available number is 0~7.
* @param chainGroup Trigger chain group index. Available number is 0~7.
* @return ADC conversion result value.
*/
uint32_t ADC_ETC_GetADCConversionValue(ADC_ETC_Type *base, uint32_t triggerGroup, uint32_t chainGroup);
#if defined(__cplusplus)
}
#endif
#endif /* _FSL_ADC_ETC_H_ */

View File

@ -0,0 +1,56 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* Copyright 2016-2017 NXP
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include "fsl_aipstz.h"
/*******************************************************************************
* Definitions
******************************************************************************/
/*******************************************************************************
* Prototypes
******************************************************************************/
void AIPSTZ_SetMasterPriviledgeLevel(AIPSTZ_Type *base, aipstz_master_t master, uint32_t privilegeConfig)
{
uint32_t mask = ((uint32_t)master >> 8) - 1;
uint32_t shift = (uint32_t)master & 0xFF;
base->MPR = (base->MPR & (~(mask << shift))) | (privilegeConfig << shift);
}
void AIPSTZ_SetPeripheralAccessControl(AIPSTZ_Type *base, aipstz_peripheral_t peripheral, uint32_t accessControl)
{
volatile uint32_t *reg = (uint32_t *)((uint32_t)base + ((uint32_t)peripheral >> 16));
uint32_t mask = (((uint32_t)peripheral & 0xFF00U) >> 8) - 1;
uint32_t shift = (uint32_t)peripheral & 0xFF;
*reg = (*reg & (~(mask << shift))) | ((accessControl & mask) << shift);
}

View File

@ -0,0 +1,151 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* Copyright 2017 NXP
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _FSL_AIPSTZ_H_
#define _FSL_AIPSTZ_H_
#include "fsl_common.h"
/*!
* @addtogroup aipstz
* @{
*/
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @name Driver version */
/*@{*/
#define FSL_AIPSTZ_DRIVER_VERSION (MAKE_VERSION(2, 0, 0)) /*!< Version 2.0.0 */
/*@}*/
/*! @brief List of AIPSTZ privilege configuration.*/
typedef enum _aipstz_master_privilege_level {
kAIPSTZ_MasterBufferedWriteEnable = (1U << 3), /*!< Write accesses from this master are allowed to be buffered. */
kAIPSTZ_MasterTrustedForReadEnable = (1U << 2), /*!< This master is trusted for read accesses. */
kAIPSTZ_MasterTrustedForWriteEnable = (1U << 1), /*!< This master is trusted for write accesses. */
kAIPSTZ_MasterForceUserModeEnable = 1U /*!< Accesses from this master are forced to user-mode. */
} aipstz_master_privilege_level_t;
/*! @brief List of AIPSTZ masters. Organized by width for the 8-15 bits and shift for lower 8 bits.*/
typedef enum _aipstz_master {
kAIPSTZ_Master0 = (0x400U | 28U),
kAIPSTZ_Master1 = (0x400U | 24U),
kAIPSTZ_Master2 = (0x400U | 20U),
kAIPSTZ_Master3 = (0x400U | 16U),
kAIPSTZ_Master5 = (0x400U | 8U)
} aipstz_master_t;
/*! @brief List of AIPSTZ peripheral access control configuration.*/
typedef enum _aipstz_peripheral_access_control {
kAIPSTZ_PeripheralAllowUntrustedMaster = 1U,
kAIPSTZ_PeripheralWriteProtected = (1U < 1),
kAIPSTZ_PeripheralRequireSupervisor = (1U < 2),
kAIPSTZ_PeripheralAllowBufferedWrite = (1U < 2)
} aipstz_peripheral_access_control_t;
/*! @brief List of AIPSTZ peripherals. Organized by register offset for higher 32 bits, width for the 8-15 bits and shift for lower 8 bits.*/
typedef enum _aipstz_peripheral {
kAIPSTZ_Peripheral0 = ((0x40 << 16) | (4 << 8) | 28),
kAIPSTZ_Peripheral1 = ((0x40 << 16) | (4 << 8) | 24),
kAIPSTZ_Peripheral2 = ((0x40 << 16) | (4 << 8) | 20),
kAIPSTZ_Peripheral3 = ((0x40 << 16) | (4 << 8) | 16),
kAIPSTZ_Peripheral4 = ((0x40 << 16) | (4 << 8) | 12),
kAIPSTZ_Peripheral5 = ((0x40 << 16) | (4 << 8) | 8),
kAIPSTZ_Peripheral6 = ((0x40 << 16) | (4 << 8) | 4),
kAIPSTZ_Peripheral7 = ((0x40 << 16) | (4 << 8) | 0),
kAIPSTZ_Peripheral8 = ((0x44 << 16) | (4 << 8) | 28),
kAIPSTZ_Peripheral9 = ((0x44 << 16) | (4 << 8) | 24),
kAIPSTZ_Peripheral10 = ((0x44 << 16) | (4 << 8) | 20),
kAIPSTZ_Peripheral11 = ((0x44 << 16) | (4 << 8) | 16),
kAIPSTZ_Peripheral12 = ((0x44 << 16) | (4 << 8) | 12),
kAIPSTZ_Peripheral13 = ((0x44 << 16) | (4 << 8) | 8),
kAIPSTZ_Peripheral14 = ((0x44 << 16) | (4 << 8) | 4),
kAIPSTZ_Peripheral15 = ((0x44 << 16) | (4 << 8) | 0),
kAIPSTZ_Peripheral16 = ((0x48 << 16) | (4 << 8) | 28),
kAIPSTZ_Peripheral17 = ((0x48 << 16) | (4 << 8) | 24),
kAIPSTZ_Peripheral18 = ((0x48 << 16) | (4 << 8) | 20),
kAIPSTZ_Peripheral19 = ((0x48 << 16) | (4 << 8) | 16),
kAIPSTZ_Peripheral20 = ((0x48 << 16) | (4 << 8) | 12),
kAIPSTZ_Peripheral21 = ((0x48 << 16) | (4 << 8) | 8),
kAIPSTZ_Peripheral22 = ((0x48 << 16) | (4 << 8) | 4),
kAIPSTZ_Peripheral23 = ((0x48 << 16) | (4 << 8) | 0),
kAIPSTZ_Peripheral24 = ((0x4C << 16) | (4 << 8) | 28),
kAIPSTZ_Peripheral25 = ((0x4C << 16) | (4 << 8) | 24),
kAIPSTZ_Peripheral26 = ((0x4C << 16) | (4 << 8) | 20),
kAIPSTZ_Peripheral27 = ((0x4C << 16) | (4 << 8) | 16),
kAIPSTZ_Peripheral28 = ((0x4C << 16) | (4 << 8) | 12),
kAIPSTZ_Peripheral29 = ((0x4C << 16) | (4 << 8) | 8),
kAIPSTZ_Peripheral30 = ((0x4C << 16) | (4 << 8) | 4),
kAIPSTZ_Peripheral31 = ((0x4C << 16) | (4 << 8) | 0),
kAIPSTZ_Peripheral32 = ((0x50 << 16) | (4 << 8) | 28),
kAIPSTZ_Peripheral33 = ((0x50 << 16) | (4 << 8) | 24)
} aipstz_peripheral_t;
/*******************************************************************************
* API
******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif
/*!
* @name Initialization and deinitialization
* @{
*/
/*!
* @brief Configure the privilege level for master.
*
* @param base AIPSTZ peripheral base pointer
* @param master Masters for AIPSTZ.
* @param privilegeConfig Configuration is ORed from @aipstz_master_privilege_level_t.
*/
void AIPSTZ_SetMasterPriviledgeLevel(AIPSTZ_Type *base, aipstz_master_t master, uint32_t privilegeConfig);
/*!
* @brief Configure the access for peripheral.
*
* @param base AIPSTZ peripheral base pointer
* @param master Peripheral for AIPSTZ.
* @param accessControl Configuration is ORed from @aipstz_peripheral_access_control_t.
*/
void AIPSTZ_SetPeripheralAccessControl(AIPSTZ_Type *base, aipstz_peripheral_t peripheral, uint32_t accessControl);
/*! @}*/
#if defined(__cplusplus)
}
#endif
/*! @}*/
#endif /* _FSL_AIPSTZ_H_ */

View File

@ -0,0 +1,147 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* Copyright 2016-2017 NXP
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include "fsl_aoi.h"
/*******************************************************************************
* Variables
******************************************************************************/
/*! @brief Pointers to aoi bases for each instance. */
static AOI_Type *const s_aoiBases[] = AOI_BASE_PTRS;
#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
/*! @brief Pointers to aoi clocks for each instance. */
static const clock_ip_name_t s_aoiClocks[] = AOI_CLOCKS;
#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
/*******************************************************************************
* Prototypes
******************************************************************************/
/*!
* @brief Get instance number for AOI module.
*
* @param base AOI peripheral base address
*
* @return The AOI instance
*/
static uint32_t AOI_GetInstance(AOI_Type *base);
/*******************************************************************************
* Code
******************************************************************************/
static uint32_t AOI_GetInstance(AOI_Type *base)
{
uint32_t instance;
/* Find the instance index from base address mappings. */
for (instance = 0; instance < ARRAY_SIZE(s_aoiBases); instance++)
{
if (s_aoiBases[instance] == base)
{
break;
}
}
assert(instance < ARRAY_SIZE(s_aoiBases));
return instance;
}
void AOI_Init(AOI_Type *base)
{
#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
/* Enable the clock gate from clock manager. */
CLOCK_EnableClock(s_aoiClocks[AOI_GetInstance(base)]);
#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
}
void AOI_Deinit(AOI_Type *base)
{
#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
/* Disable the clock gate from clock manager */
CLOCK_DisableClock(s_aoiClocks[AOI_GetInstance(base)]);
#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
}
void AOI_GetEventLogicConfig(AOI_Type *base, aoi_event_t event, aoi_event_config_t *config)
{
assert(event < FSL_FEATURE_AOI_EVENT_COUNT);
assert(config != NULL);
uint16_t value = 0;
/* Read BFCRT01 register at event index. */
value = base->BFCRT[event].BFCRT01;
config->PT0AC = (aoi_input_config_t)((value & AOI_BFCRT01_PT0_AC_MASK) >> AOI_BFCRT01_PT0_AC_SHIFT);
config->PT0BC = (aoi_input_config_t)((value & AOI_BFCRT01_PT0_BC_MASK) >> AOI_BFCRT01_PT0_BC_SHIFT);
config->PT0CC = (aoi_input_config_t)((value & AOI_BFCRT01_PT0_CC_MASK) >> AOI_BFCRT01_PT0_CC_SHIFT);
config->PT0DC = (aoi_input_config_t)((value & AOI_BFCRT01_PT0_DC_MASK) >> AOI_BFCRT01_PT0_DC_SHIFT);
config->PT1AC = (aoi_input_config_t)((value & AOI_BFCRT01_PT1_AC_MASK) >> AOI_BFCRT01_PT1_AC_SHIFT);
config->PT1BC = (aoi_input_config_t)((value & AOI_BFCRT01_PT1_BC_MASK) >> AOI_BFCRT01_PT1_BC_SHIFT);
config->PT1CC = (aoi_input_config_t)((value & AOI_BFCRT01_PT1_CC_MASK) >> AOI_BFCRT01_PT1_CC_SHIFT);
config->PT1DC = (aoi_input_config_t)((value & AOI_BFCRT01_PT1_DC_MASK) >> AOI_BFCRT01_PT1_DC_SHIFT);
/* Read BFCRT23 register at event index. */
value = 0;
value = base->BFCRT[event].BFCRT23;
config->PT2AC = (aoi_input_config_t)((value & AOI_BFCRT23_PT2_AC_MASK) >> AOI_BFCRT23_PT2_AC_SHIFT);
config->PT2BC = (aoi_input_config_t)((value & AOI_BFCRT23_PT2_BC_MASK) >> AOI_BFCRT23_PT2_BC_SHIFT);
config->PT2CC = (aoi_input_config_t)((value & AOI_BFCRT23_PT2_CC_MASK) >> AOI_BFCRT23_PT2_CC_SHIFT);
config->PT2DC = (aoi_input_config_t)((value & AOI_BFCRT23_PT2_DC_MASK) >> AOI_BFCRT23_PT2_DC_SHIFT);
config->PT3AC = (aoi_input_config_t)((value & AOI_BFCRT23_PT3_AC_MASK) >> AOI_BFCRT23_PT3_AC_SHIFT);
config->PT3BC = (aoi_input_config_t)((value & AOI_BFCRT23_PT3_BC_MASK) >> AOI_BFCRT23_PT3_BC_SHIFT);
config->PT3CC = (aoi_input_config_t)((value & AOI_BFCRT23_PT3_CC_MASK) >> AOI_BFCRT23_PT3_CC_SHIFT);
config->PT3DC = (aoi_input_config_t)((value & AOI_BFCRT23_PT3_DC_MASK) >> AOI_BFCRT23_PT3_DC_SHIFT);
}
void AOI_SetEventLogicConfig(AOI_Type *base, aoi_event_t event, const aoi_event_config_t *eventConfig)
{
assert(eventConfig != NULL);
assert(event < FSL_FEATURE_AOI_EVENT_COUNT);
uint16_t value = 0;
/* Calculate value to configure product term 0, 1 */
value = AOI_BFCRT01_PT0_AC(eventConfig->PT0AC) | AOI_BFCRT01_PT0_BC(eventConfig->PT0BC) |
AOI_BFCRT01_PT0_CC(eventConfig->PT0CC) | AOI_BFCRT01_PT0_DC(eventConfig->PT0DC) |
AOI_BFCRT01_PT1_AC(eventConfig->PT1AC) | AOI_BFCRT01_PT1_BC(eventConfig->PT1BC) |
AOI_BFCRT01_PT1_CC(eventConfig->PT1CC) | AOI_BFCRT01_PT1_DC(eventConfig->PT1DC);
/* Write value to register */
base->BFCRT[event].BFCRT01 = value;
/* Reset and calculate value to configure product term 2, 3 */
value = 0;
value = AOI_BFCRT23_PT2_AC(eventConfig->PT2AC) | AOI_BFCRT23_PT2_BC(eventConfig->PT2BC) |
AOI_BFCRT23_PT2_CC(eventConfig->PT2CC) | AOI_BFCRT23_PT2_DC(eventConfig->PT2DC) |
AOI_BFCRT23_PT3_AC(eventConfig->PT3AC) | AOI_BFCRT23_PT3_BC(eventConfig->PT3BC) |
AOI_BFCRT23_PT3_CC(eventConfig->PT3CC) | AOI_BFCRT23_PT3_DC(eventConfig->PT3DC);
/* Write value to register */
base->BFCRT[event].BFCRT23 = value;
}

View File

@ -0,0 +1,209 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* Copyright 2016-2017 NXP
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _FSL_AOI_H_
#define _FSL_AOI_H_
#include "fsl_common.h"
/*!
* @addtogroup aoi
* @{
*/
/*******************************************************************************
* Definitions
******************************************************************************/
#ifndef AOI
#define AOI AOI0 /*!< AOI peripheral address */
#endif
/*! @name Driver version */
/*@{*/
#define FSL_AOI_DRIVER_VERSION (MAKE_VERSION(2, 0, 0)) /*!< Version 2.0.0. */
/*@}*/
/*!
* @brief AOI input configurations.
*
* The selection item represents the Boolean evaluations.
*/
typedef enum _aoi_input_config
{
kAOI_LogicZero = 0x0U, /*!< Forces the input to logical zero. */
kAOI_InputSignal = 0x1U, /*!< Passes the input signal. */
kAOI_InvInputSignal = 0x2U, /*!< Inverts the input signal. */
kAOI_LogicOne = 0x3U /*!< Forces the input to logical one. */
} aoi_input_config_t;
/*!
* @brief AOI event indexes, where an event is the collection of the four product
* terms (0, 1, 2, and 3) and the four signal inputs (A, B, C, and D).
*/
typedef enum _aoi_event
{
kAOI_Event0 = 0x0U, /*!< Event 0 index */
kAOI_Event1 = 0x1U, /*!< Event 1 index */
kAOI_Event2 = 0x2U, /*!< Event 2 index */
kAOI_Event3 = 0x3U /*!< Event 3 index */
} aoi_event_t;
/*!
* @brief AOI event configuration structure
*
* Defines structure _aoi_event_config and use the AOI_SetEventLogicConfig() function to make
* whole event configuration.
*/
typedef struct _aoi_event_config
{
aoi_input_config_t PT0AC; /*!< Product term 0 input A */
aoi_input_config_t PT0BC; /*!< Product term 0 input B */
aoi_input_config_t PT0CC; /*!< Product term 0 input C */
aoi_input_config_t PT0DC; /*!< Product term 0 input D */
aoi_input_config_t PT1AC; /*!< Product term 1 input A */
aoi_input_config_t PT1BC; /*!< Product term 1 input B */
aoi_input_config_t PT1CC; /*!< Product term 1 input C */
aoi_input_config_t PT1DC; /*!< Product term 1 input D */
aoi_input_config_t PT2AC; /*!< Product term 2 input A */
aoi_input_config_t PT2BC; /*!< Product term 2 input B */
aoi_input_config_t PT2CC; /*!< Product term 2 input C */
aoi_input_config_t PT2DC; /*!< Product term 2 input D */
aoi_input_config_t PT3AC; /*!< Product term 3 input A */
aoi_input_config_t PT3BC; /*!< Product term 3 input B */
aoi_input_config_t PT3CC; /*!< Product term 3 input C */
aoi_input_config_t PT3DC; /*!< Product term 3 input D */
} aoi_event_config_t;
/*******************************************************************************
* API
******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif /* __cplusplus*/
/*!
* @name AOI Initialization
* @{
*/
/*!
* @brief Initializes an AOI instance for operation.
*
* This function un-gates the AOI clock.
*
* @param base AOI peripheral address.
*/
void AOI_Init(AOI_Type *base);
/*!
* @brief Deinitializes an AOI instance for operation.
*
* This function shutdowns AOI module.
*
* @param base AOI peripheral address.
*/
void AOI_Deinit(AOI_Type *base);
/*@}*/
/*!
* @name AOI Get Set Operation
* @{
*/
/*!
* @brief Gets the Boolean evaluation associated.
*
* This function returns the Boolean evaluation associated.
*
* Example:
@code
aoi_event_config_t demoEventLogicStruct;
AOI_GetEventLogicConfig(AOI, kAOI_Event0, &demoEventLogicStruct);
@endcode
*
* @param base AOI peripheral address.
* @param event Index of the event which will be set of type aoi_event_t.
* @param config Selected input configuration .
*/
void AOI_GetEventLogicConfig(AOI_Type *base, aoi_event_t event, aoi_event_config_t *config);
/*!
* @brief Configures an AOI event.
*
* This function configures an AOI event according
* to the aoiEventConfig structure. This function configures all inputs (A, B, C, and D)
* of all product terms (0, 1, 2, and 3) of a desired event.
*
* Example:
@code
aoi_event_config_t demoEventLogicStruct;
demoEventLogicStruct.PT0AC = kAOI_InvInputSignal;
demoEventLogicStruct.PT0BC = kAOI_InputSignal;
demoEventLogicStruct.PT0CC = kAOI_LogicOne;
demoEventLogicStruct.PT0DC = kAOI_LogicOne;
demoEventLogicStruct.PT1AC = kAOI_LogicZero;
demoEventLogicStruct.PT1BC = kAOI_LogicOne;
demoEventLogicStruct.PT1CC = kAOI_LogicOne;
demoEventLogicStruct.PT1DC = kAOI_LogicOne;
demoEventLogicStruct.PT2AC = kAOI_LogicZero;
demoEventLogicStruct.PT2BC = kAOI_LogicOne;
demoEventLogicStruct.PT2CC = kAOI_LogicOne;
demoEventLogicStruct.PT2DC = kAOI_LogicOne;
demoEventLogicStruct.PT3AC = kAOI_LogicZero;
demoEventLogicStruct.PT3BC = kAOI_LogicOne;
demoEventLogicStruct.PT3CC = kAOI_LogicOne;
demoEventLogicStruct.PT3DC = kAOI_LogicOne;
AOI_SetEventLogicConfig(AOI, kAOI_Event0, demoEventLogicStruct);
@endcode
*
* @param base AOI peripheral address.
* @param event Event which will be configured of type aoi_event_t.
* @param eventConfig Pointer to type aoi_event_config_t structure. The user is responsible for
* filling out the members of this structure and passing the pointer to this function.
*/
void AOI_SetEventLogicConfig(AOI_Type *base, aoi_event_t event, const aoi_event_config_t *eventConfig);
#if defined(__cplusplus)
}
#endif /* __cplusplus*/
/*@}*/
/*!* @} */
#endif /* _FSL_AOI_H_*/

View File

@ -0,0 +1,234 @@
/*
* Copyright 2017 NXP
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include "fsl_bee.h"
/*******************************************************************************
* Definitions
******************************************************************************/
/*******************************************************************************
* Variables
******************************************************************************/
/*******************************************************************************
* Code
******************************************************************************/
static void aligned_memcpy(void *dst, const void *src, size_t size)
{
register uint32_t *to32 = (uint32_t *)(uintptr_t)dst;
register const uint32_t *from32 = (const uint32_t *)(uintptr_t)src;
while (size >= sizeof(uint32_t))
{
*to32 = *from32;
size -= sizeof(uint32_t);
to32++;
from32++;
}
}
void BEE_Init(BEE_Type *base)
{
#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
CLOCK_EnableClock(kCLOCK_Bee);
#endif
base->CTRL = BEE_CTRL_CTRL_SFTRST_N_MASK | BEE_CTRL_CTRL_CLK_EN_MASK;
}
void BEE_Deinit(BEE_Type *base)
{
base->CTRL &=
~(BEE_CTRL_BEE_ENABLE_MASK | BEE_CTRL_CTRL_SFTRST_N_MASK | BEE_CTRL_CTRL_CLK_EN_MASK | BEE_CTRL_KEY_VALID_MASK);
#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
CLOCK_DisableClock(kCLOCK_Bee);
#endif
}
void BEE_GetDefaultConfig(bee_region_config_t *config)
{
assert(config);
config->mode = kBEE_AesEcbMode;
config->regionBot = 0U;
config->regionTop = 0U;
config->addrOffset = 0xF0000000U;
config->regionEn = kBEE_RegionDisabled;
}
status_t BEE_SetRegionConfig(BEE_Type *base, bee_region_t region, const bee_region_config_t *config)
{
IOMUXC_GPR_Type *iomuxc = IOMUXC_GPR;
bool reenable = false;
/* Wait until BEE is in idle state */
while (!(BEE_GetStatusFlags(base) & kBEE_IdleFlag))
{
}
/* Disable BEE before region configuration in case it is enabled. */
if ((base->CTRL >> BEE_CTRL_BEE_ENABLE_SHIFT) & 1)
{
BEE_Disable(base);
reenable = true;
}
if (region == kBEE_Region0)
{
/* Region 0 config */
iomuxc->GPR18 = config->regionBot;
iomuxc->GPR19 = config->regionTop;
base->CTRL |= BEE_CTRL_CTRL_AES_MODE_R0(config->mode);
base->ADDR_OFFSET0 = BEE_ADDR_OFFSET0_ADDR_OFFSET0(config->addrOffset);
}
else if (region == kBEE_Region1)
{
/* Region 1 config */
iomuxc->GPR20 = config->regionBot;
iomuxc->GPR21 = config->regionTop;
base->CTRL |= BEE_CTRL_CTRL_AES_MODE_R1(config->mode);
base->ADDR_OFFSET1 = BEE_ADDR_OFFSET1_ADDR_OFFSET0(config->addrOffset);
base->REGION1_BOT = BEE_REGION1_BOT_REGION1_BOT(config->regionBot);
base->REGION1_TOP = BEE_REGION1_TOP_REGION1_TOP(config->regionTop);
}
else
{
return kStatus_InvalidArgument;
}
/* Enable/disable region if desired */
if (config->regionEn == kBEE_RegionEnabled)
{
iomuxc->GPR11 |= IOMUXC_GPR_GPR11_BEE_DE_RX_EN(1 << region);
}
else
{
iomuxc->GPR11 &= ~IOMUXC_GPR_GPR11_BEE_DE_RX_EN(1 << region);
}
/* Reenable BEE if it was enabled before. */
if (reenable)
{
BEE_Enable(base);
}
return kStatus_Success;
}
status_t BEE_SetRegionKey(
BEE_Type *base, bee_region_t region, const uint8_t *key, size_t keySize, const uint8_t *nonce, size_t nonceSize)
{
bool reenable = false;
/* Key must be 32-bit aligned */
if (((uintptr_t)key & 0x3u) || (keySize != 16))
{
return kStatus_InvalidArgument;
}
/* Wait until BEE is in idle state */
while (!(BEE_GetStatusFlags(base) & kBEE_IdleFlag))
{
}
/* Disable BEE before region configuration in case it is enabled. */
if ((base->CTRL >> BEE_CTRL_BEE_ENABLE_SHIFT) & 1)
{
BEE_Disable(base);
reenable = true;
}
if (region == kBEE_Region0)
{
base->CTRL &= ~BEE_CTRL_KEY_REGION_SEL_MASK;
if (nonce)
{
if (nonceSize != 16)
{
return kStatus_InvalidArgument;
}
memcpy((uint32_t *)&base->CTR_NONCE0_W0, nonce, nonceSize);
}
}
else if (region == kBEE_Region1)
{
base->CTRL |= BEE_CTRL_KEY_REGION_SEL_MASK;
if (nonce)
{
if (nonceSize != 16)
{
return kStatus_InvalidArgument;
}
memcpy((uint32_t *)&base->CTR_NONCE1_W0, nonce, nonceSize);
}
}
else
{
return kStatus_InvalidArgument;
}
/* Try to load key. If BEE key selection fuse is programmed to use OTMP key on this device, this operation should
* fail. */
aligned_memcpy((uint32_t *)&base->AES_KEY0_W0, key, keySize);
if (memcmp((uint32_t *)&base->AES_KEY0_W0, key, keySize) != 0)
{
return kStatus_Fail;
}
/* Reenable BEE if it was enabled before. */
if (reenable)
{
BEE_Enable(base);
}
return kStatus_Success;
}
uint32_t BEE_GetStatusFlags(BEE_Type *base)
{
return base->STATUS;
}
void BEE_ClearStatusFlags(BEE_Type *base, uint32_t mask)
{
/* w1c */
base->STATUS |= mask;
}

View File

@ -0,0 +1,224 @@
/*
* Copyright 2017 NXP
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _FSL_BEE_H_
#define _FSL_BEE_H_
#include "fsl_common.h"
/*******************************************************************************
* Definitions
*******************************************************************************/
/*! @name Driver version */
/*@{*/
/*! @brief BEE driver version. Version 2.0.0.
*
* Current version: 2.0.0
*
* Change log:
* - Version 2.0.0
* - Initial version
*/
#define FSL_BEE_DRIVER_VERSION (MAKE_VERSION(2, 0, 0))
/*@}*/
typedef enum _bee_aes_mode
{
kBEE_AesEcbMode = 0U, /*!< AES ECB Mode */
kBEE_AesCtrMode = 1U /*!< AES CTR Mode */
} bee_aes_mode_t;
typedef enum _bee_region
{
kBEE_Region0 = 0U, /*!< BEE region 0 */
kBEE_Region1 = 1U /*!< BEE region 1 */
} bee_region_t;
typedef enum _bee_region_enable
{
kBEE_RegionDisabled = 0U, /*!< BEE region disabled */
kBEE_RegionEnabled = 1U /*!< BEE region enabled */
} bee_region_enable_t;
typedef enum _bee_status_flags
{
kBEE_DisableAbortFlag = 1U, /*!< Disable abort flag. */
kBEE_Reg0ReadSecViolation = 2U, /*!< Region-0 read channel security violation */
kBEE_ReadIllegalAccess = 4U, /*!< Read channel illegal access detected */
kBEE_Reg1ReadSecViolation = 8U, /*!< Region-1 read channel security violation */
kBEE_Reg0AccessViolation = 16U, /*!< Protected region-0 access violation */
kBEE_Reg1AccessViolation = 32U, /*!< Protected region-1 access violation */
kBEE_IdleFlag = BEE_STATUS_BEE_IDLE_MASK /*!< Idle flag */
} bee_status_flags_t;
/*! @brief BEE region configuration structure. */
typedef struct _bee_region_config
{
bee_aes_mode_t mode; /*!< AES mode used for encryption/decryption */
uint32_t regionBot; /*!< Region bottom address */
uint32_t regionTop; /*!< Region top address */
uint32_t addrOffset; /*!< Region address offset */
bee_region_enable_t regionEn; /*!< Region enable/disable */
} bee_region_config_t;
/*******************************************************************************
* API
******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif
/*!
* @brief Resets BEE module to factory default values.
*
* This function performs hardware reset of BEE module. Attributes and keys from software for both regions are cleared.
*
* @param base BEE peripheral address.
*/
void BEE_Init(BEE_Type *base);
/*!
* @brief Resets BEE module, clears keys for both regions and disables clock to the BEE.
*
* This function performs hardware reset of BEE module and disables clocks. Attributes and keys from software for both
* regions are cleared.
*
* @param base BEE peripheral address.
*/
void BEE_Deinit(BEE_Type *base);
/*!
* @brief Enables BEE decryption.
*
* This function enables decryption using BEE.
*
* @param base BEE peripheral address.
*/
static inline void BEE_Enable(BEE_Type *base)
{
base->CTRL |= BEE_CTRL_BEE_ENABLE_MASK | BEE_CTRL_KEY_VALID_MASK;
}
/*!
* @brief Disables BEE decryption.
*
* This function disables decryption using BEE.
*
* @param base BEE peripheral address.
*/
static inline void BEE_Disable(BEE_Type *base)
{
base->CTRL &= ~BEE_CTRL_BEE_ENABLE_MASK | BEE_CTRL_KEY_VALID_MASK;
}
/*!
* @brief Loads default values to the BEE region configuration structure.
*
* Loads default values to the BEE region configuration structure. The default values are as follows:
* @code
* config->mode = kBEE_AesCbcMode;
* config->regionBot = 0U;
* config->regionTop = 0U;
* config->addrOffset = 0xF0000000U;
* config->regionEn = kBEE_RegionDisabled;
* @endcode
*
* @param config Configuration structure for BEE region.
*/
void BEE_GetDefaultConfig(bee_region_config_t *config);
/*!
* @brief Sets BEE region configuration.
*
* This function sets BEE region settings accorging to given configuration structure.
*
* @param base BEE peripheral address.
* @param region Selection of the BEE region to be configured.
* @param config Configuration structure for BEE region.
*/
status_t BEE_SetRegionConfig(BEE_Type *base, bee_region_t region, const bee_region_config_t *config);
/*!
* @brief Loads the AES key and nonce for selected region into BEE key registers.
*
* This function loads given AES key and nonce(only AES CTR mode) to BEE register for the given region.
*
* Please note, that eFuse BEE_KEYx_SEL must be set accordingly to be able to load and use key loaded in BEE registers.
* Otherwise, key cannot loaded and BEE will use key from OTPMK or SW_GP2.
*
* @param base BEE peripheral address.
* @param region Selection of the BEE region to be configured.
* @param key AES key.
* @param keySize Size of AES key.
* @param nonce AES nonce.
* @param nonceSize Size of AES nonce.
*/
status_t BEE_SetRegionKey(
BEE_Type *base, bee_region_t region, const uint8_t *key, size_t keySize, const uint8_t *nonce, size_t nonceSize);
/*!
* @brief Gets the BEE status flags.
*
* This function returns status of BEE peripheral.
*
* @param base BEE peripheral address.
*
* @return The status flags. This is the logical OR of members of the
* enumeration ::bee_status_flags_t
*/
uint32_t BEE_GetStatusFlags(BEE_Type *base);
/*!
* @brief Clears the BEE status flags.
*
* @param base BEE peripheral base address.
* @param mask The status flags to clear. This is a logical OR of members of the
* enumeration ::bee_status_flags_t
*/
void BEE_ClearStatusFlags(BEE_Type *base, uint32_t mask);
/*!
* @brief Computes offset to be set for specifed memory location.
*
* This function calculates offset that must be set for BEE region to access physical memory location.
*
* @param addressMemory Address of physical memory location.
*/
static inline uint32_t BEE_GetOffset(uint32_t addressMemory)
{
return (addressMemory >> 16);
}
#if defined(__cplusplus)
}
#endif
#endif /* _FSL_BEE_H_ */

View File

@ -0,0 +1,460 @@
/*
* Copyright (c) 2016, Freescale Semiconductor, Inc.
* Copyright 2016-2017 NXP
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include "fsl_cache.h"
/*******************************************************************************
* Definitions
******************************************************************************/
#if (FSL_FEATURE_SOC_L2CACHEC_COUNT > 0)
#define L2CACHE_OPERATION_TIMEOUT 0xFFFFFU
#define L2CACHE_8WAYS_MASK 0xFFU
#define L2CACHE_16WAYS_MASK 0xFFFFU
#define L2CACHE_SMALLWAYS_NUM 8U
#define L2CACHE_1KBCOVERTOB 1024U
#define L2CACHE_SAMLLWAYS_SIZE 16U
#define L2CACHE_LOCKDOWN_REGNUM 8 /*!< Lock down register numbers.*/
/*******************************************************************************
* Prototypes
******************************************************************************/
/*!
* @brief Set for all ways and waiting for the operation finished.
* This is provided for all the background operations.
*
* @param auxCtlReg The auxiliary control register.
* @param regAddr The register address to be operated.
*/
static void L2CACHE_SetAndWaitBackGroundOperate(uint32_t auxCtlReg, uint32_t regAddr);
/*!
* @brief Invalidates the Level 2 cache line by physical address.
* This function invalidates a cache line by physcial address.
*
* @param address The physical addderss of the cache.
* The format of the address shall be :
* bit 31 ~ bit n+1 | bitn ~ bit5 | bit4 ~ bit0
* Tag | index | 0
* Note: the physical address shall be aligned to the line size - 32B (256 bit).
* so keep the last 5 bits (bit 4 ~ bit 0) of the physical address always be zero.
* If the input address is not aligned, it will be changed to 32-byte aligned address.
* The n is varies according to the index width.
* @return The actual 32-byte aligned physical address be operated.
*/
static uint32_t L2CACHE_InvalidateLineByAddr(uint32_t address);
/*!
* @brief Cleans the Level 2 cache line based on the physical address.
* This function cleans a cache line based on a physcial address.
*
* @param address The physical addderss of the cache.
* The format of the address shall be :
* bit 31 ~ bit n+1 | bitn ~ bit5 | bit4 ~ bit0
* Tag | index | 0
* Note: the physical address shall be aligned to the line size - 32B (256 bit).
* so keep the last 5 bits (bit 4 ~ bit 0) of the physical address always be zero.
* If the input address is not aligned, it will be changed to 32-byte aligned address.
* The n is varies according to the index width.
* @return The actual 32-byte aligned physical address be operated.
*/
static uint32_t L2CACHE_CleanLineByAddr(uint32_t address);
/*!
* @brief Cleans and invalidates the Level 2 cache line based on the physical address.
* This function cleans and invalidates a cache line based on a physcial address.
*
* @param address The physical addderss of the cache.
* The format of the address shall be :
* bit 31 ~ bit n+1 | bitn ~ bit5 | bit4 ~ bit0
* Tag | index | 0
* Note: the physical address shall be aligned to the line size - 32B (256 bit).
* so keep the last 5 bits (bit 4 ~ bit 0) of the physical address always be zero.
* If the input address is not aligned, it will be changed to 32-byte aligned address.
* The n is varies according to the index width.
* @return The actual 32-byte aligned physical address be operated.
*/
static uint32_t L2CACHE_CleanInvalidateLineByAddr(uint32_t address);
/*!
* @brief Gets the number of the Level 2 cache and the way size.
* This function cleans and invalidates a cache line based on a physcial address.
*
* @param num_ways The number of the cache way.
* @param size_way The way size.
*/
static void L2CACHE_GetWayNumSize(uint32_t *num_ways, uint32_t *size_way);
/*******************************************************************************
* Code
******************************************************************************/
static void L2CACHE_SetAndWaitBackGroundOperate(uint32_t auxCtlReg, uint32_t regAddr)
{
uint16_t mask = L2CACHE_8WAYS_MASK;
uint32_t timeout = L2CACHE_OPERATION_TIMEOUT;
/* Check the ways used at first. */
if (auxCtlReg & L2CACHEC_REG1_AUX_CONTROL_ASSOCIATIVITY_MASK)
{
mask = L2CACHE_16WAYS_MASK;
}
/* Set the opeartion for all ways/entries of the cache. */
*(uint32_t *)regAddr = mask;
/* Waiting for until the operation is complete. */
while ((*(uint32_t *)regAddr & mask) && timeout)
{
__ASM("nop");
timeout--;
}
}
static uint32_t L2CACHE_InvalidateLineByAddr(uint32_t address)
{
/* Align the address first. */
address &= ~(uint32_t)(FSL_FEATURE_L2CACHE_LINESIZE_BYTE - 1);
/* Invalidate the cache line by physical address. */
L2CACHEC->REG7_INV_PA = address;
return address;
}
static uint32_t L2CACHE_CleanLineByAddr(uint32_t address)
{
/* Align the address first. */
address &= ~(uint32_t)(FSL_FEATURE_L2CACHE_LINESIZE_BYTE - 1);
/* Invalidate the cache line by physical address. */
L2CACHEC->REG7_CLEAN_PA = address;
return address;
}
static uint32_t L2CACHE_CleanInvalidateLineByAddr(uint32_t address)
{
/* Align the address first. */
address &= ~(uint32_t)(FSL_FEATURE_L2CACHE_LINESIZE_BYTE - 1);
/* Clean and invalidate the cache line by physical address. */
L2CACHEC->REG7_CLEAN_INV_PA = address;
return address;
}
static void L2CACHE_GetWayNumSize(uint32_t *num_ways, uint32_t *size_way)
{
assert(num_ways);
assert(size_way);
uint32_t number = (L2CACHEC->REG1_AUX_CONTROL & L2CACHEC_REG1_AUX_CONTROL_ASSOCIATIVITY_MASK) >>
L2CACHEC_REG1_AUX_CONTROL_ASSOCIATIVITY_SHIFT;
uint32_t size = (L2CACHEC->REG1_AUX_CONTROL & L2CACHEC_REG1_AUX_CONTROL_WAYSIZE_MASK) >>
L2CACHEC_REG1_AUX_CONTROL_WAYSIZE_SHIFT;
*num_ways = (number + 1) * L2CACHE_SMALLWAYS_NUM;
if (!size)
{
/* 0 internally mapped to the same size as 1 - 16KB.*/
size += 1;
}
*size_way = (1 << (size - 1)) * L2CACHE_SAMLLWAYS_SIZE * L2CACHE_1KBCOVERTOB;
}
void L2CACHE_Init(l2cache_config_t *config)
{
assert (config);
uint16_t waysNum = 0xFFU; /* Default use the 8-way mask. */
uint8_t count;
uint32_t auxReg = 0;
/*The aux register must be configured when the cachec is disabled
* So disable first if the cache controller is enabled.
*/
if (L2CACHEC->REG1_CONTROL & L2CACHEC_REG1_CONTROL_CE_MASK)
{
L2CACHE_Disable();
}
/* Unlock all entries. */
if (L2CACHEC->REG1_AUX_CONTROL & L2CACHEC_REG1_AUX_CONTROL_ASSOCIATIVITY_MASK)
{
waysNum = 0xFFFFU;
}
for (count = 0; count < L2CACHE_LOCKDOWN_REGNUM; count ++)
{
L2CACHE_LockdownByWayEnable(count, waysNum, false);
}
/* Set the ways and way-size etc. */
auxReg = L2CACHEC_REG1_AUX_CONTROL_ASSOCIATIVITY(config->wayNum) |
L2CACHEC_REG1_AUX_CONTROL_WAYSIZE(config->waySize) |
L2CACHEC_REG1_AUX_CONTROL_CRP(config->repacePolicy) |
L2CACHEC_REG1_AUX_CONTROL_IPE(config->istrPrefetchEnable) |
L2CACHEC_REG1_AUX_CONTROL_DPE(config->dataPrefetchEnable) |
L2CACHEC_REG1_AUX_CONTROL_NLE(config->nsLockdownEnable) |
L2CACHEC_REG1_AUX_CONTROL_FWA(config->writeAlloc) |
L2CACHEC_REG1_AUX_CONTROL_HPSDRE(config->writeAlloc);
L2CACHEC->REG1_AUX_CONTROL = auxReg;
/* Set the tag/data ram latency. */
if (config->lateConfig)
{
uint32_t data = 0;
/* Tag latency. */
data = L2CACHEC_REG1_TAG_RAM_CONTROL_SL(config->lateConfig->tagSetupLate)|
L2CACHEC_REG1_TAG_RAM_CONTROL_SL(config->lateConfig->tagSetupLate)|
L2CACHEC_REG1_TAG_RAM_CONTROL_RAL(config->lateConfig->tagReadLate)|
L2CACHEC_REG1_TAG_RAM_CONTROL_WAL(config->lateConfig->dataWriteLate);
L2CACHEC->REG1_TAG_RAM_CONTROL = data;
/* Data latency. */
data = L2CACHEC_REG1_DATA_RAM_CONTROL_SL(config->lateConfig->dataSetupLate)|
L2CACHEC_REG1_DATA_RAM_CONTROL_SL(config->lateConfig->dataSetupLate)|
L2CACHEC_REG1_DATA_RAM_CONTROL_RAL(config->lateConfig->dataReadLate)|
L2CACHEC_REG1_DATA_RAM_CONTROL_WAL(config->lateConfig->dataWriteLate);
L2CACHEC->REG1_DATA_RAM_CONTROL = data;
}
}
void L2CACHE_GetDefaultConfig(l2cache_config_t *config)
{
assert(config);
uint32_t number = (L2CACHEC->REG1_AUX_CONTROL & L2CACHEC_REG1_AUX_CONTROL_ASSOCIATIVITY_MASK) >>
L2CACHEC_REG1_AUX_CONTROL_ASSOCIATIVITY_SHIFT;
uint32_t size = (L2CACHEC->REG1_AUX_CONTROL & L2CACHEC_REG1_AUX_CONTROL_WAYSIZE_MASK) >>
L2CACHEC_REG1_AUX_CONTROL_WAYSIZE_SHIFT;
/* Get the default value */
config->wayNum = (l2cache_way_num_t)number;
config->waySize = (l2cache_way_size)size;
config->repacePolicy = kL2CACHE_Roundrobin;
config->lateConfig = NULL;
config->istrPrefetchEnable = false;
config->dataPrefetchEnable = false;
config->nsLockdownEnable = false;
config->writeAlloc = kL2CACHE_UseAwcache;
}
void L2CACHE_Enable(void)
{
/* Invalidate first. */
L2CACHE_Invalidate();
/* Enable the level 2 cache controller. */
L2CACHEC->REG1_CONTROL = L2CACHEC_REG1_CONTROL_CE_MASK;
}
void L2CACHE_Disable(void)
{
/* First CleanInvalidate all enties in the cache. */
L2CACHE_CleanInvalidate();
/* Disable the level 2 cache controller. */
L2CACHEC->REG1_CONTROL &= ~L2CACHEC_REG1_CONTROL_CE_MASK;
/* DSB - data sync barrier.*/
__DSB();
}
void L2CACHE_Invalidate(void)
{
/* Invalidate all entries in cache. */
L2CACHE_SetAndWaitBackGroundOperate(L2CACHEC->REG1_AUX_CONTROL, (uint32_t)&L2CACHEC->REG7_INV_WAY);
/* Cache sync. */
L2CACHEC->REG7_CACHE_SYNC = 0;
}
void L2CACHE_Clean(void)
{
/* Clean all entries of the cache. */
L2CACHE_SetAndWaitBackGroundOperate(L2CACHEC->REG1_AUX_CONTROL, (uint32_t)&L2CACHEC->REG7_CLEAN_WAY);
/* Cache sync. */
L2CACHEC->REG7_CACHE_SYNC = 0;
}
void L2CACHE_CleanInvalidate(void)
{
/* Clean all entries of the cache. */
L2CACHE_SetAndWaitBackGroundOperate(L2CACHEC->REG1_AUX_CONTROL, (uint32_t)&L2CACHEC->REG7_CLEAN_INV_WAY);
/* Cache sync. */
L2CACHEC->REG7_CACHE_SYNC = 0;
}
void L2CACHE_InvalidateByRange(uint32_t address, uint32_t size_byte)
{
uint32_t endAddr = address + size_byte;
/* Invalidate addresses in the range. */
while (address < endAddr)
{
address = L2CACHE_InvalidateLineByAddr(address);
/* Update the size. */
address += FSL_FEATURE_L2CACHE_LINESIZE_BYTE;
}
/* Cache sync. */
L2CACHEC->REG7_CACHE_SYNC = 0;
}
void L2CACHE_CleanByRange(uint32_t address, uint32_t size_byte)
{
uint32_t num_ways = 0;
uint32_t size_way = 0;
uint32_t endAddr = address + size_byte;
/* Get the number and size of the cache way. */
L2CACHE_GetWayNumSize(&num_ways, &size_way);
/* Check if the clean size is over the cache size. */
if ((endAddr - address) > num_ways * size_way)
{
L2CACHE_Clean();
return;
}
/* Clean addresses in the range. */
while ((address & ~(uint32_t)(FSL_FEATURE_L2CACHE_LINESIZE_BYTE - 1)) < endAddr)
{
/* Clean the address in the range. */
address = L2CACHE_CleanLineByAddr(address);
address += FSL_FEATURE_L2CACHE_LINESIZE_BYTE;
}
L2CACHEC->REG7_CACHE_SYNC = 0;
}
void L2CACHE_CleanInvalidateByRange(uint32_t address, uint32_t size_byte)
{
uint32_t num_ways = 0;
uint32_t size_way = 0;
uint32_t endAddr = address + size_byte;
/* Get the number and size of the cache way. */
L2CACHE_GetWayNumSize(&num_ways, &size_way);
/* Check if the clean size is over the cache size. */
if ((endAddr - address) > num_ways * size_way)
{
L2CACHE_CleanInvalidate();
return;
}
/* Clean addresses in the range. */
while ((address & ~(uint32_t)(FSL_FEATURE_L2CACHE_LINESIZE_BYTE - 1)) < endAddr)
{
/* Clean the address in the range. */
address = L2CACHE_CleanInvalidateLineByAddr(address);
address += FSL_FEATURE_L2CACHE_LINESIZE_BYTE;
}
L2CACHEC->REG7_CACHE_SYNC = 0;
}
void L2CACHE_LockdownByWayEnable(uint32_t masterId, uint32_t mask, bool enable)
{
uint8_t num_ways = (L2CACHEC->REG1_AUX_CONTROL & L2CACHEC_REG1_AUX_CONTROL_ASSOCIATIVITY_MASK) >>
L2CACHEC_REG1_AUX_CONTROL_ASSOCIATIVITY_SHIFT;
num_ways = (num_ways + 1) * L2CACHE_SMALLWAYS_NUM;
assert(mask < (1U << num_ways));
assert(masterId < L2CACHE_LOCKDOWN_REGNUM);
uint32_t dataReg = L2CACHEC->LOCKDOWN[masterId].REG9_D_LOCKDOWN;
uint32_t istrReg = L2CACHEC->LOCKDOWN[masterId].REG9_I_LOCKDOWN;
if (enable)
{
/* Data lockdown. */
L2CACHEC->LOCKDOWN[masterId].REG9_D_LOCKDOWN = dataReg | mask;
/* Instruction lockdown. */
L2CACHEC->LOCKDOWN[masterId].REG9_I_LOCKDOWN = istrReg | mask;
}
else
{
/* Data lockdown. */
L2CACHEC->LOCKDOWN[masterId].REG9_D_LOCKDOWN = dataReg & ~mask;
/* Instruction lockdown. */
L2CACHEC->LOCKDOWN[masterId].REG9_I_LOCKDOWN = istrReg & ~mask;
}
}
#endif /* FSL_FEATURE_SOC_L2CACHEC_COUNT > 0 */
void L1CACHE_InvalidateICacheByRange(uint32_t address, uint32_t size_byte)
{
#if (__DCACHE_PRESENT == 1U)
uint32_t addr = address & (uint32_t)~(FSL_FEATURE_L1ICACHE_LINESIZE_BYTE - 1);
int32_t size = size_byte + address - addr;
uint32_t linesize = 32U;
__DSB();
while (size > 0)
{
SCB->ICIMVAU = addr;
addr += linesize;
size -= linesize;
}
__DSB();
__ISB();
#endif
}
void ICACHE_InvalidateByRange(uint32_t address, uint32_t size_byte)
{
#if (FSL_FEATURE_SOC_L2CACHEC_COUNT > 0)
#if defined(FSL_SDK_DISBLE_L2CACHE_PRESENT) && !FSL_SDK_DISBLE_L2CACHE_PRESENT
L2CACHE_InvalidateByRange(address, size_byte);
#endif /* !FSL_SDK_DISBLE_L2CACHE_PRESENT */
#endif /* FSL_FEATURE_SOC_L2CACHEC_COUNT > 0 */
L1CACHE_InvalidateICacheByRange(address, size_byte);
}
void DCACHE_InvalidateByRange(uint32_t address, uint32_t size_byte)
{
#if (FSL_FEATURE_SOC_L2CACHEC_COUNT > 0)
#if defined(FSL_SDK_DISBLE_L2CACHE_PRESENT) && !FSL_SDK_DISBLE_L2CACHE_PRESENT
L2CACHE_InvalidateByRange(address, size_byte);
#endif /* !FSL_SDK_DISBLE_L2CACHE_PRESENT */
#endif /* FSL_FEATURE_SOC_L2CACHEC_COUNT > 0 */
L1CACHE_InvalidateDCacheByRange(address, size_byte);
}
void DCACHE_CleanByRange(uint32_t address, uint32_t size_byte)
{
L1CACHE_CleanDCacheByRange(address, size_byte);
#if (FSL_FEATURE_SOC_L2CACHEC_COUNT > 0)
#if defined(FSL_SDK_DISBLE_L2CACHE_PRESENT) && !FSL_SDK_DISBLE_L2CACHE_PRESENT
L2CACHE_CleanByRange(address, size_byte);
#endif /* !FSL_SDK_DISBLE_L2CACHE_PRESENT */
#endif /* FSL_FEATURE_SOC_L2CACHEC_COUNT > 0 */
}
void DCACHE_CleanInvalidateByRange(uint32_t address, uint32_t size_byte)
{
L1CACHE_CleanInvalidateDCacheByRange(address, size_byte);
#if (FSL_FEATURE_SOC_L2CACHEC_COUNT > 0)
#if defined(FSL_SDK_DISBLE_L2CACHE_PRESENT) && !FSL_SDK_DISBLE_L2CACHE_PRESENT
L2CACHE_CleanInvalidateByRange(address, size_byte);
#endif /* !FSL_SDK_DISBLE_L2CACHE_PRESENT */
#endif /* FSL_FEATURE_SOC_L2CACHEC_COUNT > 0 */
}

View File

@ -0,0 +1,490 @@
/*
* Copyright (c) 2016, Freescale Semiconductor, Inc.
* Copyright 2016-2017 NXP
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _FSL_CACHE_H_
#define _FSL_CACHE_H_
#include "fsl_common.h"
/*!
* @addtogroup cache
* @{
*/
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @name Driver version */
/*@{*/
/*! @brief cache driver version 2.0.1. */
#define FSL_CACHE_DRIVER_VERSION (MAKE_VERSION(2, 0, 1))
/*@}*/
#if (FSL_FEATURE_SOC_L2CACHEC_COUNT > 0)
#ifndef FSL_SDK_DISBLE_L2CACHE_PRESENT
#define FSL_SDK_DISBLE_L2CACHE_PRESENT 0
#endif
#endif /* (FSL_FEATURE_SOC_L2CACHEC_COUNT > 0) */
/*******************************************************************************
* Definitions
******************************************************************************/
#if (FSL_FEATURE_SOC_L2CACHEC_COUNT > 0)
/*! @brief Number of level 2 cache controller ways. */
typedef enum _l2cache_way_num
{
kL2CACHE_8ways = 0, /*!< 8 ways. */
#if defined(FSL_FEATURE_L2CACHE_SUPPORT_16_WAY_ASSOCIATIVITY) && FSL_FEATURE_L2CACHE_SUPPORT_16_WAY_ASSOCIATIVITY
kL2CACHE_16ways /*!< 16 ways. */
#endif /* FSL_FEATURE_L2CACHE_SUPPORT_16_WAY_ASSOCIATIVITY */
} l2cache_way_num_t;
/*! @brief Level 2 cache controller way size. */
typedef enum _l2cache_way_size
{
kL2CACHE_16KBSize = 1, /*!< 16 KB way size. */
kL2CACHE_32KBSize = 2, /*!< 32 KB way size. */
kL2CACHE_64KBSize = 3, /*!< 64 KB way size. */
kL2CACHE_128KBSize = 4, /*!< 128 KB way size. */
kL2CACHE_256KBSize = 5, /*!< 256 KB way size. */
kL2CACHE_512KBSize = 6 /*!< 512 KB way size. */
} l2cache_way_size;
/*! @brief Level 2 cache controller replacement policy. */
typedef enum _l2cache_replacement
{
kL2CACHE_Pseudorandom = 0U, /*!< Peseudo-random replacement policy using an lfsr. */
kL2CACHE_Roundrobin /*!< Round-robin replacemnt policy. */
} l2cache_replacement_t;
/*! @brief Level 2 cache controller force write allocate options. */
typedef enum _l2cache_writealloc
{
kL2CACHE_UseAwcache = 0, /*!< Use AWCAHE attribute for the write allocate. */
kL2CACHE_NoWriteallocate, /*!< Force no write allocate. */
kL2CACHE_forceWriteallocate /*!< Force write allocate when write misses. */
} l2cache_writealloc_t;
/*! @brief Level 2 cache controller tag/data ram latency. */
typedef enum _l2cache_latency
{
kL2CACHE_1CycleLate = 0, /*!< 1 cycle of latency. */
kL2CACHE_2CycleLate, /*!< 2 cycle of latency. */
kL2CACHE_3CycleLate, /*!< 3 cycle of latency. */
kL2CACHE_4CycleLate, /*!< 4 cycle of latency. */
kL2CACHE_5CycleLate, /*!< 5 cycle of latency. */
kL2CACHE_6CycleLate, /*!< 6 cycle of latency. */
kL2CACHE_7CycleLate, /*!< 7 cycle of latency. */
kL2CACHE_8CycleLate /*!< 8 cycle of latency. */
} l2cache_latency_t;
/*! @brief Level 2 cache controller tag/data ram latency configure structure. */
typedef struct _l2cache_latency_config
{
l2cache_latency_t tagWriteLate; /*!< Tag write latency. */
l2cache_latency_t tagReadLate; /*!< Tag Read latency. */
l2cache_latency_t tagSetupLate; /*!< Tag setup latency. */
l2cache_latency_t dataWriteLate; /*!< Data write latency. */
l2cache_latency_t dataReadLate; /*!< Data Read latency. */
l2cache_latency_t dataSetupLate; /*!< Data setup latency. */
} L2cache_latency_config_t;
/*! @brief Level 2 cache controller configure structure. */
typedef struct _l2cache_config
{
/* ------------------------ l2 cachec basic settings ---------------------------- */
l2cache_way_num_t wayNum; /*!< The number of ways. */
l2cache_way_size waySize; /*!< The way size = Cache Ram size / wayNum. */
l2cache_replacement_t repacePolicy;/*!< Replacemnet policy. */
/* ------------------------ tag/data ram latency settings ----------------------- */
L2cache_latency_config_t *lateConfig; /*!< Tag/data latency configure. Set NUll if not required. */
/* ------------------------ Prefetch enable settings ---------------------------- */
bool istrPrefetchEnable; /*!< Instruction prefetch enable. */
bool dataPrefetchEnable; /*!< Data prefetch enable. */
/* ------------------------ Non-secure access settings -------------------------- */
bool nsLockdownEnable; /*!< None-secure lockdown enable. */
/* ------------------------ other settings -------------------------------------- */
l2cache_writealloc_t writeAlloc;/*!< Write allcoate force option. */
} l2cache_config_t;
#endif /* (FSL_FEATURE_SOC_L2CACHEC_COUNT > 0) */
/*******************************************************************************
* API
******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif
/*!
* @name Control for cortex-m7 L1 cache
*@{
*/
/*!
* @brief Enables cortex-m7 L1 instruction cache.
*
*/
static inline void L1CACHE_EnableICache(void)
{
SCB_EnableICache();
}
/*!
* @brief Disables cortex-m7 L1 instruction cache.
*
*/
static inline void L1CACHE_DisableICache(void)
{
SCB_DisableICache();
}
/*!
* @brief Invalidate cortex-m7 L1 instruction cache.
*
*/
static inline void L1CACHE_InvalidateICache(void)
{
SCB_InvalidateICache();
}
/*!
* @brief Invalidate cortex-m7 L1 instruction cache by range.
*
* @param address The start address of the memory to be invalidated.
* @param size_byte The memory size.
* @note The start address and size_byte should be 32-byte(FSL_FEATURE_L1ICACHE_LINESIZE_BYTE) aligned.
* The startAddr here will be forced to align to L1 I-cache line size if
* startAddr is not aligned. For the size_byte, application should make sure the
* alignment or make sure the right operation order if the size_byte is not aligned.
*/
void L1CACHE_InvalidateICacheByRange(uint32_t address, uint32_t size_byte);
/*!
* @brief Enables cortex-m7 L1 data cache.
*
*/
static inline void L1CACHE_EnableDCache(void)
{
SCB_EnableDCache();
}
/*!
* @brief Disables cortex-m7 L1 data cache.
*
*/
static inline void L1CACHE_DisableDCache(void)
{
SCB_DisableDCache();
}
/*!
* @brief Invalidates cortex-m7 L1 data cache.
*
*/
static inline void L1CACHE_InvalidateDCache(void)
{
SCB_InvalidateDCache();
}
/*!
* @brief Cleans cortex-m7 L1 data cache.
*
*/
static inline void L1CACHE_CleanDCache(void)
{
SCB_CleanDCache();
}
/*!
* @brief Cleans and Invalidates cortex-m7 L1 data cache.
*
*/
static inline void L1CACHE_CleanInvalidateDCache(void)
{
SCB_CleanInvalidateDCache();
}
/*!
* @brief Invalidates cortex-m7 L1 data cache by range.
*
* @param address The start address of the memory to be invalidated.
* @param size_byte The memory size.
* @note The start address and size_byte should be 32-byte(FSL_FEATURE_L1DCACHE_LINESIZE_BYTE) aligned.
* The startAddr here will be forced to align to L1 D-cache line size if
* startAddr is not aligned. For the size_byte, application should make sure the
* alignment or make sure the right operation order if the size_byte is not aligned.
*/
static inline void L1CACHE_InvalidateDCacheByRange(uint32_t address, uint32_t size_byte)
{
uint32_t startAddr = address & (uint32_t)~(FSL_FEATURE_L1DCACHE_LINESIZE_BYTE - 1);
uint32_t size = size_byte + address - startAddr;
SCB_InvalidateDCache_by_Addr((uint32_t *)startAddr, size);
}
/*!
* @brief Cleans cortex-m7 L1 data cache by range.
*
* @param address The start address of the memory to be cleaned.
* @param size_byte The memory size.
* @note The start address and size_byte should be 32-byte(FSL_FEATURE_L1DCACHE_LINESIZE_BYTE) aligned.
* The startAddr here will be forced to align to L1 D-cache line size if
* startAddr is not aligned. For the size_byte, application should make sure the
* alignment or make sure the right operation order if the size_byte is not aligned.
*/
static inline void L1CACHE_CleanDCacheByRange(uint32_t address, uint32_t size_byte)
{
uint32_t startAddr = address & (uint32_t)~(FSL_FEATURE_L1DCACHE_LINESIZE_BYTE - 1);
uint32_t size = size_byte + address - startAddr;
SCB_CleanDCache_by_Addr((uint32_t *)startAddr, size);
}
/*!
* @brief Cleans and Invalidates cortex-m7 L1 data cache by range.
*
* @param address The start address of the memory to be clean and invalidated.
* @param size_byte The memory size.
* @note The start address and size_byte should be 32-byte(FSL_FEATURE_L1DCACHE_LINESIZE_BYTE) aligned.
* The startAddr here will be forced to align to L1 D-cache line size if
* startAddr is not aligned. For the size_byte, application should make sure the
* alignment or make sure the right operation order if the size_byte is not aligned.
*/
static inline void L1CACHE_CleanInvalidateDCacheByRange(uint32_t address, uint32_t size_byte)
{
uint32_t startAddr = address & (uint32_t)~(FSL_FEATURE_L1DCACHE_LINESIZE_BYTE - 1);
uint32_t size = size_byte + address - startAddr;
SCB_CleanInvalidateDCache_by_Addr((uint32_t *)startAddr, size);
}
/*@}*/
#if (FSL_FEATURE_SOC_L2CACHEC_COUNT > 0)
/*!
* @name Control for L2 pl310 cache
*@{
*/
/*!
* @brief Initializes the level 2 cache controller module.
*
* @param config Pointer to configuration structure. See "l2cache_config_t".
*/
void L2CACHE_Init(l2cache_config_t *config);
/*!
* @brief Gets an available default settings for the cache controller.
*
* This function initializes the cache controller configuration structure with default settings.
* The default values are:
* @code
* config->waysNum = kL2CACHE_8ways;
* config->waySize = kL2CACHE_32KbSize;
* config->repacePolicy = kL2CACHE_Roundrobin;
* config->lateConfig = NULL;
* config->istrPrefetchEnable = false;
* config->dataPrefetchEnable = false;
* config->nsLockdownEnable = false;
* config->writeAlloc = kL2CACHE_UseAwcache;
* @endcode
* @param config Pointer to the configuration structure.
*/
void L2CACHE_GetDefaultConfig(l2cache_config_t *config);
/*!
* @brief Enables the level 2 cache controller.
* This function enables the cache controller. Must be written using a secure access.
* If write with a Non-secure access will cause a DECERR response.
*
*/
void L2CACHE_Enable(void);
/*!
* @brief Disables the level 2 cache controller.
* This function disables the cache controller. Must be written using a secure access.
* If write with a Non-secure access will cause a DECERR response.
*
*/
void L2CACHE_Disable(void);
/*!
* @brief Invalidates the Level 2 cache.
* This function invalidates all entries in cache.
*
*/
void L2CACHE_Invalidate(void);
/*!
* @brief Invalidates the Level 2 cache lines in the range of two physical addresses.
* This function invalidates all cache lines between two physical addresses.
*
* @param address The start address of the memory to be invalidated.
* @param size_byte The memory size.
* @note The start address and size_byte should be 32-byte(FSL_FEATURE_L2CACHE_LINESIZE_BYTE) aligned.
* The startAddr here will be forced to align to L2 line size if startAddr
* is not aligned. For the size_byte, application should make sure the
* alignment or make sure the right operation order if the size_byte is not aligned.
*/
void L2CACHE_InvalidateByRange(uint32_t address, uint32_t size_byte);
/*!
* @brief Cleans the level 2 cache controller.
* This function cleans all entries in the level 2 cache controller.
*
*/
void L2CACHE_Clean(void);
/*!
* @brief Cleans the Level 2 cache lines in the range of two physical addresses.
* This function cleans all cache lines between two physical addresses.
*
* @param address The start address of the memory to be cleaned.
* @param size_byte The memory size.
* @note The start address and size_byte should be 32-byte(FSL_FEATURE_L2CACHE_LINESIZE_BYTE) aligned.
* The startAddr here will be forced to align to L2 line size if startAddr
* is not aligned. For the size_byte, application should make sure the
* alignment or make sure the right operation order if the size_byte is not aligned.
*/
void L2CACHE_CleanByRange(uint32_t address, uint32_t size_byte);
/*!
* @brief Cleans and invalidates the level 2 cache controller.
* This function cleans and invalidates all entries in the level 2 cache controller.
*
*/
void L2CACHE_CleanInvalidate(void);
/*!
* @brief Cleans and invalidates the Level 2 cache lines in the range of two physical addresses.
* This function cleans and invalidates all cache lines between two physical addresses.
*
* @param address The start address of the memory to be cleaned and invalidated.
* @param size_byte The memory size.
* @note The start address and size_byte should be 32-byte(FSL_FEATURE_L2CACHE_LINESIZE_BYTE) aligned.
* The startAddr here will be forced to align to L2 line size if startAddr
* is not aligned. For the size_byte, application should make sure the
* alignment or make sure the right operation order if the size_byte is not aligned.
*/
void L2CACHE_CleanInvalidateByRange(uint32_t address, uint32_t size_byte);
/*!
* @brief Enables or disables to lock down the data and instruction by way.
* This function locks down the cached instruction/data by way and prevent the adresses from
* being allocated and prevent dara from being evicted out of the level 2 cache.
* But the normal cache maintenance operations that invalidate, clean or clean
* and validate cache contents affect the locked-down cache lines as normal.
*
* @param masterId The master id, range from 0 ~ 7.
* @param mask The ways to be enabled or disabled to lockdown.
* each bit in value is related to each way of the cache. for example:
* value: bit 0 ------ way 0.
* value: bit 1 ------ way 1.
* --------------------------
* value: bit 15 ------ way 15.
* Note: please make sure the value setting is align with your supported ways.
* @param enable True enable the lockdown, false to disable the lockdown.
*/
void L2CACHE_LockdownByWayEnable(uint32_t masterId, uint32_t mask, bool enable);
/*@}*/
#endif /* (FSL_FEATURE_SOC_L2CACHEC_COUNT > 0) */
/*!
* @name Unified Cache Control for all caches (cortex-m7 L1 cache + l2 pl310)
* Mainly used for many drivers for easy cache operation.
*@{
*/
/*!
* @brief Invalidates all instruction caches by range.
*
* Both cortex-m7 L1 cache line and L2 PL310 cache line length is 32-byte.
*
* @param address The physical address.
* @param size_byte size of the memory to be invalidated.
* @note address and size should be aligned to cache line size
* 32-Byte due to the cache operation unit is one cache line. The startAddr here will be forced
* to align to the cache line size if startAddr is not aligned. For the size_byte, application should
* make sure the alignment or make sure the right operation order if the size_byte is not aligned.
*/
void ICACHE_InvalidateByRange(uint32_t address, uint32_t size_byte);
/*!
* @brief Invalidates all data caches by range.
*
* Both cortex-m7 L1 cache line and L2 PL310 cache line length is 32-byte.
*
* @param address The physical address.
* @param size_byte size of the memory to be invalidated.
* @note address and size should be aligned to cache line size
* 32-Byte due to the cache operation unit is one cache line. The startAddr here will be forced
* to align to the cache line size if startAddr is not aligned. For the size_byte, application should
* make sure the alignment or make sure the right operation order if the size_byte is not aligned.
*/
void DCACHE_InvalidateByRange(uint32_t address, uint32_t size_byte);
/*!
* @brief Cleans all data caches by range.
*
* Both cortex-m7 L1 cache line and L2 PL310 cache line length is 32-byte.
*
* @param address The physical address.
* @param size_byte size of the memory to be cleaned.
* @note address and size should be aligned to cache line size
* 32-Byte due to the cache operation unit is one cache line. The startAddr here will be forced
* to align to the cache line size if startAddr is not aligned. For the size_byte, application should
* make sure the alignment or make sure the right operation order if the size_byte is not aligned.
*/
void DCACHE_CleanByRange(uint32_t address, uint32_t size_byte);
/*!
* @brief Cleans and Invalidates all data caches by range.
*
* Both cortex-m7 L1 cache line and L2 PL310 cache line length is 32-byte.
*
* @param address The physical address.
* @param size_byte size of the memory to be cleaned and invalidated.
* @note address and size should be aligned to cache line size
* 32-Byte due to the cache operation unit is one cache line. The startAddr here will be forced
* to align to the cache line size if startAddr is not aligned. For the size_byte, application should
* make sure the alignment or make sure the right operation order if the size_byte is not aligned.
*/
void DCACHE_CleanInvalidateByRange(uint32_t address, uint32_t size_byte);
/*@}*/
#if defined(__cplusplus)
}
#endif
/*! @}*/
#endif /* _FSL_CACHE_H_*/

View File

@ -0,0 +1,842 @@
/*
* Copyright 2017 NXP
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include "fsl_common.h"
#include "fsl_clock.h"
/*******************************************************************************
* Definitions
******************************************************************************/
/*******************************************************************************
* Variables
******************************************************************************/
/* External XTAL (OSC) clock frequency. */
uint32_t g_xtalFreq;
/* External RTC XTAL clock frequency. */
uint32_t g_rtcXtalFreq;
/*******************************************************************************
* Prototypes
******************************************************************************/
/*******************************************************************************
* Code
******************************************************************************/
static uint32_t CLOCK_GetPeriphClkFreq(void)
{
uint32_t freq;
/* Periph_clk2_clk ---> Periph_clk */
if (CCM->CBCDR & CCM_CBCDR_PERIPH_CLK_SEL_MASK)
{
switch (CCM->CBCMR & CCM_CBCMR_PERIPH_CLK2_SEL_MASK)
{
/* Pll3_sw_clk ---> Periph_clk2_clk ---> Periph_clk */
case CCM_CBCMR_PERIPH_CLK2_SEL(0U):
freq = CLOCK_GetPllFreq(kCLOCK_PllUsb1);
break;
/* Osc_clk ---> Periph_clk2_clk ---> Periph_clk */
case CCM_CBCMR_PERIPH_CLK2_SEL(1U):
freq = CLOCK_GetOscFreq();
break;
case CCM_CBCMR_PERIPH_CLK2_SEL(2U):
case CCM_CBCMR_PERIPH_CLK2_SEL(3U):
default:
freq = 0U;
break;
}
freq /= (((CCM->CBCDR & CCM_CBCDR_PERIPH_CLK2_PODF_MASK) >> CCM_CBCDR_PERIPH_CLK2_PODF_SHIFT) + 1U);
}
/* Pre_Periph_clk ---> Periph_clk */
else
{
switch (CCM->CBCMR & CCM_CBCMR_PRE_PERIPH_CLK_SEL_MASK)
{
/* PLL2 ---> Pre_Periph_clk ---> Periph_clk */
case CCM_CBCMR_PRE_PERIPH_CLK_SEL(0U):
freq = CLOCK_GetPllFreq(kCLOCK_PllSys);
break;
/* PLL2 PFD2 ---> Pre_Periph_clk ---> Periph_clk */
case CCM_CBCMR_PRE_PERIPH_CLK_SEL(1U):
freq = CLOCK_GetSysPfdFreq(kCLOCK_Pfd2);
break;
/* PLL2 PFD0 ---> Pre_Periph_clk ---> Periph_clk */
case CCM_CBCMR_PRE_PERIPH_CLK_SEL(2U):
freq = CLOCK_GetSysPfdFreq(kCLOCK_Pfd0);
break;
/* PLL1 divided(/2) ---> Pre_Periph_clk ---> Periph_clk */
case CCM_CBCMR_PRE_PERIPH_CLK_SEL(3U):
freq = CLOCK_GetPllFreq(kCLOCK_PllArm) / (((CCM->CACRR & CCM_CACRR_ARM_PODF_MASK) >> CCM_CACRR_ARM_PODF_SHIFT) + 1U);
break;
default:
freq = 0U;
break;
}
}
return freq;
}
void CLOCK_InitExternalClk(bool bypassXtalOsc)
{
/* This device does not support bypass XTAL OSC. */
assert(!bypassXtalOsc);
CCM_ANALOG->MISC0_CLR = CCM_ANALOG_MISC0_XTAL_24M_PWD_MASK; /* Power up */
while ((XTALOSC24M->LOWPWR_CTRL & XTALOSC24M_LOWPWR_CTRL_XTALOSC_PWRUP_STAT_MASK) == 0)
{
}
CCM_ANALOG->MISC0_SET = CCM_ANALOG_MISC0_OSC_XTALOK_EN_MASK; /* detect freq */
while ((CCM_ANALOG->MISC0 & CCM_ANALOG_MISC0_OSC_XTALOK_MASK) == 0)
{
}
CCM_ANALOG->MISC0_CLR = CCM_ANALOG_MISC0_OSC_XTALOK_EN_MASK;
}
void CLOCK_DeinitExternalClk(void)
{
CCM_ANALOG->MISC0_SET = CCM_ANALOG_MISC0_XTAL_24M_PWD_MASK; /* Power down */
}
void CLOCK_SwitchOsc(clock_osc_t osc)
{
if (osc == kCLOCK_RcOsc)
XTALOSC24M->LOWPWR_CTRL_SET = XTALOSC24M_LOWPWR_CTRL_SET_OSC_SEL_MASK;
else
XTALOSC24M->LOWPWR_CTRL_CLR = XTALOSC24M_LOWPWR_CTRL_CLR_OSC_SEL_MASK;
}
void CLOCK_InitRcOsc24M(void)
{
XTALOSC24M->LOWPWR_CTRL |= XTALOSC24M_LOWPWR_CTRL_RC_OSC_EN_MASK;
}
void CLOCK_DeinitRcOsc24M(void)
{
XTALOSC24M->LOWPWR_CTRL &= ~XTALOSC24M_LOWPWR_CTRL_RC_OSC_EN_MASK;
}
uint32_t CLOCK_GetFreq(clock_name_t name)
{
uint32_t freq;
switch (name)
{
case kCLOCK_CpuClk:
/* Periph_clk ---> AHB Clock */
case kCLOCK_AhbClk:
/* Periph_clk ---> AHB Clock */
freq = CLOCK_GetPeriphClkFreq() / (((CCM->CBCDR & CCM_CBCDR_AHB_PODF_MASK) >> CCM_CBCDR_AHB_PODF_SHIFT) + 1U);
break;
case kCLOCK_SemcClk:
/* SEMC alternative clock ---> SEMC Clock */
if (CCM->CBCDR & CCM_CBCDR_SEMC_CLK_SEL_MASK)
{
/* PLL3 PFD1 ---> SEMC alternative clock ---> SEMC Clock */
if (CCM->CBCDR & CCM_CBCDR_SEMC_ALT_CLK_SEL_MASK)
{
freq = CLOCK_GetUsb1PfdFreq(kCLOCK_Pfd1);
}
/* PLL2 PFD2 ---> SEMC alternative clock ---> SEMC Clock */
else
{
freq = CLOCK_GetSysPfdFreq(kCLOCK_Pfd2);
}
}
/* Periph_clk ---> SEMC Clock */
else
{
freq = CLOCK_GetPeriphClkFreq();
}
freq /= (((CCM->CBCDR & CCM_CBCDR_SEMC_PODF_MASK) >> CCM_CBCDR_SEMC_PODF_SHIFT) + 1U);
break;
case kCLOCK_IpgClk:
/* Periph_clk ---> AHB Clock ---> IPG Clock */
freq = CLOCK_GetPeriphClkFreq() / (((CCM->CBCDR & CCM_CBCDR_AHB_PODF_MASK) >> CCM_CBCDR_AHB_PODF_SHIFT) + 1U);
freq /= (((CCM->CBCDR & CCM_CBCDR_IPG_PODF_MASK) >> CCM_CBCDR_IPG_PODF_SHIFT) + 1U);
break;
case kCLOCK_OscClk:
freq = CLOCK_GetOscFreq();
break;
case kCLOCK_RtcClk:
freq = CLOCK_GetRtcFreq();
break;
case kCLOCK_ArmPllClk:
freq = CLOCK_GetPllFreq(kCLOCK_PllArm);
break;
case kCLOCK_Usb1PllClk:
freq = CLOCK_GetPllFreq(kCLOCK_PllUsb1);
break;
case kCLOCK_Usb1PllPfd0Clk:
freq = CLOCK_GetUsb1PfdFreq(kCLOCK_Pfd0);
break;
case kCLOCK_Usb1PllPfd1Clk:
freq = CLOCK_GetUsb1PfdFreq(kCLOCK_Pfd1);
break;
case kCLOCK_Usb1PllPfd2Clk:
freq = CLOCK_GetUsb1PfdFreq(kCLOCK_Pfd2);
break;
case kCLOCK_Usb1PllPfd3Clk:
freq = CLOCK_GetUsb1PfdFreq(kCLOCK_Pfd3);
break;
case kCLOCK_Usb2PllClk:
freq = CLOCK_GetPllFreq(kCLOCK_PllUsb2);
break;
case kCLOCK_SysPllClk:
freq = CLOCK_GetPllFreq(kCLOCK_PllSys);
break;
case kCLOCK_SysPllPfd0Clk:
freq = CLOCK_GetSysPfdFreq(kCLOCK_Pfd0);
break;
case kCLOCK_SysPllPfd1Clk:
freq = CLOCK_GetSysPfdFreq(kCLOCK_Pfd1);
break;
case kCLOCK_SysPllPfd2Clk:
freq = CLOCK_GetSysPfdFreq(kCLOCK_Pfd2);
break;
case kCLOCK_SysPllPfd3Clk:
freq = CLOCK_GetSysPfdFreq(kCLOCK_Pfd3);
break;
case kCLOCK_EnetPll0Clk:
freq = CLOCK_GetPllFreq(kCLOCK_PllEnet0);
break;
case kCLOCK_EnetPll1Clk:
freq = CLOCK_GetPllFreq(kCLOCK_PllEnet1);
break;
case kCLOCK_EnetPll2Clk:
freq = CLOCK_GetPllFreq(kCLOCK_PllEnet2);
break;
case kCLOCK_AudioPllClk:
freq = CLOCK_GetPllFreq(kCLOCK_PllAudio);
break;
case kCLOCK_VideoPllClk:
freq = CLOCK_GetPllFreq(kCLOCK_PllVideo);
break;
default:
freq = 0U;
break;
}
return freq;
}
void CLOCK_InitArmPll(const clock_arm_pll_config_t *config)
{
CCM_ANALOG->PLL_ARM = CCM_ANALOG_PLL_ARM_ENABLE_MASK |
CCM_ANALOG_PLL_ARM_DIV_SELECT(config->loopDivider);
while ((CCM_ANALOG->PLL_ARM & CCM_ANALOG_PLL_ARM_LOCK_MASK) == 0)
{
}
}
void CLOCK_DeinitArmPll(void)
{
CCM_ANALOG->PLL_ARM = CCM_ANALOG_PLL_ARM_POWERDOWN_MASK;
}
void CLOCK_InitSysPll(const clock_sys_pll_config_t *config)
{
CCM_ANALOG->PLL_SYS = CCM_ANALOG_PLL_SYS_ENABLE_MASK |
CCM_ANALOG_PLL_SYS_DIV_SELECT(config->loopDivider);
while ((CCM_ANALOG->PLL_SYS & CCM_ANALOG_PLL_SYS_LOCK_MASK) == 0)
{
}
}
void CLOCK_DeinitSysPll(void)
{
CCM_ANALOG->PLL_SYS = CCM_ANALOG_PLL_SYS_POWERDOWN_MASK;
}
void CLOCK_InitUsb1Pll(const clock_usb_pll_config_t *config)
{
CCM_ANALOG->PLL_USB1 = CCM_ANALOG_PLL_USB1_ENABLE_MASK |
CCM_ANALOG_PLL_USB1_POWER_MASK |
CCM_ANALOG_PLL_USB1_EN_USB_CLKS_MASK |
CCM_ANALOG_PLL_USB1_DIV_SELECT(config->loopDivider);
while ((CCM_ANALOG->PLL_USB1 & CCM_ANALOG_PLL_USB1_LOCK_MASK) == 0)
{
}
}
void CLOCK_DeinitUsb1Pll(void)
{
CCM_ANALOG->PLL_USB1 = 0U;
}
void CLOCK_InitUsb2Pll(const clock_usb_pll_config_t *config)
{
CCM_ANALOG->PLL_USB2 = CCM_ANALOG_PLL_USB2_ENABLE_MASK |
CCM_ANALOG_PLL_USB2_POWER_MASK |
CCM_ANALOG_PLL_USB2_EN_USB_CLKS_MASK |
CCM_ANALOG_PLL_USB2_DIV_SELECT(config->loopDivider);
while ((CCM_ANALOG->PLL_USB2 & CCM_ANALOG_PLL_USB2_LOCK_MASK) == 0)
{
}
}
void CLOCK_DeinitUsb2Pll(void)
{
CCM_ANALOG->PLL_USB2 = 0U;
}
void CLOCK_InitAudioPll(const clock_audio_pll_config_t *config)
{
uint32_t pllAudio;
uint32_t misc2 = 0;
CCM_ANALOG->PLL_AUDIO_NUM = CCM_ANALOG_PLL_AUDIO_NUM_A(config->numerator);
CCM_ANALOG->PLL_AUDIO_DENOM = CCM_ANALOG_PLL_AUDIO_DENOM_B(config->denominator);
/*
* Set post divider:
*
* ------------------------------------------------------------------------
* | config->postDivider | PLL_AUDIO[POST_DIV_SELECT] | MISC2[AUDIO_DIV] |
* ------------------------------------------------------------------------
* | 1 | 2 | 0 |
* ------------------------------------------------------------------------
* | 2 | 1 | 0 |
* ------------------------------------------------------------------------
* | 4 | 2 | 3 |
* ------------------------------------------------------------------------
* | 8 | 1 | 3 |
* ------------------------------------------------------------------------
* | 16 | 0 | 3 |
* ------------------------------------------------------------------------
*/
pllAudio = CCM_ANALOG_PLL_AUDIO_ENABLE_MASK | CCM_ANALOG_PLL_AUDIO_DIV_SELECT(config->loopDivider);
switch (config->postDivider)
{
case 16:
pllAudio |= CCM_ANALOG_PLL_AUDIO_POST_DIV_SELECT(0);
misc2 = CCM_ANALOG_MISC2_AUDIO_DIV_MSB_MASK | CCM_ANALOG_MISC2_AUDIO_DIV_LSB_MASK;
break;
case 8:
pllAudio |= CCM_ANALOG_PLL_AUDIO_POST_DIV_SELECT(1);
misc2 = CCM_ANALOG_MISC2_AUDIO_DIV_MSB_MASK | CCM_ANALOG_MISC2_AUDIO_DIV_LSB_MASK;
break;
case 4:
pllAudio |= CCM_ANALOG_PLL_AUDIO_POST_DIV_SELECT(2);
misc2 = CCM_ANALOG_MISC2_AUDIO_DIV_MSB_MASK | CCM_ANALOG_MISC2_AUDIO_DIV_LSB_MASK;
break;
case 2:
pllAudio |= CCM_ANALOG_PLL_AUDIO_POST_DIV_SELECT(1);
break;
default:
pllAudio |= CCM_ANALOG_PLL_AUDIO_POST_DIV_SELECT(2);
break;
}
CCM_ANALOG->MISC2 = (CCM_ANALOG->MISC2 & ~(CCM_ANALOG_MISC2_AUDIO_DIV_LSB_MASK | CCM_ANALOG_MISC2_AUDIO_DIV_MSB_MASK))
| misc2;
CCM_ANALOG->PLL_AUDIO = pllAudio;
while ((CCM_ANALOG->PLL_AUDIO & CCM_ANALOG_PLL_AUDIO_LOCK_MASK) == 0)
{
}
}
void CLOCK_DeinitAudioPll(void)
{
CCM_ANALOG->PLL_AUDIO = CCM_ANALOG_PLL_AUDIO_POWERDOWN_MASK;
}
void CLOCK_InitVideoPll(const clock_video_pll_config_t *config)
{
uint32_t pllVideo;
uint32_t misc2 = 0;
CCM_ANALOG->PLL_VIDEO_NUM = CCM_ANALOG_PLL_VIDEO_NUM_A(config->numerator);
CCM_ANALOG->PLL_VIDEO_DENOM = CCM_ANALOG_PLL_VIDEO_DENOM_B(config->denominator);
/*
* Set post divider:
*
* ------------------------------------------------------------------------
* | config->postDivider | PLL_VIDEO[POST_DIV_SELECT] | MISC2[VIDEO_DIV] |
* ------------------------------------------------------------------------
* | 1 | 2 | 0 |
* ------------------------------------------------------------------------
* | 2 | 1 | 0 |
* ------------------------------------------------------------------------
* | 4 | 2 | 3 |
* ------------------------------------------------------------------------
* | 8 | 1 | 3 |
* ------------------------------------------------------------------------
* | 16 | 0 | 3 |
* ------------------------------------------------------------------------
*/
pllVideo = CCM_ANALOG_PLL_VIDEO_ENABLE_MASK | CCM_ANALOG_PLL_VIDEO_DIV_SELECT(config->loopDivider);
switch (config->postDivider)
{
case 16:
pllVideo |= CCM_ANALOG_PLL_VIDEO_POST_DIV_SELECT(0);
misc2 = CCM_ANALOG_MISC2_VIDEO_DIV(3);
break;
case 8:
pllVideo |= CCM_ANALOG_PLL_VIDEO_POST_DIV_SELECT(1);
misc2 = CCM_ANALOG_MISC2_VIDEO_DIV(3);
break;
case 4:
pllVideo |= CCM_ANALOG_PLL_VIDEO_POST_DIV_SELECT(2);
misc2 = CCM_ANALOG_MISC2_VIDEO_DIV(3);
break;
case 2:
pllVideo |= CCM_ANALOG_PLL_VIDEO_POST_DIV_SELECT(1);
break;
default:
pllVideo |= CCM_ANALOG_PLL_VIDEO_POST_DIV_SELECT(2);
break;
}
CCM_ANALOG->MISC2 = (CCM_ANALOG->MISC2 & ~CCM_ANALOG_MISC2_VIDEO_DIV_MASK) | misc2;
CCM_ANALOG->PLL_VIDEO = pllVideo;
while ((CCM_ANALOG->PLL_VIDEO & CCM_ANALOG_PLL_VIDEO_LOCK_MASK) == 0)
{
}
}
void CLOCK_DeinitVideoPll(void)
{
CCM_ANALOG->PLL_VIDEO = CCM_ANALOG_PLL_VIDEO_POWERDOWN_MASK;
}
void CLOCK_InitEnetPll(const clock_enet_pll_config_t *config)
{
uint32_t enet_pll = CCM_ANALOG_PLL_ENET_ENET1_DIV_SELECT(config->loopDivider1) |
CCM_ANALOG_PLL_ENET_ENET0_DIV_SELECT(config->loopDivider0);
if (config->enableClkOutput0)
{
enet_pll |= CCM_ANALOG_PLL_ENET_ENET1_125M_EN_MASK;
}
if (config->enableClkOutput1)
{
enet_pll |= CCM_ANALOG_PLL_ENET_ENET2_125M_EN_MASK;
}
if (config->enableClkOutput2)
{
enet_pll |= CCM_ANALOG_PLL_ENET_ENET_25M_REF_EN_MASK;
}
CCM_ANALOG->PLL_ENET = enet_pll;
/* Wait for stable */
while ((CCM_ANALOG->PLL_ENET & CCM_ANALOG_PLL_ENET_LOCK_MASK) == 0)
{
}
}
void CLOCK_DeinitEnetPll(void)
{
CCM_ANALOG->PLL_ENET = CCM_ANALOG_PLL_ENET_POWERDOWN_MASK;
}
uint32_t CLOCK_GetPllFreq(clock_pll_t pll)
{
uint32_t freq;
uint32_t divSelect;
uint64_t freqTmp;
const uint32_t enetRefClkFreq[] = {
25000000U, /* 25M */
50000000U, /* 50M */
100000000U, /* 100M */
125000000U /* 125M */
};
switch (pll)
{
case kCLOCK_PllArm:
freq = ((CLOCK_GetOscFreq() * ((CCM_ANALOG->PLL_ARM & CCM_ANALOG_PLL_ARM_DIV_SELECT_MASK) >>
CCM_ANALOG_PLL_ARM_DIV_SELECT_SHIFT)) >> 1U);
break;
case kCLOCK_PllSys:
freq = CLOCK_GetOscFreq();
/* PLL output frequency = Fref * (DIV_SELECT + NUM/DENOM). */
freqTmp = ((uint64_t)freq * ((uint64_t)(CCM_ANALOG->PLL_SYS_NUM))) / ((uint64_t)(CCM_ANALOG->PLL_SYS_DENOM));
if (CCM_ANALOG->PLL_SYS & CCM_ANALOG_PLL_SYS_DIV_SELECT_MASK)
{
freq *= 22U;
}
else
{
freq *= 20U;
}
freq += (uint32_t)freqTmp;
break;
case kCLOCK_PllUsb1:
freq = (CLOCK_GetOscFreq() * ((CCM_ANALOG->PLL_USB1 & CCM_ANALOG_PLL_USB1_DIV_SELECT_MASK) ? 22U : 20U));
break;
case kCLOCK_PllAudio:
freq = CLOCK_GetOscFreq();
/* PLL output frequency = Fref * (DIV_SELECT + NUM/DENOM). */
divSelect = (CCM_ANALOG->PLL_AUDIO & CCM_ANALOG_PLL_AUDIO_DIV_SELECT_MASK) >> CCM_ANALOG_PLL_AUDIO_DIV_SELECT_SHIFT;
freqTmp = ((uint64_t)freq * ((uint64_t)(CCM_ANALOG->PLL_AUDIO_NUM))) / ((uint64_t)(CCM_ANALOG->PLL_AUDIO_DENOM));
freq = freq * divSelect + (uint32_t)freqTmp;
/* AUDIO PLL output = PLL output frequency / POSTDIV. */
/*
* Post divider:
*
* PLL_AUDIO[POST_DIV_SELECT]:
* 0x00: 4
* 0x01: 2
* 0x02: 1
*
* MISC2[AUDO_DIV]:
* 0x00: 1
* 0x01: 2
* 0x02: 1
* 0x03: 4
*/
switch (CCM_ANALOG->PLL_AUDIO & CCM_ANALOG_PLL_AUDIO_POST_DIV_SELECT_MASK)
{
case CCM_ANALOG_PLL_AUDIO_POST_DIV_SELECT(0U):
freq = freq >> 2U;
break;
case CCM_ANALOG_PLL_AUDIO_POST_DIV_SELECT(1U):
freq = freq >> 1U;
break;
default:
break;
}
switch (CCM_ANALOG->MISC2 & (CCM_ANALOG_MISC2_AUDIO_DIV_MSB_MASK | CCM_ANALOG_MISC2_AUDIO_DIV_LSB_MASK))
{
case CCM_ANALOG_MISC2_AUDIO_DIV_MSB(1) | CCM_ANALOG_MISC2_AUDIO_DIV_LSB(1):
freq >>= 2U;
break;
case CCM_ANALOG_MISC2_AUDIO_DIV_MSB(0) | CCM_ANALOG_MISC2_AUDIO_DIV_LSB(1):
freq >>= 1U;
break;
default:
break;
}
break;
case kCLOCK_PllVideo:
freq = CLOCK_GetOscFreq();
/* PLL output frequency = Fref * (DIV_SELECT + NUM/DENOM). */
divSelect = (CCM_ANALOG->PLL_VIDEO & CCM_ANALOG_PLL_VIDEO_DIV_SELECT_MASK) >> CCM_ANALOG_PLL_VIDEO_DIV_SELECT_SHIFT;
freqTmp = ((uint64_t)freq * ((uint64_t)(CCM_ANALOG->PLL_VIDEO_NUM))) / ((uint64_t)(CCM_ANALOG->PLL_VIDEO_DENOM));
freq = freq * divSelect + (uint32_t)freqTmp;
/* VIDEO PLL output = PLL output frequency / POSTDIV. */
/*
* Post divider:
*
* PLL_VIDEO[POST_DIV_SELECT]:
* 0x00: 4
* 0x01: 2
* 0x02: 1
*
* MISC2[VIDEO_DIV]:
* 0x00: 1
* 0x01: 2
* 0x02: 1
* 0x03: 4
*/
switch (CCM_ANALOG->PLL_VIDEO & CCM_ANALOG_PLL_VIDEO_POST_DIV_SELECT_MASK)
{
case CCM_ANALOG_PLL_VIDEO_POST_DIV_SELECT(0U):
freq = freq >> 2U;
break;
case CCM_ANALOG_PLL_VIDEO_POST_DIV_SELECT(1U):
freq = freq >> 1U;
break;
default:
break;
}
switch (CCM_ANALOG->MISC2 & CCM_ANALOG_MISC2_VIDEO_DIV_MASK)
{
case CCM_ANALOG_MISC2_VIDEO_DIV(3):
freq >>= 2U;
break;
case CCM_ANALOG_MISC2_VIDEO_DIV(1):
freq >>= 1U;
break;
default:
break;
}
break;
case kCLOCK_PllEnet0:
divSelect = (CCM_ANALOG->PLL_ENET & CCM_ANALOG_PLL_ENET_ENET0_DIV_SELECT_MASK)
>> CCM_ANALOG_PLL_ENET_ENET0_DIV_SELECT_SHIFT;
freq = enetRefClkFreq[divSelect];
break;
case kCLOCK_PllEnet1:
divSelect = (CCM_ANALOG->PLL_ENET & CCM_ANALOG_PLL_ENET_ENET1_DIV_SELECT_MASK)
>> CCM_ANALOG_PLL_ENET_ENET1_DIV_SELECT_SHIFT;
freq = enetRefClkFreq[divSelect];
break;
case kCLOCK_PllEnet2:
/* ref_enetpll2 if fixed at 25MHz. */
freq = 25000000UL;
break;
case kCLOCK_PllUsb2:
freq = (CLOCK_GetOscFreq() * ((CCM_ANALOG->PLL_USB2 & CCM_ANALOG_PLL_USB2_DIV_SELECT_MASK) ? 22U : 20U));
break;
default:
freq = 0U;
break;
}
return freq;
}
void CLOCK_InitSysPfd(clock_pfd_t pfd, uint8_t pfdFrac)
{
uint32_t pfdIndex = (uint32_t)pfd;
uint32_t pfd528;
pfd528 = CCM_ANALOG->PFD_528 & ~((CCM_ANALOG_PFD_528_PFD0_CLKGATE_MASK | CCM_ANALOG_PFD_528_PFD0_FRAC_MASK) << (8 * pfdIndex));
/* Disable the clock output first. */
CCM_ANALOG->PFD_528 = pfd528 | (CCM_ANALOG_PFD_528_PFD0_CLKGATE_MASK << (8 * pfdIndex));
/* Set the new value and enable output. */
CCM_ANALOG->PFD_528 = pfd528 | (CCM_ANALOG_PFD_528_PFD0_FRAC(pfdFrac) << (8 * pfdIndex));
}
void CLOCK_DeinitSysPfd(clock_pfd_t pfd)
{
CCM_ANALOG->PFD_528 |= CCM_ANALOG_PFD_528_PFD0_CLKGATE_MASK << (8 * pfd);
}
void CLOCK_InitUsb1Pfd(clock_pfd_t pfd, uint8_t pfdFrac)
{
uint32_t pfdIndex = (uint32_t)pfd;
uint32_t pfd480;
pfd480 = CCM_ANALOG->PFD_480 & ~((CCM_ANALOG_PFD_480_PFD0_CLKGATE_MASK | CCM_ANALOG_PFD_480_PFD0_FRAC_MASK) << (8 * pfdIndex));
/* Disable the clock output first. */
CCM_ANALOG->PFD_480 = pfd480 | (CCM_ANALOG_PFD_480_PFD0_CLKGATE_MASK << (8 * pfdIndex));
/* Set the new value and enable output. */
CCM_ANALOG->PFD_480 = pfd480 | (CCM_ANALOG_PFD_480_PFD0_FRAC(pfdFrac) << (8 * pfdIndex));
}
void CLOCK_DeinitUsb1Pfd(clock_pfd_t pfd)
{
CCM_ANALOG->PFD_480 |= CCM_ANALOG_PFD_480_PFD0_CLKGATE_MASK << (8 * pfd);
}
uint32_t CLOCK_GetSysPfdFreq(clock_pfd_t pfd)
{
uint32_t freq = CLOCK_GetPllFreq(kCLOCK_PllSys);
switch (pfd)
{
case kCLOCK_Pfd0:
freq /= ((CCM_ANALOG->PFD_528 & CCM_ANALOG_PFD_528_PFD0_FRAC_MASK) >> CCM_ANALOG_PFD_528_PFD0_FRAC_SHIFT);
break;
case kCLOCK_Pfd1:
freq /= ((CCM_ANALOG->PFD_528 & CCM_ANALOG_PFD_528_PFD1_FRAC_MASK) >> CCM_ANALOG_PFD_528_PFD1_FRAC_SHIFT);
break;
case kCLOCK_Pfd2:
freq /= ((CCM_ANALOG->PFD_528 & CCM_ANALOG_PFD_528_PFD2_FRAC_MASK) >> CCM_ANALOG_PFD_528_PFD2_FRAC_SHIFT);
break;
case kCLOCK_Pfd3:
freq /= ((CCM_ANALOG->PFD_528 & CCM_ANALOG_PFD_528_PFD3_FRAC_MASK) >> CCM_ANALOG_PFD_528_PFD3_FRAC_SHIFT);
break;
default:
freq = 0U;
break;
}
freq *= 18U;
return freq;
}
uint32_t CLOCK_GetUsb1PfdFreq(clock_pfd_t pfd)
{
uint32_t freq = CLOCK_GetPllFreq(kCLOCK_PllUsb1);
switch (pfd)
{
case kCLOCK_Pfd0:
freq /= ((CCM_ANALOG->PFD_480 & CCM_ANALOG_PFD_480_PFD0_FRAC_MASK) >> CCM_ANALOG_PFD_480_PFD0_FRAC_SHIFT);
break;
case kCLOCK_Pfd1:
freq /= ((CCM_ANALOG->PFD_480 & CCM_ANALOG_PFD_480_PFD1_FRAC_MASK) >> CCM_ANALOG_PFD_480_PFD1_FRAC_SHIFT);
break;
case kCLOCK_Pfd2:
freq /= ((CCM_ANALOG->PFD_480 & CCM_ANALOG_PFD_480_PFD2_FRAC_MASK) >> CCM_ANALOG_PFD_480_PFD2_FRAC_SHIFT);
break;
case kCLOCK_Pfd3:
freq /= ((CCM_ANALOG->PFD_480 & CCM_ANALOG_PFD_480_PFD3_FRAC_MASK) >> CCM_ANALOG_PFD_480_PFD3_FRAC_SHIFT);
break;
default:
freq = 0U;
break;
}
freq *= 18U;
return freq;
}
bool CLOCK_EnableUsbhs0Clock(clock_usb_src_t src, uint32_t freq)
{
CCM->CCGR6 |= CCM_CCGR6_CG0_MASK ;
USB1->USBCMD |= USBHS_USBCMD_RST_MASK;
for (volatile uint32_t i = 0; i < 400000; i++) /* Add a delay between RST and RS so make sure there is a DP pullup sequence*/
{
__ASM("nop");
}
PMU->REG_3P0 = (PMU->REG_3P0 & (~PMU_REG_3P0_OUTPUT_TRG_MASK)) | (PMU_REG_3P0_OUTPUT_TRG(0x17) | PMU_REG_3P0_ENABLE_LINREG_MASK);
return true;
}
bool CLOCK_EnableUsbhs1Clock(clock_usb_src_t src, uint32_t freq)
{
CCM->CCGR6 |= CCM_CCGR6_CG0_MASK ;
USB2->USBCMD |= USBHS_USBCMD_RST_MASK;
for (volatile uint32_t i = 0; i < 400000; i++) /* Add a delay between RST and RS so make sure there is a DP pullup sequence*/
{
__ASM("nop");
}
PMU->REG_3P0 = (PMU->REG_3P0 & (~PMU_REG_3P0_OUTPUT_TRG_MASK)) | (PMU_REG_3P0_OUTPUT_TRG(0x17) | PMU_REG_3P0_ENABLE_LINREG_MASK);
return true;
}
bool CLOCK_EnableUsbhs0PhyPllClock(clock_usb_phy_src_t src, uint32_t freq)
{
const clock_usb_pll_config_t g_ccmConfigUsbPll = {.loopDivider = 0U};
CLOCK_InitUsb1Pll(&g_ccmConfigUsbPll);
USBPHY1->CTRL &= ~USBPHY_CTRL_SFTRST_MASK; /* release PHY from reset */
USBPHY1->CTRL &= ~USBPHY_CTRL_CLKGATE_MASK;
USBPHY1->PWD = 0;
USBPHY1->CTRL |=
USBPHY_CTRL_ENAUTOCLR_PHY_PWD_MASK |
USBPHY_CTRL_ENAUTOCLR_CLKGATE_MASK |
USBPHY_CTRL_ENUTMILEVEL2_MASK |
USBPHY_CTRL_ENUTMILEVEL3_MASK;
return true;
}
bool CLOCK_EnableUsbhs1PhyPllClock(clock_usb_phy_src_t src, uint32_t freq)
{
const clock_usb_pll_config_t g_ccmConfigUsbPll = {.loopDivider = 0U};
CLOCK_InitUsb2Pll(&g_ccmConfigUsbPll);
USBPHY2->CTRL &= ~USBPHY_CTRL_SFTRST_MASK; /* release PHY from reset */
USBPHY2->CTRL &= ~USBPHY_CTRL_CLKGATE_MASK;
USBPHY2->PWD = 0;
USBPHY2->CTRL |=
USBPHY_CTRL_ENAUTOCLR_PHY_PWD_MASK |
USBPHY_CTRL_ENAUTOCLR_CLKGATE_MASK |
USBPHY_CTRL_ENUTMILEVEL2_MASK |
USBPHY_CTRL_ENUTMILEVEL3_MASK;
return true;
}
void CLOCK_DisableUsbhs0PhyPllClock(void)
{
CLOCK_DeinitUsb1Pll();
USBPHY1->CTRL |= USBPHY_CTRL_CLKGATE_MASK; /* Set to 1U to gate clocks */
}
void CLOCK_DisableUsbhs1PhyPllClock(void)
{
CLOCK_DeinitUsb2Pll();
USBPHY2->CTRL |= USBPHY_CTRL_CLKGATE_MASK; /* Set to 1U to gate clocks */
}

File diff suppressed because it is too large Load Diff

View File

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

View File

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

View File

@ -0,0 +1,162 @@
/*
* Copyright (c) 2015-2016, Freescale Semiconductor, Inc.
* Copyright 2016 NXP
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include "fsl_common.h"
#define SDK_MEM_MAGIC_NUMBER 12345U
typedef struct _mem_align_control_block
{
uint16_t identifier; /*!< Identifier for the memory control block. */
uint16_t offset; /*!< offset from aligned adress to real address */
} mem_align_cb_t;
#ifndef __GIC_PRIO_BITS
#if defined(ENABLE_RAM_VECTOR_TABLE)
uint32_t InstallIRQHandler(IRQn_Type irq, uint32_t irqHandler)
{
/* Addresses for VECTOR_TABLE and VECTOR_RAM come from the linker file */
#if defined(__CC_ARM)
extern uint32_t Image$$VECTOR_ROM$$Base[];
extern uint32_t Image$$VECTOR_RAM$$Base[];
extern uint32_t Image$$RW_m_data$$Base[];
#define __VECTOR_TABLE Image$$VECTOR_ROM$$Base
#define __VECTOR_RAM Image$$VECTOR_RAM$$Base
#define __RAM_VECTOR_TABLE_SIZE (((uint32_t)Image$$RW_m_data$$Base - (uint32_t)Image$$VECTOR_RAM$$Base))
#elif defined(__ICCARM__)
extern uint32_t __RAM_VECTOR_TABLE_SIZE[];
extern uint32_t __VECTOR_TABLE[];
extern uint32_t __VECTOR_RAM[];
#elif defined(__GNUC__)
extern uint32_t __VECTOR_TABLE[];
extern uint32_t __VECTOR_RAM[];
extern uint32_t __RAM_VECTOR_TABLE_SIZE_BYTES[];
uint32_t __RAM_VECTOR_TABLE_SIZE = (uint32_t)(__RAM_VECTOR_TABLE_SIZE_BYTES);
#endif /* defined(__CC_ARM) */
uint32_t n;
uint32_t ret;
uint32_t irqMaskValue;
irqMaskValue = DisableGlobalIRQ();
if (SCB->VTOR != (uint32_t)__VECTOR_RAM)
{
/* Copy the vector table from ROM to RAM */
for (n = 0; n < ((uint32_t)__RAM_VECTOR_TABLE_SIZE) / sizeof(uint32_t); n++)
{
__VECTOR_RAM[n] = __VECTOR_TABLE[n];
}
/* Point the VTOR to the position of vector table */
SCB->VTOR = (uint32_t)__VECTOR_RAM;
}
ret = __VECTOR_RAM[irq + 16];
/* make sure the __VECTOR_RAM is noncachable */
__VECTOR_RAM[irq + 16] = irqHandler;
EnableGlobalIRQ(irqMaskValue);
/* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
exception return operation might vector to incorrect interrupt */
#if defined __CORTEX_M && (__CORTEX_M == 4U)
__DSB();
#endif
return ret;
}
#endif /* ENABLE_RAM_VECTOR_TABLE. */
#endif /* __GIC_PRIO_BITS. */
#ifndef QN908XC_SERIES
#if (defined(FSL_FEATURE_SOC_SYSCON_COUNT) && (FSL_FEATURE_SOC_SYSCON_COUNT > 0))
void EnableDeepSleepIRQ(IRQn_Type interrupt)
{
uint32_t index = 0;
uint32_t intNumber = (uint32_t)interrupt;
while (intNumber >= 32u)
{
index++;
intNumber -= 32u;
}
SYSCON->STARTERSET[index] = 1u << intNumber;
EnableIRQ(interrupt); /* also enable interrupt at NVIC */
}
void DisableDeepSleepIRQ(IRQn_Type interrupt)
{
uint32_t index = 0;
uint32_t intNumber = (uint32_t)interrupt;
while (intNumber >= 32u)
{
index++;
intNumber -= 32u;
}
DisableIRQ(interrupt); /* also disable interrupt at NVIC */
SYSCON->STARTERCLR[index] = 1u << intNumber;
}
#endif /* FSL_FEATURE_SOC_SYSCON_COUNT */
#endif /* QN908XC_SERIES */
void *SDK_Malloc(size_t size, size_t alignbytes)
{
mem_align_cb_t *p_cb = NULL;
uint32_t alignedsize = SDK_SIZEALIGN(size, alignbytes) + alignbytes + sizeof(mem_align_cb_t);
void *p_align_addr, *p_addr = malloc(alignedsize);
if (!p_addr)
{
return NULL;
}
p_align_addr = (void *)SDK_SIZEALIGN((uint32_t)p_addr + sizeof(mem_align_cb_t), alignbytes);
p_cb = (mem_align_cb_t *)((uint32_t)p_align_addr - 4);
p_cb->identifier = SDK_MEM_MAGIC_NUMBER;
p_cb->offset = (uint32_t)p_align_addr - (uint32_t)p_addr;
return (void *)p_align_addr;
}
void SDK_Free(void *ptr)
{
mem_align_cb_t *p_cb = (mem_align_cb_t *)((uint32_t)ptr - 4);
if (p_cb->identifier != SDK_MEM_MAGIC_NUMBER)
{
return;
}
free((void *)((uint32_t)ptr - p_cb->offset));
}

View File

@ -0,0 +1,520 @@
/*
* Copyright (c) 2015-2016, Freescale Semiconductor, Inc.
* Copyright 2016-2017 NXP
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _FSL_COMMON_H_
#define _FSL_COMMON_H_
#include <assert.h>
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
#include <stdlib.h>
#if defined(__ICCARM__)
#include <stddef.h>
#endif
#include "fsl_device_registers.h"
/*!
* @addtogroup ksdk_common
* @{
*/
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @brief Construct a status code value from a group and code number. */
#define MAKE_STATUS(group, code) ((((group)*100) + (code)))
/*! @brief Construct the version number for drivers. */
#define MAKE_VERSION(major, minor, bugfix) (((major) << 16) | ((minor) << 8) | (bugfix))
/*! @name Driver version */
/*@{*/
/*! @brief common driver version 2.0.0. */
#define FSL_COMMON_DRIVER_VERSION (MAKE_VERSION(2, 0, 0))
/*@}*/
/* Debug console type definition. */
#define DEBUG_CONSOLE_DEVICE_TYPE_NONE 0U /*!< No debug console. */
#define DEBUG_CONSOLE_DEVICE_TYPE_UART 1U /*!< Debug console base on UART. */
#define DEBUG_CONSOLE_DEVICE_TYPE_LPUART 2U /*!< Debug console base on LPUART. */
#define DEBUG_CONSOLE_DEVICE_TYPE_LPSCI 3U /*!< Debug console base on LPSCI. */
#define DEBUG_CONSOLE_DEVICE_TYPE_USBCDC 4U /*!< Debug console base on USBCDC. */
#define DEBUG_CONSOLE_DEVICE_TYPE_FLEXCOMM 5U /*!< Debug console base on USBCDC. */
#define DEBUG_CONSOLE_DEVICE_TYPE_IUART 6U /*!< Debug console base on i.MX UART. */
#define DEBUG_CONSOLE_DEVICE_TYPE_VUSART 7U /*!< Debug console base on LPC_USART. */
/*! @brief Status group numbers. */
enum _status_groups
{
kStatusGroup_Generic = 0, /*!< Group number for generic status codes. */
kStatusGroup_FLASH = 1, /*!< Group number for FLASH status codes. */
kStatusGroup_LPSPI = 4, /*!< Group number for LPSPI status codes. */
kStatusGroup_FLEXIO_SPI = 5, /*!< Group number for FLEXIO SPI status codes. */
kStatusGroup_DSPI = 6, /*!< Group number for DSPI status codes. */
kStatusGroup_FLEXIO_UART = 7, /*!< Group number for FLEXIO UART status codes. */
kStatusGroup_FLEXIO_I2C = 8, /*!< Group number for FLEXIO I2C status codes. */
kStatusGroup_LPI2C = 9, /*!< Group number for LPI2C status codes. */
kStatusGroup_UART = 10, /*!< Group number for UART status codes. */
kStatusGroup_I2C = 11, /*!< Group number for UART status codes. */
kStatusGroup_LPSCI = 12, /*!< Group number for LPSCI status codes. */
kStatusGroup_LPUART = 13, /*!< Group number for LPUART status codes. */
kStatusGroup_SPI = 14, /*!< Group number for SPI status code.*/
kStatusGroup_XRDC = 15, /*!< Group number for XRDC status code.*/
kStatusGroup_SEMA42 = 16, /*!< Group number for SEMA42 status code.*/
kStatusGroup_SDHC = 17, /*!< Group number for SDHC status code */
kStatusGroup_SDMMC = 18, /*!< Group number for SDMMC status code */
kStatusGroup_SAI = 19, /*!< Group number for SAI status code */
kStatusGroup_MCG = 20, /*!< Group number for MCG status codes. */
kStatusGroup_SCG = 21, /*!< Group number for SCG status codes. */
kStatusGroup_SDSPI = 22, /*!< Group number for SDSPI status codes. */
kStatusGroup_FLEXIO_I2S = 23, /*!< Group number for FLEXIO I2S status codes */
kStatusGroup_FLEXIO_MCULCD = 24, /*!< Group number for FLEXIO LCD status codes */
kStatusGroup_FLASHIAP = 25, /*!< Group number for FLASHIAP status codes */
kStatusGroup_FLEXCOMM_I2C = 26, /*!< Group number for FLEXCOMM I2C status codes */
kStatusGroup_I2S = 27, /*!< Group number for I2S status codes */
kStatusGroup_IUART = 28, /*!< Group number for IUART status codes */
kStatusGroup_CSI = 29, /*!< Group number for CSI status codes */
kStatusGroup_MIPI_DSI = 30, /*!< Group number for MIPI DSI status codes */
kStatusGroup_SDRAMC = 35, /*!< Group number for SDRAMC status codes. */
kStatusGroup_POWER = 39, /*!< Group number for POWER status codes. */
kStatusGroup_ENET = 40, /*!< Group number for ENET status codes. */
kStatusGroup_PHY = 41, /*!< Group number for PHY status codes. */
kStatusGroup_TRGMUX = 42, /*!< Group number for TRGMUX status codes. */
kStatusGroup_SMARTCARD = 43, /*!< Group number for SMARTCARD status codes. */
kStatusGroup_LMEM = 44, /*!< Group number for LMEM status codes. */
kStatusGroup_QSPI = 45, /*!< Group number for QSPI status codes. */
kStatusGroup_DMA = 50, /*!< Group number for DMA status codes. */
kStatusGroup_EDMA = 51, /*!< Group number for EDMA status codes. */
kStatusGroup_DMAMGR = 52, /*!< Group number for DMAMGR status codes. */
kStatusGroup_FLEXCAN = 53, /*!< Group number for FlexCAN status codes. */
kStatusGroup_LTC = 54, /*!< Group number for LTC status codes. */
kStatusGroup_FLEXIO_CAMERA = 55, /*!< Group number for FLEXIO CAMERA status codes. */
kStatusGroup_LPC_SPI = 56, /*!< Group number for LPC_SPI status codes. */
kStatusGroup_LPC_USART = 57, /*!< Group number for LPC_USART status codes. */
kStatusGroup_DMIC = 58, /*!< Group number for DMIC status codes. */
kStatusGroup_SDIF = 59, /*!< Group number for SDIF status codes.*/
kStatusGroup_SPIFI = 60, /*!< Group number for SPIFI status codes. */
kStatusGroup_OTP = 61, /*!< Group number for OTP status codes. */
kStatusGroup_MCAN = 62, /*!< Group number for MCAN status codes. */
kStatusGroup_CAAM = 63, /*!< Group number for CAAM status codes. */
kStatusGroup_ECSPI = 64, /*!< Group number for ECSPI status codes. */
kStatusGroup_USDHC = 65, /*!< Group number for USDHC status codes.*/
kStatusGroup_LPC_I2C = 66, /*!< Group number for LPC_I2C status codes.*/
kStatusGroup_DCP = 67, /*!< Group number for DCP status codes.*/
kStatusGroup_MSCAN = 68, /*!< Group number for MSCAN status codes.*/
kStatusGroup_ESAI = 69, /*!< Group number for ESAI status codes. */
kStatusGroup_FLEXSPI = 70, /*!< Group number for FLEXSPI status codes. */
kStatusGroup_MMDC = 71, /*!< Group number for MMDC status codes. */
kStatusGroup_MICFIL = 72, /*!< Group number for MIC status codes. */
kStatusGroup_SDMA = 73, /*!< Group number for SDMA status codes. */
kStatusGroup_ICS = 74, /*!< Group number for ICS status codes. */
kStatusGroup_SPDIF = 75, /*!< Group number for SPDIF status codes. */
kStatusGroup_NOTIFIER = 98, /*!< Group number for NOTIFIER status codes. */
kStatusGroup_DebugConsole = 99, /*!< Group number for debug console status codes. */
kStatusGroup_SEMC = 100, /*!< Group number for SEMC status codes. */
kStatusGroup_ApplicationRangeStart = 101, /*!< Starting number for application groups. */
};
/*! @brief Generic status return codes. */
enum _generic_status
{
kStatus_Success = MAKE_STATUS(kStatusGroup_Generic, 0),
kStatus_Fail = MAKE_STATUS(kStatusGroup_Generic, 1),
kStatus_ReadOnly = MAKE_STATUS(kStatusGroup_Generic, 2),
kStatus_OutOfRange = MAKE_STATUS(kStatusGroup_Generic, 3),
kStatus_InvalidArgument = MAKE_STATUS(kStatusGroup_Generic, 4),
kStatus_Timeout = MAKE_STATUS(kStatusGroup_Generic, 5),
kStatus_NoTransferInProgress = MAKE_STATUS(kStatusGroup_Generic, 6),
};
/*! @brief Type used for all status and error return values. */
typedef int32_t status_t;
/*
* The fsl_clock.h is included here because it needs MAKE_VERSION/MAKE_STATUS/status_t
* defined in previous of this file.
*/
#include "fsl_clock.h"
/*
* Chip level peripheral reset API, for MCUs that implement peripheral reset control external to a peripheral
*/
#if ((defined(FSL_FEATURE_SOC_SYSCON_COUNT) && (FSL_FEATURE_SOC_SYSCON_COUNT > 0)) || \
(defined(FSL_FEATURE_SOC_ASYNC_SYSCON_COUNT) && (FSL_FEATURE_SOC_ASYNC_SYSCON_COUNT > 0)))
#include "fsl_reset.h"
#endif
/*! @name Min/max macros */
/* @{ */
#if !defined(MIN)
#define MIN(a, b) ((a) < (b) ? (a) : (b))
#endif
#if !defined(MAX)
#define MAX(a, b) ((a) > (b) ? (a) : (b))
#endif
/* @} */
/*! @brief Computes the number of elements in an array. */
#if !defined(ARRAY_SIZE)
#define ARRAY_SIZE(x) (sizeof(x) / sizeof((x)[0]))
#endif
/*! @name UINT16_MAX/UINT32_MAX value */
/* @{ */
#if !defined(UINT16_MAX)
#define UINT16_MAX ((uint16_t)-1)
#endif
#if !defined(UINT32_MAX)
#define UINT32_MAX ((uint32_t)-1)
#endif
/* @} */
/*! @name Timer utilities */
/* @{ */
/*! Macro to convert a microsecond period to raw count value */
#define USEC_TO_COUNT(us, clockFreqInHz) (uint64_t)((uint64_t)us * clockFreqInHz / 1000000U)
/*! Macro to convert a raw count value to microsecond */
#define COUNT_TO_USEC(count, clockFreqInHz) (uint64_t)((uint64_t)count * 1000000U / clockFreqInHz)
/*! Macro to convert a millisecond period to raw count value */
#define MSEC_TO_COUNT(ms, clockFreqInHz) (uint64_t)((uint64_t)ms * clockFreqInHz / 1000U)
/*! Macro to convert a raw count value to millisecond */
#define COUNT_TO_MSEC(count, clockFreqInHz) (uint64_t)((uint64_t)count * 1000U / clockFreqInHz)
/* @} */
/*! @name Alignment variable definition macros */
/* @{ */
#if (defined(__ICCARM__))
/**
* Workaround to disable MISRA C message suppress warnings for IAR compiler.
* http://supp.iar.com/Support/?note=24725
*/
_Pragma("diag_suppress=Pm120")
#define SDK_PRAGMA(x) _Pragma(#x)
_Pragma("diag_error=Pm120")
/*! Macro to define a variable with alignbytes alignment */
#define SDK_ALIGN(var, alignbytes) SDK_PRAGMA(data_alignment = alignbytes) var
/*! Macro to define a variable with L1 d-cache line size alignment */
#if defined(FSL_FEATURE_L1DCACHE_LINESIZE_BYTE)
#define SDK_L1DCACHE_ALIGN(var) SDK_PRAGMA(data_alignment = FSL_FEATURE_L1DCACHE_LINESIZE_BYTE) var
#endif
/*! Macro to define a variable with L2 cache line size alignment */
#if defined(FSL_FEATURE_L2CACHE_LINESIZE_BYTE)
#define SDK_L2CACHE_ALIGN(var) SDK_PRAGMA(data_alignment = FSL_FEATURE_L2CACHE_LINESIZE_BYTE) var
#endif
#elif defined(__ARMCC_VERSION)
/*! Macro to define a variable with alignbytes alignment */
#define SDK_ALIGN(var, alignbytes) __align(alignbytes) var
/*! Macro to define a variable with L1 d-cache line size alignment */
#if defined(FSL_FEATURE_L1DCACHE_LINESIZE_BYTE)
#define SDK_L1DCACHE_ALIGN(var) __align(FSL_FEATURE_L1DCACHE_LINESIZE_BYTE) var
#endif
/*! Macro to define a variable with L2 cache line size alignment */
#if defined(FSL_FEATURE_L2CACHE_LINESIZE_BYTE)
#define SDK_L2CACHE_ALIGN(var) __align(FSL_FEATURE_L2CACHE_LINESIZE_BYTE) var
#endif
#elif defined(__GNUC__)
/*! Macro to define a variable with alignbytes alignment */
#define SDK_ALIGN(var, alignbytes) var __attribute__((aligned(alignbytes)))
/*! Macro to define a variable with L1 d-cache line size alignment */
#if defined(FSL_FEATURE_L1DCACHE_LINESIZE_BYTE)
#define SDK_L1DCACHE_ALIGN(var) var __attribute__((aligned(FSL_FEATURE_L1DCACHE_LINESIZE_BYTE)))
#endif
/*! Macro to define a variable with L2 cache line size alignment */
#if defined(FSL_FEATURE_L2CACHE_LINESIZE_BYTE)
#define SDK_L2CACHE_ALIGN(var) var __attribute__((aligned(FSL_FEATURE_L2CACHE_LINESIZE_BYTE)))
#endif
#else
#error Toolchain not supported
#define SDK_ALIGN(var, alignbytes) var
#if defined(FSL_FEATURE_L1DCACHE_LINESIZE_BYTE)
#define SDK_L1DCACHE_ALIGN(var) var
#endif
#if defined(FSL_FEATURE_L2CACHE_LINESIZE_BYTE)
#define SDK_L2CACHE_ALIGN(var) var
#endif
#endif
/*! Macro to change a value to a given size aligned value */
#define SDK_SIZEALIGN(var, alignbytes) \
((unsigned int)((var) + ((alignbytes)-1)) & (unsigned int)(~(unsigned int)((alignbytes)-1)))
/* @} */
/*! Function to allocate/free L1 cache aligned memory using the malloc/free. */
void *SDK_Malloc(size_t size, size_t alignbytes);
void SDK_Free(void *ptr);
/* @} */
/*! @name Non-cacheable region definition macros */
/* For initialized non-zero non-cacheable variables, please using "AT_NONCACHEABLE_SECTION_INIT(var) ={xx};" or
* "AT_NONCACHEABLE_SECTION_ALIGN_INIT(var) ={xx};" in your projects to define them, for zero-inited non-cacheable variables,
* please using "AT_NONCACHEABLE_SECTION(var);" or "AT_NONCACHEABLE_SECTION_ALIGN(var);" to define them, these zero-inited variables
* will be initialized to zero in system startup.
*/
/* @{ */
#if (defined(__ICCARM__))
#if defined(FSL_FEATURE_L1ICACHE_LINESIZE_BYTE)
#define AT_NONCACHEABLE_SECTION(var) var @"NonCacheable"
#define AT_NONCACHEABLE_SECTION_ALIGN(var, alignbytes) SDK_PRAGMA(data_alignment = alignbytes) var @"NonCacheable"
#define AT_NONCACHEABLE_SECTION_INIT(var) var @"NonCacheable.init"
#define AT_NONCACHEABLE_SECTION_ALIGN_INIT(var, alignbytes) SDK_PRAGMA(data_alignment = alignbytes) var @"NonCacheable.init"
#else
#define AT_NONCACHEABLE_SECTION(var) var
#define AT_NONCACHEABLE_SECTION_ALIGN(var, alignbytes) SDK_PRAGMA(data_alignment = alignbytes) var
#define AT_NONCACHEABLE_SECTION_INIT(var) var
#define AT_NONCACHEABLE_SECTION_ALIGN_INIT(var, alignbytes) SDK_PRAGMA(data_alignment = alignbytes) var
#endif
#elif(defined(__ARMCC_VERSION))
#if defined(FSL_FEATURE_L1ICACHE_LINESIZE_BYTE)
#define AT_NONCACHEABLE_SECTION(var) __attribute__((section("NonCacheable"), zero_init)) var
#define AT_NONCACHEABLE_SECTION_ALIGN(var, alignbytes) \
__attribute__((section("NonCacheable"), zero_init)) __align(alignbytes) var
#define AT_NONCACHEABLE_SECTION_INIT(var) __attribute__((section("NonCacheable.init"))) var
#define AT_NONCACHEABLE_SECTION_ALIGN_INIT(var, alignbytes) \
__attribute__((section("NonCacheable.init"))) __align(alignbytes) var
#else
#define AT_NONCACHEABLE_SECTION(var) var
#define AT_NONCACHEABLE_SECTION_ALIGN(var, alignbytes) __align(alignbytes) var
#define AT_NONCACHEABLE_SECTION_INIT(var) var
#define AT_NONCACHEABLE_SECTION_ALIGN_INIT(var, alignbytes) __align(alignbytes) var
#endif
#elif(defined(__GNUC__))
/* For GCC, when the non-cacheable section is required, please define "__STARTUP_INITIALIZE_NONCACHEDATA"
* in your projects to make sure the non-cacheable section variables will be initialized in system startup.
*/
#if defined(FSL_FEATURE_L1ICACHE_LINESIZE_BYTE)
#define AT_NONCACHEABLE_SECTION_INIT(var) __attribute__((section("NonCacheable.init"))) var
#define AT_NONCACHEABLE_SECTION_ALIGN_INIT(var, alignbytes) \
__attribute__((section("NonCacheable.init"))) var __attribute__((aligned(alignbytes)))
#define AT_NONCACHEABLE_SECTION(var) __attribute__((section("NonCacheable,\"aw\",%nobits @"))) var
#define AT_NONCACHEABLE_SECTION_ALIGN(var, alignbytes) \
__attribute__((section("NonCacheable,\"aw\",%nobits @"))) var __attribute__((aligned(alignbytes)))
#else
#define AT_NONCACHEABLE_SECTION(var) var
#define AT_NONCACHEABLE_SECTION_ALIGN(var, alignbytes) var __attribute__((aligned(alignbytes)))
#define AT_NONCACHEABLE_SECTION_INIT(var) var
#define AT_NONCACHEABLE_SECTION_ALIGN_INIT(var, alignbytes) var __attribute__((aligned(alignbytes)))
#endif
#else
#error Toolchain not supported.
#define AT_NONCACHEABLE_SECTION(var) var
#define AT_NONCACHEABLE_SECTION_ALIGN(var, alignbytes) var
#define AT_NONCACHEABLE_SECTION_INIT(var) var
#define AT_NONCACHEABLE_SECTION_ALIGN_INIT(var, alignbytes) var
#endif
/* @} */
/*******************************************************************************
* API
******************************************************************************/
#if defined(__cplusplus)
extern "C"
{
#endif
/*!
* @brief Enable specific interrupt.
*
* Enable LEVEL1 interrupt. For some devices, there might be multiple interrupt
* levels. For example, there are NVIC and intmux. Here the interrupts connected
* to NVIC are the LEVEL1 interrupts, because they are routed to the core directly.
* The interrupts connected to intmux are the LEVEL2 interrupts, they are routed
* to NVIC first then routed to core.
*
* This function only enables the LEVEL1 interrupts. The number of LEVEL1 interrupts
* is indicated by the feature macro FSL_FEATURE_NUMBER_OF_LEVEL1_INT_VECTORS.
*
* @param interrupt The IRQ number.
* @retval kStatus_Success Interrupt enabled successfully
* @retval kStatus_Fail Failed to enable the interrupt
*/
static inline status_t EnableIRQ(IRQn_Type interrupt)
{
if (NotAvail_IRQn == interrupt)
{
return kStatus_Fail;
}
#if defined(FSL_FEATURE_NUMBER_OF_LEVEL1_INT_VECTORS) && (FSL_FEATURE_NUMBER_OF_LEVEL1_INT_VECTORS > 0)
if (interrupt >= FSL_FEATURE_NUMBER_OF_LEVEL1_INT_VECTORS)
{
return kStatus_Fail;
}
#endif
#if defined(__GIC_PRIO_BITS)
GIC_EnableIRQ(interrupt);
#else
NVIC_EnableIRQ(interrupt);
#endif
return kStatus_Success;
}
/*!
* @brief Disable specific interrupt.
*
* Disable LEVEL1 interrupt. For some devices, there might be multiple interrupt
* levels. For example, there are NVIC and intmux. Here the interrupts connected
* to NVIC are the LEVEL1 interrupts, because they are routed to the core directly.
* The interrupts connected to intmux are the LEVEL2 interrupts, they are routed
* to NVIC first then routed to core.
*
* This function only disables the LEVEL1 interrupts. The number of LEVEL1 interrupts
* is indicated by the feature macro FSL_FEATURE_NUMBER_OF_LEVEL1_INT_VECTORS.
*
* @param interrupt The IRQ number.
* @retval kStatus_Success Interrupt disabled successfully
* @retval kStatus_Fail Failed to disable the interrupt
*/
static inline status_t DisableIRQ(IRQn_Type interrupt)
{
if (NotAvail_IRQn == interrupt)
{
return kStatus_Fail;
}
#if defined(FSL_FEATURE_NUMBER_OF_LEVEL1_INT_VECTORS) && (FSL_FEATURE_NUMBER_OF_LEVEL1_INT_VECTORS > 0)
if (interrupt >= FSL_FEATURE_NUMBER_OF_LEVEL1_INT_VECTORS)
{
return kStatus_Fail;
}
#endif
#if defined(__GIC_PRIO_BITS)
GIC_DisableIRQ(interrupt);
#else
NVIC_DisableIRQ(interrupt);
#endif
return kStatus_Success;
}
/*!
* @brief Disable the global IRQ
*
* Disable the global interrupt and return the current primask register. User is required to provided the primask
* register for the EnableGlobalIRQ().
*
* @return Current primask value.
*/
static inline uint32_t DisableGlobalIRQ(void)
{
#if defined(CPSR_I_Msk)
uint32_t cpsr = __get_CPSR() & CPSR_I_Msk;
__disable_irq();
return cpsr;
#else
uint32_t regPrimask = __get_PRIMASK();
__disable_irq();
return regPrimask;
#endif
}
/*!
* @brief Enaable the global IRQ
*
* Set the primask register with the provided primask value but not just enable the primask. The idea is for the
* convinience of integration of RTOS. some RTOS get its own management mechanism of primask. User is required to
* use the EnableGlobalIRQ() and DisableGlobalIRQ() in pair.
*
* @param primask value of primask register to be restored. The primask value is supposed to be provided by the
* DisableGlobalIRQ().
*/
static inline void EnableGlobalIRQ(uint32_t primask)
{
#if defined(CPSR_I_Msk)
__set_CPSR((__get_CPSR() & ~CPSR_I_Msk) | primask);
#else
__set_PRIMASK(primask);
#endif
}
#if defined(ENABLE_RAM_VECTOR_TABLE)
/*!
* @brief install IRQ handler
*
* @param irq IRQ number
* @param irqHandler IRQ handler address
* @return The old IRQ handler address
*/
uint32_t InstallIRQHandler(IRQn_Type irq, uint32_t irqHandler);
#endif /* ENABLE_RAM_VECTOR_TABLE. */
#if (defined(FSL_FEATURE_SOC_SYSCON_COUNT) && (FSL_FEATURE_SOC_SYSCON_COUNT > 0))
/*!
* @brief Enable specific interrupt for wake-up from deep-sleep mode.
*
* Enable the interrupt for wake-up from deep sleep mode.
* Some interrupts are typically used in sleep mode only and will not occur during
* deep-sleep mode because relevant clocks are stopped. However, it is possible to enable
* those clocks (significantly increasing power consumption in the reduced power mode),
* making these wake-ups possible.
*
* @note This function also enables the interrupt in the NVIC (EnableIRQ() is called internally).
*
* @param interrupt The IRQ number.
*/
void EnableDeepSleepIRQ(IRQn_Type interrupt);
/*!
* @brief Disable specific interrupt for wake-up from deep-sleep mode.
*
* Disable the interrupt for wake-up from deep sleep mode.
* Some interrupts are typically used in sleep mode only and will not occur during
* deep-sleep mode because relevant clocks are stopped. However, it is possible to enable
* those clocks (significantly increasing power consumption in the reduced power mode),
* making these wake-ups possible.
*
* @note This function also disables the interrupt in the NVIC (DisableIRQ() is called internally).
*
* @param interrupt The IRQ number.
*/
void DisableDeepSleepIRQ(IRQn_Type interrupt);
#endif /* FSL_FEATURE_SOC_SYSCON_COUNT */
#if defined(__cplusplus)
}
#endif
/*! @} */
#endif /* _FSL_COMMON_H_ */

View File

@ -0,0 +1,684 @@
/*
* Copyright (c) 2017, NXP Semiconductors, 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 the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include "fsl_csi.h"
/*******************************************************************************
* Definitions
******************************************************************************/
/* Two frame buffer loaded to CSI register at most. */
#define CSI_MAX_ACTIVE_FRAME_NUM 2
/*******************************************************************************
* Prototypes
******************************************************************************/
/*!
* @brief Get the instance from the base address
*
* @param base CSI peripheral base address
*
* @return The CSI module instance
*/
static uint32_t CSI_GetInstance(CSI_Type *base);
/*!
* @brief Get the delta value of two index in queue.
*
* @param startIdx Start index.
* @param endIdx End index.
*
* @return The delta between startIdx and endIdx in queue.
*/
static uint32_t CSI_TransferGetQueueDelta(uint32_t startIdx, uint32_t endIdx);
/*!
* @brief Increase a index value in queue.
*
* This function increases the index value in the queue, if the index is out of
* the queue range, it is reset to 0.
*
* @param idx The index value to increase.
*
* @return The index value after increase.
*/
static uint32_t CSI_TransferIncreaseQueueIdx(uint32_t idx);
/*!
* @brief Get the empty frame buffer count in queue.
*
* @param base CSI peripheral base address
* @param handle Pointer to CSI driver handle.
*
* @return Number of the empty frame buffer count in queue.
*/
static uint32_t CSI_TransferGetEmptyBufferCount(CSI_Type *base, csi_handle_t *handle);
/*!
* @brief Load one empty frame buffer in queue to CSI module.
*
* Load one empty frame in queue to CSI module, this function could only be called
* when there is empty frame buffer in queue.
*
* @param base CSI peripheral base address
* @param handle Pointer to CSI driver handle.
*/
static void CSI_TransferLoadBufferToDevice(CSI_Type *base, csi_handle_t *handle);
/* Typedef for interrupt handler. */
typedef void (*csi_isr_t)(CSI_Type *base, csi_handle_t *handle);
/*******************************************************************************
* Variables
******************************************************************************/
/*! @brief Pointers to CSI bases for each instance. */
static CSI_Type *const s_csiBases[] = CSI_BASE_PTRS;
#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
/*! @brief Pointers to CSI clocks for each CSI submodule. */
static const clock_ip_name_t s_csiClocks[] = CSI_CLOCKS;
#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
/* Array for the CSI driver handle. */
static csi_handle_t *s_csiHandle[ARRAY_SIZE(s_csiBases)];
/* Array of CSI IRQ number. */
static const IRQn_Type s_csiIRQ[] = CSI_IRQS;
/* CSI ISR for transactional APIs. */
static csi_isr_t s_csiIsr;
/*******************************************************************************
* Code
******************************************************************************/
static uint32_t CSI_GetInstance(CSI_Type *base)
{
uint32_t instance;
/* Find the instance index from base address mappings. */
for (instance = 0; instance < ARRAY_SIZE(s_csiBases); instance++)
{
if (s_csiBases[instance] == base)
{
break;
}
}
assert(instance < ARRAY_SIZE(s_csiBases));
return instance;
}
static uint32_t CSI_TransferGetQueueDelta(uint32_t startIdx, uint32_t endIdx)
{
if (endIdx >= startIdx)
{
return endIdx - startIdx;
}
else
{
return startIdx + CSI_DRIVER_ACTUAL_QUEUE_SIZE - endIdx;
}
}
static uint32_t CSI_TransferIncreaseQueueIdx(uint32_t idx)
{
uint32_t ret;
/*
* Here not use the method:
* ret = (idx+1) % CSI_DRIVER_ACTUAL_QUEUE_SIZE;
*
* Because the mod function might be slow.
*/
ret = idx + 1;
if (ret >= CSI_DRIVER_ACTUAL_QUEUE_SIZE)
{
ret = 0;
}
return ret;
}
static uint32_t CSI_TransferGetEmptyBufferCount(CSI_Type *base, csi_handle_t *handle)
{
return CSI_TransferGetQueueDelta(handle->queueDrvReadIdx, handle->queueUserWriteIdx);
}
static void CSI_TransferLoadBufferToDevice(CSI_Type *base, csi_handle_t *handle)
{
/* Load the frame buffer address to CSI register. */
CSI_SetRxBufferAddr(base, handle->nextBufferIdx, handle->frameBufferQueue[handle->queueDrvReadIdx]);
handle->queueDrvReadIdx = CSI_TransferIncreaseQueueIdx(handle->queueDrvReadIdx);
handle->activeBufferNum++;
/* There are two CSI buffers, so could use XOR to get the next index. */
handle->nextBufferIdx ^= 1U;
}
status_t CSI_Init(CSI_Type *base, const csi_config_t *config)
{
assert(config);
uint32_t reg;
uint32_t imgWidth_Bytes;
imgWidth_Bytes = config->width * config->bytesPerPixel;
/* The image width and frame buffer pitch should be multiple of 8-bytes. */
if ((imgWidth_Bytes & 0x07) | ((uint32_t)config->linePitch_Bytes & 0x07))
{
return kStatus_InvalidArgument;
}
#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
uint32_t instance = CSI_GetInstance(base);
CLOCK_EnableClock(s_csiClocks[instance]);
#endif
CSI_Reset(base);
/* Configure CSICR1. CSICR1 has been reset to the default value, so could write it directly. */
reg = ((uint32_t)config->workMode) | config->polarityFlags | CSI_CSICR1_FCC_MASK;
if (config->useExtVsync)
{
reg |= CSI_CSICR1_EXT_VSYNC_MASK;
}
base->CSICR1 = reg;
/*
* Generally, CSIIMAG_PARA[IMAGE_WIDTH] indicates how many data bus cycles per line.
* One special case is when receiving 24-bit pixels through 8-bit data bus, and
* CSICR3[ZERO_PACK_EN] is enabled, in this case, the CSIIMAG_PARA[IMAGE_WIDTH]
* should be set to the pixel number per line.
*
* Currently the CSI driver only support 8-bit data bus, so generally the
* CSIIMAG_PARA[IMAGE_WIDTH] is bytes number per line. When the CSICR3[ZERO_PACK_EN]
* is enabled, CSIIMAG_PARA[IMAGE_WIDTH] is pixel number per line.
*
* NOTE: The CSIIMAG_PARA[IMAGE_WIDTH] setting code should be updated if the
* driver is upgraded to support other data bus width.
*/
if (4U == config->bytesPerPixel)
{
/* Enable zero pack. */
base->CSICR3 |= CSI_CSICR3_ZERO_PACK_EN_MASK;
/* Image parameter. */
base->CSIIMAG_PARA = ((uint32_t)(config->width) << CSI_CSIIMAG_PARA_IMAGE_WIDTH_SHIFT) |
((uint32_t)(config->height) << CSI_CSIIMAG_PARA_IMAGE_HEIGHT_SHIFT);
}
else
{
/* Image parameter. */
base->CSIIMAG_PARA = ((uint32_t)(imgWidth_Bytes) << CSI_CSIIMAG_PARA_IMAGE_WIDTH_SHIFT) |
((uint32_t)(config->height) << CSI_CSIIMAG_PARA_IMAGE_HEIGHT_SHIFT);
}
/* The CSI frame buffer bus is 8-byte width. */
base->CSIFBUF_PARA = (uint32_t)((config->linePitch_Bytes - imgWidth_Bytes) / 8U)
<< CSI_CSIFBUF_PARA_FBUF_STRIDE_SHIFT;
/* Enable auto ECC. */
base->CSICR3 |= CSI_CSICR3_ECC_AUTO_EN_MASK;
/*
* For better performance.
* The DMA burst size could be set to 16 * 8 byte, 8 * 8 byte, or 4 * 8 byte,
* choose the best burst size based on bytes per line.
*/
if (!(imgWidth_Bytes % (8 * 16)))
{
base->CSICR2 = CSI_CSICR2_DMA_BURST_TYPE_RFF(3U);
base->CSICR3 = (CSI->CSICR3 & ~CSI_CSICR3_RxFF_LEVEL_MASK) | ((2U << CSI_CSICR3_RxFF_LEVEL_SHIFT));
}
else if (!(imgWidth_Bytes % (8 * 8)))
{
base->CSICR2 = CSI_CSICR2_DMA_BURST_TYPE_RFF(2U);
base->CSICR3 = (CSI->CSICR3 & ~CSI_CSICR3_RxFF_LEVEL_MASK) | ((1U << CSI_CSICR3_RxFF_LEVEL_SHIFT));
}
else
{
base->CSICR2 = CSI_CSICR2_DMA_BURST_TYPE_RFF(1U);
base->CSICR3 = (CSI->CSICR3 & ~CSI_CSICR3_RxFF_LEVEL_MASK) | ((0U << CSI_CSICR3_RxFF_LEVEL_SHIFT));
}
CSI_ReflashFifoDma(base, kCSI_RxFifo);
return kStatus_Success;
}
void CSI_Deinit(CSI_Type *base)
{
/* Disable transfer first. */
CSI_Stop(base);
#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
uint32_t instance = CSI_GetInstance(base);
CLOCK_DisableClock(s_csiClocks[instance]);
#endif
}
void CSI_Reset(CSI_Type *base)
{
uint32_t csisr;
/* Disable transfer first. */
CSI_Stop(base);
/* Disable DMA request. */
base->CSICR3 = 0U;
/* Reset the fame count. */
base->CSICR3 |= CSI_CSICR3_FRMCNT_RST_MASK;
while (base->CSICR3 & CSI_CSICR3_FRMCNT_RST_MASK)
{
}
/* Clear the RX FIFO. */
CSI_ClearFifo(base, kCSI_AllFifo);
/* Reflash DMA. */
CSI_ReflashFifoDma(base, kCSI_AllFifo);
/* Clear the status. */
csisr = base->CSISR;
base->CSISR = csisr;
/* Set the control registers to default value. */
base->CSICR1 = CSI_CSICR1_HSYNC_POL_MASK | CSI_CSICR1_EXT_VSYNC_MASK;
base->CSICR2 = 0U;
base->CSICR3 = 0U;
#if defined(CSI_CSICR18_CSI_LCDIF_BUFFER_LINES)
base->CSICR18 = CSI_CSICR18_AHB_HPROT(0x0DU) | CSI_CSICR18_CSI_LCDIF_BUFFER_LINES(0x02U);
#else
base->CSICR18 = CSI_CSICR18_AHB_HPROT(0x0DU);
#endif
base->CSIFBUF_PARA = 0U;
base->CSIIMAG_PARA = 0U;
}
void CSI_GetDefaultConfig(csi_config_t *config)
{
assert(config);
config->width = 320U;
config->height = 240U;
config->polarityFlags = kCSI_HsyncActiveHigh | kCSI_DataLatchOnRisingEdge;
config->bytesPerPixel = 2U;
config->linePitch_Bytes = 320U * 2U;
config->workMode = kCSI_GatedClockMode;
config->dataBus = kCSI_DataBus8Bit;
config->useExtVsync = true;
}
void CSI_SetRxBufferAddr(CSI_Type *base, uint8_t index, uint32_t addr)
{
if (index)
{
base->CSIDMASA_FB2 = addr;
}
else
{
base->CSIDMASA_FB1 = addr;
}
}
void CSI_ClearFifo(CSI_Type *base, csi_fifo_t fifo)
{
uint32_t cr1;
uint32_t mask = 0U;
/* The FIFO could only be cleared when CSICR1[FCC] = 0, so first clear the FCC. */
cr1 = base->CSICR1;
base->CSICR1 = (cr1 & ~CSI_CSICR1_FCC_MASK);
if ((uint32_t)fifo & (uint32_t)kCSI_RxFifo)
{
mask |= CSI_CSICR1_CLR_RXFIFO_MASK;
}
if ((uint32_t)fifo & (uint32_t)kCSI_StatFifo)
{
mask |= CSI_CSICR1_CLR_STATFIFO_MASK;
}
base->CSICR1 = (cr1 & ~CSI_CSICR1_FCC_MASK) | mask;
/* Wait clear completed. */
while (base->CSICR1 & mask)
{
}
/* Recover the FCC. */
base->CSICR1 = cr1;
}
void CSI_ReflashFifoDma(CSI_Type *base, csi_fifo_t fifo)
{
uint32_t cr3 = 0U;
if ((uint32_t)fifo & (uint32_t)kCSI_RxFifo)
{
cr3 |= CSI_CSICR3_DMA_REFLASH_RFF_MASK;
}
if ((uint32_t)fifo & (uint32_t)kCSI_StatFifo)
{
cr3 |= CSI_CSICR3_DMA_REFLASH_SFF_MASK;
}
base->CSICR3 |= cr3;
/* Wait clear completed. */
while (base->CSICR3 & cr3)
{
}
}
void CSI_EnableFifoDmaRequest(CSI_Type *base, csi_fifo_t fifo, bool enable)
{
uint32_t cr3 = 0U;
if ((uint32_t)fifo & (uint32_t)kCSI_RxFifo)
{
cr3 |= CSI_CSICR3_DMA_REQ_EN_RFF_MASK;
}
if ((uint32_t)fifo & (uint32_t)kCSI_StatFifo)
{
cr3 |= CSI_CSICR3_DMA_REQ_EN_SFF_MASK;
}
if (enable)
{
base->CSICR3 |= cr3;
}
else
{
base->CSICR3 &= ~cr3;
}
}
void CSI_EnableInterrupts(CSI_Type *base, uint32_t mask)
{
base->CSICR1 |= (mask & CSI_CSICR1_INT_EN_MASK);
base->CSICR3 |= (mask & CSI_CSICR3_INT_EN_MASK);
base->CSICR18 |= ((mask & CSI_CSICR18_INT_EN_MASK) >> 6U);
}
void CSI_DisableInterrupts(CSI_Type *base, uint32_t mask)
{
base->CSICR1 &= ~(mask & CSI_CSICR1_INT_EN_MASK);
base->CSICR3 &= ~(mask & CSI_CSICR3_INT_EN_MASK);
base->CSICR18 &= ~((mask & CSI_CSICR18_INT_EN_MASK) >> 6U);
}
status_t CSI_TransferCreateHandle(CSI_Type *base,
csi_handle_t *handle,
csi_transfer_callback_t callback,
void *userData)
{
assert(handle);
uint32_t instance;
memset(handle, 0, sizeof(*handle));
/* Set the callback and user data. */
handle->callback = callback;
handle->userData = userData;
/* Get instance from peripheral base address. */
instance = CSI_GetInstance(base);
/* Save the handle in global variables to support the double weak mechanism. */
s_csiHandle[instance] = handle;
s_csiIsr = CSI_TransferHandleIRQ;
/* Enable interrupt. */
EnableIRQ(s_csiIRQ[instance]);
return kStatus_Success;
}
status_t CSI_TransferStart(CSI_Type *base, csi_handle_t *handle)
{
assert(handle);
uint32_t emptyBufferCount;
emptyBufferCount = CSI_TransferGetEmptyBufferCount(base, handle);
if (emptyBufferCount < 2U)
{
return kStatus_CSI_NoEmptyBuffer;
}
handle->nextBufferIdx = 0U;
handle->activeBufferNum = 0U;
/* Write to memory from second completed frame. */
base->CSICR18 = (base->CSICR18 & ~CSI_CSICR18_MASK_OPTION_MASK) | CSI_CSICR18_MASK_OPTION(2);
/* Load the frame buffer to CSI register, there are at least two empty buffers. */
CSI_TransferLoadBufferToDevice(base, handle);
CSI_TransferLoadBufferToDevice(base, handle);
/* After reflash DMA, the CSI saves frame to frame buffer 0. */
CSI_ReflashFifoDma(base, kCSI_RxFifo);
handle->transferStarted = true;
handle->transferOnGoing = true;
CSI_EnableInterrupts(base, kCSI_RxBuffer1DmaDoneInterruptEnable | kCSI_RxBuffer0DmaDoneInterruptEnable);
CSI_Start(base);
return kStatus_Success;
}
status_t CSI_TransferStop(CSI_Type *base, csi_handle_t *handle)
{
assert(handle);
CSI_Stop(base);
CSI_DisableInterrupts(base, kCSI_RxBuffer1DmaDoneInterruptEnable | kCSI_RxBuffer0DmaDoneInterruptEnable);
handle->transferStarted = false;
handle->transferOnGoing = false;
/* Stoped, reset the state flags. */
handle->queueDrvReadIdx = handle->queueDrvWriteIdx;
handle->activeBufferNum = 0U;
return kStatus_Success;
}
status_t CSI_TransferSubmitEmptyBuffer(CSI_Type *base, csi_handle_t *handle, uint32_t frameBuffer)
{
uint32_t csicr1;
if (CSI_DRIVER_QUEUE_SIZE == CSI_TransferGetQueueDelta(handle->queueUserReadIdx, handle->queueUserWriteIdx))
{
return kStatus_CSI_QueueFull;
}
/* Disable the interrupt to protect the index information in handle. */
csicr1 = base->CSICR1;
base->CSICR1 = (csicr1 & ~(CSI_CSICR1_FB2_DMA_DONE_INTEN_MASK | CSI_CSICR1_FB1_DMA_DONE_INTEN_MASK));
/* Save the empty frame buffer address to queue. */
handle->frameBufferQueue[handle->queueUserWriteIdx] = frameBuffer;
handle->queueUserWriteIdx = CSI_TransferIncreaseQueueIdx(handle->queueUserWriteIdx);
base->CSICR1 = csicr1;
if (handle->transferStarted)
{
/*
* If user has started transfer using @ref CSI_TransferStart, and the CSI is
* stopped due to no empty frame buffer in queue, then start the CSI.
*/
if ((!handle->transferOnGoing) && (CSI_TransferGetEmptyBufferCount(base, handle) >= 2U))
{
handle->transferOnGoing = true;
handle->nextBufferIdx = 0U;
/* Load the frame buffers to CSI module. */
CSI_TransferLoadBufferToDevice(base, handle);
CSI_TransferLoadBufferToDevice(base, handle);
CSI_ReflashFifoDma(base, kCSI_RxFifo);
CSI_Start(base);
}
}
return kStatus_Success;
}
status_t CSI_TransferGetFullBuffer(CSI_Type *base, csi_handle_t *handle, uint32_t *frameBuffer)
{
uint32_t csicr1;
/* No full frame buffer. */
if (handle->queueUserReadIdx == handle->queueDrvWriteIdx)
{
return kStatus_CSI_NoFullBuffer;
}
/* Disable the interrupt to protect the index information in handle. */
csicr1 = base->CSICR1;
base->CSICR1 = (csicr1 & ~(CSI_CSICR1_FB2_DMA_DONE_INTEN_MASK | CSI_CSICR1_FB1_DMA_DONE_INTEN_MASK));
*frameBuffer = handle->frameBufferQueue[handle->queueUserReadIdx];
handle->queueUserReadIdx = CSI_TransferIncreaseQueueIdx(handle->queueUserReadIdx);
base->CSICR1 = csicr1;
return kStatus_Success;
}
void CSI_TransferHandleIRQ(CSI_Type *base, csi_handle_t *handle)
{
uint32_t queueDrvWriteIdx;
uint32_t csisr = base->CSISR;
/* Clear the error flags. */
base->CSISR = csisr;
/*
* If both frame buffer 0 and frame buffer 1 flags assert, driver does not
* know which frame buffer ready just now, so reset the CSI transfer to
* start from frame buffer 0.
*/
if ((csisr & (CSI_CSISR_DMA_TSF_DONE_FB2_MASK | CSI_CSISR_DMA_TSF_DONE_FB1_MASK)) ==
(CSI_CSISR_DMA_TSF_DONE_FB2_MASK | CSI_CSISR_DMA_TSF_DONE_FB1_MASK))
{
CSI_Stop(base);
/* Reset the active buffers. */
if (1 <= handle->activeBufferNum)
{
queueDrvWriteIdx = handle->queueDrvWriteIdx;
base->CSIDMASA_FB1 = handle->frameBufferQueue[queueDrvWriteIdx];
if (2U == handle->activeBufferNum)
{
queueDrvWriteIdx = CSI_TransferIncreaseQueueIdx(queueDrvWriteIdx);
base->CSIDMASA_FB2 = handle->frameBufferQueue[queueDrvWriteIdx];
handle->nextBufferIdx = 0U;
}
else
{
handle->nextBufferIdx = 1U;
}
}
CSI_ReflashFifoDma(base, kCSI_RxFifo);
CSI_Start(base);
}
else if (csisr & (CSI_CSISR_DMA_TSF_DONE_FB2_MASK | CSI_CSISR_DMA_TSF_DONE_FB1_MASK))
{
handle->queueDrvWriteIdx = CSI_TransferIncreaseQueueIdx(handle->queueDrvWriteIdx);
handle->activeBufferNum--;
if (handle->callback)
{
handle->callback(base, handle, kStatus_CSI_FrameDone, handle->userData);
}
/* No frame buffer to save incoming data, then stop the CSI module. */
if (!(handle->activeBufferNum))
{
CSI_Stop(base);
handle->transferOnGoing = false;
}
else
{
if (CSI_TransferGetEmptyBufferCount(base, handle))
{
CSI_TransferLoadBufferToDevice(base, handle);
}
}
}
else
{
}
}
#if defined(CSI)
void CSI_DriverIRQHandler(void)
{
s_csiIsr(CSI, s_csiHandle[0]);
/* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
exception return operation might vector to incorrect interrupt */
#if defined __CORTEX_M && (__CORTEX_M == 4U)
__DSB();
#endif
}
#endif
#if defined(CSI0)
void CSI0_DriverIRQHandler(void)
{
s_csiIsr(CSI, s_csiHandle[0]);
/* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
exception return operation might vector to incorrect interrupt */
#if defined __CORTEX_M && (__CORTEX_M == 4U)
__DSB();
#endif
}
#endif

View File

@ -0,0 +1,558 @@
/*
* Copyright (c) 2017, NXP Semiconductors, 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 the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _FSL_CSI_H_
#define _FSL_CSI_H_
#include "fsl_common.h"
/*!
* @addtogroup csi_driver
* @{
*/
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @name Driver version */
/*@{*/
#define FSL_CSI_DRIVER_VERSION (MAKE_VERSION(2, 0, 0))
/*@}*/
/*! @brief Size of the frame buffer queue used in CSI transactional function. */
#ifndef CSI_DRIVER_QUEUE_SIZE
#define CSI_DRIVER_QUEUE_SIZE 4U
#endif
/*
* There is one empty room in queue, used to distinguish whether the queue
* is full or empty. When header equals tail, the queue is empty; when header
* equals tail + 1, the queue is full.
*/
#define CSI_DRIVER_ACTUAL_QUEUE_SIZE (CSI_DRIVER_QUEUE_SIZE + 1U)
/*
* The interrupt enable bits are in registers CSICR1[16:31], CSICR3[0:7],
* and CSICR18[2:9]. So merge them into an uint32_t value, place CSICR18 control
* bits to [8:15].
*/
#define CSI_CSICR1_INT_EN_MASK 0xFFFF0000U
#define CSI_CSICR3_INT_EN_MASK 0x000000FFU
#define CSI_CSICR18_INT_EN_MASK 0x0000FF00U
#if ((~CSI_CSICR1_INT_EN_MASK) & \
(CSI_CSICR1_EOF_INT_EN_MASK | CSI_CSICR1_COF_INT_EN_MASK | CSI_CSICR1_SF_OR_INTEN_MASK | \
CSI_CSICR1_RF_OR_INTEN_MASK | CSI_CSICR1_SFF_DMA_DONE_INTEN_MASK | CSI_CSICR1_STATFF_INTEN_MASK | \
CSI_CSICR1_FB2_DMA_DONE_INTEN_MASK | CSI_CSICR1_FB1_DMA_DONE_INTEN_MASK | CSI_CSICR1_RXFF_INTEN_MASK | \
CSI_CSICR1_SOF_INTEN_MASK))
#error CSI_CSICR1_INT_EN_MASK could not cover all interrupt bits in CSICR1.
#endif
#if ((~CSI_CSICR3_INT_EN_MASK) & (CSI_CSICR3_ECC_INT_EN_MASK | CSI_CSICR3_HRESP_ERR_EN_MASK))
#error CSI_CSICR3_INT_EN_MASK could not cover all interrupt bits in CSICR3.
#endif
#if ((~CSI_CSICR18_INT_EN_MASK) & ((CSI_CSICR18_FIELD0_DONE_IE_MASK | CSI_CSICR18_DMA_FIELD1_DONE_IE_MASK | CSI_CSICR18_BASEADDR_CHANGE_ERROR_IE_MASK) << 6U))
#error CSI_CSICR18_INT_EN_MASK could not cover all interrupt bits in CSICR18.
#endif
/*! @brief Error codes for the CSI driver. */
enum _csi_status
{
kStatus_CSI_NoEmptyBuffer = MAKE_STATUS(kStatusGroup_CSI, 0), /*!< No empty frame buffer in queue to load to CSI. */
kStatus_CSI_NoFullBuffer = MAKE_STATUS(kStatusGroup_CSI, 1), /*!< No full frame buffer in queue to read out. */
kStatus_CSI_QueueFull = MAKE_STATUS(kStatusGroup_CSI, 2), /*!< Queue is full, no room to save new empty buffer. */
kStatus_CSI_FrameDone = MAKE_STATUS(kStatusGroup_CSI, 3), /*!< New frame received and saved to queue. */
};
/*!
* @brief CSI work mode.
*
* The CCIR656 interlace mode is not supported currently.
*/
typedef enum _csi_work_mode
{
kCSI_GatedClockMode = CSI_CSICR1_GCLK_MODE(1U), /*!< HSYNC, VSYNC, and PIXCLK signals are used. */
kCSI_NonGatedClockMode = 0U, /*!< VSYNC, and PIXCLK signals are used. */
kCSI_CCIR656ProgressiveMode = CSI_CSICR1_CCIR_EN(1U), /*!< CCIR656 progressive mode. */
} csi_work_mode_t;
/*!
* @brief CSI data bus witdh.
*
* Currently only support 8-bit width.
*/
typedef enum _csi_data_bus
{
kCSI_DataBus8Bit, /*!< 8-bit data bus. */
} csi_data_bus_t;
/*! @brief CSI signal polarity. */
enum _csi_polarity_flags
{
kCSI_HsyncActiveLow = 0U, /*!< HSYNC is active low. */
kCSI_HsyncActiveHigh = CSI_CSICR1_HSYNC_POL_MASK, /*!< HSYNC is active high. */
kCSI_DataLatchOnRisingEdge = CSI_CSICR1_REDGE_MASK, /*!< Pixel data latched at rising edge of pixel clock. */
kCSI_DataLatchOnFallingEdge = 0U, /*!< Pixel data latched at falling edge of pixel clock. */
kCSI_VsyncActiveHigh = 0U, /*!< VSYNC is active high. */
kCSI_VsyncActiveLow = CSI_CSICR1_SOF_POL_MASK, /*!< VSYNC is active low. */
};
/*! @brief Configuration to initialize the CSI module. */
typedef struct _csi_config
{
uint16_t width; /*!< Pixels of the input frame. */
uint16_t height; /*!< Lines of the input frame. */
uint32_t polarityFlags; /*!< Timing signal polarity flags, OR'ed value of @ref _csi_polarity_flags. */
uint8_t bytesPerPixel; /*!< Bytes per pixel, valid values are:
- 2: Used for RGB565, YUV422, and so on.
- 3: Used for packed RGB888, packed YUV444, and so on.
- 4: Used for XRGB8888, XYUV444, and so on.
*/
uint16_t linePitch_Bytes; /*!< Frame buffer line pitch, must be 8-byte aligned. */
csi_work_mode_t workMode; /*!< CSI work mode. */
csi_data_bus_t dataBus; /*!< Data bus width. */
bool useExtVsync; /*!< In CCIR656 progressive mode, set true to use external VSYNC signal, set false
to use internal VSYNC signal decoded from SOF. */
} csi_config_t;
/*! @brief The CSI FIFO, used for FIFO operation. */
typedef enum _csi_fifo
{
kCSI_RxFifo = (1U << 0U), /*!< RXFIFO. */
kCSI_StatFifo = (1U << 1U), /*!< STAT FIFO. */
kCSI_AllFifo = 0x01 | 0x02, /*!< Both RXFIFO and STAT FIFO. */
} csi_fifo_t;
/*! @brief CSI feature interrupt source. */
enum _csi_interrupt_enable
{
kCSI_EndOfFrameInterruptEnable = CSI_CSICR1_EOF_INT_EN_MASK, /*!< End of frame interrupt enable. */
kCSI_ChangeOfFieldInterruptEnable = CSI_CSICR1_COF_INT_EN_MASK, /*!< Change of field interrupt enable. */
kCSI_StatFifoOverrunInterruptEnable = CSI_CSICR1_SF_OR_INTEN_MASK, /*!< STAT FIFO overrun interrupt enable. */
kCSI_RxFifoOverrunInterruptEnable = CSI_CSICR1_RF_OR_INTEN_MASK, /*!< RXFIFO overrun interrupt enable. */
kCSI_StatFifoDmaDoneInterruptEnable =
CSI_CSICR1_SFF_DMA_DONE_INTEN_MASK, /*!< STAT FIFO DMA done interrupt enable. */
kCSI_StatFifoFullInterruptEnable = CSI_CSICR1_STATFF_INTEN_MASK, /*!< STAT FIFO full interrupt enable. */
kCSI_RxBuffer1DmaDoneInterruptEnable =
CSI_CSICR1_FB2_DMA_DONE_INTEN_MASK, /*!< RX frame buffer 1 DMA transfer done. */
kCSI_RxBuffer0DmaDoneInterruptEnable =
CSI_CSICR1_FB1_DMA_DONE_INTEN_MASK, /*!< RX frame buffer 0 DMA transfer done. */
kCSI_RxFifoFullInterruptEnable = CSI_CSICR1_RXFF_INTEN_MASK, /*!< RXFIFO full interrupt enable. */
kCSI_StartOfFrameInterruptEnable = CSI_CSICR1_SOF_INTEN_MASK, /*!< Start of frame (SOF) interrupt enable. */
kCSI_EccErrorInterruptEnable = CSI_CSICR3_ECC_INT_EN_MASK, /*!< ECC error detection interrupt enable. */
kCSI_AhbResErrorInterruptEnable = CSI_CSICR3_HRESP_ERR_EN_MASK, /*!< AHB response Error interrupt enable. */
kCSI_BaseAddrChangeErrorInterruptEnable = CSI_CSICR18_BASEADDR_CHANGE_ERROR_IE_MASK << 6U, /*!< The DMA output buffer base address
changes before DMA completed. */
kCSI_Field0DoneInterruptEnable = CSI_CSICR18_FIELD0_DONE_IE_MASK << 6U, /*!< Field 0 done interrupt enable. */
kCSI_Field1DoneInterruptEnable = CSI_CSICR18_DMA_FIELD1_DONE_IE_MASK << 6U, /*!< Field 1 done interrupt enable. */
};
/*!
* @brief CSI status flags.
*
* The following status register flags can be cleared:
* - kCSI_EccErrorFlag
* - kCSI_AhbResErrorFlag
* - kCSI_ChangeOfFieldFlag
* - kCSI_StartOfFrameFlag
* - kCSI_EndOfFrameFlag
* - kCSI_RxBuffer1DmaDoneFlag
* - kCSI_RxBuffer0DmaDoneFlag
* - kCSI_StatFifoDmaDoneFlag
* - kCSI_StatFifoOverrunFlag
* - kCSI_RxFifoOverrunFlag
* - kCSI_Field0DoneFlag
* - kCSI_Field1DoneFlag
* - kCSI_BaseAddrChangeErrorFlag
*/
enum _csi_flags
{
kCSI_RxFifoDataReadyFlag = CSI_CSISR_DRDY_MASK, /*!< RXFIFO data ready. */
kCSI_EccErrorFlag = CSI_CSISR_ECC_INT_MASK, /*!< ECC error detected. */
kCSI_AhbResErrorFlag = CSI_CSISR_HRESP_ERR_INT_MASK, /*!< Hresponse (AHB bus response) Error. */
kCSI_ChangeOfFieldFlag = CSI_CSISR_COF_INT_MASK, /*!< Change of field. */
kCSI_Field0PresentFlag = CSI_CSISR_F1_INT_MASK, /*!< Field 0 present in CCIR mode. */
kCSI_Field1PresentFlag = CSI_CSISR_F2_INT_MASK, /*!< Field 1 present in CCIR mode. */
kCSI_StartOfFrameFlag = CSI_CSISR_SOF_INT_MASK, /*!< Start of frame (SOF) detected. */
kCSI_EndOfFrameFlag = CSI_CSISR_EOF_INT_MASK, /*!< End of frame (EOF) detected. */
kCSI_RxFifoFullFlag = CSI_CSISR_RxFF_INT_MASK, /*!< RXFIFO full (Number of data reaches trigger level). */
kCSI_RxBuffer1DmaDoneFlag = CSI_CSISR_DMA_TSF_DONE_FB2_MASK, /*!< RX frame buffer 1 DMA transfer done. */
kCSI_RxBuffer0DmaDoneFlag = CSI_CSISR_DMA_TSF_DONE_FB1_MASK, /*!< RX frame buffer 0 DMA transfer done. */
kCSI_StatFifoFullFlag = CSI_CSISR_STATFF_INT_MASK, /*!< STAT FIFO full (Reach trigger level). */
kCSI_StatFifoDmaDoneFlag = CSI_CSISR_DMA_TSF_DONE_SFF_MASK, /*!< STAT FIFO DMA transfer done. */
kCSI_StatFifoOverrunFlag = CSI_CSISR_SF_OR_INT_MASK, /*!< STAT FIFO overrun. */
kCSI_RxFifoOverrunFlag = CSI_CSISR_RF_OR_INT_MASK, /*!< RXFIFO overrun. */
kCSI_Field0DoneFlag = CSI_CSISR_DMA_FIELD0_DONE_MASK, /*!< Field 0 transfer done. */
kCSI_Field1DoneFlag = CSI_CSISR_DMA_FIELD1_DONE_MASK, /*!< Field 1 transfer done. */
kCSI_BaseAddrChangeErrorFlag = CSI_CSISR_BASEADDR_CHHANGE_ERROR_MASK, /*!< The DMA output buffer base address
changes before DMA completed. */
};
/* Forward declaration of the handle typedef. */
typedef struct _csi_handle csi_handle_t;
/*!
* @brief CSI transfer callback function.
*
* When a new frame is received and saved to the frame buffer queue, the callback
* is called and the pass the status @ref kStatus_CSI_FrameDone to upper layer.
*/
typedef void (*csi_transfer_callback_t)(CSI_Type *base, csi_handle_t *handle, status_t status, void *userData);
/*!
* @brief CSI handle structure.
*
* Please see the user guide for the details of the CSI driver queue mechanism.
*/
struct _csi_handle
{
uint32_t frameBufferQueue[CSI_DRIVER_ACTUAL_QUEUE_SIZE]; /*!< Frame buffer queue. */
volatile uint8_t queueUserReadIdx; /*!< Application gets full-filled frame buffer from this index. */
volatile uint8_t queueUserWriteIdx; /*!< Application puts empty frame buffer to this index. */
volatile uint8_t queueDrvReadIdx; /*!< Driver gets empty frame buffer from this index. */
volatile uint8_t queueDrvWriteIdx; /*!< Driver puts the full-filled frame buffer to this index. */
volatile uint8_t activeBufferNum; /*!< How many frame buffers are in progres currently. */
volatile uint8_t nextBufferIdx; /*!< The CSI frame buffer index to use for next frame. */
volatile bool transferStarted; /*!< User has called @ref CSI_TransferStart to start frame receiving. */
volatile bool transferOnGoing; /*!< CSI is working and receiving incoming frames. */
csi_transfer_callback_t callback; /*!< Callback function. */
void *userData; /*!< CSI callback function parameter.*/
};
/*******************************************************************************
* API
******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif
/*!
* @name Initialization and deinitialization
* @{
*/
/*!
* @brief Initialize the CSI.
*
* This function enables the CSI peripheral clock, and resets the CSI registers.
*
* @param base CSI peripheral base address.
* @param config Pointer to the configuration structure.
*
* @retval kStatus_Success Initialize successfully.
* @retval kStatus_InvalidArgument Initialize failed because of invalid argument.
*/
status_t CSI_Init(CSI_Type *base, const csi_config_t *config);
/*!
* @brief De-initialize the CSI.
*
* This function disables the CSI peripheral clock.
*
* @param base CSI peripheral base address.
*/
void CSI_Deinit(CSI_Type *base);
/*!
* @brief Reset the CSI.
*
* This function resets the CSI peripheral registers to default status.
*
* @param base CSI peripheral base address.
*/
void CSI_Reset(CSI_Type *base);
/*!
* @brief Get the default configuration for to initialize the CSI.
*
* The default configuration value is:
*
* @code
config->width = 320U;
config->height = 240U;
config->polarityFlags = kCSI_HsyncActiveHigh | kCSI_DataLatchOnRisingEdge;
config->bytesPerPixel = 2U;
config->linePitch_Bytes = 320U * 2U;
config->workMode = kCSI_GatedClockMode;
config->dataBus = kCSI_DataBus8Bit;
config->useExtVsync = true;
@endcode
*
* @param config Pointer to the CSI configuration.
*/
void CSI_GetDefaultConfig(csi_config_t *config);
/* @} */
/*!
* @name Module operation
* @{
*/
/*!
* @brief Clear the CSI FIFO.
*
* This function clears the CSI FIFO.
*
* @param base CSI peripheral base address.
* @param fifo The FIFO to clear.
*/
void CSI_ClearFifo(CSI_Type *base, csi_fifo_t fifo);
/*!
* @brief Reflash the CSI FIFO DMA.
*
* This function reflashes the CSI FIFO DMA.
*
* For RXFIFO, there are two frame buffers. When the CSI module started, it saves
* the frames to frame buffer 0 then frame buffer 1, the two buffers will be
* written by turns. After reflash DMA using this function, the CSI is reset to
* save frame to buffer 0.
*
* @param base CSI peripheral base address.
* @param fifo The FIFO DMA to reflash.
*/
void CSI_ReflashFifoDma(CSI_Type *base, csi_fifo_t fifo);
/*!
* @brief Enable or disable the CSI FIFO DMA request.
*
* @param base CSI peripheral base address.
* @param fifo The FIFO DMA reques to enable or disable.
* @param enable True to enable, false to disable.
*/
void CSI_EnableFifoDmaRequest(CSI_Type *base, csi_fifo_t fifo, bool enable);
/*!
* @brief Start to receive data.
*
* @param base CSI peripheral base address.
*/
static inline void CSI_Start(CSI_Type *base)
{
CSI_EnableFifoDmaRequest(base, kCSI_RxFifo, true);
base->CSICR18 |= CSI_CSICR18_CSI_ENABLE_MASK;
}
/*!
* @brief Stop to receiving data.
*
* @param base CSI peripheral base address.
*/
static inline void CSI_Stop(CSI_Type *base)
{
base->CSICR18 &= ~CSI_CSICR18_CSI_ENABLE_MASK;
CSI_EnableFifoDmaRequest(base, kCSI_RxFifo, false);
}
/*!
* @brief Set the RX frame buffer address.
*
* @param base CSI peripheral base address.
* @param index Buffer index.
* @param addr Frame buffer address to set.
*/
void CSI_SetRxBufferAddr(CSI_Type *base, uint8_t index, uint32_t addr);
/* @} */
/*!
* @name Interrupts
* @{
*/
/*!
* @brief Enables CSI interrupt requests.
*
* @param base CSI peripheral base address.
* @param mask The interrupts to enable, pass in as OR'ed value of @ref _csi_interrupt_enable.
*/
void CSI_EnableInterrupts(CSI_Type *base, uint32_t mask);
/*!
* @brief Disable CSI interrupt requests.
*
* @param base CSI peripheral base address.
* @param mask The interrupts to disable, pass in as OR'ed value of @ref _csi_interrupt_enable.
*/
void CSI_DisableInterrupts(CSI_Type *base, uint32_t mask);
/* @} */
/*!
* @name Status
* @{
*/
/*!
* @brief Gets the CSI status flags.
*
* @param base CSI peripheral base address.
* @return status flag, it is OR'ed value of @ref _csi_flags.
*/
static inline uint32_t CSI_GetStatusFlags(CSI_Type *base)
{
return base->CSISR;
}
/*!
* @brief Clears the CSI status flag.
*
* The flags to clear are passed in as OR'ed value of @ref _csi_flags. The following
* flags are cleared automatically by hardware:
*
* - @ref kCSI_RxFifoFullFlag,
* - @ref kCSI_StatFifoFullFlag,
* - @ref kCSI_Field0PresentFlag,
* - @ref kCSI_Field1PresentFlag,
* - @ref kCSI_RxFifoDataReadyFlag,
*
* @param base CSI peripheral base address.
* @param statusMask The status flags mask, OR'ed value of @ref _csi_flags.
*/
static inline void CSI_ClearStatusFlags(CSI_Type *base, uint32_t statusMask)
{
base->CSISR = statusMask;
}
/* @} */
/*!
* @name Transactional
* @{
*/
/*!
* @brief Initializes the CSI handle.
*
* This function initializes CSI handle, it should be called before any other
* CSI transactional functions.
*
* @param base CSI peripheral base address.
* @param handle Pointer to the handle structure.
* @param callback Callback function for CSI transfer.
* @param userData Callback function parameter.
*
* @retval kStatus_Success Handle created successfully.
*/
status_t CSI_TransferCreateHandle(CSI_Type *base,
csi_handle_t *handle,
csi_transfer_callback_t callback,
void *userData);
/*!
* @brief Start the transfer using transactional functions.
*
* When the empty frame buffers have been submit to CSI driver using function
* @ref CSI_TransferSubmitEmptyBuffer, user could call this function to start
* the transfer. The incoming frame will be saved to the empty frame buffer,
* and user could be optionally notified through callback function.
*
* @param base CSI peripheral base address.
* @param handle Pointer to the handle structure.
*
* @retval kStatus_Success Started successfully.
* @retval kStatus_CSI_NoEmptyBuffer Could not start because no empty frame buffer in queue.
*/
status_t CSI_TransferStart(CSI_Type *base, csi_handle_t *handle);
/*!
* @brief Stop the transfer using transactional functions.
*
* The driver does not clean the full frame buffers in queue. In other words, after
* calling this function, user still could get the full frame buffers in queue
* using function @ref CSI_TransferGetFullBuffer.
*
* @param base CSI peripheral base address.
* @param handle Pointer to the handle structure.
*
* @retval kStatus_Success Stoped successfully.
*/
status_t CSI_TransferStop(CSI_Type *base, csi_handle_t *handle);
/*!
* @brief Submit empty frame buffer to queue.
*
* This function could be called before @ref CSI_TransferStart or after @ref
* CSI_TransferStart. If there is no room in queue to store the empty frame
* buffer, this function returns error.
*
* @param base CSI peripheral base address.
* @param handle Pointer to the handle structure.
* @param frameBuffer Empty frame buffer to submit.
*
* @retval kStatus_Success Started successfully.
* @retval kStatus_CSI_QueueFull Could not submit because there is no room in queue.
*/
status_t CSI_TransferSubmitEmptyBuffer(CSI_Type *base, csi_handle_t *handle, uint32_t frameBuffer);
/*!
* @brief Get one full frame buffer from queue.
*
* After the transfer started using function @ref CSI_TransferStart, the incoming
* frames will be saved to the empty frame buffers in queue. This function gets
* the full-filled frame buffer from the queue. If there is no full frame buffer
* in queue, this function returns error.
*
* @param base CSI peripheral base address.
* @param handle Pointer to the handle structure.
* @param frameBuffer Full frame buffer.
*
* @retval kStatus_Success Started successfully.
* @retval kStatus_CSI_NoFullBuffer There is no full frame buffer in queue.
*/
status_t CSI_TransferGetFullBuffer(CSI_Type *base, csi_handle_t *handle, uint32_t *frameBuffer);
/*!
* @brief CSI IRQ handle function.
*
* This function handles the CSI IRQ request to work with CSI driver transactional
* APIs.
*
* @param base CSI peripheral base address.
* @param handle CSI handle pointer.
*/
void CSI_TransferHandleIRQ(CSI_Type *base, csi_handle_t *handle);
/* @} */
#if defined(__cplusplus)
}
#endif
/*! @}*/
#endif /* _FSL_CSI_H_ */

View File

@ -0,0 +1,342 @@
/*
* Copyright (c) 2017, NXP
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS 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. */
static DCDC_Type *const s_dcdcBases[] = DCDC_BASE_PTRS;
#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
/*! @brief Pointers to DCDC clocks for each instance. */
static const clock_ip_name_t s_dcdcClocks[] = DCDC_CLOCKS;
#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
/*******************************************************************************
* Code
******************************************************************************/
static uint32_t DCDC_GetInstance(DCDC_Type *base)
{
uint32_t instance;
/* Find the instance index from base address mappings. */
for (instance = 0; instance < ARRAY_SIZE(s_dcdcBases); instance++)
{
if (s_dcdcBases[instance] == base)
{
break;
}
}
assert(instance < ARRAY_SIZE(s_dcdcBases));
return instance;
}
void DCDC_Init(DCDC_Type *base)
{
#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
/* Enable the clock. */
CLOCK_EnableClock(s_dcdcClocks[DCDC_GetInstance(base)]);
#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
}
void DCDC_Deinit(DCDC_Type *base)
{
#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
/* Disable the clock. */
CLOCK_DisableClock(s_dcdcClocks[DCDC_GetInstance(base)]);
#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
}
void DCDC_SetClockSource(DCDC_Type *base, dcdc_clock_source_t clockSource)
{
uint32_t tmp32;
/* Configure the DCDC_REG0 register. */
tmp32 = base->REG0 &
~(DCDC_REG0_XTAL_24M_OK_MASK | DCDC_REG0_DISABLE_AUTO_CLK_SWITCH_MASK | DCDC_REG0_SEL_CLK_MASK |
DCDC_REG0_PWD_OSC_INT_MASK);
switch (clockSource)
{
case kDCDC_ClockInternalOsc:
tmp32 |= DCDC_REG0_DISABLE_AUTO_CLK_SWITCH_MASK;
break;
case kDCDC_ClockExternalOsc:
/* Choose the external clock and disable the internal clock. */
tmp32 |= DCDC_REG0_DISABLE_AUTO_CLK_SWITCH_MASK | DCDC_REG0_SEL_CLK_MASK | DCDC_REG0_PWD_OSC_INT_MASK;
break;
case kDCDC_ClockAutoSwitch:
/* Set to switch from internal ring osc to xtal 24M if auto mode is enabled. */
tmp32 |= DCDC_REG0_XTAL_24M_OK_MASK;
break;
default:
break;
}
base->REG0 = tmp32;
}
void DCDC_GetDefaultDetectionConfig(dcdc_detection_config_t *config)
{
assert(NULL != config);
config->enableXtalokDetection = false;
config->powerDownOverVoltageDetection = true;
config->powerDownLowVlotageDetection = false;
config->powerDownOverCurrentDetection = true;
config->powerDownPeakCurrentDetection = true;
config->powerDownZeroCrossDetection = true;
config->OverCurrentThreshold = kDCDC_OverCurrentThresholdAlt0;
config->PeakCurrentThreshold = kDCDC_PeakCurrentThresholdAlt0;
}
void DCDC_SetDetectionConfig(DCDC_Type *base, const dcdc_detection_config_t *config)
{
assert(NULL != config);
uint32_t tmp32;
/* Configure the DCDC_REG0 register. */
tmp32 = base->REG0 &
~(DCDC_REG0_XTALOK_DISABLE_MASK | DCDC_REG0_PWD_HIGH_VOLT_DET_MASK | DCDC_REG0_PWD_CMP_BATT_DET_MASK |
DCDC_REG0_PWD_OVERCUR_DET_MASK | DCDC_REG0_PWD_CUR_SNS_CMP_MASK | DCDC_REG0_PWD_ZCD_MASK |
DCDC_REG0_CUR_SNS_THRSH_MASK | DCDC_REG0_OVERCUR_TRIG_ADJ_MASK);
tmp32 |= DCDC_REG0_CUR_SNS_THRSH(config->PeakCurrentThreshold) |
DCDC_REG0_OVERCUR_TRIG_ADJ(config->OverCurrentThreshold);
if (false == config->enableXtalokDetection)
{
tmp32 |= DCDC_REG0_XTALOK_DISABLE_MASK;
}
if (config->powerDownOverVoltageDetection)
{
tmp32 |= DCDC_REG0_PWD_HIGH_VOLT_DET_MASK;
}
if (config->powerDownLowVlotageDetection)
{
tmp32 |= DCDC_REG0_PWD_CMP_BATT_DET_MASK;
}
if (config->powerDownOverCurrentDetection)
{
tmp32 |= DCDC_REG0_PWD_OVERCUR_DET_MASK;
}
if (config->powerDownPeakCurrentDetection)
{
tmp32 |= DCDC_REG0_PWD_CUR_SNS_CMP_MASK;
}
if (config->powerDownZeroCrossDetection)
{
tmp32 |= DCDC_REG0_PWD_ZCD_MASK;
}
base->REG0 = tmp32;
}
void DCDC_GetDefaultLowPowerConfig(dcdc_low_power_config_t *config)
{
assert(NULL != config);
config->enableOverloadDetection = true;
config->enableAdjustHystereticValue = false;
config->countChargingTimePeriod = kDCDC_CountChargingTimePeriod8Cycle;
config->countChargingTimeThreshold = kDCDC_CountChargingTimeThreshold32;
}
void DCDC_SetLowPowerConfig(DCDC_Type *base, const dcdc_low_power_config_t *config)
{
assert(NULL != config);
uint32_t tmp32;
/* Configure the DCDC_REG0 register. */
tmp32 = base->REG0 &
~(DCDC_REG0_EN_LP_OVERLOAD_SNS_MASK | DCDC_REG0_LP_HIGH_HYS_MASK | DCDC_REG0_LP_OVERLOAD_FREQ_SEL_MASK |
DCDC_REG0_LP_OVERLOAD_THRSH_MASK);
tmp32 |= DCDC_REG0_LP_OVERLOAD_FREQ_SEL(config->countChargingTimePeriod) |
DCDC_REG0_LP_OVERLOAD_THRSH(config->countChargingTimeThreshold);
if (config->enableOverloadDetection)
{
tmp32 |= DCDC_REG0_EN_LP_OVERLOAD_SNS_MASK;
}
if (config->enableAdjustHystereticValue)
{
tmp32 |= DCDC_REG0_LP_HIGH_HYS_MASK;
}
base->REG0 = tmp32;
}
uint32_t DCDC_GetstatusFlags(DCDC_Type *base)
{
uint32_t tmp32 = 0U;
if (DCDC_REG0_STS_DC_OK_MASK == (DCDC_REG0_STS_DC_OK_MASK & base->REG0))
{
tmp32 |= kDCDC_LockedOKStatus;
}
return tmp32;
}
void DCDC_ResetCurrentAlertSignal(DCDC_Type *base, bool enable)
{
if (enable)
{
base->REG0 |= DCDC_REG0_CURRENT_ALERT_RESET_MASK;
}
else
{
base->REG0 &= ~DCDC_REG0_CURRENT_ALERT_RESET_MASK;
}
}
void DCDC_GetDefaultLoopControlConfig(dcdc_loop_control_config_t *config)
{
assert(NULL != config);
config->enableCommonHysteresis = false;
config->enableCommonThresholdDetection = false;
config->enableInvertHysteresisSign = false;
config->enableRCThresholdDetection = false;
config->enableRCScaleCircuit = 0U;
config->complementFeedForwardStep = 0U;
config->controlParameterMagnitude = 2U;
config->integralProportionalRatio = 2U;
}
void DCDC_SetLoopControlConfig(DCDC_Type *base, const dcdc_loop_control_config_t *config)
{
assert(NULL != config);
uint32_t tmp32;
/* Configure the DCDC_REG1 register. */
tmp32 = base->REG1 & ~(DCDC_REG1_LOOPCTRL_EN_HYST_MASK | DCDC_REG1_LOOPCTRL_HST_THRESH_MASK);
if (config->enableCommonHysteresis)
{
tmp32 |= DCDC_REG1_LOOPCTRL_EN_HYST_MASK;
}
if (config->enableCommonThresholdDetection)
{
tmp32 |= DCDC_REG1_LOOPCTRL_HST_THRESH_MASK;
}
base->REG1 = tmp32;
/* configure the DCDC_REG2 register. */
tmp32 = base->REG2 &
~(DCDC_REG2_LOOPCTRL_HYST_SIGN_MASK | DCDC_REG2_LOOPCTRL_RCSCALE_THRSH_MASK |
DCDC_REG2_LOOPCTRL_EN_RCSCALE_MASK | DCDC_REG2_LOOPCTRL_DC_FF_MASK | DCDC_REG2_LOOPCTRL_DC_R_MASK |
DCDC_REG2_LOOPCTRL_DC_C_MASK);
tmp32 |= DCDC_REG2_LOOPCTRL_DC_FF(config->complementFeedForwardStep) |
DCDC_REG2_LOOPCTRL_DC_R(config->controlParameterMagnitude) |
DCDC_REG2_LOOPCTRL_DC_C(config->integralProportionalRatio) |
DCDC_REG2_LOOPCTRL_EN_RCSCALE(config->enableRCScaleCircuit);
if (config->enableInvertHysteresisSign)
{
tmp32 |= DCDC_REG2_LOOPCTRL_HYST_SIGN_MASK;
}
if (config->enableRCThresholdDetection)
{
tmp32 |= DCDC_REG2_LOOPCTRL_RCSCALE_THRSH_MASK;
}
base->REG2 = tmp32;
}
void DCDC_SetMinPowerConfig(DCDC_Type *base, const dcdc_min_power_config_t *config)
{
assert(NULL != config);
uint32_t tmp32;
tmp32 = base->REG3 & ~DCDC_REG3_MINPWR_DC_HALFCLK_MASK;
if (config->enableUseHalfFreqForContinuous)
{
tmp32 |= DCDC_REG3_MINPWR_DC_HALFCLK_MASK;
}
base->REG3 = tmp32;
}
void DCDC_AdjustTargetVoltage(DCDC_Type *base, uint32_t VDDRun, uint32_t VDDStandby)
{
uint32_t tmp32;
/* Unlock the step for the output. */
base->REG3 &= ~DCDC_REG3_DISABLE_STEP_MASK;
/* Configure the DCDC_REG3 register. */
tmp32 = base->REG3 & ~(DCDC_REG3_TARGET_LP_MASK | DCDC_REG3_TRG_MASK);
tmp32 |= DCDC_REG3_TARGET_LP(VDDStandby) | DCDC_REG3_TRG(VDDRun);
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 (DCDC_REG0_STS_DC_OK_MASK != (DCDC_REG0_STS_DC_OK_MASK & base->REG0))
{
}
}
void DCDC_SetInternalRegulatorConfig(DCDC_Type *base, const dcdc_internal_regulator_config_t *config)
{
assert(NULL != config);
uint32_t tmp32;
/* Configure the DCDC_REG1 register. */
tmp32 = base->REG1 & ~(DCDC_REG1_REG_FBK_SEL_MASK | DCDC_REG1_REG_RLOAD_SW_MASK);
tmp32 |= DCDC_REG1_REG_FBK_SEL(config->feedbackPoint);
if (config->enableLoadResistor)
{
tmp32 |= DCDC_REG1_REG_RLOAD_SW_MASK;
}
base->REG1 = tmp32;
}
void DCDC_BootIntoDCM(DCDC_Type *base)
{
base->REG0 &= ~(DCDC_REG0_PWD_ZCD_MASK | DCDC_REG0_PWD_CMP_OFFSET_MASK);
base->REG2 = (~DCDC_REG2_LOOPCTRL_EN_RCSCALE_MASK & base->REG2) | DCDC_REG2_LOOPCTRL_EN_RCSCALE(0x3U) |
DCDC_REG2_DCM_SET_CTRL_MASK;
}
void DCDC_BootIntoCCM(DCDC_Type *base)
{
base->REG0 = (~DCDC_REG0_PWD_CMP_OFFSET_MASK & base->REG0) | DCDC_REG0_PWD_ZCD_MASK;
base->REG2 = (~DCDC_REG2_LOOPCTRL_EN_RCSCALE_MASK & base->REG2) | DCDC_REG2_LOOPCTRL_EN_RCSCALE(0x3U) |
DCDC_REG2_DCM_SET_CTRL_MASK;
}

View File

@ -0,0 +1,486 @@
/*
* Copyright (c) 2017, NXP
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS 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 DCDC status flags.
*/
enum _dcdc_status_flags_t
{
kDCDC_LockedOKStatus = (1U << 0U), /*!< Indicate DCDC status. 1'b1: DCDC already settled 1'b0: DCDC is settling. */
};
/*!
* @brief The current bias of low power comparator.
*/
typedef enum _dcdc_comparator_current_bias
{
kDCDC_ComparatorCurrentBias50nA = 0U, /*!< The current bias of low power comparator is 50nA. */
kDCDC_ComparatorCurrentBias100nA = 1U, /*!< The current bias of low power comparator is 100nA. */
kDCDC_ComparatorCurrentBias200nA = 2U, /*!< The current bias of low power comparator is 200nA. */
kDCDC_ComparatorCurrentBias400nA = 3U, /*!< The current bias of low power comparator is 400nA. */
} dcdc_comparator_current_bias_t;
/*!
* @brief The threshold of over current detection.
*/
typedef enum _dcdc_over_current_threshold
{
kDCDC_OverCurrentThresholdAlt0 = 0U, /*!< 1A in the run mode, 0.25A in the power save mode. */
kDCDC_OverCurrentThresholdAlt1 = 1U, /*!< 2A in the run mode, 0.25A in the power save mode. */
kDCDC_OverCurrentThresholdAlt2 = 2U, /*!< 1A in the run mode, 0.2A in the power save mode. */
kDCDC_OverCurrentThresholdAlt3 = 3U, /*!< 2A in the run mode, 0.2A in the power save mode. */
} dcdc_over_current_threshold_t;
/*!
* @brief The threshold if peak current detection.
*/
typedef enum _dcdc_peak_current_threshold
{
kDCDC_PeakCurrentThresholdAlt0 = 0U, /*!< 150mA peak current threshold. */
kDCDC_PeakCurrentThresholdAlt1 = 1U, /*!< 250mA peak current threshold. */
kDCDC_PeakCurrentThresholdAlt2 = 2U, /*!< 350mA peak current threshold. */
kDCDC_PeakCurrentThresholdAlt3 = 3U, /*!< 450mA peak current threshold. */
kDCDC_PeakCurrentThresholdAlt4 = 4U, /*!< 550mA peak current threshold. */
kDCDC_PeakCurrentThresholdAlt5 = 5U, /*!< 650mA peak current threshold. */
} dcdc_peak_current_threshold_t;
/*!
* @brief The period of counting the charging times in power save mode.
*/
typedef enum _dcdc_count_charging_time_period
{
kDCDC_CountChargingTimePeriod8Cycle = 0U, /*!< Eight 32k cycle. */
kDCDC_CountChargingTimePeriod16Cycle = 1U, /*!< Sixteen 32k cycle. */
} dcdc_count_charging_time_period_t;
/*!
* @brief The threshold of the counting number of charging times
*/
typedef enum _dcdc_count_charging_time_threshold
{
kDCDC_CountChargingTimeThreshold32 = 0U, /*!< 0x0: 32. */
kDCDC_CountChargingTimeThreshold64 = 1U, /*!< 0x1: 64. */
kDCDC_CountChargingTimeThreshold16 = 2U, /*!< 0x2: 16. */
kDCDC_CountChargingTimeThreshold8 = 3U, /*!< 0x3: 8. */
} dcdc_count_charging_time_threshold_t;
/*!
* @brief Oscillator clock option.
*/
typedef enum _dcdc_clock_source
{
kDCDC_ClockAutoSwitch = 0U, /*!< Automatic clock switch from internal oscillator to external clock. */
kDCDC_ClockInternalOsc = 1U, /*!< Use internal oscillator. */
kDCDC_ClockExternalOsc = 2U, /*!< Use external 24M crystal oscillator. */
} dcdc_clock_source_t;
/*!
* @brief Configuration for DCDC detection.
*/
typedef struct _dcdc_detection_config
{
bool enableXtalokDetection; /*!< Enable xtalok detection circuit. */
bool powerDownOverVoltageDetection; /*!< Power down over-voltage detection comparator. */
bool powerDownLowVlotageDetection; /*!< Power down low-voltage detection comparator. */
bool powerDownOverCurrentDetection; /*!< Power down over-current detection. */
bool powerDownPeakCurrentDetection; /*!< Power down peak-current detection. */
bool powerDownZeroCrossDetection; /*!< Power down the zero cross detection function for discontinuous conductor
mode. */
dcdc_over_current_threshold_t OverCurrentThreshold; /*!< The threshold of over current detection. */
dcdc_peak_current_threshold_t PeakCurrentThreshold; /*!< The threshold of peak current detection. */
} dcdc_detection_config_t;
/*!
* @brief Configuration for the loop control.
*/
typedef struct _dcdc_loop_control_config
{
bool enableCommonHysteresis; /*!< Enable hysteresis in switching converter common mode analog comparators.
This feature will improve transient supply ripple and efficiency. */
bool enableCommonThresholdDetection; /*!< Increase the threshold detection for common mode analog comparator. */
bool enableInvertHysteresisSign; /*!< Invert the sign of the hysteresis in DC-DC analog comparators. */
bool enableRCThresholdDetection; /*!< Increase the threshold detection for RC scale circuit. */
uint32_t enableRCScaleCircuit; /*!< Available range is 0~7. Enable analog circuit of DC-DC converter to respond
faster under transient load conditions. */
uint32_t complementFeedForwardStep; /*!< Available range is 0~7. Two's complement feed forward step in duty cycle in
the switching DC-DC converter. Each time this field makes a transition from
0x0, the loop filter of the DC-DC converter is stepped once by a value
proportional to the change. This can be used to force a certain control loop
behavior, such as improving response under known heavy load transients. */
uint32_t controlParameterMagnitude; /*!< Available range is 0~15. Magnitude of proportional control parameter in the
switching DC-DC converter control loop. */
uint32_t integralProportionalRatio; /*!< Available range is 0~3.Ratio of integral control parameter to proportional
control parameter in the switching DC-DC converter, and can be used to
optimize efficiency and loop response. */
} dcdc_loop_control_config_t;
/*!
* @brief Configuration for DCDC low power.
*/
typedef struct _dcdc_low_power_config
{
bool enableOverloadDetection; /*!< Enable the overload detection in power save mode, if current is larger than the
overloading threshold (typical value is 50 mA), DCDC will switch to the run mode
automatically. */
bool enableAdjustHystereticValue; /*!< Adjust hysteretic value in low power from 12.5mV to 25mV. */
dcdc_count_charging_time_period_t
countChargingTimePeriod; /*!< The period of counting the charging times in power save mode. */
dcdc_count_charging_time_threshold_t
countChargingTimeThreshold; /*!< the threshold of the counting number of charging times during
the period that lp_overload_freq_sel sets in power save mode. */
} dcdc_low_power_config_t;
/*!
* @brief Configuration for DCDC internal regulator.
*/
typedef struct _dcdc_internal_regulator_config
{
bool enableLoadResistor; /*!< control the load resistor of the internal regulator of DCDC, the load resistor is
connected as default "true", and need set to "false" to disconnect the load
resistor. */
uint32_t feedbackPoint; /*!< Available range is 0~3. Select the feedback point of the internal regulator. */
} dcdc_internal_regulator_config_t;
/*!
* @brief Configuration for min power setting.
*/
typedef struct _dcdc_min_power_config
{
bool enableUseHalfFreqForContinuous; /*!< Set DCDC clock to half frequency for the continuous mode. */
} dcdc_min_power_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 DCDC status flags.
*
* @param base peripheral base address.
* @return Mask of asserted status flags. See to "_dcdc_status_flags_t".
*/
uint32_t DCDC_GetstatusFlags(DCDC_Type *base);
/* @} */
/*!
* @name Misc control.
* @{
*/
/*!
* @brief Enable the output range comparator.
*
* The output range comparator is disabled 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 Configure the DCDC clock source.
*
* @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 Get the default setting for detection configuration.
*
* The default configuration are set according to responding registers' setting when powered on.
* They are:
* @code
* config->enableXtalokDetection = false;
* config->powerDownOverVoltageDetection = true;
* config->powerDownLowVlotageDetection = false;
* config->powerDownOverCurrentDetection = true;
* config->powerDownPeakCurrentDetection = true;
* config->powerDownZeroCrossDetection = true;
* config->OverCurrentThreshold = kDCDC_OverCurrentThresholdAlt0;
* config->PeakCurrentThreshold = kDCDC_PeakCurrentThresholdAlt0;
* @endcode
*
* @param config Pointer to configuration structure. See to "dcdc_detection_config_t"
*/
void DCDC_GetDefaultDetectionConfig(dcdc_detection_config_t *config);
/*!
* @breif Configure the DCDC detection.
*
* @param base DCDC peripheral base address.
* @param config Pointer to configuration structure. See to "dcdc_detection_config_t"
*/
void DCDC_SetDetectionConfig(DCDC_Type *base, const dcdc_detection_config_t *config);
/*!
* @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->enableOverloadDetection = true;
* config->enableAdjustHystereticValue = false;
* config->countChargingTimePeriod = kDCDC_CountChargingTimePeriod8Cycle;
* config->countChargingTimeThreshold = kDCDC_CountChargingTimeThreshold32;
* @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 DCDC low power.
*
* @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 Reset current alert signal. Alert signal is generate by peak current detection.
*
* @param base DCDC peripheral base address.
* @param enable Switcher to reset signal. True means reset signal. False means don't reset signal.
*/
void DCDC_ResetCurrentAlertSignal(DCDC_Type *base, bool enable);
/*!
* @brief Set the bangap trim value to trim bandgap voltage.
*
* @param base DCDC peripheral base address.
* @param TrimValue The bangap trim value. Available range is 0U-31U.
*/
static inline void DCDC_SetBandgapVoltageTrimValue(DCDC_Type *base, uint32_t trimValue)
{
base->REG1 &= ~DCDC_REG1_VBG_TRIM_MASK;
base->REG1 |= DCDC_REG1_VBG_TRIM(trimValue);
}
/*!
* @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->enableCommonHysteresis = false;
* config->enableCommonThresholdDetection = false;
* config->enableInvertHysteresisSign = false;
* config->enableRCThresholdDetection = false;
* config->enableRCScaleCircuit = 0U;
* config->complementFeedForwardStep = 0U;
* config->controlParameterMagnitude = 2U;
* config->integralProportionalRatio = 2U;
* @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 DCDC loop control.
*
* @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 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 Set the current bias of low power comparator.
*
* @param base DCDC peripheral base address.
* @param biasVaule The current bias of low power comparator. Refer to "dcdc_comparator_current_bias_t".
*/
static inline void DCDC_SetLPComparatorBiasValue(DCDC_Type *base, dcdc_comparator_current_bias_t biasVaule)
{
base->REG1 &= ~DCDC_REG1_LP_CMP_ISRC_SEL_MASK;
base->REG1 |= DCDC_REG1_LP_CMP_ISRC_SEL(biasVaule);
}
static inline void DCDC_LockTargetVoltage(DCDC_Type *base)
{
base->REG3 |= DCDC_REG3_DISABLE_STEP_MASK;
}
/*!
* @brief Adjust the target voltage of VDD_SOC in run mode and low power mode.
*
* This function is to adjust the target voltage of DCDC output. Change them and finally wait until the output is
* stabled.
* Set the target value of run mode the same as low power mode before entering power save mode, because DCDC will switch
* back to run mode if it detects the current loading is larger than about 50 mA(typical value).
*
* @param base DCDC peripheral base address.
* @param VDDRun Target value in run mode. 25 mV each step from 0x00 to 0x1F. 00 is for 0.8V, 0x1F is for 1.575V.
* @param VDDStandby Target value in low power mode. 25 mV each step from 0x00 to 0x4. 00 is for 0.9V, 0x4 is for 1.0V.
*/
void DCDC_AdjustTargetVoltage(DCDC_Type *base, uint32_t VDDRun, uint32_t VDDStandby);
/*!
* @brief Configure the DCDC internal regulator.
*
* @param base DCDC peripheral base address.
* @param config Pointer to configuration structure. See to "dcdc_internal_regulator_config_t".
*/
void DCDC_SetInternalRegulatorConfig(DCDC_Type *base, const dcdc_internal_regulator_config_t *config);
/*!
* @brief Ajust delay to reduce ground noise.
*
* @param base DCDC peripheral base address.
* @param enable Enable the feature or not.
*/
static inline void DCDC_EnableAdjustDelay(DCDC_Type *base, bool enable)
{
if (enable)
{
base->REG3 |= DCDC_REG3_MISC_DELAY_TIMING_MASK;
}
else
{
base->REG3 &= ~DCDC_REG3_MISC_DELAY_TIMING_MASK;
}
}
/*!
* @brief Enable/Disable to improve the transition from heavy load to light load. It is valid while zero
* cross detection is enabled. If ouput exceeds the threshold, DCDC would return CCM from DCM.
*
* @param base DCDC peripheral base address.
* @param enable Enable the feature or not.
*/
static inline void DCDC_EnableImproveTransition(DCDC_Type *base, bool enable)
{
if (enable)
{
base->REG2 |= DCDC_REG2_DCM_SET_CTRL_MASK;
}
else
{
base->REG2 &= ~DCDC_REG2_DCM_SET_CTRL_MASK;
}
}
/* @} */
/*!
* @name Application guideline.
* @{
*/
/*!
* @brief Boot DCDC into DCM(discontinous conduction mode).
*
* pwd_zcd=0x0;
* pwd_cmp_offset=0x0;
* dcdc_loopctrl_en_rcscale=0x3 or 0x5;
* DCM_set_ctrl=1'b1;
*
* @param base DCDC peripheral base address.
*/
void DCDC_BootIntoDCM(DCDC_Type *base);
/*!
* @brief Boot DCDC into CCM(continous conduction mode).
*
* pwd_zcd=0x1;
* pwd_cmp_offset=0x0;
* dcdc_loopctrl_en_rcscale=0x3;
*
* @param base DCDC peripheral base address.
*/
void DCDC_BootIntoCCM(DCDC_Type *base);
#if defined(__cplusplus)
}
#endif
#endif /* __FSL_DCDC_H__ */

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,553 @@
/*
* Copyright 2017 NXP
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _FSL_DCP_H_
#define _FSL_DCP_H_
#include "fsl_common.h"
/*! @brief DCP status return codes. */
enum _dcp_status
{
kStatus_DCP_Again = MAKE_STATUS(kStatusGroup_DCP, 0), /*!< Non-blocking function shall be called again. */
};
/*******************************************************************************
* Definitions
*******************************************************************************/
/*!
* @addtogroup dcp_driver
* @{
*/
/*! @name Driver version */
/*@{*/
/*! @brief DCP driver version. Version 2.0.0.
*
* Current version: 2.0.0
*
* Change log:
* - Version 2.0.0
* - Initial version
*/
#define FSL_DCP_DRIVER_VERSION (MAKE_VERSION(2, 0, 0))
/*@}*/
/*! @brief DCP channel enable.
*
*/
typedef enum _dcp_ch_enable
{
kDCP_chDisable = 0U, /*!< DCP channel disable */
kDCP_ch0Enable = 1U, /*!< DCP channel 0 enable */
kDCP_ch1Enable = 2U, /*!< DCP channel 1 enable */
kDCP_ch2Enable = 4U, /*!< DCP channel 2 enable */
kDCP_ch3Enable = 8U, /*!< DCP channel 3 enable */
kDCP_chEnableAll = 15U, /*!< DCP channel enable all */
} _dcp_ch_enable_t;
/*! @brief DCP interrupt enable.
*
*/
typedef enum _dcp_ch_int_enable
{
kDCP_chIntDisable = 0U, /*!< DCP interrupts disable */
kDCP_ch0IntEnable = 1U, /*!< DCP channel 0 interrupt enable */
kDCP_ch1IntEnable = 2U, /*!< DCP channel 1 interrupt enable */
kDCP_ch2IntEnable = 4U, /*!< DCP channel 2 interrupt enable */
kDCP_ch3IntEnable = 8U, /*!< DCP channel 3 interrupt enable */
} _dcp_ch_int_enable_t;
/*! @brief DCP channel selection.
*
*/
typedef enum _dcp_channel
{
kDCP_Channel0 = (1u << 16), /*!< DCP channel 0. */
kDCP_Channel1 = (1u << 17), /*!< DCP channel 1. */
kDCP_Channel2 = (1u << 18), /*!< DCP channel 2. */
kDCP_Channel3 = (1u << 19), /*!< DCP channel 3. */
} dcp_channel_t;
/*! @brief DCP key slot selection.
*
*/
typedef enum _dcp_key_slot
{
kDCP_KeySlot0 = 0U, /*!< DCP key slot 0. */
kDCP_KeySlot1 = 1U, /*!< DCP key slot 1. */
kDCP_KeySlot2 = 2U, /*!< DCP key slot 2.*/
kDCP_KeySlot3 = 3U, /*!< DCP key slot 3. */
kDCP_OtpKey = 4U, /*!< DCP OTP key. */
kDCP_OtpUniqueKey = 5U, /*!< DCP unique OTP key. */
kDCP_PayloadKey = 6U, /*!< DCP payload key. */
} dcp_key_slot_t;
/*! @brief DCP's work packet. */
typedef struct _dcp_work_packet
{
uint32_t nextCmdAddress;
uint32_t control0;
uint32_t control1;
uint32_t sourceBufferAddress;
uint32_t destinationBufferAddress;
uint32_t bufferSize;
uint32_t payloadPointer;
uint32_t status;
} dcp_work_packet_t;
/*! @brief Specify DCP's key resource and DCP channel. */
typedef struct _dcp_handle
{
dcp_channel_t channel; /*!< Specify DCP channel. */
dcp_key_slot_t keySlot; /*!< For operations with key (such as AES encryption/decryption), specify DCP key slot. */
uint32_t keyWord[4];
uint32_t iv[4];
} dcp_handle_t;
/*! @brief DCP's context buffer, used by DCP for context switching between channels. */
typedef struct _dcp_context
{
uint32_t x[208 / sizeof(uint32_t)];
} dcp_context_t;
/*! @brief DCP's configuration structure. */
typedef struct _dcp_config
{
bool gatherResidualWrites; /*!< Enable the ragged writes to the unaligned buffers. */
bool enableContextCaching; /*!< Enable the caching of contexts between the operations. */
bool enableContextSwitching; /*!< Enable automatic context switching for the channels. */
uint8_t enableChannel; /*!< DCP channel enable. */
uint8_t enableChannelInterrupt; /*!< Per-channel interrupt enable. */
} dcp_config_t;
/*! @} */
/*******************************************************************************
* AES Definitions
*******************************************************************************/
/*!
* @addtogroup dcp_driver_aes
* @{
*/
/*! AES block size in bytes */
#define DCP_AES_BLOCK_SIZE 16
/*!
*@}
*/ /* end of dcp_driver_aes */
/*******************************************************************************
* HASH Definitions
******************************************************************************/
/*!
* @addtogroup dcp_driver_hash
* @{
*/
/* DCP cannot correctly compute hash for message with zero size. When enabled, driver bypases DCP and returns correct
* hash value. If you are sure, that the driver will never be called with zero sized message, you can disable this
* feature to reduce code size */
#define DCP_HASH_CAVP_COMPATIBLE
/*! @brief Supported cryptographic block cipher functions for HASH creation */
typedef enum _dcp_hash_algo_t
{
kDCP_Sha1, /*!< SHA_1 */
kDCP_Sha256, /*!< SHA_256 */
kDCP_Crc32, /*!< CRC_32 */
} dcp_hash_algo_t;
/*! @brief DCP HASH Context size. */
#define DCP_SHA_BLOCK_SIZE 128 /*!< internal buffer block size */
#define DCP_HASH_BLOCK_SIZE DCP_SHA_BLOCK_SIZE /*!< DCP hash block size */
/*! @brief DCP HASH Context size. */
#define DCP_HASH_CTX_SIZE 58
/*! @brief Storage type used to save hash context. */
typedef struct _dcp_hash_ctx_t
{
uint32_t x[DCP_HASH_CTX_SIZE];
} dcp_hash_ctx_t;
/*!
*@}
*/ /* end of dcp_driver_hash */
/*******************************************************************************
* API
******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif
/*!
* @addtogroup dcp_driver
* @{
*/
/*!
* @brief Enables clock to and enables DCP
*
* Enable DCP clock and configure DCP.
*
* @param base DCP base address
* @param config Pointer to configuration structure.
*/
void DCP_Init(DCP_Type *base, const dcp_config_t *config);
/*!
* @brief Disable DCP clock
*
* Reset DCP and Disable DCP clock.
*
* @param base DCP base address
*/
void DCP_Deinit(DCP_Type *base);
/*!
* @brief Gets the default configuration structure.
*
* This function initializes the DCP configuration structure to a default value. The default
* values are as follows.
* dcpConfig->gatherResidualWrites = true;
* dcpConfig->enableContextCaching = true;
* dcpConfig->enableContextSwitching = true;
* dcpConfig->enableChannnel = kDCP_chEnableAll;
* dcpConfig->enableChannelInterrupt = kDCP_chIntDisable;
*
* @param[out] config Pointer to configuration structure.
*/
void DCP_GetDefaultConfig(dcp_config_t *config);
/*!
* @brief Poll and wait on DCP channel.
*
* Polls the specified DCP channel until current it completes activity.
*
* @param base DCP peripheral base address.
* @param handle Specifies DCP channel.
* @return kStatus_Success When data processing completes without error.
* @return kStatus_Fail When error occurs.
*/
status_t DCP_WaitForChannelComplete(DCP_Type *base, dcp_handle_t *handle);
/*!
*@}
*/ /* end of dcp_driver */
/*******************************************************************************
* AES API
******************************************************************************/
/*!
* @addtogroup dcp_driver_aes
* @{
*/
/*!
* @brief Set AES key to dcp_handle_t struct and optionally to DCP.
*
* Sets the AES key for encryption/decryption with the dcp_handle_t structure.
* The dcp_handle_t input argument specifies keySlot.
* If the keySlot is kDCP_OtpKey, the function will check the OTP_KEY_READY bit and will return it's ready to use
* status.
* For other keySlot selections, the function will copy and hold the key in dcp_handle_t struct.
* If the keySlot is one of the four DCP SRAM-based keys (one of kDCP_KeySlot0, kDCP_KeySlot1, kDCP_KeySlot2,
* kDCP_KeySlot3),
* this function will also load the supplied key to the specified keySlot in DCP.
*
* @param base DCP peripheral base address.
* @param handle Handle used for the request.
* @param key 0-mod-4 aligned pointer to AES key.
* @param keySize AES key size in bytes. Shall equal 16.
* @return status from set key operation
*/
status_t DCP_AES_SetKey(DCP_Type *base, dcp_handle_t *handle, const uint8_t *key, size_t keySize);
/*!
* @brief Encrypts AES on one or multiple 128-bit block(s).
*
* Encrypts AES.
* The source plaintext and destination ciphertext can overlap in system memory.
*
* @param base DCP peripheral base address
* @param handle Handle used for this request.
* @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.
* @return Status from encrypt operation
*/
status_t DCP_AES_EncryptEcb(
DCP_Type *base, dcp_handle_t *handle, const uint8_t *plaintext, uint8_t *ciphertext, size_t size);
/*!
* @brief Decrypts AES on one or multiple 128-bit block(s).
*
* Decrypts AES.
* The source ciphertext and destination plaintext can overlap in system memory.
*
* @param base DCP peripheral base address
* @param handle Handle used for this request.
* @param ciphertext Input plain text to encrypt
* @param[out] plaintext Output cipher text
* @param size Size of input and output data in bytes. Must be multiple of 16 bytes.
* @return Status from decrypt operation
*/
status_t DCP_AES_DecryptEcb(
DCP_Type *base, dcp_handle_t *handle, const uint8_t *ciphertext, uint8_t *plaintext, size_t size);
/*!
* @brief Encrypts AES using CBC block mode.
*
* Encrypts AES using CBC block mode.
* The source plaintext and destination ciphertext can overlap in system memory.
*
* @param base DCP peripheral base address
* @param handle Handle used for this request.
* @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.
* @return Status from encrypt operation
*/
status_t DCP_AES_EncryptCbc(DCP_Type *base,
dcp_handle_t *handle,
const uint8_t *plaintext,
uint8_t *ciphertext,
size_t size,
const uint8_t iv[16]);
/*!
* @brief Decrypts AES using CBC block mode.
*
* Decrypts AES using CBC block mode.
* The source ciphertext and destination plaintext can overlap in system memory.
*
* @param base DCP peripheral base address
* @param handle Handle used for this request.
* @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.
* @return Status from decrypt operation
*/
status_t DCP_AES_DecryptCbc(DCP_Type *base,
dcp_handle_t *handle,
const uint8_t *ciphertext,
uint8_t *plaintext,
size_t size,
const uint8_t iv[16]);
/*!
*@}
*/ /* end of dcp_driver_aes */
/*!
* @addtogroup dcp_nonblocking_driver_aes
* @{
*/
/*!
* @brief Encrypts AES using the ECB block mode.
*
* Puts AES ECB encrypt work packet to DCP channel.
*
* @param base DCP peripheral base address
* @param handle Handle used for this request.
* @param[out] dcpPacket Memory for the DCP work packet.
* @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.
* @return kStatus_Success The work packet has been scheduled at DCP channel.
* @return kStatus_DCP_Again The DCP channel is busy processing previous request.
*/
status_t DCP_AES_EncryptEcbNonBlocking(DCP_Type *base,
dcp_handle_t *handle,
dcp_work_packet_t *dcpPacket,
const uint8_t *plaintext,
uint8_t *ciphertext,
size_t size);
/*!
* @brief Decrypts AES using ECB block mode.
*
* Puts AES ECB decrypt dcpPacket to DCP input job ring.
*
* @param base DCP peripheral base address
* @param handle Handle used for this request.
* @param[out] dcpPacket Memory for the DCP work packet.
* @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.
* @return kStatus_Success The work packet has been scheduled at DCP channel.
* @return kStatus_DCP_Again The DCP channel is busy processing previous request.
*/
status_t DCP_AES_DecryptEcbNonBlocking(DCP_Type *base,
dcp_handle_t *handle,
dcp_work_packet_t *dcpPacket,
const uint8_t *ciphertext,
uint8_t *plaintext,
size_t size);
/*!
* @brief Encrypts AES using CBC block mode.
*
* Puts AES CBC encrypt dcpPacket to DCP input job ring.
*
* @param base DCP peripheral base address
* @param handle Handle used for this request. Specifies jobRing.
* @param[out] dcpPacket Memory for the DCP work packet.
* @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.
* @return kStatus_Success The work packet has been scheduled at DCP channel.
* @return kStatus_DCP_Again The DCP channel is busy processing previous request.
*/
status_t DCP_AES_EncryptCbcNonBlocking(DCP_Type *base,
dcp_handle_t *handle,
dcp_work_packet_t *dcpPacket,
const uint8_t *plaintext,
uint8_t *ciphertext,
size_t size,
const uint8_t *iv);
/*!
* @brief Decrypts AES using CBC block mode.
*
* Puts AES CBC decrypt dcpPacket to DCP input job ring.
*
* @param base DCP peripheral base address
* @param handle Handle used for this request. Specifies jobRing.
* @param[out] dcpPacket Memory for the DCP work packet.
* @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.
* @return kStatus_Success The work packet has been scheduled at DCP channel.
* @return kStatus_DCP_Again The DCP channel is busy processing previous request.
*/
status_t DCP_AES_DecryptCbcNonBlocking(DCP_Type *base,
dcp_handle_t *handle,
dcp_work_packet_t *dcpPacket,
const uint8_t *ciphertext,
uint8_t *plaintext,
size_t size,
const uint8_t *iv);
/*!
*@}
*/ /* end of dcp_nonblocking_driver_aes */
/*******************************************************************************
* HASH API
******************************************************************************/
/*!
* @addtogroup dcp_driver_hash
* @{
*/
/*!
* @brief Initialize HASH context
*
* This function initializes the HASH.
*
* @param base DCP peripheral base address
* @param handle Specifies the DCP channel used for hashing.
* @param[out] ctx Output hash context
* @param algo Underlaying algorithm to use for hash computation.
* @return Status of initialization
*/
status_t DCP_HASH_Init(DCP_Type *base, dcp_handle_t *handle, dcp_hash_ctx_t *ctx, dcp_hash_algo_t algo);
/*!
* @brief Add data to current HASH
*
* Add data to current HASH. This can be called repeatedly with an arbitrary amount of data to be
* hashed. The functions blocks. If it returns kStatus_Success, the running hash
* has been updated (DCP has processed the input data), so the memory at @ref input pointer
* can be released back to system. The DCP context buffer is updated with the running hash
* and with all necessary information to support possible context switch.
*
* @param base DCP peripheral base address
* @param[in,out] ctx HASH context
* @param input Input data
* @param inputSize Size of input data in bytes
* @return Status of the hash update operation
*/
status_t DCP_HASH_Update(DCP_Type *base, dcp_hash_ctx_t *ctx, const uint8_t *input, size_t inputSize);
/*!
* @brief Finalize hashing
*
* Outputs the final hash (computed by DCP_HASH_Update()) and erases the context.
*
* @param[in,out] ctx Input hash context
* @param[out] output Output hash data
* @param[in,out] outputSize Optional parameter (can be passed as NULL). On function entry, it specifies the size of
* output[] buffer. On function return, it stores the number of updated output bytes.
* @return Status of the hash finish operation
*/
status_t DCP_HASH_Finish(DCP_Type *base, dcp_hash_ctx_t *ctx, uint8_t *output, size_t *outputSize);
/*!
* @brief Create HASH on given data
*
* Perform the full SHA or CRC32 in one function call. The function is blocking.
*
* @param base DCP peripheral base address
* @param handle Handle used for the request.
* @param algo Underlaying algorithm to use for hash computation.
* @param input Input data
* @param inputSize Size of input data in bytes
* @param[out] output Output hash data
* @param[out] outputSize Output parameter storing the size of the output hash in bytes
* @return Status of the one call hash operation.
*/
status_t DCP_HASH(DCP_Type *base,
dcp_handle_t *handle,
dcp_hash_algo_t algo,
const uint8_t *input,
size_t inputSize,
uint8_t *output,
size_t *outputSize);
/*!
*@}
*/ /* end of dcp_driver_hash */
#if defined(__cplusplus)
}
#endif
#endif /* _FSL_DCP_H_ */

View File

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

View File

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

File diff suppressed because it is too large Load Diff

View File

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

View File

@ -0,0 +1,297 @@
/*
* Copyright (c) 2017, NXP Semiconductors, 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 the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include "fsl_elcdif.h"
/*******************************************************************************
* Prototypes
******************************************************************************/
/*!
* @brief Get instance number for ELCDIF module.
*
* @param base ELCDIF peripheral base address
*/
static uint32_t ELCDIF_GetInstance(LCDIF_Type *base);
/*******************************************************************************
* Variables
******************************************************************************/
/*! @brief Pointers to ELCDIF bases for each instance. */
static LCDIF_Type *const s_elcdifBases[] = LCDIF_BASE_PTRS;
#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
/*! @brief Pointers to eLCDIF apb_clk for each instance. */
static const clock_ip_name_t s_elcdifApbClocks[] = LCDIF_CLOCKS;
#if defined(LCDIF_PERIPH_CLOCKS)
/*! @brief Pointers to eLCDIF pix_clk for each instance. */
static const clock_ip_name_t s_elcdifPixClocks[] = LCDIF_PERIPH_CLOCKS;
#endif
#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
/*! @brief The control register value to select different pixel format. */
elcdif_pixel_format_reg_t s_pixelFormatReg[] = {
/* kELCDIF_PixelFormatRAW8 */
{/* Register CTRL. */
LCDIF_CTRL_WORD_LENGTH(1U),
/* Register CTRL1. */
LCDIF_CTRL1_BYTE_PACKING_FORMAT(0x0FU)},
/* kELCDIF_PixelFormatRGB565 */
{/* Register CTRL. */
LCDIF_CTRL_WORD_LENGTH(0U),
/* Register CTRL1. */
LCDIF_CTRL1_BYTE_PACKING_FORMAT(0x0FU)},
/* kELCDIF_PixelFormatRGB666 */
{/* Register CTRL. */
LCDIF_CTRL_WORD_LENGTH(3U) | LCDIF_CTRL_DATA_FORMAT_24_BIT(1U),
/* Register CTRL1. */
LCDIF_CTRL1_BYTE_PACKING_FORMAT(0x07U)},
/* kELCDIF_PixelFormatXRGB8888 */
{/* Register CTRL. 24-bit. */
LCDIF_CTRL_WORD_LENGTH(3U),
/* Register CTRL1. */
LCDIF_CTRL1_BYTE_PACKING_FORMAT(0x07U)},
/* kELCDIF_PixelFormatRGB888 */
{/* Register CTRL. 24-bit. */
LCDIF_CTRL_WORD_LENGTH(3U),
/* Register CTRL1. */
LCDIF_CTRL1_BYTE_PACKING_FORMAT(0x0FU)},
};
/*******************************************************************************
* Codes
******************************************************************************/
static uint32_t ELCDIF_GetInstance(LCDIF_Type *base)
{
uint32_t instance;
/* Find the instance index from base address mappings. */
for (instance = 0; instance < ARRAY_SIZE(s_elcdifBases); instance++)
{
if (s_elcdifBases[instance] == base)
{
break;
}
}
assert(instance < ARRAY_SIZE(s_elcdifBases));
return instance;
}
void ELCDIF_RgbModeInit(LCDIF_Type *base, const elcdif_rgb_mode_config_t *config)
{
assert(config);
assert(config->pixelFormat < ARRAY_SIZE(s_pixelFormatReg));
#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
uint32_t instance = ELCDIF_GetInstance(base);
/* Enable the clock. */
CLOCK_EnableClock(s_elcdifApbClocks[instance]);
#if defined(LCDIF_PERIPH_CLOCKS)
CLOCK_EnableClock(s_elcdifPixClocks[instance]);
#endif
#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
/* Reset. */
ELCDIF_Reset(base);
base->CTRL = s_pixelFormatReg[(uint32_t)config->pixelFormat].regCtrl | (uint32_t)(config->dataBus) |
LCDIF_CTRL_DOTCLK_MODE_MASK | /* RGB mode. */
LCDIF_CTRL_BYPASS_COUNT_MASK | /* Keep RUN bit set. */
LCDIF_CTRL_MASTER_MASK;
base->CTRL1 = s_pixelFormatReg[(uint32_t)config->pixelFormat].regCtrl1;
base->TRANSFER_COUNT = ((uint32_t)config->panelHeight << LCDIF_TRANSFER_COUNT_V_COUNT_SHIFT) |
((uint32_t)config->panelWidth << LCDIF_TRANSFER_COUNT_H_COUNT_SHIFT);
base->VDCTRL0 = LCDIF_VDCTRL0_ENABLE_PRESENT_MASK | /* Data enable signal. */
LCDIF_VDCTRL0_VSYNC_PERIOD_UNIT_MASK | /* VSYNC period in the unit of display clock. */
LCDIF_VDCTRL0_VSYNC_PULSE_WIDTH_UNIT_MASK | /* VSYNC pulse width in the unit of display clock. */
(uint32_t)config->polarityFlags | (uint32_t)config->vsw;
base->VDCTRL1 = config->vsw + config->panelHeight + config->vfp + config->vbp;
base->VDCTRL2 = ((uint32_t)config->hsw << LCDIF_VDCTRL2_HSYNC_PULSE_WIDTH_SHIFT) |
((uint32_t)(config->hfp + config->hbp + config->panelWidth + config->hsw))
<< LCDIF_VDCTRL2_HSYNC_PERIOD_SHIFT;
base->VDCTRL3 = (((uint32_t)config->hbp + config->hsw) << LCDIF_VDCTRL3_HORIZONTAL_WAIT_CNT_SHIFT) |
(((uint32_t)config->vbp + config->vsw) << LCDIF_VDCTRL3_VERTICAL_WAIT_CNT_SHIFT);
base->VDCTRL4 = LCDIF_VDCTRL4_SYNC_SIGNALS_ON_MASK |
((uint32_t)config->panelWidth << LCDIF_VDCTRL4_DOTCLK_H_VALID_DATA_CNT_SHIFT);
base->CUR_BUF = config->bufferAddr;
base->NEXT_BUF = config->bufferAddr;
}
void ELCDIF_RgbModeGetDefaultConfig(elcdif_rgb_mode_config_t *config)
{
assert(config);
config->panelWidth = 480U;
config->panelHeight = 272U;
config->hsw = 41;
config->hfp = 4;
config->hbp = 8;
config->vsw = 10;
config->vfp = 4;
config->vbp = 2;
config->polarityFlags = kELCDIF_VsyncActiveLow | kELCDIF_HsyncActiveLow | kELCDIF_DataEnableActiveLow |
kELCDIF_DriveDataOnFallingClkEdge;
config->bufferAddr = 0U;
config->pixelFormat = kELCDIF_PixelFormatRGB888;
config->dataBus = kELCDIF_DataBus24Bit;
}
void ELCDIF_Deinit(LCDIF_Type *base)
{
ELCDIF_Reset(base);
#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
uint32_t instance = ELCDIF_GetInstance(base);
/* Disable the clock. */
#if defined(LCDIF_PERIPH_CLOCKS)
CLOCK_DisableClock(s_elcdifPixClocks[instance]);
#endif
CLOCK_DisableClock(s_elcdifApbClocks[instance]);
#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
}
void ELCDIF_RgbModeStop(LCDIF_Type *base)
{
base->CTRL_CLR = LCDIF_CTRL_DOTCLK_MODE_MASK;
/* Wait for data transfer finished. */
while (base->CTRL & LCDIF_CTRL_DOTCLK_MODE_MASK)
{
}
}
void ELCDIF_Reset(LCDIF_Type *base)
{
volatile uint32_t i = 0x100;
/* Disable the clock gate. */
base->CTRL_CLR = LCDIF_CTRL_CLKGATE_MASK;
/* Confirm the clock gate is disabled. */
while (base->CTRL & LCDIF_CTRL_CLKGATE_MASK)
{
}
/* Reset the block. */
base->CTRL_SET = LCDIF_CTRL_SFTRST_MASK;
/* Confirm the reset bit is set. */
while (!(base->CTRL & LCDIF_CTRL_SFTRST_MASK))
{
}
/* Delay for the reset. */
while (i--)
{
}
/* Bring the module out of reset. */
base->CTRL_CLR = LCDIF_CTRL_SFTRST_MASK;
/* Disable the clock gate. */
base->CTRL_CLR = LCDIF_CTRL_CLKGATE_MASK;
}
#if !(defined(FSL_FEATURE_LCDIF_HAS_NO_AS) && FSL_FEATURE_LCDIF_HAS_NO_AS)
void ELCDIF_SetAlphaSurfaceBufferConfig(LCDIF_Type *base, const elcdif_as_buffer_config_t *config)
{
assert(config);
base->AS_CTRL = (base->AS_CTRL & ~LCDIF_AS_CTRL_FORMAT_MASK) | LCDIF_AS_CTRL_FORMAT(config->pixelFormat);
base->AS_BUF = config->bufferAddr;
base->AS_NEXT_BUF = config->bufferAddr;
}
void ELCDIF_SetAlphaSurfaceBlendConfig(LCDIF_Type *base, const elcdif_as_blend_config_t *config)
{
assert(config);
uint32_t reg;
reg = base->AS_CTRL;
reg &= ~(LCDIF_AS_CTRL_ALPHA_INVERT_MASK | LCDIF_AS_CTRL_ROP_MASK | LCDIF_AS_CTRL_ALPHA_MASK |
LCDIF_AS_CTRL_ALPHA_CTRL_MASK);
reg |= (LCDIF_AS_CTRL_ROP(config->ropMode) | LCDIF_AS_CTRL_ALPHA(config->alpha) |
LCDIF_AS_CTRL_ALPHA_CTRL(config->alphaMode));
if (config->invertAlpha)
{
reg |= LCDIF_AS_CTRL_ALPHA_INVERT_MASK;
}
base->AS_CTRL = reg;
}
#endif /* FSL_FEATURE_LCDIF_HAS_NO_AS */
#if (defined(FSL_FEATURE_LCDIF_HAS_LUT) && FSL_FEATURE_LCDIF_HAS_LUT)
status_t ELCDIF_UpdateLut(
LCDIF_Type *base, elcdif_lut_t lut, uint16_t startIndex, const uint32_t *lutData, uint16_t count)
{
volatile uint32_t *regLutAddr;
volatile uint32_t *regLutData;
uint32_t i;
/* Only has 256 entries. */
if (startIndex + count > ELCDIF_LUT_ENTRY_NUM)
{
return kStatus_InvalidArgument;
}
if (kELCDIF_Lut0 == lut)
{
regLutAddr = &(base->LUT0_ADDR);
regLutData = &(base->LUT0_DATA);
}
else
{
regLutAddr = &(base->LUT1_ADDR);
regLutData = &(base->LUT1_DATA);
}
*regLutAddr = startIndex;
for (i = 0; i < count; i++)
{
*regLutData = lutData[i];
for (volatile uint32_t j = 0; j < 0x80; j++)
{
}
}
return kStatus_Success;
}
#endif /* FSL_FEATURE_LCDIF_HAS_LUT */

View File

@ -0,0 +1,764 @@
/*
* Copyright (c) 2017, NXP Semiconductors, 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 the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _FSL_ELCDIF_H_
#define _FSL_ELCDIF_H_
#include "fsl_common.h"
/*!
* @addtogroup elcdif
* @{
*/
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @name Driver version */
/*@{*/
/*! @brief eLCDIF driver version */
#define FSL_ELCDIF_DRIVER_VERSION (MAKE_VERSION(2, 0, 0)) /*!< Version 2.0.0. */
/*@}*/
/* All IRQ flags in CTRL1 register. */
#define ELCDIF_CTRL1_IRQ_MASK \
(LCDIF_CTRL1_BM_ERROR_IRQ_MASK | LCDIF_CTRL1_OVERFLOW_IRQ_MASK | LCDIF_CTRL1_UNDERFLOW_IRQ_MASK | \
LCDIF_CTRL1_CUR_FRAME_DONE_IRQ_MASK | LCDIF_CTRL1_VSYNC_EDGE_IRQ_MASK)
/* All IRQ enable control bits in CTRL1 register. */
#define ELCDIF_CTRL1_IRQ_EN_MASK \
(LCDIF_CTRL1_BM_ERROR_IRQ_EN_MASK | LCDIF_CTRL1_OVERFLOW_IRQ_EN_MASK | LCDIF_CTRL1_UNDERFLOW_IRQ_EN_MASK | \
LCDIF_CTRL1_CUR_FRAME_DONE_IRQ_EN_MASK | LCDIF_CTRL1_VSYNC_EDGE_IRQ_EN_MASK)
/* All IRQ flags in AS_CTRL register. */
#if defined(LCDIF_AS_CTRL_CSI_SYNC_ON_IRQ_MASK)
#define ELCDIF_AS_CTRL_IRQ_MASK (LCDIF_AS_CTRL_CSI_SYNC_ON_IRQ_MASK)
#else
#define ELCDIF_AS_CTRL_IRQ_MASK 0U
#endif
/* All IRQ enable control bits in AS_CTRL register. */
#if defined(LCDIF_AS_CTRL_CSI_SYNC_ON_IRQ_EN_MASK)
#define ELCDIF_AS_CTRL_IRQ_EN_MASK (LCDIF_AS_CTRL_CSI_SYNC_ON_IRQ_EN_MASK)
#else
#define ELCDIF_AS_CTRL_IRQ_EN_MASK 0U
#endif
#if ((ELCDIF_CTRL1_IRQ_MASK & ELCDIF_AS_CTRL_IRQ_MASK) || (ELCDIF_AS_CTRL_IRQ_MASK & ELCDIF_AS_CTRL_IRQ_EN_MASK))
#error Interrupt bits overlap, need to update the interrupt functions.
#endif
/* LUT memory entery number. */
#define ELCDIF_LUT_ENTRY_NUM 256
/*!
* @brief eLCDIF signal polarity flags
*/
enum _elcdif_polarity_flags
{
kELCDIF_VsyncActiveLow = 0U, /*!< VSYNC active low. */
kELCDIF_VsyncActiveHigh = LCDIF_VDCTRL0_VSYNC_POL_MASK, /*!< VSYNC active high. */
kELCDIF_HsyncActiveLow = 0U, /*!< HSYNC active low. */
kELCDIF_HsyncActiveHigh = LCDIF_VDCTRL0_HSYNC_POL_MASK, /*!< HSYNC active high. */
kELCDIF_DataEnableActiveLow = 0U, /*!< Data enable line active low. */
kELCDIF_DataEnableActiveHigh = LCDIF_VDCTRL0_ENABLE_POL_MASK, /*!< Data enable line active high. */
kELCDIF_DriveDataOnFallingClkEdge = 0U, /*!< Drive data on falling clock edge, capture data
on rising clock edge. */
kELCDIF_DriveDataOnRisingClkEdge = LCDIF_VDCTRL0_DOTCLK_POL_MASK, /*!< Drive data on falling
clock edge, capture data
on rising clock edge. */
};
/*!
* @brief The eLCDIF interrupts to enable.
*/
enum _elcdif_interrupt_enable
{
kELCDIF_BusMasterErrorInterruptEnable = LCDIF_CTRL1_BM_ERROR_IRQ_EN_MASK, /*!< Bus master error interrupt. */
kELCDIF_TxFifoOverflowInterruptEnable = LCDIF_CTRL1_OVERFLOW_IRQ_EN_MASK, /*!< TXFIFO overflow interrupt. */
kELCDIF_TxFifoUnderflowInterruptEnable = LCDIF_CTRL1_UNDERFLOW_IRQ_EN_MASK, /*!< TXFIFO underflow interrupt. */
kELCDIF_CurFrameDoneInterruptEnable =
LCDIF_CTRL1_CUR_FRAME_DONE_IRQ_EN_MASK, /*!< Interrupt when hardware enters vertical blanking state. */
kELCDIF_VsyncEdgeInterruptEnable =
LCDIF_CTRL1_VSYNC_EDGE_IRQ_EN_MASK, /*!< Interrupt when hardware encounters VSYNC edge. */
#if defined(LCDIF_AS_CTRL_CSI_SYNC_ON_IRQ_EN_MASK)
kELCDIF_SciSyncOnInterruptEnable =
LCDIF_AS_CTRL_CSI_SYNC_ON_IRQ_EN_MASK, /*!< Interrupt when eLCDIF lock with CSI input. */
#endif
};
/*!
* @brief The eLCDIF interrupt status flags.
*/
enum _elcdif_interrupt_flags
{
kELCDIF_BusMasterError = LCDIF_CTRL1_BM_ERROR_IRQ_MASK, /*!< Bus master error interrupt. */
kELCDIF_TxFifoOverflow = LCDIF_CTRL1_OVERFLOW_IRQ_MASK, /*!< TXFIFO overflow interrupt. */
kELCDIF_TxFifoUnderflow = LCDIF_CTRL1_UNDERFLOW_IRQ_MASK, /*!< TXFIFO underflow interrupt. */
kELCDIF_CurFrameDone =
LCDIF_CTRL1_CUR_FRAME_DONE_IRQ_MASK, /*!< Interrupt when hardware enters vertical blanking state. */
kELCDIF_VsyncEdge = LCDIF_CTRL1_VSYNC_EDGE_IRQ_MASK, /*!< Interrupt when hardware encounters VSYNC edge. */
#if defined(LCDIF_AS_CTRL_CSI_SYNC_ON_IRQ_MASK)
kELCDIF_SciSyncOn = LCDIF_AS_CTRL_CSI_SYNC_ON_IRQ_MASK, /*!< Interrupt when eLCDIF lock with CSI input. */
#endif
};
/*!
* @brief eLCDIF status flags
*/
enum _elcdif_status_flags
{
kELCDIF_LFifoFull = LCDIF_STAT_LFIFO_FULL_MASK, /*!< LFIFO full. */
kELCDIF_LFifoEmpty = LCDIF_STAT_LFIFO_EMPTY_MASK, /*!< LFIFO empty. */
kELCDIF_TxFifoFull = LCDIF_STAT_TXFIFO_FULL_MASK, /*!< TXFIFO full. */
kELCDIF_TxFifoEmpty = LCDIF_STAT_TXFIFO_EMPTY_MASK, /*!< TXFIFO empty. */
#if defined(LCDIF_STAT_BUSY_MASK)
kELCDIF_LcdControllerBusy = LCDIF_STAT_BUSY_MASK, /*!< The external LCD controller busy signal. */
#endif
#if defined(LCDIF_STAT_DVI_CURRENT_FIELD_MASK)
kELCDIF_CurDviField2 = LCDIF_STAT_DVI_CURRENT_FIELD_MASK, /*!< Current DVI filed, if set, then current filed is 2,
otherwise current filed is 1. */
#endif
};
/*!
* @brief The pixel format.
*
* This enumerator should be defined together with the array s_pixelFormatReg.
* To support new pixel format, enhance this enumerator and s_pixelFormatReg.
*/
typedef enum _elcdif_pixel_format
{
kELCDIF_PixelFormatRAW8 = 0, /*!< RAW 8 bit, four data use 32 bits. */
kELCDIF_PixelFormatRGB565 = 1, /*!< RGB565, two pixel use 32 bits. */
kELCDIF_PixelFormatRGB666 = 2, /*!< RGB666 unpacked, one pixel uses 32 bits, high byte unused,
upper 2 bits of other bytes unused. */
kELCDIF_PixelFormatXRGB8888 = 3, /*!< XRGB8888 unpacked, one pixel uses 32 bits, high byte unused. */
kELCDIF_PixelFormatRGB888 = 4, /*!< RGB888 packed, one pixel uses 24 bits. */
} elcdif_pixel_format_t;
/*! @brief The LCD data bus type. */
typedef enum _elcdif_lcd_data_bus
{
kELCDIF_DataBus8Bit = LCDIF_CTRL_LCD_DATABUS_WIDTH(1), /*!< 8-bit data bus. */
kELCDIF_DataBus16Bit = LCDIF_CTRL_LCD_DATABUS_WIDTH(0), /*!< 16-bit data bus, support RGB565. */
kELCDIF_DataBus18Bit = LCDIF_CTRL_LCD_DATABUS_WIDTH(2), /*!< 18-bit data bus, support RGB666. */
kELCDIF_DataBus24Bit = LCDIF_CTRL_LCD_DATABUS_WIDTH(3), /*!< 24-bit data bus, support RGB888. */
} elcdif_lcd_data_bus_t;
/*!
* @brief The register value when using different pixel format.
*
* These register bits control the pixel format:
* - CTRL[DATA_FORMAT_24_BIT]
* - CTRL[DATA_FORMAT_18_BIT]
* - CTRL[DATA_FORMAT_16_BIT]
* - CTRL[WORD_LENGTH]
* - CTRL1[BYTE_PACKING_FORMAT]
*/
typedef struct _elcdif_pixel_format_reg
{
uint32_t regCtrl; /*!< Value of register CTRL. */
uint32_t regCtrl1; /*!< Value of register CTRL1. */
} elcdif_pixel_format_reg_t;
/*!
* @brief eLCDIF configure structure for RGB mode (DOTCLK mode).
*/
typedef struct _elcdif_rgb_mode_config
{
uint16_t panelWidth; /*!< Display panel width, pixels per line. */
uint16_t panelHeight; /*!< Display panel height, how many lines per panel. */
uint8_t hsw; /*!< HSYNC pulse width. */
uint8_t hfp; /*!< Horizontal front porch. */
uint8_t hbp; /*!< Horizontal back porch. */
uint8_t vsw; /*!< VSYNC pulse width. */
uint8_t vfp; /*!< Vrtical front porch. */
uint8_t vbp; /*!< Vertical back porch. */
uint32_t polarityFlags; /*!< OR'ed value of @ref _elcdif_polarity_flags, used to contol the signal polarity. */
uint32_t bufferAddr; /*!< Frame buffer address. */
elcdif_pixel_format_t pixelFormat; /*!< Pixel format. */
elcdif_lcd_data_bus_t dataBus; /*!< LCD data bus. */
} elcdif_rgb_mode_config_t;
/*!
* @brief eLCDIF alpha surface pixel format.
*/
typedef enum _elcdif_as_pixel_format
{
kELCDIF_AsPixelFormatARGB8888 = 0x0, /*!< 32-bit pixels with alpha. */
kELCDIF_AsPixelFormatRGB888 = 0x4, /*!< 32-bit pixels without alpha (unpacked 24-bit format) */
kELCDIF_AsPixelFormatARGB1555 = 0x8, /*!< 16-bit pixels with alpha. */
kELCDIF_AsPixelFormatARGB4444 = 0x9, /*!< 16-bit pixels with alpha. */
kELCDIF_AsPixelFormatRGB555 = 0xC, /*!< 16-bit pixels without alpha. */
kELCDIF_AsPixelFormatRGB444 = 0xD, /*!< 16-bit pixels without alpha. */
kELCDIF_AsPixelFormatRGB565 = 0xE, /*!< 16-bit pixels without alpha. */
} elcdif_as_pixel_format_t;
/*!
* @brief eLCDIF alpha surface buffer configuration.
*/
typedef struct _elcdif_as_buffer_config
{
uint32_t bufferAddr; /*!< Buffer address. */
elcdif_as_pixel_format_t pixelFormat; /*!< Pixel format. */
} elcdif_as_buffer_config_t;
/*!
* @brief eLCDIF alpha mode during blending.
*/
typedef enum _elcdif_alpha_mode
{
kELCDIF_AlphaEmbedded, /*!< The alpha surface pixel alpha value will be used for blend. */
kELCDIF_AlphaOverride, /*!< The user defined alpha value will be used for blend directly. */
kELCDIF_AlphaMultiply, /*!< The alpha surface pixel alpha value scaled the user defined
alpha value will be used for blend, for example, pixel alpha set
set to 200, user defined alpha set to 100, then the reault alpha
is 200 * 100 / 255. */
kELCDIF_AlphaRop /*!< Raster operation. */
} elcdif_alpha_mode_t;
/*!
* @brief eLCDIF ROP mode during blending.
*
* Explanation:
* - AS: Alpha surface
* - PS: Process surface
* - nAS: Alpha surface NOT value
* - nPS: Process surface NOT value
*/
typedef enum _elcdif_rop_mode
{
kELCDIF_RopMaskAs = 0x0, /*!< AS AND PS. */
kELCDIF_RopMaskNotAs = 0x1, /*!< nAS AND PS. */
kELCDIF_RopMaskAsNot = 0x2, /*!< AS AND nPS. */
kELCDIF_RopMergeAs = 0x3, /*!< AS OR PS. */
kELCDIF_RopMergeNotAs = 0x4, /*!< nAS OR PS. */
kELCDIF_RopMergeAsNot = 0x5, /*!< AS OR nPS. */
kELCDIF_RopNotCopyAs = 0x6, /*!< nAS. */
kELCDIF_RopNot = 0x7, /*!< nPS. */
kELCDIF_RopNotMaskAs = 0x8, /*!< AS NAND PS. */
kELCDIF_RopNotMergeAs = 0x9, /*!< AS NOR PS. */
kELCDIF_RopXorAs = 0xA, /*!< AS XOR PS. */
kELCDIF_RopNotXorAs = 0xB /*!< AS XNOR PS. */
} elcdif_rop_mode_t;
/*!
* @brief eLCDIF alpha surface blending configuration.
*/
typedef struct _elcdif_as_blend_config
{
uint8_t alpha; /*!< User defined alpha value, only used when @ref alphaMode is @ref kELCDIF_AlphaOverride or @ref
kELCDIF_AlphaRop. */
bool invertAlpha; /*!< Set true to invert the alpha. */
elcdif_alpha_mode_t alphaMode; /*!< Alpha mode. */
elcdif_rop_mode_t ropMode; /*!< ROP mode, only valid when @ref alphaMode is @ref kELCDIF_AlphaRop. */
} elcdif_as_blend_config_t;
/*!
* @brief eLCDIF LUT
*
* The Lookup Table (LUT) is used to expand the 8 bits pixel to 24 bits pixel
* before output to external displayer.
*
* There are two 256x24 bits LUT memory in LCDIF, the LSB of frame buffer address
* determins which memory to use.
*/
typedef enum _elcdif_lut
{
kELCDIF_Lut0 = 0, /*!< LUT 0. */
kELCDIF_Lut1, /*!< LUT 1. */
} elcdif_lut_t;
/*******************************************************************************
* APIs
******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif /* __cplusplus */
/*!
* @name eLCDIF initialization and de-initialization
* @{
*/
/*!
* @brief Initializes the eLCDIF to work in RGB mode (DOTCLK mode).
*
* This function ungates the eLCDIF clock and configures the eLCDIF peripheral according
* to the configuration structure.
*
* @param base eLCDIF peripheral base address.
* @param config Pointer to the configuration structure.
*/
void ELCDIF_RgbModeInit(LCDIF_Type *base, const elcdif_rgb_mode_config_t *config);
/*!
* @brief Gets the eLCDIF default configuration structure for RGB (DOTCLK) mode.
*
* This function sets the configuration structure to default values.
* The default configuration is set to the following values.
* @code
config->panelWidth = 480U;
config->panelHeight = 272U;
config->hsw = 41;
config->hfp = 4;
config->hbp = 8;
config->vsw = 10;
config->vfp = 4;
config->vbp = 2;
config->polarityFlags = kELCDIF_VsyncActiveLow |
kELCDIF_HsyncActiveLow |
kELCDIF_DataEnableActiveLow |
kELCDIF_DriveDataOnFallingClkEdge;
config->bufferAddr = 0U;
config->pixelFormat = kELCDIF_PixelFormatRGB888;
config->dataBus = kELCDIF_DataBus24Bit;
@code
*
* @param config Pointer to the eLCDIF configuration structure.
*/
void ELCDIF_RgbModeGetDefaultConfig(elcdif_rgb_mode_config_t *config);
/*!
* @brief Deinitializes the eLCDIF peripheral.
*
* @param base eLCDIF peripheral base address.
*/
void ELCDIF_Deinit(LCDIF_Type *base);
/* @} */
/*!
* @name Module operation
* @{
*/
/*!
* @brief Start to display in RGB (DOTCLK) mode.
*
* @param base eLCDIF peripheral base address.
*/
static inline void ELCDIF_RgbModeStart(LCDIF_Type *base)
{
base->CTRL_SET = LCDIF_CTRL_RUN_MASK | LCDIF_CTRL_DOTCLK_MODE_MASK;
}
/*!
* @brief Stop display in RGB (DOTCLK) mode and wait until finished.
*
* @param base eLCDIF peripheral base address.
*/
void ELCDIF_RgbModeStop(LCDIF_Type *base);
/*!
* @brief Set the next frame buffer address to display.
*
* @param base eLCDIF peripheral base address.
* @param bufferAddr The frame buffer address to set.
*/
static inline void ELCDIF_SetNextBufferAddr(LCDIF_Type *base, uint32_t bufferAddr)
{
base->NEXT_BUF = bufferAddr;
}
/*!
* @brief Reset the eLCDIF peripheral.
*
* @param base eLCDIF peripheral base address.
*/
void ELCDIF_Reset(LCDIF_Type *base);
#if !(defined(FSL_FEATURE_LCDIF_HAS_NO_RESET_PIN) && FSL_FEATURE_LCDIF_HAS_NO_RESET_PIN)
/*!
* @brief Pull up or down the reset pin for the externel LCD controller.
*
* @param base eLCDIF peripheral base address.
* @param pullUp True to pull up reset pin, false to pull down.
*/
static inline void ELCDIF_PullUpResetPin(LCDIF_Type *base, bool pullUp)
{
if (pullUp)
{
base->CTRL1_SET = LCDIF_CTRL1_RESET_MASK;
}
else
{
base->CTRL1_CLR = LCDIF_CTRL1_RESET_MASK;
}
}
#endif
/*!
* @brief Enable or disable the hand shake with PXP.
*
* @param base eLCDIF peripheral base address.
* @param enable True to enable, false to disable.
*/
static inline void ELCDIF_EnablePxpHandShake(LCDIF_Type *base, bool enable)
{
if (enable)
{
base->CTRL_SET = LCDIF_CTRL_ENABLE_PXP_HANDSHAKE_MASK;
}
else
{
base->CTRL_CLR = LCDIF_CTRL_ENABLE_PXP_HANDSHAKE_MASK;
}
}
/* @} */
/*!
* @name Status
* @{
*/
/*!
* @brief Get the CRC value of the frame sent out.
*
* When a frame is sent complete (the interrupt @ref kELCDIF_CurFrameDone assert), this function
* can be used to get the CRC value of the frame sent.
*
* @param base eLCDIF peripheral base address.
* @return The CRC value.
*
* @note The CRC value is dependent on the LCD_DATABUS_WIDTH.
*/
static inline uint32_t ELCDIF_GetCrcValue(LCDIF_Type *base)
{
return base->CRC_STAT;
}
/*!
* @brief Get the bus master error virtual address.
*
* When bus master error occurs (the interrupt kELCDIF_BusMasterError assert), this function
* can get the virtual address at which the AXI master received an error
* response from the slave.
*
* @param base eLCDIF peripheral base address.
* @return The error virtual address.
*/
static inline uint32_t ELCDIF_GetBusMasterErrorAddr(LCDIF_Type *base)
{
return base->BM_ERROR_STAT;
}
/*!
* @brief Get the eLCDIF status.
*
* The status flags are returned as a mask value, application could check the
* corresponding bit. Example:
*
* @code
uint32_t statusFlags;
statusFlags = ELCDIF_GetStatus(LCDIF);
// If LFIFO is full.
if (kELCDIF_LFifoFull & statusFlags)
{
// ...;
}
// If TXFIFO is empty.
if (kELCDIF_TxFifoEmpty & statusFlags)
{
// ...;
}
@endcode
*
* @param base eLCDIF peripheral base address.
* @return The mask value of status flags, it is OR'ed value of @ref _elcdif_status_flags.
*/
static inline uint32_t ELCDIF_GetStatus(LCDIF_Type *base)
{
return base->STAT & (LCDIF_STAT_LFIFO_FULL_MASK | LCDIF_STAT_LFIFO_EMPTY_MASK | LCDIF_STAT_TXFIFO_FULL_MASK |
LCDIF_STAT_TXFIFO_EMPTY_MASK
#if defined(LCDIF_STAT_BUSY_MASK)
| LCDIF_STAT_BUSY_MASK
#endif
#if defined(LCDIF_STAT_DVI_CURRENT_FIELD_MASK)
| LCDIF_STAT_DVI_CURRENT_FIELD_MASK
#endif
);
}
/*!
* @brief Get current count in Latency buffer (LFIFO).
*
* @param base eLCDIF peripheral base address.
* @return The LFIFO current count
*/
static inline uint32_t ELCDIF_GetLFifoCount(LCDIF_Type *base)
{
return (base->STAT & LCDIF_STAT_LFIFO_COUNT_MASK) >> LCDIF_STAT_LFIFO_COUNT_SHIFT;
}
/* @} */
/*!
* @name Interrupts
* @{
*/
/*!
* @brief Enables eLCDIF interrupt requests.
*
* @param base eLCDIF peripheral base address.
* @param mask interrupt source, OR'ed value of _elcdif_interrupt_enable.
*/
static inline void ELCDIF_EnableInterrupts(LCDIF_Type *base, uint32_t mask)
{
base->CTRL1_SET = (mask & ELCDIF_CTRL1_IRQ_EN_MASK);
#if !(defined(FSL_FEATURE_LCDIF_HAS_NO_AS) && FSL_FEATURE_LCDIF_HAS_NO_AS)
base->AS_CTRL |= (mask & ELCDIF_AS_CTRL_IRQ_EN_MASK);
#endif
}
/*!
* @brief Disables eLCDIF interrupt requests.
*
* @param base eLCDIF peripheral base address.
* @param mask interrupt source, OR'ed value of _elcdif_interrupt_enable.
*/
static inline void ELCDIF_DisableInterrupts(LCDIF_Type *base, uint32_t mask)
{
base->CTRL1_CLR = (mask & ELCDIF_CTRL1_IRQ_EN_MASK);
#if !(defined(FSL_FEATURE_LCDIF_HAS_NO_AS) && FSL_FEATURE_LCDIF_HAS_NO_AS)
base->AS_CTRL &= ~(mask & ELCDIF_AS_CTRL_IRQ_EN_MASK);
#endif
}
/*!
* @brief Get eLCDIF interrupt peding status.
*
* @param base eLCDIF peripheral base address.
* @return Interrupt pending status, OR'ed value of _elcdif_interrupt_flags.
*/
static inline uint32_t ELCDIF_GetInterruptStatus(LCDIF_Type *base)
{
uint32_t flags;
flags = (base->CTRL1 & ELCDIF_CTRL1_IRQ_MASK);
#if !(defined(FSL_FEATURE_LCDIF_HAS_NO_AS) && FSL_FEATURE_LCDIF_HAS_NO_AS)
flags |= (base->AS_CTRL & ELCDIF_AS_CTRL_IRQ_MASK);
#endif
return flags;
}
/*!
* @brief Clear eLCDIF interrupt peding status.
*
* @param base eLCDIF peripheral base address.
* @param mask of the flags to clear, OR'ed value of _elcdif_interrupt_flags.
*/
static inline void ELCDIF_ClearInterruptStatus(LCDIF_Type *base, uint32_t mask)
{
base->CTRL1_CLR = (mask & ELCDIF_CTRL1_IRQ_MASK);
#if !(defined(FSL_FEATURE_LCDIF_HAS_NO_AS) && FSL_FEATURE_LCDIF_HAS_NO_AS)
base->AS_CTRL &= ~(mask & ELCDIF_AS_CTRL_IRQ_MASK);
#endif
}
/* @} */
#if !(defined(FSL_FEATURE_LCDIF_HAS_NO_AS) && FSL_FEATURE_LCDIF_HAS_NO_AS)
/*!
* @name Alpha surface
* @{
*/
/*!
* @brief Set the configuration for alpha surface buffer.
*
* @param base eLCDIF peripheral base address.
* @param config Pointer to the configuration structure.
*/
void ELCDIF_SetAlphaSurfaceBufferConfig(LCDIF_Type *base, const elcdif_as_buffer_config_t *config);
/*!
* @brief Set the alpha surface blending configuration.
*
* @param base eLCDIF peripheral base address.
* @param config Pointer to the configuration structure.
*/
void ELCDIF_SetAlphaSurfaceBlendConfig(LCDIF_Type *base, const elcdif_as_blend_config_t *config);
/*!
* @brief Set the next alpha surface buffer address.
*
* @param base eLCDIF peripheral base address.
* @param bufferAddr Alpha surface buffer address.
*/
static inline void ELCDIF_SetNextAlphaSurfaceBufferAddr(LCDIF_Type *base, uint32_t bufferAddr)
{
base->AS_NEXT_BUF = bufferAddr;
}
/*!
* @brief Set the overlay color key.
*
* If a pixel in the current overlay image with a color that falls in the range
* from the @p colorKeyLow to @p colorKeyHigh range, it will use the process surface
* pixel value for that location.
*
* @param base eLCDIF peripheral base address.
* @param colorKeyLow Color key low range.
* @param colorKeyHigh Color key high range.
*
* @note Colorkey operations are higher priority than alpha or ROP operations
*/
static inline void ELCDIF_SetOverlayColorKey(LCDIF_Type *base, uint32_t colorKeyLow, uint32_t colorKeyHigh)
{
base->AS_CLRKEYLOW = colorKeyLow;
base->AS_CLRKEYHIGH = colorKeyHigh;
}
/*!
* @brief Enable or disable the color key.
*
* @param base eLCDIF peripheral base address.
* @param enable True to enable, false to disable.
*/
static inline void ELCDIF_EnableOverlayColorKey(LCDIF_Type *base, bool enable)
{
if (enable)
{
base->AS_CTRL |= LCDIF_AS_CTRL_ENABLE_COLORKEY_MASK;
}
else
{
base->AS_CTRL &= ~LCDIF_AS_CTRL_ENABLE_COLORKEY_MASK;
}
}
/*!
* @brief Enable or disable the alpha surface.
*
* @param base eLCDIF peripheral base address.
* @param enable True to enable, false to disable.
*/
static inline void ELCDIF_EnableAlphaSurface(LCDIF_Type *base, bool enable)
{
if (enable)
{
base->AS_CTRL |= LCDIF_AS_CTRL_AS_ENABLE_MASK;
}
else
{
base->AS_CTRL &= ~LCDIF_AS_CTRL_AS_ENABLE_MASK;
}
}
/*!
* @brief Enable or disable the process surface.
*
* Process surface is the normal frame buffer. The process surface content
* is controlled by @ref ELCDIF_SetNextBufferAddr.
*
* @param base eLCDIF peripheral base address.
* @param enable True to enable, false to disable.
*/
static inline void ELCDIF_EnableProcessSurface(LCDIF_Type *base, bool enable)
{
if (enable)
{
base->AS_CTRL &= ~LCDIF_AS_CTRL_PS_DISABLE_MASK;
}
else
{
base->AS_CTRL |= LCDIF_AS_CTRL_PS_DISABLE_MASK;
}
}
/* @} */
#endif /* FSL_FEATURE_LCDIF_HAS_NO_AS */
#if (defined(FSL_FEATURE_LCDIF_HAS_LUT) && FSL_FEATURE_LCDIF_HAS_LUT)
/*!
* @name LUT
*
* The Lookup Table (LUT) is used to expand the 8 bits pixel to 24 bits pixel
* before output to external displayer.
*
* There are two 256x24 bits LUT memory in LCDIF, the LSB of frame buffer address
* determins which memory to use.
*
* @{
*/
/*!
* @brief Enable or disable the LUT.
*
* @param base eLCDIF peripheral base address.
* @param enable True to enable, false to disable.
*/
static inline void ELCDIF_EnableLut(LCDIF_Type *base, bool enable)
{
if (enable)
{
base->LUT_CTRL &= ~LCDIF_LUT_CTRL_LUT_BYPASS_MASK;
}
else
{
base->LUT_CTRL |= LCDIF_LUT_CTRL_LUT_BYPASS_MASK;
}
}
/*!
* @brief Load the LUT value.
*
* This function loads the LUT value to the specific LUT memory, user can
* specify the start entry index.
*
* @param base eLCDIF peripheral base address.
* @param lut Which LUT to load.
* @param startIndex The start index of the LUT entry to update.
* @param lutData The LUT data to load.
* @param count Count of @p lutData.
* @retval kStatus_Success Initialization success.
* @retval kStatus_InvalidArgument Wrong argument.
*/
status_t ELCDIF_UpdateLut(
LCDIF_Type *base, elcdif_lut_t lut, uint16_t startIndex, const uint32_t *lutData, uint16_t count);
/* @} */
#endif /* FSL_FEATURE_LCDIF_HAS_LUT */
#if defined(__cplusplus)
}
#endif /* __cplusplus */
/* @} */
#endif /*_FSL_ELCDIF_H_*/

View File

@ -0,0 +1,479 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* Copyright 2016-2017 NXP
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include "fsl_enc.h"
/*******************************************************************************
* Definitions
******************************************************************************/
#define ENC_CTRL_W1C_FLAGS (ENC_CTRL_HIRQ_MASK | ENC_CTRL_XIRQ_MASK | ENC_CTRL_DIRQ_MASK | ENC_CTRL_CMPIRQ_MASK)
#define ENC_CTRL2_W1C_FLAGS (ENC_CTRL2_SABIRQ_MASK | ENC_CTRL2_ROIRQ_MASK | ENC_CTRL2_RUIRQ_MASK)
/*******************************************************************************
* Prototypes
******************************************************************************/
/*!
* @brief Get instance number for ENC module.
*
* @param base ENC peripheral base address
*/
static uint32_t ENC_GetInstance(ENC_Type *base);
/*******************************************************************************
* Variables
******************************************************************************/
/*! @brief Pointers to ENC bases for each instance. */
static ENC_Type *const s_encBases[] = ENC_BASE_PTRS;
#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
/*! @brief Pointers to ENC clocks for each instance. */
static const clock_ip_name_t s_encClocks[] = ENC_CLOCKS;
#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
/*******************************************************************************
* Code
******************************************************************************/
static uint32_t ENC_GetInstance(ENC_Type *base)
{
uint32_t instance;
/* Find the instance index from base address mappings. */
for (instance = 0; instance < ARRAY_SIZE(s_encBases); instance++)
{
if (s_encBases[instance] == base)
{
break;
}
}
assert(instance < ARRAY_SIZE(s_encBases));
return instance;
}
void ENC_Init(ENC_Type *base, const enc_config_t *config)
{
assert(NULL != config);
uint32_t tmp16;
#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
/* Enable the clock. */
CLOCK_EnableClock(s_encClocks[ENC_GetInstance(base)]);
#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
/* ENC_CTRL. */
tmp16 = base->CTRL & (uint16_t)(~(ENC_CTRL_W1C_FLAGS | ENC_CTRL_HIP_MASK | ENC_CTRL_HNE_MASK | ENC_CTRL_REV_MASK |
ENC_CTRL_PH1_MASK | ENC_CTRL_XIP_MASK | ENC_CTRL_XNE_MASK | ENC_CTRL_WDE_MASK));
/* For HOME trigger. */
if (kENC_HOMETriggerDisabled != config->HOMETriggerMode)
{
tmp16 |= ENC_CTRL_HIP_MASK;
if (kENC_HOMETriggerOnFallingEdge == config->HOMETriggerMode)
{
tmp16 |= ENC_CTRL_HNE_MASK;
}
}
/* For encoder work mode. */
if (config->enableReverseDirection)
{
tmp16 |= ENC_CTRL_REV_MASK;
}
if (kENC_DecoderWorkAsSignalPhaseCountMode == config->decoderWorkMode)
{
tmp16 |= ENC_CTRL_PH1_MASK;
}
/* For INDEX trigger. */
if (kENC_INDEXTriggerDisabled != config->INDEXTriggerMode)
{
tmp16 |= ENC_CTRL_XIP_MASK;
if (kENC_INDEXTriggerOnFallingEdge == config->INDEXTriggerMode)
{
tmp16 |= ENC_CTRL_XNE_MASK;
}
}
/* Watchdog. */
if (config->enableWatchdog)
{
tmp16 |= ENC_CTRL_WDE_MASK;
base->WTR = config->watchdogTimeoutValue; /* WDOG can be only available when the feature is enabled. */
}
base->CTRL = tmp16;
/* ENC_FILT. */
base->FILT = ENC_FILT_FILT_CNT(config->filterCount) | ENC_FILT_FILT_PER(config->filterSamplePeriod);
/* ENC_CTRL2. */
tmp16 = base->CTRL2 & (uint16_t)(~(ENC_CTRL2_W1C_FLAGS | ENC_CTRL2_OUTCTL_MASK | ENC_CTRL2_REVMOD_MASK |
ENC_CTRL2_MOD_MASK | ENC_CTRL2_UPDPOS_MASK | ENC_CTRL2_UPDHLD_MASK));
if (kENC_POSMATCHOnReadingAnyPositionCounter == config->positionMatchMode)
{
tmp16 |= ENC_CTRL2_OUTCTL_MASK;
}
if (kENC_RevolutionCountOnRollOverModulus == config->revolutionCountCondition)
{
tmp16 |= ENC_CTRL2_REVMOD_MASK;
}
if (config->enableModuloCountMode)
{
tmp16 |= ENC_CTRL2_MOD_MASK;
/* Set modulus value. */
base->UMOD = (uint16_t)(config->positionModulusValue >> 16U); /* Upper 16 bits. */
base->LMOD = (uint16_t)(config->positionModulusValue); /* Lower 16 bits. */
}
if (config->enableTRIGGERClearPositionCounter)
{
tmp16 |= ENC_CTRL2_UPDPOS_MASK;
}
if (config->enableTRIGGERClearHoldPositionCounter)
{
tmp16 |= ENC_CTRL2_UPDHLD_MASK;
}
base->CTRL2 = tmp16;
/* ENC_UCOMP & ENC_LCOMP. */
base->UCOMP = (uint16_t)(config->positionCompareValue >> 16U); /* Upper 16 bits. */
base->LCOMP = (uint16_t)(config->positionCompareValue); /* Lower 16 bits. */
/* ENC_UINIT & ENC_LINIT. */
base->UINIT = (uint16_t)(config->positionInitialValue >> 16U); /* Upper 16 bits. */
base->LINIT = (uint16_t)(config->positionInitialValue); /* Lower 16 bits. */
}
void ENC_Deinit(ENC_Type *base)
{
#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
/* Disable the clock. */
CLOCK_DisableClock(s_encClocks[ENC_GetInstance(base)]);
#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
}
void ENC_GetDefaultConfig(enc_config_t *config)
{
assert(NULL != config);
config->enableReverseDirection = false;
config->decoderWorkMode = kENC_DecoderWorkAsNormalMode;
config->HOMETriggerMode = kENC_HOMETriggerDisabled;
config->INDEXTriggerMode = kENC_INDEXTriggerDisabled;
config->enableTRIGGERClearPositionCounter = false;
config->enableTRIGGERClearHoldPositionCounter = false;
config->enableWatchdog = false;
config->watchdogTimeoutValue = 0U;
config->filterCount = 0U;
config->filterSamplePeriod = 0U;
config->positionMatchMode = kENC_POSMATCHOnPositionCounterEqualToComapreValue;
config->positionCompareValue = 0xFFFFFFFFU;
config->revolutionCountCondition = kENC_RevolutionCountOnINDEXPulse;
config->enableModuloCountMode = false;
config->positionModulusValue = 0U;
config->positionInitialValue = 0U;
}
void ENC_DoSoftwareLoadInitialPositionValue(ENC_Type *base)
{
uint16_t tmp16 = base->CTRL & (uint16_t)(~ENC_CTRL_W1C_FLAGS);
tmp16 |= ENC_CTRL_SWIP_MASK; /* Write 1 to trigger the command for loading initial position value. */
base->CTRL = tmp16;
}
void ENC_SetSelfTestConfig(ENC_Type *base, const enc_self_test_config_t *config)
{
uint16_t tmp16 = 0U;
if (NULL == config) /* Pass "NULL" to disable the feature. */
{
base->TST = 0U;
return;
}
tmp16 = ENC_TST_TEN_MASK | ENC_TST_TCE_MASK | ENC_TST_TEST_PERIOD(config->signalPeriod) |
ENC_TST_TEST_COUNT(config->signalCount);
if (kENC_SelfTestDirectionNegative == config->signalDirection)
{
tmp16 |= ENC_TST_QDN_MASK;
}
base->TST = tmp16;
}
void ENC_EnableWatchdog(ENC_Type *base, bool enable)
{
uint16_t tmp16 = base->CTRL & (uint16_t)(~(ENC_CTRL_W1C_FLAGS | ENC_CTRL_WDE_MASK));
if (enable)
{
tmp16 |= ENC_CTRL_WDE_MASK;
}
base->CTRL = tmp16;
}
uint32_t ENC_GetStatusFlags(ENC_Type *base)
{
uint32_t ret32 = 0U;
/* ENC_CTRL. */
if (ENC_CTRL_HIRQ_MASK == (ENC_CTRL_HIRQ_MASK & base->CTRL))
{
ret32 |= kENC_HOMETransitionFlag;
}
if (ENC_CTRL_XIRQ_MASK == (ENC_CTRL_XIRQ_MASK & base->CTRL))
{
ret32 |= kENC_INDEXPulseFlag;
}
if (ENC_CTRL_DIRQ_MASK == (ENC_CTRL_DIRQ_MASK & base->CTRL))
{
ret32 |= kENC_WatchdogTimeoutFlag;
}
if (ENC_CTRL_CMPIRQ_MASK == (ENC_CTRL_CMPIRQ_MASK & base->CTRL))
{
ret32 |= kENC_PositionCompareFlag;
}
/* ENC_CTRL2. */
if (ENC_CTRL2_SABIRQ_MASK == (ENC_CTRL2_SABIRQ_MASK & base->CTRL2))
{
ret32 |= kENC_SimultBothPhaseChangeFlag;
}
if (ENC_CTRL2_ROIRQ_MASK == (ENC_CTRL2_ROIRQ_MASK & base->CTRL2))
{
ret32 |= kENC_PositionRollOverFlag;
}
if (ENC_CTRL2_RUIRQ_MASK == (ENC_CTRL2_RUIRQ_MASK & base->CTRL2))
{
ret32 |= kENC_PositionRollUnderFlag;
}
if (ENC_CTRL2_DIR_MASK == (ENC_CTRL2_DIR_MASK & base->CTRL2))
{
ret32 |= kENC_LastCountDirectionFlag;
}
return ret32;
}
void ENC_ClearStatusFlags(ENC_Type *base, uint32_t mask)
{
uint32_t tmp16 = 0U;
/* ENC_CTRL. */
if (kENC_HOMETransitionFlag == (kENC_HOMETransitionFlag & mask))
{
tmp16 |= ENC_CTRL_HIRQ_MASK;
}
if (kENC_INDEXPulseFlag == (kENC_INDEXPulseFlag & mask))
{
tmp16 |= ENC_CTRL_XIRQ_MASK;
}
if (kENC_WatchdogTimeoutFlag == (kENC_WatchdogTimeoutFlag & mask))
{
tmp16 |= ENC_CTRL_DIRQ_MASK;
}
if (kENC_PositionCompareFlag == (kENC_PositionCompareFlag & mask))
{
tmp16 |= ENC_CTRL_CMPIRQ_MASK;
}
if (0U != tmp16)
{
base->CTRL = (base->CTRL & (uint16_t)(~ENC_CTRL_W1C_FLAGS)) | tmp16;
}
/* ENC_CTRL2. */
tmp16 = 0U;
if (kENC_SimultBothPhaseChangeFlag == (kENC_SimultBothPhaseChangeFlag & mask))
{
tmp16 |= ENC_CTRL2_SABIRQ_MASK;
}
if (kENC_PositionRollOverFlag == (kENC_PositionRollOverFlag & mask))
{
tmp16 |= ENC_CTRL2_ROIRQ_MASK;
}
if (kENC_PositionRollUnderFlag == (kENC_PositionRollUnderFlag & mask))
{
tmp16 |= ENC_CTRL2_RUIRQ_MASK;
}
if (0U != tmp16)
{
base->CTRL2 = (base->CTRL2 & (uint16_t)(~ENC_CTRL2_W1C_FLAGS)) | tmp16;
}
}
void ENC_EnableInterrupts(ENC_Type *base, uint32_t mask)
{
uint32_t tmp16 = 0U;
/* ENC_CTRL. */
if (kENC_HOMETransitionInterruptEnable == (kENC_HOMETransitionInterruptEnable & mask))
{
tmp16 |= ENC_CTRL_HIE_MASK;
}
if (kENC_INDEXPulseInterruptEnable == (kENC_INDEXPulseInterruptEnable & mask))
{
tmp16 |= ENC_CTRL_XIE_MASK;
}
if (kENC_WatchdogTimeoutInterruptEnable == (kENC_WatchdogTimeoutInterruptEnable & mask))
{
tmp16 |= ENC_CTRL_DIE_MASK;
}
if (kENC_PositionCompareInerruptEnable == (kENC_PositionCompareInerruptEnable & mask))
{
tmp16 |= ENC_CTRL_CMPIE_MASK;
}
if (tmp16 != 0U)
{
base->CTRL = (base->CTRL & (uint16_t)(~ENC_CTRL_W1C_FLAGS)) | tmp16;
}
/* ENC_CTRL2. */
tmp16 = 0U;
if (kENC_SimultBothPhaseChangeInterruptEnable == (kENC_SimultBothPhaseChangeInterruptEnable & mask))
{
tmp16 |= ENC_CTRL2_SABIE_MASK;
}
if (kENC_PositionRollOverInterruptEnable == (kENC_PositionRollOverInterruptEnable & mask))
{
tmp16 |= ENC_CTRL2_ROIE_MASK;
}
if (kENC_PositionRollUnderInterruptEnable == (kENC_PositionRollUnderInterruptEnable & mask))
{
tmp16 |= ENC_CTRL2_RUIE_MASK;
}
if (tmp16 != 0U)
{
base->CTRL2 = (base->CTRL2 & (uint16_t)(~ENC_CTRL2_W1C_FLAGS)) | tmp16;
}
}
void ENC_DisableInterrupts(ENC_Type *base, uint32_t mask)
{
uint16_t tmp16 = 0U;
/* ENC_CTRL. */
if (kENC_HOMETransitionInterruptEnable == (kENC_HOMETransitionInterruptEnable & mask))
{
tmp16 |= ENC_CTRL_HIE_MASK;
}
if (kENC_INDEXPulseInterruptEnable == (kENC_INDEXPulseInterruptEnable & mask))
{
tmp16 |= ENC_CTRL_XIE_MASK;
}
if (kENC_WatchdogTimeoutInterruptEnable == (kENC_WatchdogTimeoutInterruptEnable & mask))
{
tmp16 |= ENC_CTRL_DIE_MASK;
}
if (kENC_PositionCompareInerruptEnable == (kENC_PositionCompareInerruptEnable & mask))
{
tmp16 |= ENC_CTRL_CMPIE_MASK;
}
if (0U != tmp16)
{
base->CTRL = (uint16_t)(base->CTRL & (uint16_t)(~ENC_CTRL_W1C_FLAGS)) & (uint16_t)(~tmp16);
}
/* ENC_CTRL2. */
tmp16 = 0U;
if (kENC_SimultBothPhaseChangeInterruptEnable == (kENC_SimultBothPhaseChangeInterruptEnable & mask))
{
tmp16 |= ENC_CTRL2_SABIE_MASK;
}
if (kENC_PositionRollOverInterruptEnable == (kENC_PositionRollOverInterruptEnable & mask))
{
tmp16 |= ENC_CTRL2_ROIE_MASK;
}
if (kENC_PositionRollUnderInterruptEnable == (kENC_PositionRollUnderInterruptEnable & mask))
{
tmp16 |= ENC_CTRL2_RUIE_MASK;
}
if (tmp16 != 0U)
{
base->CTRL2 = (uint16_t)(base->CTRL2 & (uint16_t)(~ENC_CTRL2_W1C_FLAGS)) & (uint16_t)(~tmp16);
}
}
uint32_t ENC_GetEnabledInterrupts(ENC_Type *base)
{
uint32_t ret32 = 0U;
/* ENC_CTRL. */
if (ENC_CTRL_HIE_MASK == (ENC_CTRL_HIE_MASK & base->CTRL))
{
ret32 |= kENC_HOMETransitionInterruptEnable;
}
if (ENC_CTRL_XIE_MASK == (ENC_CTRL_XIE_MASK & base->CTRL))
{
ret32 |= kENC_INDEXPulseInterruptEnable;
}
if (ENC_CTRL_DIE_MASK == (ENC_CTRL_DIE_MASK & base->CTRL))
{
ret32 |= kENC_WatchdogTimeoutInterruptEnable;
}
if (ENC_CTRL_CMPIE_MASK == (ENC_CTRL_CMPIE_MASK & base->CTRL))
{
ret32 |= kENC_PositionCompareInerruptEnable;
}
/* ENC_CTRL2. */
if (ENC_CTRL2_SABIE_MASK == (ENC_CTRL2_SABIE_MASK & base->CTRL2))
{
ret32 |= kENC_SimultBothPhaseChangeInterruptEnable;
}
if (ENC_CTRL2_ROIE_MASK == (ENC_CTRL2_ROIE_MASK & base->CTRL2))
{
ret32 |= kENC_PositionRollOverInterruptEnable;
}
if (ENC_CTRL2_RUIE_MASK == (ENC_CTRL2_RUIE_MASK & base->CTRL2))
{
ret32 |= kENC_PositionRollUnderInterruptEnable;
}
return ret32;
}
void ENC_SetInitialPositionValue(ENC_Type *base, uint32_t value)
{
base->UINIT = (uint16_t)(value >> 16U); /* Set upper 16 bits. */
base->LINIT = (uint16_t)(value); /* Set lower 16 bits. */
}
uint32_t ENC_GetPositionValue(ENC_Type *base)
{
uint32_t ret32;
ret32 = base->UPOS; /* Get upper 16 bits and make a snapshot. */
ret32 <<= 16U;
ret32 |= base->LPOSH; /* Get lower 16 bits from hold register. */
return ret32;
}
uint32_t ENC_GetHoldPositionValue(ENC_Type *base)
{
uint32_t ret32;
ret32 = base->UPOSH; /* Get upper 16 bits and make a snapshot. */
ret32 <<= 16U;
ret32 |= base->LPOSH; /* Get lower 16 bits from hold register. */
return ret32;
}

View File

@ -0,0 +1,464 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* Copyright 2016-2017 NXP
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _FSL_ENC_H_
#define _FSL_ENC_H_
#include "fsl_common.h"
/*!
* @addtogroup enc
* @{
*/
/*******************************************************************************
* Definitions
******************************************************************************/
#define FSL_ENC_DRIVER_VERSION (MAKE_VERSION(2, 0, 0)) /*!< Version 2.0.0. */
/*!
* @brief Interrupt enable/disable mask.
*/
enum _enc_interrupt_enable
{
kENC_HOMETransitionInterruptEnable = (1U << 0U), /*!< HOME interrupt enable. */
kENC_INDEXPulseInterruptEnable = (1U << 1U), /*!< INDEX pulse interrupt enable. */
kENC_WatchdogTimeoutInterruptEnable = (1U << 2U), /*!< Watchdog timeout interrupt enable. */
kENC_PositionCompareInerruptEnable = (1U << 3U), /*!< Position compare interrupt enable. */
kENC_SimultBothPhaseChangeInterruptEnable =
(1U << 4U), /*!< Simultaneous PHASEA and PHASEB change interrupt enable. */
kENC_PositionRollOverInterruptEnable = (1U << 5U), /*!< Roll-over interrupt enable. */
kENC_PositionRollUnderInterruptEnable = (1U << 6U), /*!< Roll-under interrupt enable. */
};
/*!
* @brief Status flag mask.
*
* These flags indicate the counter's events.
*/
enum _enc_status_flags
{
kENC_HOMETransitionFlag = (1U << 0U), /*!< HOME signal transition interrupt request. */
kENC_INDEXPulseFlag = (1U << 1U), /*!< INDEX Pulse Interrupt Request. */
kENC_WatchdogTimeoutFlag = (1U << 2U), /*!< Watchdog timeout interrupt request. */
kENC_PositionCompareFlag = (1U << 3U), /*!< Position compare interrupt request. */
kENC_SimultBothPhaseChangeFlag = (1U << 4U), /*!< Simultaneous PHASEA and PHASEB change interrupt request. */
kENC_PositionRollOverFlag = (1U << 5U), /*!< Roll-over interrupt request. */
kENC_PositionRollUnderFlag = (1U << 6U), /*!< Roll-under interrupt request. */
kENC_LastCountDirectionFlag = (1U << 7U), /*!< Last count was in the up direction, or the down direction. */
};
/*!
* @brief Signal status flag mask.
*
* These flags indicate the counter's signal.
*/
enum _enc_signal_status_flags
{
kENC_RawHOMEStatusFlag = ENC_IMR_HOME_MASK, /*!< Raw HOME input. */
kENC_RawINDEXStatusFlag = ENC_IMR_INDEX_MASK, /*!< Raw INDEX input. */
kENC_RawPHBStatusFlag = ENC_IMR_PHB_MASK, /*!< Raw PHASEB input. */
kENC_RawPHAEXStatusFlag = ENC_IMR_PHA_MASK, /*!< Raw PHASEA input. */
kENC_FilteredHOMEStatusFlag = ENC_IMR_FHOM_MASK, /*!< The filtered version of HOME input. */
kENC_FilteredINDEXStatusFlag = ENC_IMR_FIND_MASK, /*!< The filtered version of INDEX input. */
kENC_FilteredPHBStatusFlag = ENC_IMR_FPHB_MASK, /*!< The filtered version of PHASEB input. */
kENC_FilteredPHAStatusFlag = ENC_IMR_FPHA_MASK, /*!< The filtered version of PHASEA input. */
};
/*!
* @brief Define HOME signal's trigger mode.
*
* The ENC would count the trigger from HOME signal line.
*/
typedef enum _enc_home_trigger_mode
{
kENC_HOMETriggerDisabled = 0U, /*!< HOME signal's trigger is disabled. */
kENC_HOMETriggerOnRisingEdge, /*!< Use positive going edge-to-trigger initialization of position counters. */
kENC_HOMETriggerOnFallingEdge, /*!< Use negative going edge-to-trigger initialization of position counters. */
} enc_home_trigger_mode_t;
/*!
* @brief Define INDEX signal's trigger mode.
*
* The ENC would count the trigger from INDEX signal line.
*/
typedef enum _enc_index_trigger_mode
{
kENC_INDEXTriggerDisabled = 0U, /*!< INDEX signal's trigger is disabled. */
kENC_INDEXTriggerOnRisingEdge, /*!< Use positive going edge-to-trigger initialization of position counters. */
kENC_INDEXTriggerOnFallingEdge, /*!< Use negative going edge-to-trigger initialization of position counters. */
} enc_index_trigger_mode_t;
/*!
* @brief Define type for decoder work mode.
*
* The normal work mode uses the standard quadrature decoder with PHASEA and PHASEB. When in signal phase count mode,
* a positive transition of the PHASEA input generates a count signal while the PHASEB input and the reverse direction
* control the counter direction. If the reverse direction is not enabled, PHASEB = 0 means counting up and PHASEB = 1
* means counting down. Otherwise, the direction is reversed.
*/
typedef enum _enc_decoder_work_mode
{
kENC_DecoderWorkAsNormalMode = 0U, /*!< Use standard quadrature decoder with PHASEA and PHASEB. */
kENC_DecoderWorkAsSignalPhaseCountMode, /*!< PHASEA input generates a count signal while PHASEB input control the
direction. */
} enc_decoder_work_mode_t;
/*!
* @brief Define type for the condition of POSMATCH pulses.
*/
typedef enum _enc_position_match_mode
{
kENC_POSMATCHOnPositionCounterEqualToComapreValue = 0U, /*!< POSMATCH pulses when a match occurs between the
position counters (POS) and the compare value (COMP). */
kENC_POSMATCHOnReadingAnyPositionCounter, /*!< POSMATCH pulses when any position counter register is read. */
} enc_position_match_mode_t;
/*!
* @brief Define type for determining how the revolution counter (REV) is incremented/decremented.
*/
typedef enum _enc_revolution_count_condition
{
kENC_RevolutionCountOnINDEXPulse = 0U, /*!< Use INDEX pulse to increment/decrement revolution counter. */
kENC_RevolutionCountOnRollOverModulus, /*!< Use modulus counting roll-over/under to increment/decrement revolution
counter. */
} enc_revolution_count_condition_t;
/*!
* @brief Define type for direction of self test generated signal.
*/
typedef enum _enc_self_test_direction
{
kENC_SelfTestDirectionPositive = 0U, /*!< Self test generates the signal in positive direction. */
kENC_SelfTestDirectionNegative, /*!< Self test generates the signal in negative direction. */
} enc_self_test_direction_t;
/*!
* @brief Define user configuration structure for ENC module.
*/
typedef struct _enc_config
{
/* Basic counter. */
bool enableReverseDirection; /*!< Enable reverse direction counting. */
enc_decoder_work_mode_t decoderWorkMode; /*!< Enable signal phase count mode. */
/* Signal detection. */
enc_home_trigger_mode_t HOMETriggerMode; /*!< Enable HOME to initialize position counters. */
enc_index_trigger_mode_t INDEXTriggerMode; /*!< Enable INDEX to initialize position counters. */
bool enableTRIGGERClearPositionCounter; /*!< Clear POSD, REV, UPOS and LPOS on rising edge of TRIGGER, or not. */
bool enableTRIGGERClearHoldPositionCounter; /*!< Enable update of hold registers on rising edge of TRIGGER, or not.
*/
/* Watchdog. */
bool enableWatchdog; /*!< Enable the watchdog to detect if the target is moving or not. */
uint16_t watchdogTimeoutValue; /*!< Watchdog timeout count value. It stores the timeout count for the quadrature
decoder module watchdog timer. This field is only available when
"enableWatchdog" = true. The available value is a 16-bit unsigned number.*/
/* Filter for PHASEA, PHASEB, INDEX and HOME. */
uint16_t filterCount; /*!< Input Filter Sample Count. This value should be chosen to reduce the probability of
noisy samples causing an incorrect transition to be recognized. The value represent the
number of consecutive samples that must agree prior to the input filter accepting an
input transition. A value of 0x0 represents 3 samples. A value of 0x7 represents 10
samples. The Available range is 0 - 7.*/
uint16_t filterSamplePeriod; /*!< Input Filter Sample Period. This value should be set such that the sampling period
is larger than the period of the expected noise. This value represents the
sampling period (in IPBus clock cycles) of the decoder input signals.
The available range is 0 - 255. */
/* Position compare. */
enc_position_match_mode_t positionMatchMode; /*!< The condition of POSMATCH pulses. */
uint32_t positionCompareValue; /*!< Position compare value. The available value is a 32-bit number.*/
/* Modulus counting. */
enc_revolution_count_condition_t revolutionCountCondition; /*!< Revolution Counter Modulus Enable. */
bool enableModuloCountMode; /*!< Enable Modulo Counting. */
uint32_t positionModulusValue; /*!< Position modulus value. This value would be available only when
"enableModuloCountMode" = true. The available value is a 32-bit number. */
uint32_t positionInitialValue; /*!< Position initial value. The available value is a 32-bit number. */
} enc_config_t;
/*!
* @brief Define configuration structure for self test module.
*
* The self test module provides a quadrature test signal to the inputs of the quadrature decoder module.
* This is a factory test feature. It is also useful to customers' software development and testing.
*/
typedef struct _enc_self_test_config
{
enc_self_test_direction_t signalDirection; /*!< Direction of self test generated signal. */
uint16_t signalCount; /*!< Hold the number of quadrature advances to generate. The available range is 0 - 255.*/
uint16_t signalPeriod; /*!< Hold the period of quadrature phase in IPBus clock cycles.
The available range is 0 - 31. */
} enc_self_test_config_t;
#if defined(__cplusplus)
extern "C" {
#endif
/*******************************************************************************
* API
******************************************************************************/
/*!
* @name Initialization and De-initialization
* @{
*/
/*!
* @brief Initialization for the ENC module.
*
* This function is to make the initialization for the ENC module. It should be called firstly before any operation to
* the ENC with the operations like:
* - Enable the clock for ENC module.
* - Configure the ENC's working attributes.
*
* @param base ENC peripheral base address.
* @param config Pointer to configuration structure. See to "enc_config_t".
*/
void ENC_Init(ENC_Type *base, const enc_config_t *config);
/*!
* @brief De-initialization for the ENC module.
*
* This function is to make the de-initialization for the ENC module. It could be called when ENC is no longer used with
* the operations like:
* - Disable the clock for ENC module.
*
* @param base ENC peripheral base address.
*/
void ENC_Deinit(ENC_Type *base);
/*!
* @brief Get an available pre-defined settings for ENC's configuration.
*
* This function initializes the ENC configuration structure with an available settings, the default value are:
* @code
* config->enableReverseDirection = false;
* config->decoderWorkMode = kENC_DecoderWorkAsNormalMode;
* config->HOMETriggerMode = kENC_HOMETriggerDisabled;
* config->INDEXTriggerMode = kENC_INDEXTriggerDisabled;
* config->enableTRIGGERClearPositionCounter = false;
* config->enableTRIGGERClearHoldPositionCounter = false;
* config->enableWatchdog = false;
* config->watchdogTimeoutValue = 0U;
* config->filterCount = 0U;
* config->filterSamplePeriod = 0U;
* config->positionMatchMode = kENC_POSMATCHOnPositionCounterEqualToComapreValue;
* config->positionCompareValue = 0xFFFFFFFFU;
* config->revolutionCountCondition = kENC_RevolutionCountOnINDEXPulse;
* config->enableModuloCountMode = false;
* config->positionModulusValue = 0U;
* config->positionInitialValue = 0U;
* @endcode
* @param config Pointer to a variable of configuration structure. See to "enc_config_t".
*/
void ENC_GetDefaultConfig(enc_config_t *config);
/*!
* @brief Load the initial position value to position counter.
*
* This function is to transfer the initial position value (UINIT and LINIT) contents to position counter (UPOS and
* LPOS), so that to provide the consistent operation the position counter registers.
*
* @param base ENC peripheral base address.
*/
void ENC_DoSoftwareLoadInitialPositionValue(ENC_Type *base);
/*!
* @brief Enable and configure the self test function.
*
* This function is to enable and configuration the self test function. It controls and sets the frequency of a
* quadrature signal generator. It provides a quadrature test signal to the inputs of the quadrature decoder module.
* It is a factory test feature; however, it may be useful to customers' software development and testing.
*
* @param base ENC peripheral base address.
* @param config Pointer to configuration structure. See to "enc_self_test_config_t". Pass "NULL" to disable.
*/
void ENC_SetSelfTestConfig(ENC_Type *base, const enc_self_test_config_t *config);
/* @} */
/*!
* @name Status
* @{
*/
/*!
* @brief Get the status flags.
*
* @param base ENC peripheral base address.
*
* @return Mask value of status flags. For available mask, see to "_enc_status_flags".
*/
uint32_t ENC_GetStatusFlags(ENC_Type *base);
/*!
* @brief Clear the status flags.
*
* @param base ENC peripheral base address.
* @param mask Mask value of status flags to be cleared. For available mask, see to "_enc_status_flags".
*/
void ENC_ClearStatusFlags(ENC_Type *base, uint32_t mask);
/*!
* @brief Get the signals' real-time status.
*
* @param base ENC peripheral base address.
*
* @return Mask value of signals' real-time status. For available mask, see to "_enc_signal_status_flags"
*/
static inline uint16_t ENC_GetSignalStatusFlags(ENC_Type *base)
{
return base->IMR;
}
/* @} */
/*!
* @name Interrupts
* @{
*/
/*!
* @brief Enable the interrupts.
*
* @param base ENC peripheral base address.
* @param mask Mask value of interrupts to be enabled. For available mask, see to "_enc_interrupt_enable".
*/
void ENC_EnableInterrupts(ENC_Type *base, uint32_t mask);
/*!
* @brief Disable the interrupts.
*
* @param base ENC peripheral base address.
* @param mask Mask value of interrupts to be disabled. For available mask, see to "_enc_interrupt_enable".
*/
void ENC_DisableInterrupts(ENC_Type *base, uint32_t mask);
/*!
* @brief Get the enabled interrupts' flags.
*
* @param base ENC peripheral base address.
*
* @return Mask value of enabled interrupts.
*/
uint32_t ENC_GetEnabledInterrupts(ENC_Type *base);
/* @} */
/*!
* @name Value Operation
* @{
*/
/*!
* @brief Get the current position counter's value.
*
* @param base ENC peripheral base address.
*
* @return Current position counter's value.
*/
uint32_t ENC_GetPositionValue(ENC_Type *base);
/*!
* @brief Get the hold position counter's value.
*
* When any of the counter registers is read, the contents of each counter register is written to the corresponding hold
* register. Taking a snapshot of the counters' values provides a consistent view of a system position and a velocity to
* be attained.
*
* @param base ENC peripheral base address.
*
* @return Hold position counter's value.
*/
uint32_t ENC_GetHoldPositionValue(ENC_Type *base);
/*!
* @brief Get the position difference counter's value.
*
* @param base ENC peripheral base address.
*
* @return The position difference counter's value.
*/
static inline uint16_t ENC_GetPositionDifferenceValue(ENC_Type *base)
{
return base->POSD;
}
/*!
* @brief Get the hold position difference counter's value.
*
* When any of the counter registers is read, the contents of each counter register is written to the corresponding hold
* register. Taking a snapshot of the counters' values provides a consistent view of a system position and a velocity to
* be attained.
*
* @param base ENC peripheral base address.
*
* @return Hold position difference counter's value.
*/
static inline uint16_t ENC_GetHoldPositionDifferenceValue(ENC_Type *base)
{
return base->POSDH;
}
/*!
* @brief Get the position revolution counter's value.
*
* @param base ENC peripheral base address.
*
* @return The position revolution counter's value.
*/
static inline uint16_t ENC_GetRevolutionValue(ENC_Type *base)
{
return base->REV;
}
/*!
* @brief Get the hold position revolution counter's value.
*
* When any of the counter registers is read, the contents of each counter register is written to the corresponding hold
* register. Taking a snapshot of the counters' values provides a consistent view of a system position and a velocity to
* be attained.
*
* @param base ENC peripheral base address.
*
* @return Hold position revolution counter's value.
*/
static inline uint16_t ENC_GetHoldRevolutionValue(ENC_Type *base)
{
return base->REVH;
}
/* @} */
#if defined(__cplusplus)
}
#endif
/*
* @}
*/
#endif /* _FSL_ENC_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,102 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* Copyright 2016-2017 NXP
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include "fsl_ewm.h"
/*******************************************************************************
* Code
******************************************************************************/
void EWM_Init(EWM_Type *base, const ewm_config_t *config)
{
assert(config);
uint32_t value = 0U;
#if !((defined(FSL_FEATURE_SOC_PCC_COUNT) && FSL_FEATURE_SOC_PCC_COUNT) && \
(defined(FSL_FEATURE_PCC_SUPPORT_EWM_CLOCK_REMOVE) && FSL_FEATURE_PCC_SUPPORT_EWM_CLOCK_REMOVE))
#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
CLOCK_EnableClock(kCLOCK_Ewm0);
#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
#endif
value = EWM_CTRL_EWMEN(config->enableEwm) | EWM_CTRL_ASSIN(config->setInputAssertLogic) |
EWM_CTRL_INEN(config->enableEwmInput) | EWM_CTRL_INTEN(config->enableInterrupt);
#if defined(FSL_FEATURE_EWM_HAS_PRESCALER) && FSL_FEATURE_EWM_HAS_PRESCALER
base->CLKPRESCALER = config->prescaler;
#endif /* FSL_FEATURE_EWM_HAS_PRESCALER */
#if defined(FSL_FEATURE_EWM_HAS_CLOCK_SELECT) && FSL_FEATURE_EWM_HAS_CLOCK_SELECT
base->CLKCTRL = config->clockSource;
#endif /* FSL_FEATURE_EWM_HAS_CLOCK_SELECT*/
base->CMPL = config->compareLowValue;
base->CMPH = config->compareHighValue;
base->CTRL = value;
}
void EWM_Deinit(EWM_Type *base)
{
EWM_DisableInterrupts(base, kEWM_InterruptEnable);
#if !((defined(FSL_FEATURE_SOC_PCC_COUNT) && FSL_FEATURE_SOC_PCC_COUNT) && \
(defined(FSL_FEATURE_PCC_SUPPORT_EWM_CLOCK_REMOVE) && FSL_FEATURE_PCC_SUPPORT_EWM_CLOCK_REMOVE))
#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
CLOCK_DisableClock(kCLOCK_Ewm0);
#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
#endif /* FSL_FEATURE_PCC_SUPPORT_EWM_CLOCK_REMOVE */
}
void EWM_GetDefaultConfig(ewm_config_t *config)
{
assert(config);
config->enableEwm = true;
config->enableEwmInput = false;
config->setInputAssertLogic = false;
config->enableInterrupt = false;
#if defined(FSL_FEATURE_EWM_HAS_CLOCK_SELECT) && FSL_FEATURE_EWM_HAS_CLOCK_SELECT
config->clockSource = kEWM_LpoClockSource0;
#endif /* FSL_FEATURE_EWM_HAS_CLOCK_SELECT*/
#if defined(FSL_FEATURE_EWM_HAS_PRESCALER) && FSL_FEATURE_EWM_HAS_PRESCALER
config->prescaler = 0U;
#endif /* FSL_FEATURE_EWM_HAS_PRESCALER */
config->compareLowValue = 0U;
config->compareHighValue = 0xFEU;
}
void EWM_Refresh(EWM_Type *base)
{
uint32_t primaskValue = 0U;
/* Disable the global interrupt to protect refresh sequence */
primaskValue = DisableGlobalIRQ();
base->SERV = (uint8_t)0xB4U;
base->SERV = (uint8_t)0x2CU;
EnableGlobalIRQ(primaskValue);
}

View File

@ -0,0 +1,241 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* Copyright 2016-2017 NXP
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _FSL_EWM_H_
#define _FSL_EWM_H_
#include "fsl_common.h"
/*!
* @addtogroup ewm
* @{
*/
/*******************************************************************************
* Definitions
*******************************************************************************/
/*! @name Driver version */
/*@{*/
/*! @brief EWM driver version 2.0.1. */
#define FSL_EWM_DRIVER_VERSION (MAKE_VERSION(2, 0, 1))
/*@}*/
/*! @brief Describes EWM clock source. */
#if defined(FSL_FEATURE_EWM_HAS_CLOCK_SELECT) && FSL_FEATURE_EWM_HAS_CLOCK_SELECT
typedef enum _ewm_lpo_clock_source
{
kEWM_LpoClockSource0 = 0U, /*!< EWM clock sourced from lpo_clk[0]*/
kEWM_LpoClockSource1 = 1U, /*!< EWM clock sourced from lpo_clk[1]*/
kEWM_LpoClockSource2 = 2U, /*!< EWM clock sourced from lpo_clk[2]*/
kEWM_LpoClockSource3 = 3U, /*!< EWM clock sourced from lpo_clk[3]*/
} ewm_lpo_clock_source_t;
#endif /* FSL_FEATURE_EWM_HAS_CLOCK_SELECT */
/*!
* @brief Data structure for EWM configuration.
*
* This structure is used to configure the EWM.
*/
typedef struct _ewm_config
{
bool enableEwm; /*!< Enable EWM module */
bool enableEwmInput; /*!< Enable EWM_in input */
bool setInputAssertLogic; /*!< EWM_in signal assertion state */
bool enableInterrupt; /*!< Enable EWM interrupt */
#if defined(FSL_FEATURE_EWM_HAS_CLOCK_SELECT) && FSL_FEATURE_EWM_HAS_CLOCK_SELECT
ewm_lpo_clock_source_t clockSource; /*!< Clock source select */
#endif /* FSL_FEATURE_EWM_HAS_CLOCK_SELECT */
#if defined(FSL_FEATURE_EWM_HAS_PRESCALER) && FSL_FEATURE_EWM_HAS_PRESCALER
uint8_t prescaler; /*!< Clock prescaler value */
#endif /* FSL_FEATURE_EWM_HAS_PRESCALER */
uint8_t compareLowValue; /*!< Compare low-register value */
uint8_t compareHighValue; /*!< Compare high-register value */
} ewm_config_t;
/*!
* @brief EWM interrupt configuration structure with default settings all disabled.
*
* This structure contains the settings for all of EWM interrupt configurations.
*/
enum _ewm_interrupt_enable_t
{
kEWM_InterruptEnable = EWM_CTRL_INTEN_MASK, /*!< Enable the EWM to generate an interrupt*/
};
/*!
* @brief EWM status flags.
*
* This structure contains the constants for the EWM status flags for use in the EWM functions.
*/
enum _ewm_status_flags_t
{
kEWM_RunningFlag = EWM_CTRL_EWMEN_MASK, /*!< Running flag, set when EWM is enabled*/
};
/*******************************************************************************
* API
*******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif /* __cplusplus */
/*!
* @name EWM initialization and de-initialization
* @{
*/
/*!
* @brief Initializes the EWM peripheral.
*
* This function is used to initialize the EWM. After calling, the EWM
* runs immediately according to the configuration.
* Note that, except for the interrupt enable control bit, other control bits and registers are write once after a
* CPU reset. Modifying them more than once generates a bus transfer error.
*
* This is an example.
* @code
* ewm_config_t config;
* EWM_GetDefaultConfig(&config);
* config.compareHighValue = 0xAAU;
* EWM_Init(ewm_base,&config);
* @endcode
*
* @param base EWM peripheral base address
* @param config The configuration of the EWM
*/
void EWM_Init(EWM_Type *base, const ewm_config_t *config);
/*!
* @brief Deinitializes the EWM peripheral.
*
* This function is used to shut down the EWM.
*
* @param base EWM peripheral base address
*/
void EWM_Deinit(EWM_Type *base);
/*!
* @brief Initializes the EWM configuration structure.
*
* This function initializes the EWM configuration structure to default values. The default
* values are as follows.
* @code
* ewmConfig->enableEwm = true;
* ewmConfig->enableEwmInput = false;
* ewmConfig->setInputAssertLogic = false;
* ewmConfig->enableInterrupt = false;
* ewmConfig->ewm_lpo_clock_source_t = kEWM_LpoClockSource0;
* ewmConfig->prescaler = 0;
* ewmConfig->compareLowValue = 0;
* ewmConfig->compareHighValue = 0xFEU;
* @endcode
*
* @param config Pointer to the EWM configuration structure.
* @see ewm_config_t
*/
void EWM_GetDefaultConfig(ewm_config_t *config);
/* @} */
/*!
* @name EWM functional Operation
* @{
*/
/*!
* @brief Enables the EWM interrupt.
*
* This function enables the EWM interrupt.
*
* @param base EWM peripheral base address
* @param mask The interrupts to enable
* The parameter can be combination of the following source if defined
* @arg kEWM_InterruptEnable
*/
static inline void EWM_EnableInterrupts(EWM_Type *base, uint32_t mask)
{
base->CTRL |= mask;
}
/*!
* @brief Disables the EWM interrupt.
*
* This function enables the EWM interrupt.
*
* @param base EWM peripheral base address
* @param mask The interrupts to disable
* The parameter can be combination of the following source if defined
* @arg kEWM_InterruptEnable
*/
static inline void EWM_DisableInterrupts(EWM_Type *base, uint32_t mask)
{
base->CTRL &= ~mask;
}
/*!
* @brief Gets all status flags.
*
* This function gets all status flags.
*
* This is an example for getting the running flag.
* @code
* uint32_t status;
* status = EWM_GetStatusFlags(ewm_base) & kEWM_RunningFlag;
* @endcode
* @param base EWM peripheral base address
* @return State of the status flag: asserted (true) or not-asserted (false).@see _ewm_status_flags_t
* - True: a related status flag has been set.
* - False: a related status flag is not set.
*/
static inline uint32_t EWM_GetStatusFlags(EWM_Type *base)
{
return (base->CTRL & EWM_CTRL_EWMEN_MASK);
}
/*!
* @brief Services the EWM.
*
* This function resets the EWM counter to zero.
*
* @param base EWM peripheral base address
*/
void EWM_Refresh(EWM_Type *base);
/*@}*/
#if defined(__cplusplus)
}
#endif /* __cplusplus */
/*! @}*/
#endif /* _FSL_EWM_H_ */

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,311 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* Copyright 2016-2017 NXP
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include "fsl_flexio.h"
/*******************************************************************************
* Definitions
******************************************************************************/
/*< @brief user configurable flexio handle count. */
#define FLEXIO_HANDLE_COUNT 2
/*******************************************************************************
* Variables
******************************************************************************/
/*< @brief pointer to array of FLEXIO handle. */
static void *s_flexioHandle[FLEXIO_HANDLE_COUNT];
/*< @brief pointer to array of FLEXIO IP types. */
static void *s_flexioType[FLEXIO_HANDLE_COUNT];
/*< @brief pointer to array of FLEXIO Isr. */
static flexio_isr_t s_flexioIsr[FLEXIO_HANDLE_COUNT];
#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
/*! @brief Pointers to flexio clocks for each instance. */
const clock_ip_name_t s_flexioClocks[] = FLEXIO_CLOCKS;
#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
/*! @brief Pointers to flexio bases for each instance. */
FLEXIO_Type *const s_flexioBases[] = FLEXIO_BASE_PTRS;
/*******************************************************************************
* Codes
******************************************************************************/
uint32_t FLEXIO_GetInstance(FLEXIO_Type *base)
{
uint32_t instance;
/* Find the instance index from base address mappings. */
for (instance = 0; instance < ARRAY_SIZE(s_flexioBases); instance++)
{
if (s_flexioBases[instance] == base)
{
break;
}
}
assert(instance < ARRAY_SIZE(s_flexioBases));
return instance;
}
void FLEXIO_Init(FLEXIO_Type *base, const flexio_config_t *userConfig)
{
uint32_t ctrlReg = 0;
#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
CLOCK_EnableClock(s_flexioClocks[FLEXIO_GetInstance(base)]);
#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
FLEXIO_Reset(base);
ctrlReg = base->CTRL;
ctrlReg &= ~(FLEXIO_CTRL_DOZEN_MASK | FLEXIO_CTRL_DBGE_MASK | FLEXIO_CTRL_FASTACC_MASK | FLEXIO_CTRL_FLEXEN_MASK);
ctrlReg |= (FLEXIO_CTRL_DBGE(userConfig->enableInDebug) | FLEXIO_CTRL_FASTACC(userConfig->enableFastAccess) |
FLEXIO_CTRL_FLEXEN(userConfig->enableFlexio));
if (!userConfig->enableInDoze)
{
ctrlReg |= FLEXIO_CTRL_DOZEN_MASK;
}
base->CTRL = ctrlReg;
}
void FLEXIO_Deinit(FLEXIO_Type *base)
{
FLEXIO_Enable(base, false);
#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
CLOCK_DisableClock(s_flexioClocks[FLEXIO_GetInstance(base)]);
#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
}
void FLEXIO_GetDefaultConfig(flexio_config_t *userConfig)
{
assert(userConfig);
userConfig->enableFlexio = true;
userConfig->enableInDoze = false;
userConfig->enableInDebug = true;
userConfig->enableFastAccess = false;
}
void FLEXIO_Reset(FLEXIO_Type *base)
{
/*do software reset, software reset operation affect all other FLEXIO registers except CTRL*/
base->CTRL |= FLEXIO_CTRL_SWRST_MASK;
base->CTRL = 0;
}
uint32_t FLEXIO_GetShifterBufferAddress(FLEXIO_Type *base, flexio_shifter_buffer_type_t type, uint8_t index)
{
assert(index < FLEXIO_SHIFTBUF_COUNT);
uint32_t address = 0;
switch (type)
{
case kFLEXIO_ShifterBuffer:
address = (uint32_t) & (base->SHIFTBUF[index]);
break;
case kFLEXIO_ShifterBufferBitSwapped:
address = (uint32_t) & (base->SHIFTBUFBIS[index]);
break;
case kFLEXIO_ShifterBufferByteSwapped:
address = (uint32_t) & (base->SHIFTBUFBYS[index]);
break;
case kFLEXIO_ShifterBufferBitByteSwapped:
address = (uint32_t) & (base->SHIFTBUFBBS[index]);
break;
#if defined(FSL_FEATURE_FLEXIO_HAS_SHFT_BUFFER_NIBBLE_BYTE_SWAP) && FSL_FEATURE_FLEXIO_HAS_SHFT_BUFFER_NIBBLE_BYTE_SWAP
case kFLEXIO_ShifterBufferNibbleByteSwapped:
address = (uint32_t) & (base->SHIFTBUFNBS[index]);
break;
#endif
#if defined(FSL_FEATURE_FLEXIO_HAS_SHFT_BUFFER_HALF_WORD_SWAP) && FSL_FEATURE_FLEXIO_HAS_SHFT_BUFFER_HALF_WORD_SWAP
case kFLEXIO_ShifterBufferHalfWordSwapped:
address = (uint32_t) & (base->SHIFTBUFHWS[index]);
break;
#endif
#if defined(FSL_FEATURE_FLEXIO_HAS_SHFT_BUFFER_NIBBLE_SWAP) && FSL_FEATURE_FLEXIO_HAS_SHFT_BUFFER_NIBBLE_SWAP
case kFLEXIO_ShifterBufferNibbleSwapped:
address = (uint32_t) & (base->SHIFTBUFNIS[index]);
break;
#endif
default:
break;
}
return address;
}
void FLEXIO_SetShifterConfig(FLEXIO_Type *base, uint8_t index, const flexio_shifter_config_t *shifterConfig)
{
base->SHIFTCFG[index] = FLEXIO_SHIFTCFG_INSRC(shifterConfig->inputSource)
#if defined(FSL_FEATURE_FLEXIO_HAS_PARALLEL_WIDTH) && FSL_FEATURE_FLEXIO_HAS_PARALLEL_WIDTH
| FLEXIO_SHIFTCFG_PWIDTH(shifterConfig->parallelWidth)
#endif /* FSL_FEATURE_FLEXIO_HAS_PARALLEL_WIDTH */
| FLEXIO_SHIFTCFG_SSTOP(shifterConfig->shifterStop) |
FLEXIO_SHIFTCFG_SSTART(shifterConfig->shifterStart);
base->SHIFTCTL[index] =
FLEXIO_SHIFTCTL_TIMSEL(shifterConfig->timerSelect) | FLEXIO_SHIFTCTL_TIMPOL(shifterConfig->timerPolarity) |
FLEXIO_SHIFTCTL_PINCFG(shifterConfig->pinConfig) | FLEXIO_SHIFTCTL_PINSEL(shifterConfig->pinSelect) |
FLEXIO_SHIFTCTL_PINPOL(shifterConfig->pinPolarity) | FLEXIO_SHIFTCTL_SMOD(shifterConfig->shifterMode);
}
void FLEXIO_SetTimerConfig(FLEXIO_Type *base, uint8_t index, const flexio_timer_config_t *timerConfig)
{
base->TIMCFG[index] =
FLEXIO_TIMCFG_TIMOUT(timerConfig->timerOutput) | FLEXIO_TIMCFG_TIMDEC(timerConfig->timerDecrement) |
FLEXIO_TIMCFG_TIMRST(timerConfig->timerReset) | FLEXIO_TIMCFG_TIMDIS(timerConfig->timerDisable) |
FLEXIO_TIMCFG_TIMENA(timerConfig->timerEnable) | FLEXIO_TIMCFG_TSTOP(timerConfig->timerStop) |
FLEXIO_TIMCFG_TSTART(timerConfig->timerStart);
base->TIMCMP[index] = FLEXIO_TIMCMP_CMP(timerConfig->timerCompare);
base->TIMCTL[index] = FLEXIO_TIMCTL_TRGSEL(timerConfig->triggerSelect) |
FLEXIO_TIMCTL_TRGPOL(timerConfig->triggerPolarity) |
FLEXIO_TIMCTL_TRGSRC(timerConfig->triggerSource) |
FLEXIO_TIMCTL_PINCFG(timerConfig->pinConfig) | FLEXIO_TIMCTL_PINSEL(timerConfig->pinSelect) |
FLEXIO_TIMCTL_PINPOL(timerConfig->pinPolarity) | FLEXIO_TIMCTL_TIMOD(timerConfig->timerMode);
}
status_t FLEXIO_RegisterHandleIRQ(void *base, void *handle, flexio_isr_t isr)
{
assert(base);
assert(handle);
assert(isr);
uint8_t index = 0;
/* Find the an empty handle pointer to store the handle. */
for (index = 0; index < FLEXIO_HANDLE_COUNT; index++)
{
if (s_flexioHandle[index] == NULL)
{
/* Register FLEXIO simulated driver base, handle and isr. */
s_flexioType[index] = base;
s_flexioHandle[index] = handle;
s_flexioIsr[index] = isr;
break;
}
}
if (index == FLEXIO_HANDLE_COUNT)
{
return kStatus_OutOfRange;
}
else
{
return kStatus_Success;
}
}
status_t FLEXIO_UnregisterHandleIRQ(void *base)
{
assert(base);
uint8_t index = 0;
/* Find the index from base address mappings. */
for (index = 0; index < FLEXIO_HANDLE_COUNT; index++)
{
if (s_flexioType[index] == base)
{
/* Unregister FLEXIO simulated driver handle and isr. */
s_flexioType[index] = NULL;
s_flexioHandle[index] = NULL;
s_flexioIsr[index] = NULL;
break;
}
}
if (index == FLEXIO_HANDLE_COUNT)
{
return kStatus_OutOfRange;
}
else
{
return kStatus_Success;
}
}
void FLEXIO_CommonIRQHandler(void)
{
uint8_t index;
for (index = 0; index < FLEXIO_HANDLE_COUNT; index++)
{
if (s_flexioHandle[index])
{
s_flexioIsr[index](s_flexioType[index], s_flexioHandle[index]);
}
}
/* Add for ARM errata 838869, affects Cortex-M4, Cortex-M4F Store immediate overlapping
exception return operation might vector to incorrect interrupt */
#if defined __CORTEX_M && (__CORTEX_M == 4U)
__DSB();
#endif
}
void FLEXIO_DriverIRQHandler(void)
{
FLEXIO_CommonIRQHandler();
}
void FLEXIO0_DriverIRQHandler(void)
{
FLEXIO_CommonIRQHandler();
}
void FLEXIO1_DriverIRQHandler(void)
{
FLEXIO_CommonIRQHandler();
}
void UART2_FLEXIO_DriverIRQHandler(void)
{
FLEXIO_CommonIRQHandler();
}
void FLEXIO2_DriverIRQHandler(void)
{
FLEXIO_CommonIRQHandler();
}

View File

@ -0,0 +1,705 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* Copyright 2016-2017 NXP
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _FSL_FLEXIO_H_
#define _FSL_FLEXIO_H_
#include "fsl_common.h"
/*!
* @addtogroup flexio_driver
* @{
*/
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @name Driver version */
/*@{*/
/*! @brief FlexIO driver version 2.0.1. */
#define FSL_FLEXIO_DRIVER_VERSION (MAKE_VERSION(2, 0, 1))
/*@}*/
/*! @brief Calculate FlexIO timer trigger.*/
#define FLEXIO_TIMER_TRIGGER_SEL_PININPUT(x) ((uint32_t)(x) << 1U)
#define FLEXIO_TIMER_TRIGGER_SEL_SHIFTnSTAT(x) (((uint32_t)(x) << 2U) | 0x1U)
#define FLEXIO_TIMER_TRIGGER_SEL_TIMn(x) (((uint32_t)(x) << 2U) | 0x3U)
/*! @brief Define time of timer trigger polarity.*/
typedef enum _flexio_timer_trigger_polarity
{
kFLEXIO_TimerTriggerPolarityActiveHigh = 0x0U, /*!< Active high. */
kFLEXIO_TimerTriggerPolarityActiveLow = 0x1U, /*!< Active low. */
} flexio_timer_trigger_polarity_t;
/*! @brief Define type of timer trigger source.*/
typedef enum _flexio_timer_trigger_source
{
kFLEXIO_TimerTriggerSourceExternal = 0x0U, /*!< External trigger selected. */
kFLEXIO_TimerTriggerSourceInternal = 0x1U, /*!< Internal trigger selected. */
} flexio_timer_trigger_source_t;
/*! @brief Define type of timer/shifter pin configuration.*/
typedef enum _flexio_pin_config
{
kFLEXIO_PinConfigOutputDisabled = 0x0U, /*!< Pin output disabled. */
kFLEXIO_PinConfigOpenDrainOrBidirection = 0x1U, /*!< Pin open drain or bidirectional output enable. */
kFLEXIO_PinConfigBidirectionOutputData = 0x2U, /*!< Pin bidirectional output data. */
kFLEXIO_PinConfigOutput = 0x3U, /*!< Pin output. */
} flexio_pin_config_t;
/*! @brief Definition of pin polarity.*/
typedef enum _flexio_pin_polarity
{
kFLEXIO_PinActiveHigh = 0x0U, /*!< Active high. */
kFLEXIO_PinActiveLow = 0x1U, /*!< Active low. */
} flexio_pin_polarity_t;
/*! @brief Define type of timer work mode.*/
typedef enum _flexio_timer_mode
{
kFLEXIO_TimerModeDisabled = 0x0U, /*!< Timer Disabled. */
kFLEXIO_TimerModeDual8BitBaudBit = 0x1U, /*!< Dual 8-bit counters baud/bit mode. */
kFLEXIO_TimerModeDual8BitPWM = 0x2U, /*!< Dual 8-bit counters PWM mode. */
kFLEXIO_TimerModeSingle16Bit = 0x3U, /*!< Single 16-bit counter mode. */
} flexio_timer_mode_t;
/*! @brief Define type of timer initial output or timer reset condition.*/
typedef enum _flexio_timer_output
{
kFLEXIO_TimerOutputOneNotAffectedByReset = 0x0U, /*!< Logic one when enabled and is not affected by timer
reset. */
kFLEXIO_TimerOutputZeroNotAffectedByReset = 0x1U, /*!< Logic zero when enabled and is not affected by timer
reset. */
kFLEXIO_TimerOutputOneAffectedByReset = 0x2U, /*!< Logic one when enabled and on timer reset. */
kFLEXIO_TimerOutputZeroAffectedByReset = 0x3U, /*!< Logic zero when enabled and on timer reset. */
} flexio_timer_output_t;
/*! @brief Define type of timer decrement.*/
typedef enum _flexio_timer_decrement_source
{
kFLEXIO_TimerDecSrcOnFlexIOClockShiftTimerOutput = 0x0U, /*!< Decrement counter on FlexIO clock, Shift clock
equals Timer output. */
kFLEXIO_TimerDecSrcOnTriggerInputShiftTimerOutput = 0x1U, /*!< Decrement counter on Trigger input (both edges),
Shift clock equals Timer output. */
kFLEXIO_TimerDecSrcOnPinInputShiftPinInput = 0x2U, /*!< Decrement counter on Pin input (both edges),
Shift clock equals Pin input. */
kFLEXIO_TimerDecSrcOnTriggerInputShiftTriggerInput = 0x3U, /*!< Decrement counter on Trigger input (both edges),
Shift clock equals Trigger input. */
} flexio_timer_decrement_source_t;
/*! @brief Define type of timer reset condition.*/
typedef enum _flexio_timer_reset_condition
{
kFLEXIO_TimerResetNever = 0x0U, /*!< Timer never reset. */
kFLEXIO_TimerResetOnTimerPinEqualToTimerOutput = 0x2U, /*!< Timer reset on Timer Pin equal to Timer Output. */
kFLEXIO_TimerResetOnTimerTriggerEqualToTimerOutput = 0x3U, /*!< Timer reset on Timer Trigger equal to
Timer Output. */
kFLEXIO_TimerResetOnTimerPinRisingEdge = 0x4U, /*!< Timer reset on Timer Pin rising edge. */
kFLEXIO_TimerResetOnTimerTriggerRisingEdge = 0x6U, /*!< Timer reset on Trigger rising edge. */
kFLEXIO_TimerResetOnTimerTriggerBothEdge = 0x7U, /*!< Timer reset on Trigger rising or falling edge. */
} flexio_timer_reset_condition_t;
/*! @brief Define type of timer disable condition.*/
typedef enum _flexio_timer_disable_condition
{
kFLEXIO_TimerDisableNever = 0x0U, /*!< Timer never disabled. */
kFLEXIO_TimerDisableOnPreTimerDisable = 0x1U, /*!< Timer disabled on Timer N-1 disable. */
kFLEXIO_TimerDisableOnTimerCompare = 0x2U, /*!< Timer disabled on Timer compare. */
kFLEXIO_TimerDisableOnTimerCompareTriggerLow = 0x3U, /*!< Timer disabled on Timer compare and Trigger Low. */
kFLEXIO_TimerDisableOnPinBothEdge = 0x4U, /*!< Timer disabled on Pin rising or falling edge. */
kFLEXIO_TimerDisableOnPinBothEdgeTriggerHigh = 0x5U, /*!< Timer disabled on Pin rising or falling edge provided
Trigger is high. */
kFLEXIO_TimerDisableOnTriggerFallingEdge = 0x6U, /*!< Timer disabled on Trigger falling edge. */
} flexio_timer_disable_condition_t;
/*! @brief Define type of timer enable condition.*/
typedef enum _flexio_timer_enable_condition
{
kFLEXIO_TimerEnabledAlways = 0x0U, /*!< Timer always enabled. */
kFLEXIO_TimerEnableOnPrevTimerEnable = 0x1U, /*!< Timer enabled on Timer N-1 enable. */
kFLEXIO_TimerEnableOnTriggerHigh = 0x2U, /*!< Timer enabled on Trigger high. */
kFLEXIO_TimerEnableOnTriggerHighPinHigh = 0x3U, /*!< Timer enabled on Trigger high and Pin high. */
kFLEXIO_TimerEnableOnPinRisingEdge = 0x4U, /*!< Timer enabled on Pin rising edge. */
kFLEXIO_TimerEnableOnPinRisingEdgeTriggerHigh = 0x5U, /*!< Timer enabled on Pin rising edge and Trigger high. */
kFLEXIO_TimerEnableOnTriggerRisingEdge = 0x6U, /*!< Timer enabled on Trigger rising edge. */
kFLEXIO_TimerEnableOnTriggerBothEdge = 0x7U, /*!< Timer enabled on Trigger rising or falling edge. */
} flexio_timer_enable_condition_t;
/*! @brief Define type of timer stop bit generate condition.*/
typedef enum _flexio_timer_stop_bit_condition
{
kFLEXIO_TimerStopBitDisabled = 0x0U, /*!< Stop bit disabled. */
kFLEXIO_TimerStopBitEnableOnTimerCompare = 0x1U, /*!< Stop bit is enabled on timer compare. */
kFLEXIO_TimerStopBitEnableOnTimerDisable = 0x2U, /*!< Stop bit is enabled on timer disable. */
kFLEXIO_TimerStopBitEnableOnTimerCompareDisable = 0x3U, /*!< Stop bit is enabled on timer compare and timer
disable. */
} flexio_timer_stop_bit_condition_t;
/*! @brief Define type of timer start bit generate condition.*/
typedef enum _flexio_timer_start_bit_condition
{
kFLEXIO_TimerStartBitDisabled = 0x0U, /*!< Start bit disabled. */
kFLEXIO_TimerStartBitEnabled = 0x1U, /*!< Start bit enabled. */
} flexio_timer_start_bit_condition_t;
/*! @brief Define type of timer polarity for shifter control. */
typedef enum _flexio_shifter_timer_polarity
{
kFLEXIO_ShifterTimerPolarityOnPositive = 0x0U, /* Shift on positive edge of shift clock. */
kFLEXIO_ShifterTimerPolarityOnNegitive = 0x1U, /* Shift on negative edge of shift clock. */
} flexio_shifter_timer_polarity_t;
/*! @brief Define type of shifter working mode.*/
typedef enum _flexio_shifter_mode
{
kFLEXIO_ShifterDisabled = 0x0U, /*!< Shifter is disabled. */
kFLEXIO_ShifterModeReceive = 0x1U, /*!< Receive mode. */
kFLEXIO_ShifterModeTransmit = 0x2U, /*!< Transmit mode. */
kFLEXIO_ShifterModeMatchStore = 0x4U, /*!< Match store mode. */
kFLEXIO_ShifterModeMatchContinuous = 0x5U, /*!< Match continuous mode. */
#if defined(FSL_FEATURE_FLEXIO_HAS_STATE_MODE) && FSL_FEATURE_FLEXIO_HAS_STATE_MODE
kFLEXIO_ShifterModeState = 0x6U, /*!< SHIFTBUF contents are used for storing
programmable state attributes. */
#endif /* FSL_FEATURE_FLEXIO_HAS_STATE_MODE */
#if defined(FSL_FEATURE_FLEXIO_HAS_LOGIC_MODE) && FSL_FEATURE_FLEXIO_HAS_LOGIC_MODE
kFLEXIO_ShifterModeLogic = 0x7U, /*!< SHIFTBUF contents are used for implementing
programmable logic look up table. */
#endif /* FSL_FEATURE_FLEXIO_HAS_LOGIC_MODE */
} flexio_shifter_mode_t;
/*! @brief Define type of shifter input source.*/
typedef enum _flexio_shifter_input_source
{
kFLEXIO_ShifterInputFromPin = 0x0U, /*!< Shifter input from pin. */
kFLEXIO_ShifterInputFromNextShifterOutput = 0x1U, /*!< Shifter input from Shifter N+1. */
} flexio_shifter_input_source_t;
/*! @brief Define of STOP bit configuration.*/
typedef enum _flexio_shifter_stop_bit
{
kFLEXIO_ShifterStopBitDisable = 0x0U, /*!< Disable shifter stop bit. */
kFLEXIO_ShifterStopBitLow = 0x2U, /*!< Set shifter stop bit to logic low level. */
kFLEXIO_ShifterStopBitHigh = 0x3U, /*!< Set shifter stop bit to logic high level. */
} flexio_shifter_stop_bit_t;
/*! @brief Define type of START bit configuration.*/
typedef enum _flexio_shifter_start_bit
{
kFLEXIO_ShifterStartBitDisabledLoadDataOnEnable = 0x0U, /*!< Disable shifter start bit, transmitter loads
data on enable. */
kFLEXIO_ShifterStartBitDisabledLoadDataOnShift = 0x1U, /*!< Disable shifter start bit, transmitter loads
data on first shift. */
kFLEXIO_ShifterStartBitLow = 0x2U, /*!< Set shifter start bit to logic low level. */
kFLEXIO_ShifterStartBitHigh = 0x3U, /*!< Set shifter start bit to logic high level. */
} flexio_shifter_start_bit_t;
/*! @brief Define FlexIO shifter buffer type*/
typedef enum _flexio_shifter_buffer_type
{
kFLEXIO_ShifterBuffer = 0x0U, /*!< Shifter Buffer N Register. */
kFLEXIO_ShifterBufferBitSwapped = 0x1U, /*!< Shifter Buffer N Bit Byte Swapped Register. */
kFLEXIO_ShifterBufferByteSwapped = 0x2U, /*!< Shifter Buffer N Byte Swapped Register. */
kFLEXIO_ShifterBufferBitByteSwapped = 0x3U, /*!< Shifter Buffer N Bit Swapped Register. */
#if defined(FSL_FEATURE_FLEXIO_HAS_SHFT_BUFFER_NIBBLE_BYTE_SWAP) && FSL_FEATURE_FLEXIO_HAS_SHFT_BUFFER_NIBBLE_BYTE_SWAP
kFLEXIO_ShifterBufferNibbleByteSwapped = 0x4U, /*!< Shifter Buffer N Nibble Byte Swapped Register. */
#endif /*FSL_FEATURE_FLEXIO_HAS_SHFT_BUFFER_NIBBLE_BYTE_SWAP*/
#if defined(FSL_FEATURE_FLEXIO_HAS_SHFT_BUFFER_HALF_WORD_SWAP) && FSL_FEATURE_FLEXIO_HAS_SHFT_BUFFER_HALF_WORD_SWAP
kFLEXIO_ShifterBufferHalfWordSwapped = 0x5U, /*!< Shifter Buffer N Half Word Swapped Register. */
#endif
#if defined(FSL_FEATURE_FLEXIO_HAS_SHFT_BUFFER_NIBBLE_SWAP) && FSL_FEATURE_FLEXIO_HAS_SHFT_BUFFER_NIBBLE_SWAP
kFLEXIO_ShifterBufferNibbleSwapped = 0x6U, /*!< Shifter Buffer N Nibble Swapped Register. */
#endif
} flexio_shifter_buffer_type_t;
/*! @brief Define FlexIO user configuration structure. */
typedef struct _flexio_config_
{
bool enableFlexio; /*!< Enable/disable FlexIO module */
bool enableInDoze; /*!< Enable/disable FlexIO operation in doze mode */
bool enableInDebug; /*!< Enable/disable FlexIO operation in debug mode */
bool enableFastAccess; /*!< Enable/disable fast access to FlexIO registers, fast access requires
the FlexIO clock to be at least twice the frequency of the bus clock. */
} flexio_config_t;
/*! @brief Define FlexIO timer configuration structure. */
typedef struct _flexio_timer_config
{
/* Trigger. */
uint32_t triggerSelect; /*!< The internal trigger selection number using MACROs. */
flexio_timer_trigger_polarity_t triggerPolarity; /*!< Trigger Polarity. */
flexio_timer_trigger_source_t triggerSource; /*!< Trigger Source, internal (see 'trgsel') or external. */
/* Pin. */
flexio_pin_config_t pinConfig; /*!< Timer Pin Configuration. */
uint32_t pinSelect; /*!< Timer Pin number Select. */
flexio_pin_polarity_t pinPolarity; /*!< Timer Pin Polarity. */
/* Timer. */
flexio_timer_mode_t timerMode; /*!< Timer work Mode. */
flexio_timer_output_t timerOutput; /*!< Configures the initial state of the Timer Output and
whether it is affected by the Timer reset. */
flexio_timer_decrement_source_t timerDecrement; /*!< Configures the source of the Timer decrement and the
source of the Shift clock. */
flexio_timer_reset_condition_t timerReset; /*!< Configures the condition that causes the timer counter
(and optionally the timer output) to be reset. */
flexio_timer_disable_condition_t timerDisable; /*!< Configures the condition that causes the Timer to be
disabled and stop decrementing. */
flexio_timer_enable_condition_t timerEnable; /*!< Configures the condition that causes the Timer to be
enabled and start decrementing. */
flexio_timer_stop_bit_condition_t timerStop; /*!< Timer STOP Bit generation. */
flexio_timer_start_bit_condition_t timerStart; /*!< Timer STRAT Bit generation. */
uint32_t timerCompare; /*!< Value for Timer Compare N Register. */
} flexio_timer_config_t;
/*! @brief Define FlexIO shifter configuration structure. */
typedef struct _flexio_shifter_config
{
/* Timer. */
uint32_t timerSelect; /*!< Selects which Timer is used for controlling the
logic/shift register and generating the Shift clock. */
flexio_shifter_timer_polarity_t timerPolarity; /*!< Timer Polarity. */
/* Pin. */
flexio_pin_config_t pinConfig; /*!< Shifter Pin Configuration. */
uint32_t pinSelect; /*!< Shifter Pin number Select. */
flexio_pin_polarity_t pinPolarity; /*!< Shifter Pin Polarity. */
/* Shifter. */
flexio_shifter_mode_t shifterMode; /*!< Configures the mode of the Shifter. */
#if defined(FSL_FEATURE_FLEXIO_HAS_PARALLEL_WIDTH) && FSL_FEATURE_FLEXIO_HAS_PARALLEL_WIDTH
uint32_t parallelWidth; /*!< Configures the parallel width when using parallel mode.*/
#endif /* FSL_FEATURE_FLEXIO_HAS_PARALLEL_WIDTH */
flexio_shifter_input_source_t inputSource; /*!< Selects the input source for the shifter. */
flexio_shifter_stop_bit_t shifterStop; /*!< Shifter STOP bit. */
flexio_shifter_start_bit_t shifterStart; /*!< Shifter START bit. */
} flexio_shifter_config_t;
/*! @brief typedef for FlexIO simulated driver interrupt handler.*/
typedef void (*flexio_isr_t)(void *base, void *handle);
/*******************************************************************************
* API
******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif /*_cplusplus*/
/*!
* @name FlexIO Initialization and De-initialization
* @{
*/
/*!
* @brief Gets the default configuration to configure the FlexIO module. The configuration
* can used directly to call the FLEXIO_Configure().
*
* Example:
@code
flexio_config_t config;
FLEXIO_GetDefaultConfig(&config);
@endcode
*
* @param userConfig pointer to flexio_config_t structure
*/
void FLEXIO_GetDefaultConfig(flexio_config_t *userConfig);
/*!
* @brief Configures the FlexIO with a FlexIO configuration. The configuration structure
* can be filled by the user or be set with default values by FLEXIO_GetDefaultConfig().
*
* Example
@code
flexio_config_t config = {
.enableFlexio = true,
.enableInDoze = false,
.enableInDebug = true,
.enableFastAccess = false
};
FLEXIO_Configure(base, &config);
@endcode
*
* @param base FlexIO peripheral base address
* @param userConfig pointer to flexio_config_t structure
*/
void FLEXIO_Init(FLEXIO_Type *base, const flexio_config_t *userConfig);
/*!
* @brief Gates the FlexIO clock. Call this API to stop the FlexIO clock.
*
* @note After calling this API, call the FLEXO_Init to use the FlexIO module.
*
* @param base FlexIO peripheral base address
*/
void FLEXIO_Deinit(FLEXIO_Type *base);
/* @} */
/*!
* @name FlexIO Basic Operation
* @{
*/
/*!
* @brief Resets the FlexIO module.
*
* @param base FlexIO peripheral base address
*/
void FLEXIO_Reset(FLEXIO_Type *base);
/*!
* @brief Enables the FlexIO module operation.
*
* @param base FlexIO peripheral base address
* @param enable true to enable, false to disable.
*/
static inline void FLEXIO_Enable(FLEXIO_Type *base, bool enable)
{
if (enable)
{
base->CTRL |= FLEXIO_CTRL_FLEXEN_MASK;
}
else
{
base->CTRL &= ~FLEXIO_CTRL_FLEXEN_MASK;
}
}
#if defined(FSL_FEATURE_FLEXIO_HAS_PIN_STATUS) && FSL_FEATURE_FLEXIO_HAS_PIN_STATUS
/*!
* @brief Reads the input data on each of the FlexIO pins.
*
* @param base FlexIO peripheral base address
* @return FlexIO pin input data
*/
static inline uint32_t FLEXIO_ReadPinInput(FLEXIO_Type *base)
{
return base->PIN;
}
#endif /*FSL_FEATURE_FLEXIO_HAS_PIN_STATUS*/
#if defined(FSL_FEATURE_FLEXIO_HAS_STATE_MODE) && FSL_FEATURE_FLEXIO_HAS_STATE_MODE
/*!
* @brief Gets the current state pointer for state mode use.
*
* @param base FlexIO peripheral base address
* @return current State pointer
*/
static inline uint8_t FLEXIO_GetShifterState(FLEXIO_Type *base)
{
return ((base->SHIFTSTATE) & FLEXIO_SHIFTSTATE_STATE_MASK);
}
#endif /*FSL_FEATURE_FLEXIO_HAS_STATE_MODE*/
/*!
* @brief Configures the shifter with the shifter configuration. The configuration structure
* covers both the SHIFTCTL and SHIFTCFG registers. To configure the shifter to the proper
* mode, select which timer controls the shifter to shift, whether to generate start bit/stop
* bit, and the polarity of start bit and stop bit.
*
* Example
@code
flexio_shifter_config_t config = {
.timerSelect = 0,
.timerPolarity = kFLEXIO_ShifterTimerPolarityOnPositive,
.pinConfig = kFLEXIO_PinConfigOpenDrainOrBidirection,
.pinPolarity = kFLEXIO_PinActiveLow,
.shifterMode = kFLEXIO_ShifterModeTransmit,
.inputSource = kFLEXIO_ShifterInputFromPin,
.shifterStop = kFLEXIO_ShifterStopBitHigh,
.shifterStart = kFLEXIO_ShifterStartBitLow
};
FLEXIO_SetShifterConfig(base, &config);
@endcode
*
* @param base FlexIO peripheral base address
* @param index Shifter index
* @param shifterConfig Pointer to flexio_shifter_config_t structure
*/
void FLEXIO_SetShifterConfig(FLEXIO_Type *base, uint8_t index, const flexio_shifter_config_t *shifterConfig);
/*!
* @brief Configures the timer with the timer configuration. The configuration structure
* covers both the TIMCTL and TIMCFG registers. To configure the timer to the proper
* mode, select trigger source for timer and the timer pin output and the timing for timer.
*
* Example
@code
flexio_timer_config_t config = {
.triggerSelect = FLEXIO_TIMER_TRIGGER_SEL_SHIFTnSTAT(0),
.triggerPolarity = kFLEXIO_TimerTriggerPolarityActiveLow,
.triggerSource = kFLEXIO_TimerTriggerSourceInternal,
.pinConfig = kFLEXIO_PinConfigOpenDrainOrBidirection,
.pinSelect = 0,
.pinPolarity = kFLEXIO_PinActiveHigh,
.timerMode = kFLEXIO_TimerModeDual8BitBaudBit,
.timerOutput = kFLEXIO_TimerOutputZeroNotAffectedByReset,
.timerDecrement = kFLEXIO_TimerDecSrcOnFlexIOClockShiftTimerOutput,
.timerReset = kFLEXIO_TimerResetOnTimerPinEqualToTimerOutput,
.timerDisable = kFLEXIO_TimerDisableOnTimerCompare,
.timerEnable = kFLEXIO_TimerEnableOnTriggerHigh,
.timerStop = kFLEXIO_TimerStopBitEnableOnTimerDisable,
.timerStart = kFLEXIO_TimerStartBitEnabled
};
FLEXIO_SetTimerConfig(base, &config);
@endcode
*
* @param base FlexIO peripheral base address
* @param index Timer index
* @param timerConfig Pointer to the flexio_timer_config_t structure
*/
void FLEXIO_SetTimerConfig(FLEXIO_Type *base, uint8_t index, const flexio_timer_config_t *timerConfig);
/* @} */
/*!
* @name FlexIO Interrupt Operation
* @{
*/
/*!
* @brief Enables the shifter status interrupt. The interrupt generates when the corresponding SSF is set.
*
* @param base FlexIO peripheral base address
* @param mask The shifter status mask which can be calculated by (1 << shifter index)
* @note For multiple shifter status interrupt enable, for example, two shifter status enable, can calculate
* the mask by using ((1 << shifter index0) | (1 << shifter index1))
*/
static inline void FLEXIO_EnableShifterStatusInterrupts(FLEXIO_Type *base, uint32_t mask)
{
base->SHIFTSIEN |= mask;
}
/*!
* @brief Disables the shifter status interrupt. The interrupt won't generate when the corresponding SSF is set.
*
* @param base FlexIO peripheral base address
* @param mask The shifter status mask which can be calculated by (1 << shifter index)
* @note For multiple shifter status interrupt enable, for example, two shifter status enable, can calculate
* the mask by using ((1 << shifter index0) | (1 << shifter index1))
*/
static inline void FLEXIO_DisableShifterStatusInterrupts(FLEXIO_Type *base, uint32_t mask)
{
base->SHIFTSIEN &= ~mask;
}
/*!
* @brief Enables the shifter error interrupt. The interrupt generates when the corresponding SEF is set.
*
* @param base FlexIO peripheral base address
* @param mask The shifter error mask which can be calculated by (1 << shifter index)
* @note For multiple shifter error interrupt enable, for example, two shifter error enable, can calculate
* the mask by using ((1 << shifter index0) | (1 << shifter index1))
*/
static inline void FLEXIO_EnableShifterErrorInterrupts(FLEXIO_Type *base, uint32_t mask)
{
base->SHIFTEIEN |= mask;
}
/*!
* @brief Disables the shifter error interrupt. The interrupt won't generate when the corresponding SEF is set.
*
* @param base FlexIO peripheral base address
* @param mask The shifter error mask which can be calculated by (1 << shifter index)
* @note For multiple shifter error interrupt enable, for example, two shifter error enable, can calculate
* the mask by using ((1 << shifter index0) | (1 << shifter index1))
*/
static inline void FLEXIO_DisableShifterErrorInterrupts(FLEXIO_Type *base, uint32_t mask)
{
base->SHIFTEIEN &= ~mask;
}
/*!
* @brief Enables the timer status interrupt. The interrupt generates when the corresponding SSF is set.
*
* @param base FlexIO peripheral base address
* @param mask The timer status mask which can be calculated by (1 << timer index)
* @note For multiple timer status interrupt enable, for example, two timer status enable, can calculate
* the mask by using ((1 << timer index0) | (1 << timer index1))
*/
static inline void FLEXIO_EnableTimerStatusInterrupts(FLEXIO_Type *base, uint32_t mask)
{
base->TIMIEN |= mask;
}
/*!
* @brief Disables the timer status interrupt. The interrupt won't generate when the corresponding SSF is set.
*
* @param base FlexIO peripheral base address
* @param mask The timer status mask which can be calculated by (1 << timer index)
* @note For multiple timer status interrupt enable, for example, two timer status enable, can calculate
* the mask by using ((1 << timer index0) | (1 << timer index1))
*/
static inline void FLEXIO_DisableTimerStatusInterrupts(FLEXIO_Type *base, uint32_t mask)
{
base->TIMIEN &= ~mask;
}
/* @} */
/*!
* @name FlexIO Status Operation
* @{
*/
/*!
* @brief Gets the shifter status flags.
*
* @param base FlexIO peripheral base address
* @return Shifter status flags
*/
static inline uint32_t FLEXIO_GetShifterStatusFlags(FLEXIO_Type *base)
{
return ((base->SHIFTSTAT) & FLEXIO_SHIFTSTAT_SSF_MASK);
}
/*!
* @brief Clears the shifter status flags.
*
* @param base FlexIO peripheral base address
* @param mask The shifter status mask which can be calculated by (1 << shifter index)
* @note For clearing multiple shifter status flags, for example, two shifter status flags, can calculate
* the mask by using ((1 << shifter index0) | (1 << shifter index1))
*/
static inline void FLEXIO_ClearShifterStatusFlags(FLEXIO_Type *base, uint32_t mask)
{
base->SHIFTSTAT = mask;
}
/*!
* @brief Gets the shifter error flags.
*
* @param base FlexIO peripheral base address
* @return Shifter error flags
*/
static inline uint32_t FLEXIO_GetShifterErrorFlags(FLEXIO_Type *base)
{
return ((base->SHIFTERR) & FLEXIO_SHIFTERR_SEF_MASK);
}
/*!
* @brief Clears the shifter error flags.
*
* @param base FlexIO peripheral base address
* @param mask The shifter error mask which can be calculated by (1 << shifter index)
* @note For clearing multiple shifter error flags, for example, two shifter error flags, can calculate
* the mask by using ((1 << shifter index0) | (1 << shifter index1))
*/
static inline void FLEXIO_ClearShifterErrorFlags(FLEXIO_Type *base, uint32_t mask)
{
base->SHIFTERR = mask;
}
/*!
* @brief Gets the timer status flags.
*
* @param base FlexIO peripheral base address
* @return Timer status flags
*/
static inline uint32_t FLEXIO_GetTimerStatusFlags(FLEXIO_Type *base)
{
return ((base->TIMSTAT) & FLEXIO_TIMSTAT_TSF_MASK);
}
/*!
* @brief Clears the timer status flags.
*
* @param base FlexIO peripheral base address
* @param mask The timer status mask which can be calculated by (1 << timer index)
* @note For clearing multiple timer status flags, for example, two timer status flags, can calculate
* the mask by using ((1 << timer index0) | (1 << timer index1))
*/
static inline void FLEXIO_ClearTimerStatusFlags(FLEXIO_Type *base, uint32_t mask)
{
base->TIMSTAT = mask;
}
/* @} */
/*!
* @name FlexIO DMA Operation
* @{
*/
/*!
* @brief Enables/disables the shifter status DMA. The DMA request generates when the corresponding SSF is set.
*
* @note For multiple shifter status DMA enables, for example, calculate
* the mask by using ((1 << shifter index0) | (1 << shifter index1))
*
* @param base FlexIO peripheral base address
* @param mask The shifter status mask which can be calculated by (1 << shifter index)
* @param enable True to enable, false to disable.
*/
static inline void FLEXIO_EnableShifterStatusDMA(FLEXIO_Type *base, uint32_t mask, bool enable)
{
if (enable)
{
base->SHIFTSDEN |= mask;
}
else
{
base->SHIFTSDEN &= ~mask;
}
}
/*!
* @brief Gets the shifter buffer address for the DMA transfer usage.
*
* @param base FlexIO peripheral base address
* @param type Shifter type of flexio_shifter_buffer_type_t
* @param index Shifter index
* @return Corresponding shifter buffer index
*/
uint32_t FLEXIO_GetShifterBufferAddress(FLEXIO_Type *base, flexio_shifter_buffer_type_t type, uint8_t index);
/*!
* @brief Registers the handle and the interrupt handler for the FlexIO-simulated peripheral.
*
* @param base Pointer to the FlexIO simulated peripheral type.
* @param handle Pointer to the handler for FlexIO simulated peripheral.
* @param isr FlexIO simulated peripheral interrupt handler.
* @retval kStatus_Success Successfully create the handle.
* @retval kStatus_OutOfRange The FlexIO type/handle/ISR table out of range.
*/
status_t FLEXIO_RegisterHandleIRQ(void *base, void *handle, flexio_isr_t isr);
/*!
* @brief Unregisters the handle and the interrupt handler for the FlexIO-simulated peripheral.
*
* @param base Pointer to the FlexIO simulated peripheral type.
* @retval kStatus_Success Successfully create the handle.
* @retval kStatus_OutOfRange The FlexIO type/handle/ISR table out of range.
*/
status_t FLEXIO_UnregisterHandleIRQ(void *base);
/* @} */
#if defined(__cplusplus)
}
#endif /*_cplusplus*/
/*@}*/
#endif /*_FSL_FLEXIO_H_*/

View File

@ -0,0 +1,816 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* Copyright 2016-2017 NXP
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include "fsl_flexio_i2c_master.h"
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @brief FLEXIO I2C transfer state */
enum _flexio_i2c_master_transfer_states
{
kFLEXIO_I2C_Idle = 0x0U, /*!< I2C bus idle */
kFLEXIO_I2C_CheckAddress = 0x1U, /*!< 7-bit address check state */
kFLEXIO_I2C_SendCommand = 0x2U, /*!< Send command byte phase */
kFLEXIO_I2C_SendData = 0x3U, /*!< Send data transfer phase*/
kFLEXIO_I2C_ReceiveDataBegin = 0x4U, /*!< Receive data begin transfer phase*/
kFLEXIO_I2C_ReceiveData = 0x5U, /*!< Receive data transfer phase*/
};
#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
extern const clock_ip_name_t s_flexioClocks[];
#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
extern FLEXIO_Type *const s_flexioBases[];
/*******************************************************************************
* Prototypes
******************************************************************************/
extern uint32_t FLEXIO_GetInstance(FLEXIO_Type *base);
/*!
* @brief Set up master transfer, send slave address and decide the initial
* transfer state.
*
* @param base pointer to FLEXIO_I2C_Type structure
* @param handle pointer to flexio_i2c_master_handle_t structure which stores the transfer state
* @param transfer pointer to flexio_i2c_master_transfer_t structure
*/
static status_t FLEXIO_I2C_MasterTransferInitStateMachine(FLEXIO_I2C_Type *base,
flexio_i2c_master_handle_t *handle,
flexio_i2c_master_transfer_t *xfer);
/*!
* @brief Master run transfer state machine to perform a byte of transfer.
*
* @param base pointer to FLEXIO_I2C_Type structure
* @param handle pointer to flexio_i2c_master_handle_t structure which stores the transfer state
* @param statusFlags flexio i2c hardware status
* @retval kStatus_Success Successfully run state machine
* @retval kStatus_FLEXIO_I2C_Nak Receive Nak during transfer
*/
static status_t FLEXIO_I2C_MasterTransferRunStateMachine(FLEXIO_I2C_Type *base,
flexio_i2c_master_handle_t *handle,
uint32_t statusFlags);
/*!
* @brief Complete transfer, disable interrupt and call callback.
*
* @param base pointer to FLEXIO_I2C_Type structure
* @param handle pointer to flexio_i2c_master_handle_t structure which stores the transfer state
* @param status flexio transfer status
*/
static void FLEXIO_I2C_MasterTransferComplete(FLEXIO_I2C_Type *base,
flexio_i2c_master_handle_t *handle,
status_t status);
/*******************************************************************************
* Codes
******************************************************************************/
uint32_t FLEXIO_I2C_GetInstance(FLEXIO_I2C_Type *base)
{
return FLEXIO_GetInstance(base->flexioBase);
}
static status_t FLEXIO_I2C_MasterTransferInitStateMachine(FLEXIO_I2C_Type *base,
flexio_i2c_master_handle_t *handle,
flexio_i2c_master_transfer_t *xfer)
{
bool needRestart;
uint32_t byteCount;
/* Init the handle member. */
handle->transfer.slaveAddress = xfer->slaveAddress;
handle->transfer.direction = xfer->direction;
handle->transfer.subaddress = xfer->subaddress;
handle->transfer.subaddressSize = xfer->subaddressSize;
handle->transfer.data = xfer->data;
handle->transfer.dataSize = xfer->dataSize;
handle->transfer.flags = xfer->flags;
handle->transferSize = xfer->dataSize;
/* Initial state, i2c check address state. */
handle->state = kFLEXIO_I2C_CheckAddress;
/* Clear all status before transfer. */
FLEXIO_I2C_MasterClearStatusFlags(base, kFLEXIO_I2C_ReceiveNakFlag);
/* Calculate whether need to send re-start. */
needRestart = (handle->transfer.subaddressSize != 0) && (handle->transfer.direction == kFLEXIO_I2C_Read);
/* Calculate total byte count in a frame. */
byteCount = 1;
if (!needRestart)
{
byteCount += handle->transfer.dataSize;
}
if (handle->transfer.subaddressSize != 0)
{
byteCount += handle->transfer.subaddressSize;
/* Next state, send command byte. */
handle->state = kFLEXIO_I2C_SendCommand;
}
/* Configure data count. */
if (FLEXIO_I2C_MasterSetTransferCount(base, byteCount) != kStatus_Success)
{
return kStatus_InvalidArgument;
}
while (!((FLEXIO_GetShifterStatusFlags(base->flexioBase) & (1U << base->shifterIndex[0]))))
{
}
/* Send address byte first. */
if (needRestart)
{
FLEXIO_I2C_MasterStart(base, handle->transfer.slaveAddress, kFLEXIO_I2C_Write);
}
else
{
FLEXIO_I2C_MasterStart(base, handle->transfer.slaveAddress, handle->transfer.direction);
}
return kStatus_Success;
}
static status_t FLEXIO_I2C_MasterTransferRunStateMachine(FLEXIO_I2C_Type *base,
flexio_i2c_master_handle_t *handle,
uint32_t statusFlags)
{
if (statusFlags & kFLEXIO_I2C_ReceiveNakFlag)
{
/* Clear receive nak flag. */
FLEXIO_ClearShifterErrorFlags(base->flexioBase, 1U << base->shifterIndex[1]);
if ((!((handle->state == kFLEXIO_I2C_SendData) && (handle->transfer.dataSize == 0U))) &&
(!(((handle->state == kFLEXIO_I2C_ReceiveData) || (handle->state == kFLEXIO_I2C_ReceiveDataBegin)) &&
(handle->transfer.dataSize == 1U))))
{
FLEXIO_I2C_MasterReadByte(base);
FLEXIO_I2C_MasterAbortStop(base);
handle->state = kFLEXIO_I2C_Idle;
return kStatus_FLEXIO_I2C_Nak;
}
}
if (handle->state == kFLEXIO_I2C_CheckAddress)
{
if (handle->transfer.direction == kFLEXIO_I2C_Write)
{
/* Next state, send data. */
handle->state = kFLEXIO_I2C_SendData;
}
else
{
/* Next state, receive data begin. */
handle->state = kFLEXIO_I2C_ReceiveDataBegin;
}
}
if ((statusFlags & kFLEXIO_I2C_RxFullFlag) && (handle->state != kFLEXIO_I2C_ReceiveData))
{
FLEXIO_I2C_MasterReadByte(base);
}
switch (handle->state)
{
case kFLEXIO_I2C_SendCommand:
if (statusFlags & kFLEXIO_I2C_TxEmptyFlag)
{
if (handle->transfer.subaddressSize > 0)
{
handle->transfer.subaddressSize--;
FLEXIO_I2C_MasterWriteByte(
base, ((handle->transfer.subaddress) >> (8 * handle->transfer.subaddressSize)));
if (handle->transfer.subaddressSize == 0)
{
/* Load re-start in advance. */
if (handle->transfer.direction == kFLEXIO_I2C_Read)
{
while (!((FLEXIO_GetShifterStatusFlags(base->flexioBase) & (1U << base->shifterIndex[0]))))
{
}
FLEXIO_I2C_MasterRepeatedStart(base);
}
}
}
else
{
if (handle->transfer.direction == kFLEXIO_I2C_Write)
{
/* Next state, send data. */
handle->state = kFLEXIO_I2C_SendData;
/* Send first byte of data. */
if (handle->transfer.dataSize > 0)
{
FLEXIO_I2C_MasterWriteByte(base, *handle->transfer.data);
handle->transfer.data++;
handle->transfer.dataSize--;
}
}
else
{
FLEXIO_I2C_MasterSetTransferCount(base, (handle->transfer.dataSize + 1));
FLEXIO_I2C_MasterStart(base, handle->transfer.slaveAddress, kFLEXIO_I2C_Read);
/* Next state, receive data begin. */
handle->state = kFLEXIO_I2C_ReceiveDataBegin;
}
}
}
break;
/* Send command byte. */
case kFLEXIO_I2C_SendData:
if (statusFlags & kFLEXIO_I2C_TxEmptyFlag)
{
/* Send one byte of data. */
if (handle->transfer.dataSize > 0)
{
FLEXIO_I2C_MasterWriteByte(base, *handle->transfer.data);
handle->transfer.data++;
handle->transfer.dataSize--;
}
else
{
FLEXIO_I2C_MasterStop(base);
while (!(FLEXIO_I2C_MasterGetStatusFlags(base) & kFLEXIO_I2C_RxFullFlag))
{
}
FLEXIO_I2C_MasterReadByte(base);
handle->state = kFLEXIO_I2C_Idle;
}
}
break;
case kFLEXIO_I2C_ReceiveDataBegin:
if (statusFlags & kFLEXIO_I2C_RxFullFlag)
{
handle->state = kFLEXIO_I2C_ReceiveData;
/* Send nak at the last receive byte. */
if (handle->transfer.dataSize == 1)
{
FLEXIO_I2C_MasterEnableAck(base, false);
while (!((FLEXIO_GetShifterStatusFlags(base->flexioBase) & (1U << base->shifterIndex[0]))))
{
}
FLEXIO_I2C_MasterStop(base);
}
else
{
FLEXIO_I2C_MasterEnableAck(base, true);
}
}
else if (statusFlags & kFLEXIO_I2C_TxEmptyFlag)
{
/* Read one byte of data. */
FLEXIO_I2C_MasterWriteByte(base, 0xFFFFFFFFU);
}
else
{
}
break;
case kFLEXIO_I2C_ReceiveData:
if (statusFlags & kFLEXIO_I2C_RxFullFlag)
{
*handle->transfer.data = FLEXIO_I2C_MasterReadByte(base);
handle->transfer.data++;
if (handle->transfer.dataSize--)
{
if (handle->transfer.dataSize == 0)
{
FLEXIO_I2C_MasterDisableInterrupts(base, kFLEXIO_I2C_RxFullInterruptEnable);
handle->state = kFLEXIO_I2C_Idle;
}
/* Send nak at the last receive byte. */
if (handle->transfer.dataSize == 1)
{
FLEXIO_I2C_MasterEnableAck(base, false);
while (!((FLEXIO_GetShifterStatusFlags(base->flexioBase) & (1U << base->shifterIndex[0]))))
{
}
FLEXIO_I2C_MasterStop(base);
}
}
}
else if (statusFlags & kFLEXIO_I2C_TxEmptyFlag)
{
if (handle->transfer.dataSize > 1)
{
FLEXIO_I2C_MasterWriteByte(base, 0xFFFFFFFFU);
}
}
else
{
}
break;
default:
break;
}
return kStatus_Success;
}
static void FLEXIO_I2C_MasterTransferComplete(FLEXIO_I2C_Type *base,
flexio_i2c_master_handle_t *handle,
status_t status)
{
FLEXIO_I2C_MasterDisableInterrupts(base, kFLEXIO_I2C_TxEmptyInterruptEnable | kFLEXIO_I2C_RxFullInterruptEnable);
if (handle->completionCallback)
{
handle->completionCallback(base, handle, status, handle->userData);
}
}
status_t FLEXIO_I2C_MasterInit(FLEXIO_I2C_Type *base, flexio_i2c_master_config_t *masterConfig, uint32_t srcClock_Hz)
{
assert(base && masterConfig);
flexio_shifter_config_t shifterConfig;
flexio_timer_config_t timerConfig;
uint32_t controlVal = 0;
uint16_t timerDiv = 0;
status_t result = kStatus_Success;
memset(&shifterConfig, 0, sizeof(shifterConfig));
memset(&timerConfig, 0, sizeof(timerConfig));
#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
/* Ungate flexio clock. */
CLOCK_EnableClock(s_flexioClocks[FLEXIO_I2C_GetInstance(base)]);
#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
/* Do hardware configuration. */
/* 1. Configure the shifter 0 for tx. */
shifterConfig.timerSelect = base->timerIndex[1];
shifterConfig.timerPolarity = kFLEXIO_ShifterTimerPolarityOnPositive;
shifterConfig.pinConfig = kFLEXIO_PinConfigOpenDrainOrBidirection;
shifterConfig.pinSelect = base->SDAPinIndex;
shifterConfig.pinPolarity = kFLEXIO_PinActiveLow;
shifterConfig.shifterMode = kFLEXIO_ShifterModeTransmit;
shifterConfig.inputSource = kFLEXIO_ShifterInputFromPin;
shifterConfig.shifterStop = kFLEXIO_ShifterStopBitHigh;
shifterConfig.shifterStart = kFLEXIO_ShifterStartBitLow;
FLEXIO_SetShifterConfig(base->flexioBase, base->shifterIndex[0], &shifterConfig);
/* 2. Configure the shifter 1 for rx. */
shifterConfig.timerSelect = base->timerIndex[1];
shifterConfig.timerPolarity = kFLEXIO_ShifterTimerPolarityOnNegitive;
shifterConfig.pinConfig = kFLEXIO_PinConfigOutputDisabled;
shifterConfig.pinSelect = base->SDAPinIndex;
shifterConfig.pinPolarity = kFLEXIO_PinActiveHigh;
shifterConfig.shifterMode = kFLEXIO_ShifterModeReceive;
shifterConfig.inputSource = kFLEXIO_ShifterInputFromPin;
shifterConfig.shifterStop = kFLEXIO_ShifterStopBitLow;
shifterConfig.shifterStart = kFLEXIO_ShifterStartBitDisabledLoadDataOnEnable;
FLEXIO_SetShifterConfig(base->flexioBase, base->shifterIndex[1], &shifterConfig);
/*3. Configure the timer 0 for generating bit clock. */
timerConfig.triggerSelect = FLEXIO_TIMER_TRIGGER_SEL_SHIFTnSTAT(base->shifterIndex[0]);
timerConfig.triggerPolarity = kFLEXIO_TimerTriggerPolarityActiveLow;
timerConfig.triggerSource = kFLEXIO_TimerTriggerSourceInternal;
timerConfig.pinConfig = kFLEXIO_PinConfigOpenDrainOrBidirection;
timerConfig.pinSelect = base->SCLPinIndex;
timerConfig.pinPolarity = kFLEXIO_PinActiveHigh;
timerConfig.timerMode = kFLEXIO_TimerModeDual8BitBaudBit;
timerConfig.timerOutput = kFLEXIO_TimerOutputZeroNotAffectedByReset;
timerConfig.timerDecrement = kFLEXIO_TimerDecSrcOnFlexIOClockShiftTimerOutput;
timerConfig.timerReset = kFLEXIO_TimerResetOnTimerPinEqualToTimerOutput;
timerConfig.timerDisable = kFLEXIO_TimerDisableOnTimerCompare;
timerConfig.timerEnable = kFLEXIO_TimerEnableOnTriggerHigh;
timerConfig.timerStop = kFLEXIO_TimerStopBitEnableOnTimerDisable;
timerConfig.timerStart = kFLEXIO_TimerStartBitEnabled;
/* Set TIMCMP[7:0] = (baud rate divider / 2) - 1. */
timerDiv = (srcClock_Hz / masterConfig->baudRate_Bps) / 2 - 1;
if (timerDiv > 0xFFU)
{
result = kStatus_InvalidArgument;
return result;
}
timerConfig.timerCompare = timerDiv;
FLEXIO_SetTimerConfig(base->flexioBase, base->timerIndex[0], &timerConfig);
/* 4. Configure the timer 1 for controlling shifters. */
timerConfig.triggerSelect = FLEXIO_TIMER_TRIGGER_SEL_SHIFTnSTAT(base->shifterIndex[0]);
timerConfig.triggerPolarity = kFLEXIO_TimerTriggerPolarityActiveLow;
timerConfig.triggerSource = kFLEXIO_TimerTriggerSourceInternal;
timerConfig.pinConfig = kFLEXIO_PinConfigOutputDisabled;
timerConfig.pinSelect = base->SCLPinIndex;
timerConfig.pinPolarity = kFLEXIO_PinActiveLow;
timerConfig.timerMode = kFLEXIO_TimerModeSingle16Bit;
timerConfig.timerOutput = kFLEXIO_TimerOutputOneNotAffectedByReset;
timerConfig.timerDecrement = kFLEXIO_TimerDecSrcOnPinInputShiftPinInput;
timerConfig.timerReset = kFLEXIO_TimerResetNever;
timerConfig.timerDisable = kFLEXIO_TimerDisableOnPreTimerDisable;
timerConfig.timerEnable = kFLEXIO_TimerEnableOnPrevTimerEnable;
timerConfig.timerStop = kFLEXIO_TimerStopBitEnableOnTimerCompare;
timerConfig.timerStart = kFLEXIO_TimerStartBitEnabled;
/* Set TIMCMP[15:0] = (number of bits x 2) - 1. */
timerConfig.timerCompare = 8 * 2 - 1;
FLEXIO_SetTimerConfig(base->flexioBase, base->timerIndex[1], &timerConfig);
/* Configure FLEXIO I2C Master. */
controlVal = base->flexioBase->CTRL;
controlVal &=
~(FLEXIO_CTRL_DOZEN_MASK | FLEXIO_CTRL_DBGE_MASK | FLEXIO_CTRL_FASTACC_MASK | FLEXIO_CTRL_FLEXEN_MASK);
controlVal |= (FLEXIO_CTRL_DBGE(masterConfig->enableInDebug) | FLEXIO_CTRL_FASTACC(masterConfig->enableFastAccess) |
FLEXIO_CTRL_FLEXEN(masterConfig->enableMaster));
if (!masterConfig->enableInDoze)
{
controlVal |= FLEXIO_CTRL_DOZEN_MASK;
}
base->flexioBase->CTRL = controlVal;
return result;
}
void FLEXIO_I2C_MasterDeinit(FLEXIO_I2C_Type *base)
{
base->flexioBase->SHIFTCFG[base->shifterIndex[0]] = 0;
base->flexioBase->SHIFTCTL[base->shifterIndex[0]] = 0;
base->flexioBase->SHIFTCFG[base->shifterIndex[1]] = 0;
base->flexioBase->SHIFTCTL[base->shifterIndex[1]] = 0;
base->flexioBase->TIMCFG[base->timerIndex[0]] = 0;
base->flexioBase->TIMCMP[base->timerIndex[0]] = 0;
base->flexioBase->TIMCTL[base->timerIndex[0]] = 0;
base->flexioBase->TIMCFG[base->timerIndex[1]] = 0;
base->flexioBase->TIMCMP[base->timerIndex[1]] = 0;
base->flexioBase->TIMCTL[base->timerIndex[1]] = 0;
/* Clear the shifter flag. */
base->flexioBase->SHIFTSTAT = (1U << base->shifterIndex[0]);
base->flexioBase->SHIFTSTAT = (1U << base->shifterIndex[1]);
/* Clear the timer flag. */
base->flexioBase->TIMSTAT = (1U << base->timerIndex[0]);
base->flexioBase->TIMSTAT = (1U << base->timerIndex[1]);
}
void FLEXIO_I2C_MasterGetDefaultConfig(flexio_i2c_master_config_t *masterConfig)
{
assert(masterConfig);
masterConfig->enableMaster = true;
masterConfig->enableInDoze = false;
masterConfig->enableInDebug = true;
masterConfig->enableFastAccess = false;
/* Default baud rate at 100kbps. */
masterConfig->baudRate_Bps = 100000U;
}
uint32_t FLEXIO_I2C_MasterGetStatusFlags(FLEXIO_I2C_Type *base)
{
uint32_t status = 0;
status =
((FLEXIO_GetShifterStatusFlags(base->flexioBase) & (1U << base->shifterIndex[0])) >> base->shifterIndex[0]);
status |=
(((FLEXIO_GetShifterStatusFlags(base->flexioBase) & (1U << base->shifterIndex[1])) >> (base->shifterIndex[1]))
<< 1U);
status |=
(((FLEXIO_GetShifterErrorFlags(base->flexioBase) & (1U << base->shifterIndex[1])) >> (base->shifterIndex[1]))
<< 2U);
return status;
}
void FLEXIO_I2C_MasterClearStatusFlags(FLEXIO_I2C_Type *base, uint32_t mask)
{
if (mask & kFLEXIO_I2C_TxEmptyFlag)
{
FLEXIO_ClearShifterStatusFlags(base->flexioBase, 1U << base->shifterIndex[0]);
}
if (mask & kFLEXIO_I2C_RxFullFlag)
{
FLEXIO_ClearShifterStatusFlags(base->flexioBase, 1U << base->shifterIndex[1]);
}
if (mask & kFLEXIO_I2C_ReceiveNakFlag)
{
FLEXIO_ClearShifterErrorFlags(base->flexioBase, 1U << base->shifterIndex[1]);
}
}
void FLEXIO_I2C_MasterEnableInterrupts(FLEXIO_I2C_Type *base, uint32_t mask)
{
if (mask & kFLEXIO_I2C_TxEmptyInterruptEnable)
{
FLEXIO_EnableShifterStatusInterrupts(base->flexioBase, 1U << base->shifterIndex[0]);
}
if (mask & kFLEXIO_I2C_RxFullInterruptEnable)
{
FLEXIO_EnableShifterStatusInterrupts(base->flexioBase, 1U << base->shifterIndex[1]);
}
}
void FLEXIO_I2C_MasterDisableInterrupts(FLEXIO_I2C_Type *base, uint32_t mask)
{
if (mask & kFLEXIO_I2C_TxEmptyInterruptEnable)
{
FLEXIO_DisableShifterStatusInterrupts(base->flexioBase, 1U << base->shifterIndex[0]);
}
if (mask & kFLEXIO_I2C_RxFullInterruptEnable)
{
FLEXIO_DisableShifterStatusInterrupts(base->flexioBase, 1U << base->shifterIndex[1]);
}
}
void FLEXIO_I2C_MasterSetBaudRate(FLEXIO_I2C_Type *base, uint32_t baudRate_Bps, uint32_t srcClock_Hz)
{
uint16_t timerDiv = 0;
uint16_t timerCmp = 0;
FLEXIO_Type *flexioBase = base->flexioBase;
/* Set TIMCMP[7:0] = (baud rate divider / 2) - 1.*/
timerDiv = srcClock_Hz / baudRate_Bps;
timerDiv = timerDiv / 2 - 1U;
timerCmp = flexioBase->TIMCMP[base->timerIndex[0]];
timerCmp &= 0xFF00;
timerCmp |= timerDiv;
flexioBase->TIMCMP[base->timerIndex[0]] = timerCmp;
}
status_t FLEXIO_I2C_MasterSetTransferCount(FLEXIO_I2C_Type *base, uint8_t count)
{
if (count > 14U)
{
return kStatus_InvalidArgument;
}
uint16_t timerCmp = 0;
uint32_t timerConfig = 0;
FLEXIO_Type *flexioBase = base->flexioBase;
timerCmp = flexioBase->TIMCMP[base->timerIndex[0]];
timerCmp &= 0x00FFU;
timerCmp |= (count * 18 + 1U) << 8U;
flexioBase->TIMCMP[base->timerIndex[0]] = timerCmp;
timerConfig = flexioBase->TIMCFG[base->timerIndex[0]];
timerConfig &= ~FLEXIO_TIMCFG_TIMDIS_MASK;
timerConfig |= FLEXIO_TIMCFG_TIMDIS(kFLEXIO_TimerDisableOnTimerCompare);
flexioBase->TIMCFG[base->timerIndex[0]] = timerConfig;
return kStatus_Success;
}
void FLEXIO_I2C_MasterStart(FLEXIO_I2C_Type *base, uint8_t address, flexio_i2c_direction_t direction)
{
uint32_t data;
data = ((uint32_t)address) << 1U | ((direction == kFLEXIO_I2C_Read) ? 1U : 0U);
FLEXIO_I2C_MasterWriteByte(base, data);
}
void FLEXIO_I2C_MasterRepeatedStart(FLEXIO_I2C_Type *base)
{
/* Prepare for RESTART condition, no stop.*/
FLEXIO_I2C_MasterWriteByte(base, 0xFFFFFFFFU);
}
void FLEXIO_I2C_MasterStop(FLEXIO_I2C_Type *base)
{
/* Prepare normal stop. */
FLEXIO_I2C_MasterSetTransferCount(base, 0x0U);
FLEXIO_I2C_MasterWriteByte(base, 0x0U);
}
void FLEXIO_I2C_MasterAbortStop(FLEXIO_I2C_Type *base)
{
uint32_t tmpConfig;
/* Prepare abort stop. */
tmpConfig = base->flexioBase->TIMCFG[base->timerIndex[0]];
tmpConfig &= ~FLEXIO_TIMCFG_TIMDIS_MASK;
tmpConfig |= FLEXIO_TIMCFG_TIMDIS(kFLEXIO_TimerDisableOnPinBothEdge);
base->flexioBase->TIMCFG[base->timerIndex[0]] = tmpConfig;
}
void FLEXIO_I2C_MasterEnableAck(FLEXIO_I2C_Type *base, bool enable)
{
uint32_t tmpConfig = 0;
tmpConfig = base->flexioBase->SHIFTCFG[base->shifterIndex[0]];
tmpConfig &= ~FLEXIO_SHIFTCFG_SSTOP_MASK;
if (enable)
{
tmpConfig |= FLEXIO_SHIFTCFG_SSTOP(kFLEXIO_ShifterStopBitLow);
}
else
{
tmpConfig |= FLEXIO_SHIFTCFG_SSTOP(kFLEXIO_ShifterStopBitHigh);
}
base->flexioBase->SHIFTCFG[base->shifterIndex[0]] = tmpConfig;
}
status_t FLEXIO_I2C_MasterWriteBlocking(FLEXIO_I2C_Type *base, const uint8_t *txBuff, uint8_t txSize)
{
assert(txBuff);
assert(txSize);
uint32_t status;
while (txSize--)
{
FLEXIO_I2C_MasterWriteByte(base, *txBuff++);
/* Wait until data transfer complete. */
while (!((status = FLEXIO_I2C_MasterGetStatusFlags(base)) & kFLEXIO_I2C_RxFullFlag))
{
}
if (status & kFLEXIO_I2C_ReceiveNakFlag)
{
FLEXIO_ClearShifterErrorFlags(base->flexioBase, 1U << base->shifterIndex[1]);
return kStatus_FLEXIO_I2C_Nak;
}
}
return kStatus_Success;
}
void FLEXIO_I2C_MasterReadBlocking(FLEXIO_I2C_Type *base, uint8_t *rxBuff, uint8_t rxSize)
{
assert(rxBuff);
assert(rxSize);
while (rxSize--)
{
/* Wait until data transfer complete. */
while (!(FLEXIO_I2C_MasterGetStatusFlags(base) & kFLEXIO_I2C_RxFullFlag))
{
}
*rxBuff++ = FLEXIO_I2C_MasterReadByte(base);
}
}
status_t FLEXIO_I2C_MasterTransferBlocking(FLEXIO_I2C_Type *base, flexio_i2c_master_transfer_t *xfer)
{
assert(xfer);
flexio_i2c_master_handle_t tmpHandle;
uint32_t statusFlags;
uint32_t result = kStatus_Success;
/* Zero the handle. */
memset(&tmpHandle, 0, sizeof(tmpHandle));
/* Set up transfer machine. */
FLEXIO_I2C_MasterTransferInitStateMachine(base, &tmpHandle, xfer);
do
{
/* Wait either tx empty or rx full flag is asserted. */
while (!((statusFlags = FLEXIO_I2C_MasterGetStatusFlags(base)) &
(kFLEXIO_I2C_TxEmptyFlag | kFLEXIO_I2C_RxFullFlag)))
{
}
result = FLEXIO_I2C_MasterTransferRunStateMachine(base, &tmpHandle, statusFlags);
} while ((tmpHandle.state != kFLEXIO_I2C_Idle) && (result == kStatus_Success));
return result;
}
status_t FLEXIO_I2C_MasterTransferCreateHandle(FLEXIO_I2C_Type *base,
flexio_i2c_master_handle_t *handle,
flexio_i2c_master_transfer_callback_t callback,
void *userData)
{
assert(handle);
IRQn_Type flexio_irqs[] = FLEXIO_IRQS;
/* Zero the handle. */
memset(handle, 0, sizeof(*handle));
/* Register callback and userData. */
handle->completionCallback = callback;
handle->userData = userData;
/* Enable interrupt in NVIC. */
EnableIRQ(flexio_irqs[FLEXIO_I2C_GetInstance(base)]);
/* Save the context in global variables to support the double weak mechanism. */
return FLEXIO_RegisterHandleIRQ(base, handle, FLEXIO_I2C_MasterTransferHandleIRQ);
}
status_t FLEXIO_I2C_MasterTransferNonBlocking(FLEXIO_I2C_Type *base,
flexio_i2c_master_handle_t *handle,
flexio_i2c_master_transfer_t *xfer)
{
assert(handle);
assert(xfer);
if (handle->state != kFLEXIO_I2C_Idle)
{
return kStatus_FLEXIO_I2C_Busy;
}
else
{
/* Set up transfer machine. */
FLEXIO_I2C_MasterTransferInitStateMachine(base, handle, xfer);
/* Enable both tx empty and rxfull interrupt. */
FLEXIO_I2C_MasterEnableInterrupts(base, kFLEXIO_I2C_TxEmptyInterruptEnable | kFLEXIO_I2C_RxFullInterruptEnable);
return kStatus_Success;
}
}
void FLEXIO_I2C_MasterTransferAbort(FLEXIO_I2C_Type *base, flexio_i2c_master_handle_t *handle)
{
assert(handle);
/* Disable interrupts. */
FLEXIO_I2C_MasterDisableInterrupts(base, kFLEXIO_I2C_TxEmptyInterruptEnable | kFLEXIO_I2C_RxFullInterruptEnable);
/* Reset to idle state. */
handle->state = kFLEXIO_I2C_Idle;
}
status_t FLEXIO_I2C_MasterTransferGetCount(FLEXIO_I2C_Type *base, flexio_i2c_master_handle_t *handle, size_t *count)
{
if (!count)
{
return kStatus_InvalidArgument;
}
*count = handle->transferSize - handle->transfer.dataSize;
return kStatus_Success;
}
void FLEXIO_I2C_MasterTransferHandleIRQ(void *i2cType, void *i2cHandle)
{
FLEXIO_I2C_Type *base = (FLEXIO_I2C_Type *)i2cType;
flexio_i2c_master_handle_t *handle = (flexio_i2c_master_handle_t *)i2cHandle;
uint32_t statusFlags;
status_t result;
statusFlags = FLEXIO_I2C_MasterGetStatusFlags(base);
result = FLEXIO_I2C_MasterTransferRunStateMachine(base, handle, statusFlags);
if (handle->state == kFLEXIO_I2C_Idle)
{
FLEXIO_I2C_MasterTransferComplete(base, handle, result);
}
}

View File

@ -0,0 +1,483 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* Copyright 2016-2017 NXP
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _FSL_FLEXIO_I2C_MASTER_H_
#define _FSL_FLEXIO_I2C_MASTER_H_
#include "fsl_common.h"
#include "fsl_flexio.h"
/*!
* @addtogroup flexio_i2c_master
* @{
*/
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @name Driver version */
/*@{*/
/*! @brief FlexIO I2C master driver version 2.1.2. */
#define FSL_FLEXIO_I2C_MASTER_DRIVER_VERSION (MAKE_VERSION(2, 1, 2))
/*@}*/
/*! @brief FlexIO I2C transfer status*/
enum _flexio_i2c_status
{
kStatus_FLEXIO_I2C_Busy = MAKE_STATUS(kStatusGroup_FLEXIO_I2C, 0), /*!< I2C is busy doing transfer. */
kStatus_FLEXIO_I2C_Idle = MAKE_STATUS(kStatusGroup_FLEXIO_I2C, 1), /*!< I2C is busy doing transfer. */
kStatus_FLEXIO_I2C_Nak = MAKE_STATUS(kStatusGroup_FLEXIO_I2C, 2), /*!< NAK received during transfer. */
};
/*! @brief Define FlexIO I2C master interrupt mask. */
enum _flexio_i2c_master_interrupt
{
kFLEXIO_I2C_TxEmptyInterruptEnable = 0x1U, /*!< Tx buffer empty interrupt enable. */
kFLEXIO_I2C_RxFullInterruptEnable = 0x2U, /*!< Rx buffer full interrupt enable. */
};
/*! @brief Define FlexIO I2C master status mask. */
enum _flexio_i2c_master_status_flags
{
kFLEXIO_I2C_TxEmptyFlag = 0x1U, /*!< Tx shifter empty flag. */
kFLEXIO_I2C_RxFullFlag = 0x2U, /*!< Rx shifter full/Transfer complete flag. */
kFLEXIO_I2C_ReceiveNakFlag = 0x4U, /*!< Receive NAK flag. */
};
/*! @brief Direction of master transfer.*/
typedef enum _flexio_i2c_direction
{
kFLEXIO_I2C_Write = 0x0U, /*!< Master send to slave. */
kFLEXIO_I2C_Read = 0x1U, /*!< Master receive from slave. */
} flexio_i2c_direction_t;
/*! @brief Define FlexIO I2C master access structure typedef. */
typedef struct _flexio_i2c_type
{
FLEXIO_Type *flexioBase; /*!< FlexIO base pointer. */
uint8_t SDAPinIndex; /*!< Pin select for I2C SDA. */
uint8_t SCLPinIndex; /*!< Pin select for I2C SCL. */
uint8_t shifterIndex[2]; /*!< Shifter index used in FlexIO I2C. */
uint8_t timerIndex[2]; /*!< Timer index used in FlexIO I2C. */
} FLEXIO_I2C_Type;
/*! @brief Define FlexIO I2C master user configuration structure. */
typedef struct _flexio_i2c_master_config
{
bool enableMaster; /*!< Enables the FlexIO I2C peripheral at initialization time. */
bool enableInDoze; /*!< Enable/disable FlexIO operation in doze mode. */
bool enableInDebug; /*!< Enable/disable FlexIO operation in debug mode. */
bool enableFastAccess; /*!< Enable/disable fast access to FlexIO registers, fast access requires
the FlexIO clock to be at least twice the frequency of the bus clock. */
uint32_t baudRate_Bps; /*!< Baud rate in Bps. */
} flexio_i2c_master_config_t;
/*! @brief Define FlexIO I2C master transfer structure. */
typedef struct _flexio_i2c_master_transfer
{
uint32_t flags; /*!< Transfer flag which controls the transfer, reserved for FlexIO I2C. */
uint8_t slaveAddress; /*!< 7-bit slave address. */
flexio_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. */
} flexio_i2c_master_transfer_t;
/*! @brief FlexIO I2C master handle typedef. */
typedef struct _flexio_i2c_master_handle flexio_i2c_master_handle_t;
/*! @brief FlexIO I2C master transfer callback typedef. */
typedef void (*flexio_i2c_master_transfer_callback_t)(FLEXIO_I2C_Type *base,
flexio_i2c_master_handle_t *handle,
status_t status,
void *userData);
/*! @brief Define FlexIO I2C master handle structure. */
struct _flexio_i2c_master_handle
{
flexio_i2c_master_transfer_t transfer; /*!< FlexIO I2C master transfer copy. */
size_t transferSize; /*!< Total bytes to be transferred. */
uint8_t state; /*!< Transfer state maintained during transfer. */
flexio_i2c_master_transfer_callback_t completionCallback; /*!< Callback function called at transfer event. */
/*!< Callback function called at transfer event. */
void *userData; /*!< Callback parameter passed to callback function. */
};
/*******************************************************************************
* API
******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif /*_cplusplus*/
/*!
* @name Initialization and deinitialization
* @{
*/
/*!
* @brief Ungates the FlexIO clock, resets the FlexIO module, and configures the FlexIO I2C
* hardware configuration.
*
* Example
@code
FLEXIO_I2C_Type base = {
.flexioBase = FLEXIO,
.SDAPinIndex = 0,
.SCLPinIndex = 1,
.shifterIndex = {0,1},
.timerIndex = {0,1}
};
flexio_i2c_master_config_t config = {
.enableInDoze = false,
.enableInDebug = true,
.enableFastAccess = false,
.baudRate_Bps = 100000
};
FLEXIO_I2C_MasterInit(base, &config, srcClock_Hz);
@endcode
*
* @param base Pointer to FLEXIO_I2C_Type structure.
* @param masterConfig Pointer to flexio_i2c_master_config_t structure.
* @param srcClock_Hz FlexIO source clock in Hz.
* @retval kStatus_Success Initialization successful
* @retval kStatus_InvalidArgument The source clock exceed upper range limitation
*/
status_t FLEXIO_I2C_MasterInit(FLEXIO_I2C_Type *base, flexio_i2c_master_config_t *masterConfig, uint32_t srcClock_Hz);
/*!
* @brief De-initializes the FlexIO I2C master peripheral. Calling this API Resets the FlexIO I2C master
* shifer and timer config, module can't work unless the FLEXIO_I2C_MasterInit is called.
*
* @param base pointer to FLEXIO_I2C_Type structure.
*/
void FLEXIO_I2C_MasterDeinit(FLEXIO_I2C_Type *base);
/*!
* @brief Gets the default configuration to configure the FlexIO module. The configuration
* can be used directly for calling the FLEXIO_I2C_MasterInit().
*
* Example:
@code
flexio_i2c_master_config_t config;
FLEXIO_I2C_MasterGetDefaultConfig(&config);
@endcode
* @param masterConfig Pointer to flexio_i2c_master_config_t structure.
*/
void FLEXIO_I2C_MasterGetDefaultConfig(flexio_i2c_master_config_t *masterConfig);
/*!
* @brief Enables/disables the FlexIO module operation.
*
* @param base Pointer to FLEXIO_I2C_Type structure.
* @param enable Pass true to enable module, false does not have any effect.
*/
static inline void FLEXIO_I2C_MasterEnable(FLEXIO_I2C_Type *base, bool enable)
{
if (enable)
{
base->flexioBase->CTRL |= FLEXIO_CTRL_FLEXEN_MASK;
}
}
/* @} */
/*!
* @name Status
* @{
*/
/*!
* @brief Gets the FlexIO I2C master status flags.
*
* @param base Pointer to FLEXIO_I2C_Type structure
* @return Status flag, use status flag to AND #_flexio_i2c_master_status_flags can get the related status.
*/
uint32_t FLEXIO_I2C_MasterGetStatusFlags(FLEXIO_I2C_Type *base);
/*!
* @brief Clears the FlexIO I2C master status flags.
*
* @param base Pointer to FLEXIO_I2C_Type structure.
* @param mask Status flag.
* The parameter can be any combination of the following values:
* @arg kFLEXIO_I2C_RxFullFlag
* @arg kFLEXIO_I2C_ReceiveNakFlag
*/
void FLEXIO_I2C_MasterClearStatusFlags(FLEXIO_I2C_Type *base, uint32_t mask);
/*@}*/
/*!
* @name Interrupts
* @{
*/
/*!
* @brief Enables the FlexIO i2c master interrupt requests.
*
* @param base Pointer to FLEXIO_I2C_Type structure.
* @param mask Interrupt source.
* Currently only one interrupt request source:
* @arg kFLEXIO_I2C_TransferCompleteInterruptEnable
*/
void FLEXIO_I2C_MasterEnableInterrupts(FLEXIO_I2C_Type *base, uint32_t mask);
/*!
* @brief Disables the FlexIO I2C master interrupt requests.
*
* @param base Pointer to FLEXIO_I2C_Type structure.
* @param mask Interrupt source.
*/
void FLEXIO_I2C_MasterDisableInterrupts(FLEXIO_I2C_Type *base, uint32_t mask);
/*@}*/
/*!
* @name Bus Operations
* @{
*/
/*!
* @brief Sets the FlexIO I2C master transfer baudrate.
*
* @param base Pointer to FLEXIO_I2C_Type structure
* @param baudRate_Bps the baud rate value in HZ
* @param srcClock_Hz source clock in HZ
*/
void FLEXIO_I2C_MasterSetBaudRate(FLEXIO_I2C_Type *base, uint32_t baudRate_Bps, uint32_t srcClock_Hz);
/*!
* @brief Sends START + 7-bit address to the bus.
*
* @note This API should be called when the transfer configuration is ready to send a START signal
* and 7-bit address to the bus. This is a non-blocking API, which returns directly after the address
* is put into the data register but the address transfer is not finished on the bus. Ensure that
* the kFLEXIO_I2C_RxFullFlag status is asserted before calling this API.
* @param base Pointer to FLEXIO_I2C_Type structure.
* @param address 7-bit address.
* @param direction transfer direction.
* This parameter is one of the values in flexio_i2c_direction_t:
* @arg kFLEXIO_I2C_Write: Transmit
* @arg kFLEXIO_I2C_Read: Receive
*/
void FLEXIO_I2C_MasterStart(FLEXIO_I2C_Type *base, uint8_t address, flexio_i2c_direction_t direction);
/*!
* @brief Sends the stop signal on the bus.
*
* @param base Pointer to FLEXIO_I2C_Type structure.
*/
void FLEXIO_I2C_MasterStop(FLEXIO_I2C_Type *base);
/*!
* @brief Sends the repeated start signal on the bus.
*
* @param base Pointer to FLEXIO_I2C_Type structure.
*/
void FLEXIO_I2C_MasterRepeatedStart(FLEXIO_I2C_Type *base);
/*!
* @brief Sends the stop signal when transfer is still on-going.
*
* @param base Pointer to FLEXIO_I2C_Type structure.
*/
void FLEXIO_I2C_MasterAbortStop(FLEXIO_I2C_Type *base);
/*!
* @brief Configures the sent ACK/NAK for the following byte.
*
* @param base Pointer to FLEXIO_I2C_Type structure.
* @param enable True to configure send ACK, false configure to send NAK.
*/
void FLEXIO_I2C_MasterEnableAck(FLEXIO_I2C_Type *base, bool enable);
/*!
* @brief Sets the number of bytes to be transferred from a start signal to a stop signal.
*
* @note Call this API before a transfer begins because the timer generates a number of clocks according
* to the number of bytes that need to be transferred.
*
* @param base Pointer to FLEXIO_I2C_Type structure.
* @param count Number of bytes need to be transferred from a start signal to a re-start/stop signal
* @retval kStatus_Success Successfully configured the count.
* @retval kStatus_InvalidArgument Input argument is invalid.
*/
status_t FLEXIO_I2C_MasterSetTransferCount(FLEXIO_I2C_Type *base, uint8_t count);
/*!
* @brief Writes one byte of data to the I2C bus.
*
* @note This is a non-blocking API, which returns directly after the data is put into the
* data register but the data transfer is not finished on the bus. Ensure that
* the TxEmptyFlag is asserted before calling this API.
*
* @param base Pointer to FLEXIO_I2C_Type structure.
* @param data a byte of data.
*/
static inline void FLEXIO_I2C_MasterWriteByte(FLEXIO_I2C_Type *base, uint32_t data)
{
base->flexioBase->SHIFTBUFBBS[base->shifterIndex[0]] = data;
}
/*!
* @brief Reads one byte of data from the I2C bus.
*
* @note This is a non-blocking API, which returns directly after the data is read from the
* data register. Ensure that the data is ready in the register.
*
* @param base Pointer to FLEXIO_I2C_Type structure.
* @return data byte read.
*/
static inline uint8_t FLEXIO_I2C_MasterReadByte(FLEXIO_I2C_Type *base)
{
return base->flexioBase->SHIFTBUFBIS[base->shifterIndex[1]];
}
/*!
* @brief Sends a buffer of data in bytes.
*
* @note This function blocks via polling until all bytes have been sent.
*
* @param base Pointer to FLEXIO_I2C_Type structure.
* @param txBuff The data bytes to send.
* @param txSize The number of data bytes to send.
* @retval kStatus_Success Successfully write data.
* @retval kStatus_FLEXIO_I2C_Nak Receive NAK during writing data.
*/
status_t FLEXIO_I2C_MasterWriteBlocking(FLEXIO_I2C_Type *base, const uint8_t *txBuff, uint8_t txSize);
/*!
* @brief Receives a buffer of bytes.
*
* @note This function blocks via polling until all bytes have been received.
*
* @param base Pointer to FLEXIO_I2C_Type structure.
* @param rxBuff The buffer to store the received bytes.
* @param rxSize The number of data bytes to be received.
*/
void FLEXIO_I2C_MasterReadBlocking(FLEXIO_I2C_Type *base, uint8_t *rxBuff, uint8_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 receiving NAK.
*
* @param base pointer to FLEXIO_I2C_Type structure.
* @param xfer pointer to flexio_i2c_master_transfer_t structure.
* @return status of status_t.
*/
status_t FLEXIO_I2C_MasterTransferBlocking(FLEXIO_I2C_Type *base, flexio_i2c_master_transfer_t *xfer);
/*@}*/
/*Transactional APIs*/
/*!
* @name Transactional
* @{
*/
/*!
* @brief Initializes the I2C handle which is used in transactional functions.
*
* @param base Pointer to FLEXIO_I2C_Type structure.
* @param handle Pointer to flexio_i2c_master_handle_t structure to store the transfer state.
* @param callback Pointer to user callback function.
* @param userData User param passed to the callback function.
* @retval kStatus_Success Successfully create the handle.
* @retval kStatus_OutOfRange The FlexIO type/handle/isr table out of range.
*/
status_t FLEXIO_I2C_MasterTransferCreateHandle(FLEXIO_I2C_Type *base,
flexio_i2c_master_handle_t *handle,
flexio_i2c_master_transfer_callback_t callback,
void *userData);
/*!
* @brief Performs a master interrupt non-blocking transfer on the I2C bus.
*
* @note The API returns immediately after the transfer initiates.
* Call FLEXIO_I2C_MasterGetTransferCount to poll the transfer status to check whether
* the transfer is finished. If the return status is not kStatus_FLEXIO_I2C_Busy, the transfer
* is finished.
*
* @param base Pointer to FLEXIO_I2C_Type structure
* @param handle Pointer to flexio_i2c_master_handle_t structure which stores the transfer state
* @param xfer pointer to flexio_i2c_master_transfer_t structure
* @retval kStatus_Success Successfully start a transfer.
* @retval kStatus_FLEXIO_I2C_Busy FlexIO I2C is not idle, is running another transfer.
*/
status_t FLEXIO_I2C_MasterTransferNonBlocking(FLEXIO_I2C_Type *base,
flexio_i2c_master_handle_t *handle,
flexio_i2c_master_transfer_t *xfer);
/*!
* @brief Gets the master transfer status during a interrupt non-blocking transfer.
*
* @param base Pointer to FLEXIO_I2C_Type structure.
* @param handle Pointer to flexio_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 FLEXIO_I2C_MasterTransferGetCount(FLEXIO_I2C_Type *base, flexio_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 Pointer to FLEXIO_I2C_Type structure
* @param handle Pointer to flexio_i2c_master_handle_t structure which stores the transfer state
*/
void FLEXIO_I2C_MasterTransferAbort(FLEXIO_I2C_Type *base, flexio_i2c_master_handle_t *handle);
/*!
* @brief Master interrupt handler.
*
* @param i2cType Pointer to FLEXIO_I2C_Type structure
* @param i2cHandle Pointer to flexio_i2c_master_transfer_t structure
*/
void FLEXIO_I2C_MasterTransferHandleIRQ(void *i2cType, void *i2cHandle);
/*@}*/
#if defined(__cplusplus)
}
#endif /*_cplusplus*/
/*@}*/
#endif /*_FSL_FLEXIO_I2C_MASTER_H_*/

View File

@ -0,0 +1,666 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* Copyright 2016-2017 NXP
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include "fsl_flexio_i2s.h"
/*******************************************************************************
* Definitations
******************************************************************************/
enum _sai_transfer_state
{
kFLEXIO_I2S_Busy = 0x0U, /*!< FLEXIO_I2S is busy */
kFLEXIO_I2S_Idle, /*!< Transfer is done. */
};
/*******************************************************************************
* Prototypes
******************************************************************************/
extern uint32_t FLEXIO_GetInstance(FLEXIO_Type *base);
/*!
* @brief Receive a piece of data in non-blocking way.
*
* @param base FLEXIO I2S base pointer
* @param bitWidth How many bits in a audio word, usually 8/16/24/32 bits.
* @param buffer Pointer to the data to be read.
* @param size Bytes to be read.
*/
static void FLEXIO_I2S_ReadNonBlocking(FLEXIO_I2S_Type *base, uint8_t bitWidth, uint8_t *rxData, size_t size);
/*!
* @brief sends a piece of data in non-blocking way.
*
* @param base FLEXIO I2S base pointer
* @param bitWidth How many bits in a audio word, usually 8/16/24/32 bits.
* @param buffer Pointer to the data to be written.
* @param size Bytes to be written.
*/
static void FLEXIO_I2S_WriteNonBlocking(FLEXIO_I2S_Type *base, uint8_t bitWidth, uint8_t *txData, size_t size);
/*******************************************************************************
* Variables
******************************************************************************/
#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
extern const clock_ip_name_t s_flexioClocks[];
#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
extern FLEXIO_Type *const s_flexioBases[];
/*******************************************************************************
* Code
******************************************************************************/
uint32_t FLEXIO_I2S_GetInstance(FLEXIO_I2S_Type *base)
{
return FLEXIO_GetInstance(base->flexioBase);
}
static void FLEXIO_I2S_WriteNonBlocking(FLEXIO_I2S_Type *base, uint8_t bitWidth, uint8_t *txData, size_t size)
{
uint32_t i = 0;
uint8_t j = 0;
uint8_t bytesPerWord = bitWidth / 8U;
uint32_t data = 0;
uint32_t temp = 0;
for (i = 0; i < size / bytesPerWord; i++)
{
for (j = 0; j < bytesPerWord; j++)
{
temp = (uint32_t)(*txData);
data |= (temp << (8U * j));
txData++;
}
base->flexioBase->SHIFTBUFBIS[base->txShifterIndex] = (data << (32U - bitWidth));
data = 0;
}
}
static void FLEXIO_I2S_ReadNonBlocking(FLEXIO_I2S_Type *base, uint8_t bitWidth, uint8_t *rxData, size_t size)
{
uint32_t i = 0;
uint8_t j = 0;
uint8_t bytesPerWord = bitWidth / 8U;
uint32_t data = 0;
for (i = 0; i < size / bytesPerWord; i++)
{
data = (base->flexioBase->SHIFTBUFBIS[base->rxShifterIndex] >> (32U - bitWidth));
for (j = 0; j < bytesPerWord; j++)
{
*rxData = (data >> (8U * j)) & 0xFF;
rxData++;
}
}
}
void FLEXIO_I2S_Init(FLEXIO_I2S_Type *base, const flexio_i2s_config_t *config)
{
assert(base && config);
flexio_shifter_config_t shifterConfig = {0};
flexio_timer_config_t timerConfig = {0};
#if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
/* Ungate flexio clock. */
CLOCK_EnableClock(s_flexioClocks[FLEXIO_I2S_GetInstance(base)]);
#endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
/* Set shifter for I2S Tx data */
shifterConfig.timerSelect = base->bclkTimerIndex;
shifterConfig.pinSelect = base->txPinIndex;
shifterConfig.timerPolarity = config->txTimerPolarity;
shifterConfig.pinConfig = kFLEXIO_PinConfigOutput;
shifterConfig.pinPolarity = config->txPinPolarity;
shifterConfig.shifterMode = kFLEXIO_ShifterModeTransmit;
shifterConfig.inputSource = kFLEXIO_ShifterInputFromPin;
shifterConfig.shifterStop = kFLEXIO_ShifterStopBitDisable;
if (config->masterSlave == kFLEXIO_I2S_Master)
{
shifterConfig.shifterStart = kFLEXIO_ShifterStartBitDisabledLoadDataOnShift;
}
else
{
shifterConfig.shifterStart = kFLEXIO_ShifterStartBitDisabledLoadDataOnEnable;
}
FLEXIO_SetShifterConfig(base->flexioBase, base->txShifterIndex, &shifterConfig);
/* Set shifter for I2S Rx Data */
shifterConfig.timerSelect = base->bclkTimerIndex;
shifterConfig.pinSelect = base->rxPinIndex;
shifterConfig.timerPolarity = config->rxTimerPolarity;
shifterConfig.pinConfig = kFLEXIO_PinConfigOutputDisabled;
shifterConfig.pinPolarity = config->rxPinPolarity;
shifterConfig.shifterMode = kFLEXIO_ShifterModeReceive;
shifterConfig.inputSource = kFLEXIO_ShifterInputFromPin;
shifterConfig.shifterStop = kFLEXIO_ShifterStopBitDisable;
shifterConfig.shifterStart = kFLEXIO_ShifterStartBitDisabledLoadDataOnEnable;
FLEXIO_SetShifterConfig(base->flexioBase, base->rxShifterIndex, &shifterConfig);
/* Set Timer to I2S frame sync */
if (config->masterSlave == kFLEXIO_I2S_Master)
{
timerConfig.triggerSelect = FLEXIO_TIMER_TRIGGER_SEL_PININPUT(base->txPinIndex);
timerConfig.triggerPolarity = kFLEXIO_TimerTriggerPolarityActiveHigh;
timerConfig.triggerSource = kFLEXIO_TimerTriggerSourceExternal;
timerConfig.pinConfig = kFLEXIO_PinConfigOutput;
timerConfig.pinSelect = base->fsPinIndex;
timerConfig.pinPolarity = config->fsPinPolarity;
timerConfig.timerMode = kFLEXIO_TimerModeSingle16Bit;
timerConfig.timerOutput = kFLEXIO_TimerOutputOneNotAffectedByReset;
timerConfig.timerDecrement = kFLEXIO_TimerDecSrcOnFlexIOClockShiftTimerOutput;
timerConfig.timerReset = kFLEXIO_TimerResetNever;
timerConfig.timerDisable = kFLEXIO_TimerDisableNever;
timerConfig.timerEnable = kFLEXIO_TimerEnableOnPrevTimerEnable;
timerConfig.timerStart = kFLEXIO_TimerStartBitDisabled;
timerConfig.timerStop = kFLEXIO_TimerStopBitDisabled;
}
else
{
timerConfig.triggerSelect = FLEXIO_TIMER_TRIGGER_SEL_PININPUT(base->bclkPinIndex);
timerConfig.triggerPolarity = kFLEXIO_TimerTriggerPolarityActiveHigh;
timerConfig.triggerSource = kFLEXIO_TimerTriggerSourceInternal;
timerConfig.pinConfig = kFLEXIO_PinConfigOutputDisabled;
timerConfig.pinSelect = base->fsPinIndex;
timerConfig.pinPolarity = config->fsPinPolarity;
timerConfig.timerMode = kFLEXIO_TimerModeSingle16Bit;
timerConfig.timerOutput = kFLEXIO_TimerOutputOneNotAffectedByReset;
timerConfig.timerDecrement = kFLEXIO_TimerDecSrcOnTriggerInputShiftTriggerInput;
timerConfig.timerReset = kFLEXIO_TimerResetNever;
timerConfig.timerDisable = kFLEXIO_TimerDisableOnTimerCompare;
timerConfig.timerEnable = kFLEXIO_TimerEnableOnPinRisingEdge;
timerConfig.timerStart = kFLEXIO_TimerStartBitDisabled;
timerConfig.timerStop = kFLEXIO_TimerStopBitDisabled;
}
FLEXIO_SetTimerConfig(base->flexioBase, base->fsTimerIndex, &timerConfig);
/* Set Timer to I2S bit clock */
if (config->masterSlave == kFLEXIO_I2S_Master)
{
timerConfig.triggerSelect = FLEXIO_TIMER_TRIGGER_SEL_SHIFTnSTAT(base->txShifterIndex);
timerConfig.triggerPolarity = kFLEXIO_TimerTriggerPolarityActiveLow;
timerConfig.triggerSource = kFLEXIO_TimerTriggerSourceInternal;
timerConfig.pinSelect = base->bclkPinIndex;
timerConfig.pinConfig = kFLEXIO_PinConfigOutput;
timerConfig.pinPolarity = config->bclkPinPolarity;
timerConfig.timerMode = kFLEXIO_TimerModeDual8BitBaudBit;
timerConfig.timerOutput = kFLEXIO_TimerOutputOneNotAffectedByReset;
timerConfig.timerDecrement = kFLEXIO_TimerDecSrcOnFlexIOClockShiftTimerOutput;
timerConfig.timerReset = kFLEXIO_TimerResetNever;
timerConfig.timerDisable = kFLEXIO_TimerDisableNever;
timerConfig.timerEnable = kFLEXIO_TimerEnableOnTriggerHigh;
timerConfig.timerStart = kFLEXIO_TimerStartBitEnabled;
timerConfig.timerStop = kFLEXIO_TimerStopBitDisabled;
}
else
{
timerConfig.triggerSelect = FLEXIO_TIMER_TRIGGER_SEL_TIMn(base->fsTimerIndex);
timerConfig.triggerPolarity = kFLEXIO_TimerTriggerPolarityActiveHigh;
timerConfig.triggerSource = kFLEXIO_TimerTriggerSourceInternal;
timerConfig.pinSelect = base->bclkPinIndex;
timerConfig.pinConfig = kFLEXIO_PinConfigOutputDisabled;
timerConfig.pinPolarity = config->bclkPinPolarity;
timerConfig.timerMode = kFLEXIO_TimerModeSingle16Bit;
timerConfig.timerOutput = kFLEXIO_TimerOutputOneNotAffectedByReset;
timerConfig.timerDecrement = kFLEXIO_TimerDecSrcOnPinInputShiftPinInput;
timerConfig.timerReset = kFLEXIO_TimerResetNever;
timerConfig.timerDisable = kFLEXIO_TimerDisableOnTimerCompareTriggerLow;
timerConfig.timerEnable = kFLEXIO_TimerEnableOnPinRisingEdgeTriggerHigh;
timerConfig.timerStart = kFLEXIO_TimerStartBitDisabled;
timerConfig.timerStop = kFLEXIO_TimerStopBitDisabled;
}
FLEXIO_SetTimerConfig(base->flexioBase, base->bclkTimerIndex, &timerConfig);
/* If enable flexio I2S */
if (config->enableI2S)
{
base->flexioBase->CTRL |= FLEXIO_CTRL_FLEXEN_MASK;
}
else
{
base->flexioBase->CTRL &= ~FLEXIO_CTRL_FLEXEN_MASK;
}
}
void FLEXIO_I2S_GetDefaultConfig(flexio_i2s_config_t *config)
{
config->masterSlave = kFLEXIO_I2S_Master;
config->enableI2S = true;
config->txPinPolarity = kFLEXIO_PinActiveHigh;
config->rxPinPolarity = kFLEXIO_PinActiveHigh;
config->bclkPinPolarity = kFLEXIO_PinActiveHigh;
config->fsPinPolarity = kFLEXIO_PinActiveLow;
config->txTimerPolarity = kFLEXIO_ShifterTimerPolarityOnPositive;
config->rxTimerPolarity = kFLEXIO_ShifterTimerPolarityOnNegitive;
}
void FLEXIO_I2S_Deinit(FLEXIO_I2S_Type *base)
{
base->flexioBase->SHIFTCFG[base->txShifterIndex] = 0;
base->flexioBase->SHIFTCTL[base->txShifterIndex] = 0;
base->flexioBase->SHIFTCFG[base->rxShifterIndex] = 0;
base->flexioBase->SHIFTCTL[base->rxShifterIndex] = 0;
base->flexioBase->TIMCFG[base->fsTimerIndex] = 0;
base->flexioBase->TIMCMP[base->fsTimerIndex] = 0;
base->flexioBase->TIMCTL[base->fsTimerIndex] = 0;
base->flexioBase->TIMCFG[base->bclkTimerIndex] = 0;
base->flexioBase->TIMCMP[base->bclkTimerIndex] = 0;
base->flexioBase->TIMCTL[base->bclkTimerIndex] = 0;
}
void FLEXIO_I2S_EnableInterrupts(FLEXIO_I2S_Type *base, uint32_t mask)
{
if (mask & kFLEXIO_I2S_TxDataRegEmptyInterruptEnable)
{
FLEXIO_EnableShifterStatusInterrupts(base->flexioBase, 1U << base->txShifterIndex);
}
if (mask & kFLEXIO_I2S_RxDataRegFullInterruptEnable)
{
FLEXIO_EnableShifterStatusInterrupts(base->flexioBase, 1U << base->rxShifterIndex);
}
}
uint32_t FLEXIO_I2S_GetStatusFlags(FLEXIO_I2S_Type *base)
{
uint32_t status = 0;
status = ((FLEXIO_GetShifterStatusFlags(base->flexioBase) & (1U << base->txShifterIndex)) >> base->txShifterIndex);
status |=
(((FLEXIO_GetShifterStatusFlags(base->flexioBase) & (1U << base->rxShifterIndex)) >> (base->rxShifterIndex))
<< 1U);
return status;
}
void FLEXIO_I2S_DisableInterrupts(FLEXIO_I2S_Type *base, uint32_t mask)
{
if (mask & kFLEXIO_I2S_TxDataRegEmptyInterruptEnable)
{
FLEXIO_DisableShifterStatusInterrupts(base->flexioBase, 1U << base->txShifterIndex);
}
if (mask & kFLEXIO_I2S_RxDataRegFullInterruptEnable)
{
FLEXIO_DisableShifterStatusInterrupts(base->flexioBase, 1U << base->rxShifterIndex);
}
}
void FLEXIO_I2S_MasterSetFormat(FLEXIO_I2S_Type *base, flexio_i2s_format_t *format, uint32_t srcClock_Hz)
{
uint32_t timDiv = srcClock_Hz / (format->sampleRate_Hz * 32U * 2U);
uint32_t bclkDiv = 0;
/* Shall keep bclk and fs div an integer */
if (timDiv % 2)
{
timDiv += 1U;
}
/* Set Frame sync timer cmp */
base->flexioBase->TIMCMP[base->fsTimerIndex] = FLEXIO_TIMCMP_CMP(32U * timDiv - 1U);
/* Set bit clock timer cmp */
bclkDiv = ((timDiv / 2U - 1U) | (63U << 8U));
base->flexioBase->TIMCMP[base->bclkTimerIndex] = FLEXIO_TIMCMP_CMP(bclkDiv);
}
void FLEXIO_I2S_SlaveSetFormat(FLEXIO_I2S_Type *base, flexio_i2s_format_t *format)
{
/* Set Frame sync timer cmp */
base->flexioBase->TIMCMP[base->fsTimerIndex] = FLEXIO_TIMCMP_CMP(32U * 4U - 3U);
/* Set bit clock timer cmp */
base->flexioBase->TIMCMP[base->bclkTimerIndex] = FLEXIO_TIMCMP_CMP(32U * 2U - 1U);
}
void FLEXIO_I2S_WriteBlocking(FLEXIO_I2S_Type *base, uint8_t bitWidth, uint8_t *txData, size_t size)
{
uint32_t i = 0;
uint8_t bytesPerWord = bitWidth / 8U;
for (i = 0; i < size / bytesPerWord; i++)
{
/* Wait until it can write data */
while ((FLEXIO_I2S_GetStatusFlags(base) & kFLEXIO_I2S_TxDataRegEmptyFlag) == 0)
{
}
FLEXIO_I2S_WriteNonBlocking(base, bitWidth, txData, bytesPerWord);
txData += bytesPerWord;
}
/* Wait until the last data is sent */
while ((FLEXIO_I2S_GetStatusFlags(base) & kFLEXIO_I2S_TxDataRegEmptyFlag) == 0)
{
}
}
void FLEXIO_I2S_ReadBlocking(FLEXIO_I2S_Type *base, uint8_t bitWidth, uint8_t *rxData, size_t size)
{
uint32_t i = 0;
uint8_t bytesPerWord = bitWidth / 8U;
for (i = 0; i < size / bytesPerWord; i++)
{
/* Wait until data is received */
while (!(FLEXIO_GetShifterStatusFlags(base->flexioBase) & (1U << base->rxShifterIndex)))
{
}
FLEXIO_I2S_ReadNonBlocking(base, bitWidth, rxData, bytesPerWord);
rxData += bytesPerWord;
}
}
void FLEXIO_I2S_TransferTxCreateHandle(FLEXIO_I2S_Type *base,
flexio_i2s_handle_t *handle,
flexio_i2s_callback_t callback,
void *userData)
{
assert(handle);
IRQn_Type flexio_irqs[] = FLEXIO_IRQS;
/* Zero the handle. */
memset(handle, 0, sizeof(*handle));
/* Store callback and user data. */
handle->callback = callback;
handle->userData = userData;
/* Save the context in global variables to support the double weak mechanism. */
FLEXIO_RegisterHandleIRQ(base, handle, FLEXIO_I2S_TransferTxHandleIRQ);
/* Set the TX/RX state. */
handle->state = kFLEXIO_I2S_Idle;
/* Enable interrupt in NVIC. */
EnableIRQ(flexio_irqs[FLEXIO_I2S_GetInstance(base)]);
}
void FLEXIO_I2S_TransferRxCreateHandle(FLEXIO_I2S_Type *base,
flexio_i2s_handle_t *handle,
flexio_i2s_callback_t callback,
void *userData)
{
assert(handle);
IRQn_Type flexio_irqs[] = FLEXIO_IRQS;
/* Zero the handle. */
memset(handle, 0, sizeof(*handle));
/* Store callback and user data. */
handle->callback = callback;
handle->userData = userData;
/* Save the context in global variables to support the double weak mechanism. */
FLEXIO_RegisterHandleIRQ(base, handle, FLEXIO_I2S_TransferRxHandleIRQ);
/* Set the TX/RX state. */
handle->state = kFLEXIO_I2S_Idle;
/* Enable interrupt in NVIC. */
EnableIRQ(flexio_irqs[FLEXIO_I2S_GetInstance(base)]);
}
void FLEXIO_I2S_TransferSetFormat(FLEXIO_I2S_Type *base,
flexio_i2s_handle_t *handle,
flexio_i2s_format_t *format,
uint32_t srcClock_Hz)
{
assert(handle && format);
/* Set the bitWidth to handle */
handle->bitWidth = format->bitWidth;
/* Set sample rate */
if (srcClock_Hz != 0)
{
/* It is master */
FLEXIO_I2S_MasterSetFormat(base, format, srcClock_Hz);
}
else
{
FLEXIO_I2S_SlaveSetFormat(base, format);
}
}
status_t FLEXIO_I2S_TransferSendNonBlocking(FLEXIO_I2S_Type *base,
flexio_i2s_handle_t *handle,
flexio_i2s_transfer_t *xfer)
{
assert(handle);
/* Check if the queue is full */
if (handle->queue[handle->queueUser].data)
{
return kStatus_FLEXIO_I2S_QueueFull;
}
if ((xfer->dataSize == 0) || (xfer->data == NULL))
{
return kStatus_InvalidArgument;
}
/* Add into queue */
handle->queue[handle->queueUser].data = xfer->data;
handle->queue[handle->queueUser].dataSize = xfer->dataSize;
handle->transferSize[handle->queueUser] = xfer->dataSize;
handle->queueUser = (handle->queueUser + 1) % FLEXIO_I2S_XFER_QUEUE_SIZE;
/* Set the state to busy */
handle->state = kFLEXIO_I2S_Busy;
FLEXIO_I2S_EnableInterrupts(base, kFLEXIO_I2S_TxDataRegEmptyInterruptEnable);
/* Enable Tx transfer */
FLEXIO_I2S_Enable(base, true);
return kStatus_Success;
}
status_t FLEXIO_I2S_TransferReceiveNonBlocking(FLEXIO_I2S_Type *base,
flexio_i2s_handle_t *handle,
flexio_i2s_transfer_t *xfer)
{
assert(handle);
/* Check if the queue is full */
if (handle->queue[handle->queueUser].data)
{
return kStatus_FLEXIO_I2S_QueueFull;
}
if ((xfer->dataSize == 0) || (xfer->data == NULL))
{
return kStatus_InvalidArgument;
}
/* Add into queue */
handle->queue[handle->queueUser].data = xfer->data;
handle->queue[handle->queueUser].dataSize = xfer->dataSize;
handle->transferSize[handle->queueUser] = xfer->dataSize;
handle->queueUser = (handle->queueUser + 1) % FLEXIO_I2S_XFER_QUEUE_SIZE;
/* Set state to busy */
handle->state = kFLEXIO_I2S_Busy;
/* Enable interrupt */
FLEXIO_I2S_EnableInterrupts(base, kFLEXIO_I2S_RxDataRegFullInterruptEnable);
/* Enable Rx transfer */
FLEXIO_I2S_Enable(base, true);
return kStatus_Success;
}
void FLEXIO_I2S_TransferAbortSend(FLEXIO_I2S_Type *base, flexio_i2s_handle_t *handle)
{
assert(handle);
/* Stop Tx transfer and disable interrupt */
FLEXIO_I2S_DisableInterrupts(base, kFLEXIO_I2S_TxDataRegEmptyInterruptEnable);
handle->state = kFLEXIO_I2S_Idle;
/* Clear the queue */
memset(handle->queue, 0, sizeof(flexio_i2s_transfer_t) * FLEXIO_I2S_XFER_QUEUE_SIZE);
handle->queueDriver = 0;
handle->queueUser = 0;
}
void FLEXIO_I2S_TransferAbortReceive(FLEXIO_I2S_Type *base, flexio_i2s_handle_t *handle)
{
assert(handle);
/* Stop rx transfer and disable interrupt */
FLEXIO_I2S_DisableInterrupts(base, kFLEXIO_I2S_RxDataRegFullInterruptEnable);
handle->state = kFLEXIO_I2S_Idle;
/* Clear the queue */
memset(handle->queue, 0, sizeof(flexio_i2s_transfer_t) * FLEXIO_I2S_XFER_QUEUE_SIZE);
handle->queueDriver = 0;
handle->queueUser = 0;
}
status_t FLEXIO_I2S_TransferGetSendCount(FLEXIO_I2S_Type *base, flexio_i2s_handle_t *handle, size_t *count)
{
assert(handle);
status_t status = kStatus_Success;
if (handle->state != kFLEXIO_I2S_Busy)
{
status = kStatus_NoTransferInProgress;
}
else
{
*count = (handle->transferSize[handle->queueDriver] - handle->queue[handle->queueDriver].dataSize);
}
return status;
}
status_t FLEXIO_I2S_TransferGetReceiveCount(FLEXIO_I2S_Type *base, flexio_i2s_handle_t *handle, size_t *count)
{
assert(handle);
status_t status = kStatus_Success;
if (handle->state != kFLEXIO_I2S_Busy)
{
status = kStatus_NoTransferInProgress;
}
else
{
*count = (handle->transferSize[handle->queueDriver] - handle->queue[handle->queueDriver].dataSize);
}
return status;
}
void FLEXIO_I2S_TransferTxHandleIRQ(void *i2sBase, void *i2sHandle)
{
assert(i2sHandle);
flexio_i2s_handle_t *handle = (flexio_i2s_handle_t *)i2sHandle;
FLEXIO_I2S_Type *base = (FLEXIO_I2S_Type *)i2sBase;
uint8_t *buffer = handle->queue[handle->queueDriver].data;
uint8_t dataSize = handle->bitWidth / 8U;
/* Handle error */
if (FLEXIO_GetShifterErrorFlags(base->flexioBase) & (1U << base->txShifterIndex))
{
FLEXIO_ClearShifterErrorFlags(base->flexioBase, (1U << base->txShifterIndex));
}
/* Handle transfer */
if (((FLEXIO_I2S_GetStatusFlags(base) & kFLEXIO_I2S_TxDataRegEmptyFlag) != 0) &&
(handle->queue[handle->queueDriver].data != NULL))
{
FLEXIO_I2S_WriteNonBlocking(base, handle->bitWidth, buffer, dataSize);
/* Update internal counter */
handle->queue[handle->queueDriver].dataSize -= dataSize;
handle->queue[handle->queueDriver].data += dataSize;
}
/* If finished a blcok, call the callback function */
if ((handle->queue[handle->queueDriver].dataSize == 0U) && (handle->queue[handle->queueDriver].data != NULL))
{
memset(&handle->queue[handle->queueDriver], 0, sizeof(flexio_i2s_transfer_t));
handle->queueDriver = (handle->queueDriver + 1) % FLEXIO_I2S_XFER_QUEUE_SIZE;
if (handle->callback)
{
(handle->callback)(base, handle, kStatus_Success, handle->userData);
}
}
/* If all data finished, just stop the transfer */
if (handle->queue[handle->queueDriver].data == NULL)
{
FLEXIO_I2S_TransferAbortSend(base, handle);
}
}
void FLEXIO_I2S_TransferRxHandleIRQ(void *i2sBase, void *i2sHandle)
{
assert(i2sHandle);
flexio_i2s_handle_t *handle = (flexio_i2s_handle_t *)i2sHandle;
FLEXIO_I2S_Type *base = (FLEXIO_I2S_Type *)i2sBase;
uint8_t *buffer = handle->queue[handle->queueDriver].data;
uint8_t dataSize = handle->bitWidth / 8U;
/* Handle transfer */
if (((FLEXIO_I2S_GetStatusFlags(base) & kFLEXIO_I2S_RxDataRegFullFlag) != 0) &&
(handle->queue[handle->queueDriver].data != NULL))
{
FLEXIO_I2S_ReadNonBlocking(base, handle->bitWidth, buffer, dataSize);
/* Update internal state */
handle->queue[handle->queueDriver].dataSize -= dataSize;
handle->queue[handle->queueDriver].data += dataSize;
}
/* If finished a blcok, call the callback function */
if ((handle->queue[handle->queueDriver].dataSize == 0U) && (handle->queue[handle->queueDriver].data != NULL))
{
memset(&handle->queue[handle->queueDriver], 0, sizeof(flexio_i2s_transfer_t));
handle->queueDriver = (handle->queueDriver + 1) % FLEXIO_I2S_XFER_QUEUE_SIZE;
if (handle->callback)
{
(handle->callback)(base, handle, kStatus_Success, handle->userData);
}
}
/* If all data finished, just stop the transfer */
if (handle->queue[handle->queueDriver].data == NULL)
{
FLEXIO_I2S_TransferAbortReceive(base, handle);
}
}

View File

@ -0,0 +1,570 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* Copyright 2016-2017 NXP
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _FSL_FLEXIO_I2S_H_
#define _FSL_FLEXIO_I2S_H_
#include "fsl_common.h"
#include "fsl_flexio.h"
/*!
* @addtogroup flexio_i2s
* @{
*/
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @name Driver version */
/*@{*/
/*! @brief FlexIO I2S driver version 2.1.1. */
#define FSL_FLEXIO_I2S_DRIVER_VERSION (MAKE_VERSION(2, 1, 2))
/*@}*/
/*! @brief FlexIO I2S transfer status */
enum _flexio_i2s_status
{
kStatus_FLEXIO_I2S_Idle = MAKE_STATUS(kStatusGroup_FLEXIO_I2S, 0), /*!< FlexIO I2S is in idle state */
kStatus_FLEXIO_I2S_TxBusy = MAKE_STATUS(kStatusGroup_FLEXIO_I2S, 1), /*!< FlexIO I2S Tx is busy */
kStatus_FLEXIO_I2S_RxBusy = MAKE_STATUS(kStatusGroup_FLEXIO_I2S, 2), /*!< FlexIO I2S Tx is busy */
kStatus_FLEXIO_I2S_Error = MAKE_STATUS(kStatusGroup_FLEXIO_I2S, 3), /*!< FlexIO I2S error occurred */
kStatus_FLEXIO_I2S_QueueFull = MAKE_STATUS(kStatusGroup_FLEXIO_I2S, 4), /*!< FlexIO I2S transfer queue is full. */
};
/*! @brief Define FlexIO I2S access structure typedef */
typedef struct _flexio_i2s_type
{
FLEXIO_Type *flexioBase; /*!< FlexIO base pointer */
uint8_t txPinIndex; /*!< Tx data pin index in FlexIO pins */
uint8_t rxPinIndex; /*!< Rx data pin index */
uint8_t bclkPinIndex; /*!< Bit clock pin index */
uint8_t fsPinIndex; /*!< Frame sync pin index */
uint8_t txShifterIndex; /*!< Tx data shifter index */
uint8_t rxShifterIndex; /*!< Rx data shifter index */
uint8_t bclkTimerIndex; /*!< Bit clock timer index */
uint8_t fsTimerIndex; /*!< Frame sync timer index */
} FLEXIO_I2S_Type;
/*! @brief Master or slave mode */
typedef enum _flexio_i2s_master_slave
{
kFLEXIO_I2S_Master = 0x0U, /*!< Master mode */
kFLEXIO_I2S_Slave = 0x1U /*!< Slave mode */
} flexio_i2s_master_slave_t;
/*! @brief Define FlexIO FlexIO I2S interrupt mask. */
enum _flexio_i2s_interrupt_enable
{
kFLEXIO_I2S_TxDataRegEmptyInterruptEnable = 0x1U, /*!< Transmit buffer empty interrupt enable. */
kFLEXIO_I2S_RxDataRegFullInterruptEnable = 0x2U, /*!< Receive buffer full interrupt enable. */
};
/*! @brief Define FlexIO FlexIO I2S status mask. */
enum _flexio_i2s_status_flags
{
kFLEXIO_I2S_TxDataRegEmptyFlag = 0x1U, /*!< Transmit buffer empty flag. */
kFLEXIO_I2S_RxDataRegFullFlag = 0x2U, /*!< Receive buffer full flag. */
};
/*! @brief FlexIO I2S configure structure */
typedef struct _flexio_i2s_config
{
bool enableI2S; /*!< Enable FlexIO I2S */
flexio_i2s_master_slave_t masterSlave; /*!< Master or slave */
flexio_pin_polarity_t txPinPolarity; /*!< Tx data pin polarity, active high or low */
flexio_pin_polarity_t rxPinPolarity; /*!< Rx data pin polarity */
flexio_pin_polarity_t bclkPinPolarity; /*!< Bit clock pin polarity */
flexio_pin_polarity_t fsPinPolarity; /*!< Frame sync pin polarity */
flexio_shifter_timer_polarity_t txTimerPolarity; /*!< Tx data valid on bclk rising or falling edge */
flexio_shifter_timer_polarity_t rxTimerPolarity; /*!< Rx data valid on bclk rising or falling edge */
} flexio_i2s_config_t;
/*! @brief FlexIO I2S audio format, FlexIO I2S only support the same format in Tx and Rx */
typedef struct _flexio_i2s_format
{
uint8_t bitWidth; /*!< Bit width of audio data, always 8/16/24/32 bits */
uint32_t sampleRate_Hz; /*!< Sample rate of the audio data */
} flexio_i2s_format_t;
/*!@brief FlexIO I2S transfer queue size, user can refine it according to use case. */
#define FLEXIO_I2S_XFER_QUEUE_SIZE (4)
/*! @brief Audio sample rate */
typedef enum _flexio_i2s_sample_rate
{
kFLEXIO_I2S_SampleRate8KHz = 8000U, /*!< Sample rate 8000Hz */
kFLEXIO_I2S_SampleRate11025Hz = 11025U, /*!< Sample rate 11025Hz */
kFLEXIO_I2S_SampleRate12KHz = 12000U, /*!< Sample rate 12000Hz */
kFLEXIO_I2S_SampleRate16KHz = 16000U, /*!< Sample rate 16000Hz */
kFLEXIO_I2S_SampleRate22050Hz = 22050U, /*!< Sample rate 22050Hz */
kFLEXIO_I2S_SampleRate24KHz = 24000U, /*!< Sample rate 24000Hz */
kFLEXIO_I2S_SampleRate32KHz = 32000U, /*!< Sample rate 32000Hz */
kFLEXIO_I2S_SampleRate44100Hz = 44100U, /*!< Sample rate 44100Hz */
kFLEXIO_I2S_SampleRate48KHz = 48000U, /*!< Sample rate 48000Hz */
kFLEXIO_I2S_SampleRate96KHz = 96000U /*!< Sample rate 96000Hz */
} flexio_i2s_sample_rate_t;
/*! @brief Audio word width */
typedef enum _flexio_i2s_word_width
{
kFLEXIO_I2S_WordWidth8bits = 8U, /*!< Audio data width 8 bits */
kFLEXIO_I2S_WordWidth16bits = 16U, /*!< Audio data width 16 bits */
kFLEXIO_I2S_WordWidth24bits = 24U, /*!< Audio data width 24 bits */
kFLEXIO_I2S_WordWidth32bits = 32U /*!< Audio data width 32 bits */
} flexio_i2s_word_width_t;
/*! @brief Define FlexIO I2S transfer structure. */
typedef struct _flexio_i2s_transfer
{
uint8_t *data; /*!< Data buffer start pointer */
size_t dataSize; /*!< Bytes to be transferred. */
} flexio_i2s_transfer_t;
typedef struct _flexio_i2s_handle flexio_i2s_handle_t;
/*! @brief FlexIO I2S xfer callback prototype */
typedef void (*flexio_i2s_callback_t)(FLEXIO_I2S_Type *base,
flexio_i2s_handle_t *handle,
status_t status,
void *userData);
/*! @brief Define FlexIO I2S handle structure. */
struct _flexio_i2s_handle
{
uint32_t state; /*!< Internal state */
flexio_i2s_callback_t callback; /*!< Callback function called at transfer event*/
void *userData; /*!< Callback parameter passed to callback function*/
uint8_t bitWidth; /*!< Bit width for transfer, 8/16/24/32bits */
flexio_i2s_transfer_t queue[FLEXIO_I2S_XFER_QUEUE_SIZE]; /*!< Transfer queue storing queued transfer */
size_t transferSize[FLEXIO_I2S_XFER_QUEUE_SIZE]; /*!< Data bytes need to transfer */
volatile uint8_t queueUser; /*!< Index for user to queue transfer */
volatile uint8_t queueDriver; /*!< Index for driver to get the transfer data and size */
};
/*******************************************************************************
* API
******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif /*_cplusplus*/
/*!
* @name Initialization and deinitialization
* @{
*/
/*!
* @brief Initializes the FlexIO I2S.
*
* This API configures FlexIO pins and shifter to I2S and configures the FlexIO I2S with a configuration structure.
* The configuration structure can be filled by the user, or be set with default values by
* FLEXIO_I2S_GetDefaultConfig().
*
* @note This API should be called at the beginning of the application to use
* the FlexIO I2S driver. Otherwise, any access to the FlexIO I2S module can cause hard fault
* because the clock is not enabled.
*
* @param base FlexIO I2S base pointer
* @param config FlexIO I2S configure structure.
*/
void FLEXIO_I2S_Init(FLEXIO_I2S_Type *base, const flexio_i2s_config_t *config);
/*!
* @brief Sets the FlexIO I2S configuration structure to default values.
*
* The purpose of this API is to get the configuration structure initialized for use in FLEXIO_I2S_Init().
* Users may use the initialized structure unchanged in FLEXIO_I2S_Init() or modify
* some fields of the structure before calling FLEXIO_I2S_Init().
*
* @param config pointer to master configuration structure
*/
void FLEXIO_I2S_GetDefaultConfig(flexio_i2s_config_t *config);
/*!
* @brief De-initializes the FlexIO I2S.
*
* Calling this API resets the FlexIO I2S shifter and timer config. After calling this API,
* call the FLEXO_I2S_Init to use the FlexIO I2S module.
*
* @param base FlexIO I2S base pointer
*/
void FLEXIO_I2S_Deinit(FLEXIO_I2S_Type *base);
/*!
* @brief Enables/disables the FlexIO I2S module operation.
*
* @param base Pointer to FLEXIO_I2S_Type
* @param enable True to enable, false dose not have any effect.
*/
static inline void FLEXIO_I2S_Enable(FLEXIO_I2S_Type *base, bool enable)
{
if (enable)
{
base->flexioBase->CTRL |= FLEXIO_CTRL_FLEXEN_MASK;
}
}
/*! @} */
/*!
* @name Status
* @{
*/
/*!
* @brief Gets the FlexIO I2S status flags.
*
* @param base Pointer to FLEXIO_I2S_Type structure
* @return Status flag, which are ORed by the enumerators in the _flexio_i2s_status_flags.
*/
uint32_t FLEXIO_I2S_GetStatusFlags(FLEXIO_I2S_Type *base);
/*! @} */
/*!
* @name Interrupts
* @{
*/
/*!
* @brief Enables the FlexIO I2S interrupt.
*
* This function enables the FlexIO UART interrupt.
*
* @param base Pointer to FLEXIO_I2S_Type structure
* @param mask interrupt source
*/
void FLEXIO_I2S_EnableInterrupts(FLEXIO_I2S_Type *base, uint32_t mask);
/*!
* @brief Disables the FlexIO I2S interrupt.
*
* This function enables the FlexIO UART interrupt.
*
* @param base pointer to FLEXIO_I2S_Type structure
* @param mask interrupt source
*/
void FLEXIO_I2S_DisableInterrupts(FLEXIO_I2S_Type *base, uint32_t mask);
/*! @} */
/*!
* @name DMA Control
* @{
*/
/*!
* @brief Enables/disables the FlexIO I2S Tx DMA requests.
*
* @param base FlexIO I2S base pointer
* @param enable True means enable DMA, false means disable DMA.
*/
static inline void FLEXIO_I2S_TxEnableDMA(FLEXIO_I2S_Type *base, bool enable)
{
FLEXIO_EnableShifterStatusDMA(base->flexioBase, 1 << base->txShifterIndex, enable);
}
/*!
* @brief Enables/disables the FlexIO I2S Rx DMA requests.
*
* @param base FlexIO I2S base pointer
* @param enable True means enable DMA, false means disable DMA.
*/
static inline void FLEXIO_I2S_RxEnableDMA(FLEXIO_I2S_Type *base, bool enable)
{
FLEXIO_EnableShifterStatusDMA(base->flexioBase, 1 << base->rxShifterIndex, enable);
}
/*!
* @brief Gets the FlexIO I2S send data register address.
*
* This function returns the I2S data register address, mainly used by DMA/eDMA.
*
* @param base Pointer to FLEXIO_I2S_Type structure
* @return FlexIO i2s send data register address.
*/
static inline uint32_t FLEXIO_I2S_TxGetDataRegisterAddress(FLEXIO_I2S_Type *base)
{
return FLEXIO_GetShifterBufferAddress(base->flexioBase, kFLEXIO_ShifterBufferBitSwapped, base->txShifterIndex);
}
/*!
* @brief Gets the FlexIO I2S receive data register address.
*
* This function returns the I2S data register address, mainly used by DMA/eDMA.
*
* @param base Pointer to FLEXIO_I2S_Type structure
* @return FlexIO i2s receive data register address.
*/
static inline uint32_t FLEXIO_I2S_RxGetDataRegisterAddress(FLEXIO_I2S_Type *base)
{
return FLEXIO_GetShifterBufferAddress(base->flexioBase, kFLEXIO_ShifterBufferBitSwapped, base->rxShifterIndex);
}
/*! @} */
/*!
* @name Bus Operations
* @{
*/
/*!
* @brief Configures the FlexIO I2S audio format in master mode.
*
* Audio format can be changed in run-time of FlexIO I2S. This function configures the sample rate and audio data
* format to be transferred.
*
* @param base Pointer to FLEXIO_I2S_Type structure
* @param format Pointer to FlexIO I2S audio data format structure.
* @param srcClock_Hz I2S master clock source frequency in Hz.
*/
void FLEXIO_I2S_MasterSetFormat(FLEXIO_I2S_Type *base, flexio_i2s_format_t *format, uint32_t srcClock_Hz);
/*!
* @brief Configures the FlexIO I2S audio format in slave mode.
*
* Audio format can be changed in run-time of FlexIO I2S. This function configures the sample rate and audio data
* format to be transferred.
*
* @param base Pointer to FLEXIO_I2S_Type structure
* @param format Pointer to FlexIO I2S audio data format structure.
*/
void FLEXIO_I2S_SlaveSetFormat(FLEXIO_I2S_Type *base, flexio_i2s_format_t *format);
/*!
* @brief Sends data using a blocking method.
*
* @note This function blocks via polling until data is ready to be sent.
*
* @param base FlexIO I2S base pointer.
* @param bitWidth How many bits in a audio word, usually 8/16/24/32 bits.
* @param txData Pointer to the data to be written.
* @param size Bytes to be written.
*/
void FLEXIO_I2S_WriteBlocking(FLEXIO_I2S_Type *base, uint8_t bitWidth, uint8_t *txData, size_t size);
/*!
* @brief Writes data into a data register.
*
* @param base FlexIO I2S base pointer.
* @param bitWidth How many bits in a audio word, usually 8/16/24/32 bits.
* @param data Data to be written.
*/
static inline void FLEXIO_I2S_WriteData(FLEXIO_I2S_Type *base, uint8_t bitWidth, uint32_t data)
{
base->flexioBase->SHIFTBUFBIS[base->txShifterIndex] = (data << (32U - bitWidth));
}
/*!
* @brief Receives a piece of data using a blocking method.
*
* @note This function blocks via polling until data is ready to be sent.
*
* @param base FlexIO I2S base pointer
* @param bitWidth How many bits in a audio word, usually 8/16/24/32 bits.
* @param rxData Pointer to the data to be read.
* @param size Bytes to be read.
*/
void FLEXIO_I2S_ReadBlocking(FLEXIO_I2S_Type *base, uint8_t bitWidth, uint8_t *rxData, size_t size);
/*!
* @brief Reads a data from the data register.
*
* @param base FlexIO I2S base pointer
* @return Data read from data register.
*/
static inline uint32_t FLEXIO_I2S_ReadData(FLEXIO_I2S_Type *base)
{
return base->flexioBase->SHIFTBUFBIS[base->rxShifterIndex];
}
/*! @} */
/*!
* @name Transactional
* @{
*/
/*!
* @brief Initializes the FlexIO I2S handle.
*
* This function initializes the FlexIO I2S handle which can be used for other
* FlexIO I2S transactional APIs. Call this API once to get the
* initialized handle.
*
* @param base Pointer to FLEXIO_I2S_Type structure
* @param handle Pointer to flexio_i2s_handle_t structure to store the transfer state.
* @param callback FlexIO I2S callback function, which is called while finished a block.
* @param userData User parameter for the FlexIO I2S callback.
*/
void FLEXIO_I2S_TransferTxCreateHandle(FLEXIO_I2S_Type *base,
flexio_i2s_handle_t *handle,
flexio_i2s_callback_t callback,
void *userData);
/*!
* @brief Configures the FlexIO I2S audio format.
*
* Audio format can be changed at run-time of FlexIO I2S. This function configures the sample rate and audio data
* format to be transferred.
*
* @param base Pointer to FLEXIO_I2S_Type structure.
* @param handle FlexIO I2S handle pointer.
* @param format Pointer to audio data format structure.
* @param srcClock_Hz FlexIO I2S bit clock source frequency in Hz. This parameter should be 0 while in slave mode.
*/
void FLEXIO_I2S_TransferSetFormat(FLEXIO_I2S_Type *base,
flexio_i2s_handle_t *handle,
flexio_i2s_format_t *format,
uint32_t srcClock_Hz);
/*!
* @brief Initializes the FlexIO I2S receive handle.
*
* This function initializes the FlexIO I2S handle which can be used for other
* FlexIO I2S transactional APIs. Call this API once to get the
* initialized handle.
*
* @param base Pointer to FLEXIO_I2S_Type structure.
* @param handle Pointer to flexio_i2s_handle_t structure to store the transfer state.
* @param callback FlexIO I2S callback function, which is called while finished a block.
* @param userData User parameter for the FlexIO I2S callback.
*/
void FLEXIO_I2S_TransferRxCreateHandle(FLEXIO_I2S_Type *base,
flexio_i2s_handle_t *handle,
flexio_i2s_callback_t callback,
void *userData);
/*!
* @brief Performs an interrupt non-blocking send transfer on FlexIO I2S.
*
* @note The API returns immediately after transfer initiates.
* Call FLEXIO_I2S_GetRemainingBytes to poll the transfer status and check whether
* the transfer is finished. If the return status is 0, the transfer is finished.
*
* @param base Pointer to FLEXIO_I2S_Type structure.
* @param handle Pointer to flexio_i2s_handle_t structure which stores the transfer state
* @param xfer Pointer to flexio_i2s_transfer_t structure
* @retval kStatus_Success Successfully start the data transmission.
* @retval kStatus_FLEXIO_I2S_TxBusy Previous transmission still not finished, data not all written to TX register yet.
* @retval kStatus_InvalidArgument The input parameter is invalid.
*/
status_t FLEXIO_I2S_TransferSendNonBlocking(FLEXIO_I2S_Type *base,
flexio_i2s_handle_t *handle,
flexio_i2s_transfer_t *xfer);
/*!
* @brief Performs an interrupt non-blocking receive transfer on FlexIO I2S.
*
* @note The API returns immediately after transfer initiates.
* Call FLEXIO_I2S_GetRemainingBytes to poll the transfer status to check whether
* the transfer is finished. If the return status is 0, the transfer is finished.
*
* @param base Pointer to FLEXIO_I2S_Type structure.
* @param handle Pointer to flexio_i2s_handle_t structure which stores the transfer state
* @param xfer Pointer to flexio_i2s_transfer_t structure
* @retval kStatus_Success Successfully start the data receive.
* @retval kStatus_FLEXIO_I2S_RxBusy Previous receive still not finished.
* @retval kStatus_InvalidArgument The input parameter is invalid.
*/
status_t FLEXIO_I2S_TransferReceiveNonBlocking(FLEXIO_I2S_Type *base,
flexio_i2s_handle_t *handle,
flexio_i2s_transfer_t *xfer);
/*!
* @brief Aborts the current send.
*
* @note This API can be called at any time when interrupt non-blocking transfer initiates
* to abort the transfer in a early time.
*
* @param base Pointer to FLEXIO_I2S_Type structure.
* @param handle Pointer to flexio_i2s_handle_t structure which stores the transfer state
*/
void FLEXIO_I2S_TransferAbortSend(FLEXIO_I2S_Type *base, flexio_i2s_handle_t *handle);
/*!
* @brief Aborts the current receive.
*
* @note This API can be called at any time when interrupt non-blocking transfer initiates
* to abort the transfer in a early time.
*
* @param base Pointer to FLEXIO_I2S_Type structure.
* @param handle Pointer to flexio_i2s_handle_t structure which stores the transfer state
*/
void FLEXIO_I2S_TransferAbortReceive(FLEXIO_I2S_Type *base, flexio_i2s_handle_t *handle);
/*!
* @brief Gets the remaining bytes to be sent.
*
* @param base Pointer to FLEXIO_I2S_Type structure.
* @param handle Pointer to flexio_i2s_handle_t structure which stores the transfer state
* @param count Bytes sent.
* @retval kStatus_Success Succeed get the transfer count.
* @retval kStatus_NoTransferInProgress There is not a non-blocking transaction currently in progress.
*/
status_t FLEXIO_I2S_TransferGetSendCount(FLEXIO_I2S_Type *base, flexio_i2s_handle_t *handle, size_t *count);
/*!
* @brief Gets the remaining bytes to be received.
*
* @param base Pointer to FLEXIO_I2S_Type structure.
* @param handle Pointer to flexio_i2s_handle_t structure which stores the transfer state
* @return count Bytes received.
* @retval kStatus_Success Succeed get the transfer count.
* @retval kStatus_NoTransferInProgress There is not a non-blocking transaction currently in progress.
*/
status_t FLEXIO_I2S_TransferGetReceiveCount(FLEXIO_I2S_Type *base, flexio_i2s_handle_t *handle, size_t *count);
/*!
* @brief Tx interrupt handler.
*
* @param i2sBase Pointer to FLEXIO_I2S_Type structure.
* @param i2sHandle Pointer to flexio_i2s_handle_t structure
*/
void FLEXIO_I2S_TransferTxHandleIRQ(void *i2sBase, void *i2sHandle);
/*!
* @brief Rx interrupt handler.
*
* @param i2sBase Pointer to FLEXIO_I2S_Type structure.
* @param i2sHandle Pointer to flexio_i2s_handle_t structure.
*/
void FLEXIO_I2S_TransferRxHandleIRQ(void *i2sBase, void *i2sHandle);
/*! @} */
#if defined(__cplusplus)
}
#endif /*_cplusplus*/
/*! @} */
#endif /* _FSL_FLEXIO_I2S_H_ */

View File

@ -0,0 +1,367 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* Copyright 2016-2017 NXP
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include "fsl_flexio_i2s_edma.h"
/*******************************************************************************
* Definitations
******************************************************************************/
/* Used for 32byte aligned */
#define STCD_ADDR(address) (edma_tcd_t *)(((uint32_t)address + 32) & ~0x1FU)
/*<! Structure definition for flexio_i2s_edma_private_handle_t. The structure is private. */
typedef struct _flexio_i2s_edma_private_handle
{
FLEXIO_I2S_Type *base;
flexio_i2s_edma_handle_t *handle;
} flexio_i2s_edma_private_handle_t;
enum _flexio_i2s_edma_transfer_state
{
kFLEXIO_I2S_Busy = 0x0U, /*!< FLEXIO I2S is busy */
kFLEXIO_I2S_Idle, /*!< Transfer is done. */
};
/*<! Private handle only used for internally. */
static flexio_i2s_edma_private_handle_t s_edmaPrivateHandle[2];
/*******************************************************************************
* Prototypes
******************************************************************************/
/*!
* @brief FLEXIO I2S EDMA callback for send.
*
* @param handle pointer to flexio_i2s_edma_handle_t structure which stores the transfer state.
* @param userData Parameter for user callback.
* @param done If the DMA transfer finished.
* @param tcds The TCD index.
*/
static void FLEXIO_I2S_TxEDMACallback(edma_handle_t *handle, void *userData, bool done, uint32_t tcds);
/*!
* @brief FLEXIO I2S EDMA callback for receive.
*
* @param handle pointer to flexio_i2s_edma_handle_t structure which stores the transfer state.
* @param userData Parameter for user callback.
* @param done If the DMA transfer finished.
* @param tcds The TCD index.
*/
static void FLEXIO_I2S_RxEDMACallback(edma_handle_t *handle, void *userData, bool done, uint32_t tcds);
/*******************************************************************************
* Code
******************************************************************************/
static void FLEXIO_I2S_TxEDMACallback(edma_handle_t *handle, void *userData, bool done, uint32_t tcds)
{
flexio_i2s_edma_private_handle_t *privHandle = (flexio_i2s_edma_private_handle_t *)userData;
flexio_i2s_edma_handle_t *flexio_i2sHandle = privHandle->handle;
/* If finished a blcok, call the callback function */
memset(&flexio_i2sHandle->queue[flexio_i2sHandle->queueDriver], 0, sizeof(flexio_i2s_transfer_t));
flexio_i2sHandle->queueDriver = (flexio_i2sHandle->queueDriver + 1) % FLEXIO_I2S_XFER_QUEUE_SIZE;
if (flexio_i2sHandle->callback)
{
(flexio_i2sHandle->callback)(privHandle->base, flexio_i2sHandle, kStatus_Success, flexio_i2sHandle->userData);
}
/* If all data finished, just stop the transfer */
if (flexio_i2sHandle->queue[flexio_i2sHandle->queueDriver].data == NULL)
{
FLEXIO_I2S_TransferAbortSendEDMA(privHandle->base, flexio_i2sHandle);
}
}
static void FLEXIO_I2S_RxEDMACallback(edma_handle_t *handle, void *userData, bool done, uint32_t tcds)
{
flexio_i2s_edma_private_handle_t *privHandle = (flexio_i2s_edma_private_handle_t *)userData;
flexio_i2s_edma_handle_t *flexio_i2sHandle = privHandle->handle;
/* If finished a blcok, call the callback function */
memset(&flexio_i2sHandle->queue[flexio_i2sHandle->queueDriver], 0, sizeof(flexio_i2s_transfer_t));
flexio_i2sHandle->queueDriver = (flexio_i2sHandle->queueDriver + 1) % FLEXIO_I2S_XFER_QUEUE_SIZE;
if (flexio_i2sHandle->callback)
{
(flexio_i2sHandle->callback)(privHandle->base, flexio_i2sHandle, kStatus_Success, flexio_i2sHandle->userData);
}
/* If all data finished, just stop the transfer */
if (flexio_i2sHandle->queue[flexio_i2sHandle->queueDriver].data == NULL)
{
FLEXIO_I2S_TransferAbortReceiveEDMA(privHandle->base, flexio_i2sHandle);
}
}
void FLEXIO_I2S_TransferTxCreateHandleEDMA(FLEXIO_I2S_Type *base,
flexio_i2s_edma_handle_t *handle,
flexio_i2s_edma_callback_t callback,
void *userData,
edma_handle_t *dmaHandle)
{
assert(handle && dmaHandle);
/* Zero the handle. */
memset(handle, 0, sizeof(*handle));
/* Set flexio_i2s base to handle */
handle->dmaHandle = dmaHandle;
handle->callback = callback;
handle->userData = userData;
/* Set FLEXIO I2S state to idle */
handle->state = kFLEXIO_I2S_Idle;
s_edmaPrivateHandle[0].base = base;
s_edmaPrivateHandle[0].handle = handle;
/* Need to use scatter gather */
EDMA_InstallTCDMemory(dmaHandle, STCD_ADDR(handle->tcd), FLEXIO_I2S_XFER_QUEUE_SIZE);
/* Install callback for Tx dma channel */
EDMA_SetCallback(dmaHandle, FLEXIO_I2S_TxEDMACallback, &s_edmaPrivateHandle[0]);
}
void FLEXIO_I2S_TransferRxCreateHandleEDMA(FLEXIO_I2S_Type *base,
flexio_i2s_edma_handle_t *handle,
flexio_i2s_edma_callback_t callback,
void *userData,
edma_handle_t *dmaHandle)
{
assert(handle && dmaHandle);
/* Zero the handle. */
memset(handle, 0, sizeof(*handle));
/* Set flexio_i2s base to handle */
handle->dmaHandle = dmaHandle;
handle->callback = callback;
handle->userData = userData;
/* Set FLEXIO I2S state to idle */
handle->state = kFLEXIO_I2S_Idle;
s_edmaPrivateHandle[1].base = base;
s_edmaPrivateHandle[1].handle = handle;
/* Need to use scatter gather */
EDMA_InstallTCDMemory(dmaHandle, STCD_ADDR(handle->tcd), FLEXIO_I2S_XFER_QUEUE_SIZE);
/* Install callback for Tx dma channel */
EDMA_SetCallback(dmaHandle, FLEXIO_I2S_RxEDMACallback, &s_edmaPrivateHandle[1]);
}
void FLEXIO_I2S_TransferSetFormatEDMA(FLEXIO_I2S_Type *base,
flexio_i2s_edma_handle_t *handle,
flexio_i2s_format_t *format,
uint32_t srcClock_Hz)
{
assert(handle && format);
/* Configure the audio format to FLEXIO I2S registers */
if (srcClock_Hz != 0)
{
/* It is master */
FLEXIO_I2S_MasterSetFormat(base, format, srcClock_Hz);
}
else
{
FLEXIO_I2S_SlaveSetFormat(base, format);
}
/* Get the tranfer size from format, this should be used in EDMA configuration */
handle->bytesPerFrame = format->bitWidth / 8U;
}
status_t FLEXIO_I2S_TransferSendEDMA(FLEXIO_I2S_Type *base,
flexio_i2s_edma_handle_t *handle,
flexio_i2s_transfer_t *xfer)
{
assert(handle && xfer);
edma_transfer_config_t config = {0};
uint32_t destAddr = FLEXIO_I2S_TxGetDataRegisterAddress(base) + (4U - handle->bytesPerFrame);
/* Check if input parameter invalid */
if ((xfer->data == NULL) || (xfer->dataSize == 0U))
{
return kStatus_InvalidArgument;
}
if (handle->queue[handle->queueUser].data)
{
return kStatus_FLEXIO_I2S_QueueFull;
}
/* Change the state of handle */
handle->state = kFLEXIO_I2S_Busy;
/* Update the queue state */
handle->queue[handle->queueUser].data = xfer->data;
handle->queue[handle->queueUser].dataSize = xfer->dataSize;
handle->transferSize[handle->queueUser] = xfer->dataSize;
handle->queueUser = (handle->queueUser + 1) % FLEXIO_I2S_XFER_QUEUE_SIZE;
/* Prepare edma configure */
EDMA_PrepareTransfer(&config, xfer->data, handle->bytesPerFrame, (void *)destAddr, handle->bytesPerFrame,
handle->bytesPerFrame, xfer->dataSize, kEDMA_MemoryToPeripheral);
/* Store the initially configured eDMA minor byte transfer count into the FLEXIO I2S handle */
handle->nbytes = handle->bytesPerFrame;
EDMA_SubmitTransfer(handle->dmaHandle, &config);
/* Start DMA transfer */
EDMA_StartTransfer(handle->dmaHandle);
/* Enable DMA enable bit */
FLEXIO_I2S_TxEnableDMA(base, true);
/* Enable FLEXIO I2S Tx clock */
FLEXIO_I2S_Enable(base, true);
return kStatus_Success;
}
status_t FLEXIO_I2S_TransferReceiveEDMA(FLEXIO_I2S_Type *base,
flexio_i2s_edma_handle_t *handle,
flexio_i2s_transfer_t *xfer)
{
assert(handle && xfer);
edma_transfer_config_t config = {0};
uint32_t srcAddr = FLEXIO_I2S_RxGetDataRegisterAddress(base) + (4U - handle->bytesPerFrame);
/* Check if input parameter invalid */
if ((xfer->data == NULL) || (xfer->dataSize == 0U))
{
return kStatus_InvalidArgument;
}
if (handle->queue[handle->queueUser].data)
{
return kStatus_FLEXIO_I2S_QueueFull;
}
/* Change the state of handle */
handle->state = kFLEXIO_I2S_Busy;
/* Update queue state */
handle->queue[handle->queueUser].data = xfer->data;
handle->queue[handle->queueUser].dataSize = xfer->dataSize;
handle->transferSize[handle->queueUser] = xfer->dataSize;
handle->queueUser = (handle->queueUser + 1) % FLEXIO_I2S_XFER_QUEUE_SIZE;
/* Prepare edma configure */
EDMA_PrepareTransfer(&config, (void *)srcAddr, handle->bytesPerFrame, xfer->data, handle->bytesPerFrame,
handle->bytesPerFrame, xfer->dataSize, kEDMA_PeripheralToMemory);
/* Store the initially configured eDMA minor byte transfer count into the FLEXIO I2S handle */
handle->nbytes = handle->bytesPerFrame;
EDMA_SubmitTransfer(handle->dmaHandle, &config);
/* Start DMA transfer */
EDMA_StartTransfer(handle->dmaHandle);
/* Enable DMA enable bit */
FLEXIO_I2S_RxEnableDMA(base, true);
/* Enable FLEXIO I2S Rx clock */
FLEXIO_I2S_Enable(base, true);
return kStatus_Success;
}
void FLEXIO_I2S_TransferAbortSendEDMA(FLEXIO_I2S_Type *base, flexio_i2s_edma_handle_t *handle)
{
assert(handle);
/* Disable dma */
EDMA_AbortTransfer(handle->dmaHandle);
/* Disable DMA enable bit */
FLEXIO_I2S_TxEnableDMA(base, false);
/* Set the handle state */
handle->state = kFLEXIO_I2S_Idle;
}
void FLEXIO_I2S_TransferAbortReceiveEDMA(FLEXIO_I2S_Type *base, flexio_i2s_edma_handle_t *handle)
{
assert(handle);
/* Disable dma */
EDMA_AbortTransfer(handle->dmaHandle);
/* Disable DMA enable bit */
FLEXIO_I2S_RxEnableDMA(base, false);
/* Set the handle state */
handle->state = kFLEXIO_I2S_Idle;
}
status_t FLEXIO_I2S_TransferGetSendCountEDMA(FLEXIO_I2S_Type *base, flexio_i2s_edma_handle_t *handle, size_t *count)
{
assert(handle);
status_t status = kStatus_Success;
if (handle->state != kFLEXIO_I2S_Busy)
{
status = kStatus_NoTransferInProgress;
}
else
{
*count = handle->transferSize[handle->queueDriver] -
(uint32_t)handle->nbytes *
EDMA_GetRemainingMajorLoopCount(handle->dmaHandle->base, handle->dmaHandle->channel);
}
return status;
}
status_t FLEXIO_I2S_TransferGetReceiveCountEDMA(FLEXIO_I2S_Type *base, flexio_i2s_edma_handle_t *handle, size_t *count)
{
assert(handle);
status_t status = kStatus_Success;
if (handle->state != kFLEXIO_I2S_Busy)
{
status = kStatus_NoTransferInProgress;
}
else
{
*count = handle->transferSize[handle->queueDriver] -
(uint32_t)handle->nbytes *
EDMA_GetRemainingMajorLoopCount(handle->dmaHandle->base, handle->dmaHandle->channel);
}
return status;
}

View File

@ -0,0 +1,218 @@
/*
* Copyright (c) 2015, Freescale Semiconductor, Inc.
* Copyright 2016-2017 NXP
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o Redistributions in binary form must reproduce the above copyright notice, this
* list of conditions and the following disclaimer in the documentation and/or
* other materials provided with the distribution.
*
* o Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived from this
* software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _FSL_FLEXIO_I2S_EDMA_H_
#define _FSL_FLEXIO_I2S_EDMA_H_
#include "fsl_flexio_i2s.h"
#include "fsl_edma.h"
/*!
* @addtogroup flexio_edma_i2s
* @{
*/
/*******************************************************************************
* Definitions
******************************************************************************/
typedef struct _flexio_i2s_edma_handle flexio_i2s_edma_handle_t;
/*! @brief FlexIO I2S eDMA transfer callback function for finish and error */
typedef void (*flexio_i2s_edma_callback_t)(FLEXIO_I2S_Type *base,
flexio_i2s_edma_handle_t *handle,
status_t status,
void *userData);
/*! @brief FlexIO I2S DMA transfer handle, users should not touch the content of the handle.*/
struct _flexio_i2s_edma_handle
{
edma_handle_t *dmaHandle; /*!< DMA handler for FlexIO I2S send */
uint8_t bytesPerFrame; /*!< Bytes in a frame */
uint8_t nbytes; /*!< eDMA minor byte transfer count initially configured. */
uint32_t state; /*!< Internal state for FlexIO I2S eDMA transfer */
flexio_i2s_edma_callback_t callback; /*!< Callback for users while transfer finish or error occurred */
void *userData; /*!< User callback parameter */
edma_tcd_t tcd[FLEXIO_I2S_XFER_QUEUE_SIZE + 1U]; /*!< TCD pool for eDMA transfer. */
flexio_i2s_transfer_t queue[FLEXIO_I2S_XFER_QUEUE_SIZE]; /*!< Transfer queue storing queued transfer. */
size_t transferSize[FLEXIO_I2S_XFER_QUEUE_SIZE]; /*!< Data bytes need to transfer */
volatile uint8_t queueUser; /*!< Index for user to queue transfer. */
volatile uint8_t queueDriver; /*!< Index for driver to get the transfer data and size */
};
/*******************************************************************************
* APIs
******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif
/*!
* @name eDMA Transactional
* @{
*/
/*!
* @brief Initializes the FlexIO I2S eDMA handle.
*
* This function initializes the FlexIO I2S master DMA handle which can be used for other FlexIO I2S master
* transactional APIs.
* Usually, for a specified FlexIO I2S instance, call this API once to get the initialized handle.
*
* @param base FlexIO I2S peripheral base address.
* @param handle FlexIO I2S eDMA handle pointer.
* @param callback FlexIO I2S eDMA callback function called while finished a block.
* @param userData User parameter for callback.
* @param dmaHandle eDMA handle for FlexIO I2S. This handle is a static value allocated by users.
*/
void FLEXIO_I2S_TransferTxCreateHandleEDMA(FLEXIO_I2S_Type *base,
flexio_i2s_edma_handle_t *handle,
flexio_i2s_edma_callback_t callback,
void *userData,
edma_handle_t *dmaHandle);
/*!
* @brief Initializes the FlexIO I2S Rx eDMA handle.
*
* This function initializes the FlexIO I2S slave DMA handle which can be used for other FlexIO I2S master transactional
* APIs.
* Usually, for a specified FlexIO I2S instance, call this API once to get the initialized handle.
*
* @param base FlexIO I2S peripheral base address.
* @param handle FlexIO I2S eDMA handle pointer.
* @param callback FlexIO I2S eDMA callback function called while finished a block.
* @param userData User parameter for callback.
* @param dmaHandle eDMA handle for FlexIO I2S. This handle is a static value allocated by users.
*/
void FLEXIO_I2S_TransferRxCreateHandleEDMA(FLEXIO_I2S_Type *base,
flexio_i2s_edma_handle_t *handle,
flexio_i2s_edma_callback_t callback,
void *userData,
edma_handle_t *dmaHandle);
/*!
* @brief Configures the FlexIO I2S Tx audio format.
*
* Audio format can be changed in run-time of FlexIO I2S. This function configures the sample rate and audio data
* format to be transferred. This function also sets the eDMA parameter according to format.
*
* @param base FlexIO I2S peripheral base address.
* @param handle FlexIO I2S eDMA handle pointer
* @param format Pointer to FlexIO I2S audio data format structure.
* @param srcClock_Hz FlexIO I2S clock source frequency in Hz, it should be 0 while in slave mode.
* @retval kStatus_Success Audio format set successfully.
* @retval kStatus_InvalidArgument The input arguments is invalid.
*/
void FLEXIO_I2S_TransferSetFormatEDMA(FLEXIO_I2S_Type *base,
flexio_i2s_edma_handle_t *handle,
flexio_i2s_format_t *format,
uint32_t srcClock_Hz);
/*!
* @brief Performs a non-blocking FlexIO I2S transfer using DMA.
*
* @note This interface returned immediately after transfer initiates. Users should call
* FLEXIO_I2S_GetTransferStatus to poll the transfer status and check whether the FlexIO I2S transfer is finished.
*
* @param base FlexIO I2S peripheral base address.
* @param handle FlexIO I2S DMA handle pointer.
* @param xfer Pointer to DMA transfer structure.
* @retval kStatus_Success Start a FlexIO I2S eDMA send successfully.
* @retval kStatus_InvalidArgument The input arguments is invalid.
* @retval kStatus_TxBusy FlexIO I2S is busy sending data.
*/
status_t FLEXIO_I2S_TransferSendEDMA(FLEXIO_I2S_Type *base,
flexio_i2s_edma_handle_t *handle,
flexio_i2s_transfer_t *xfer);
/*!
* @brief Performs a non-blocking FlexIO I2S receive using eDMA.
*
* @note This interface returned immediately after transfer initiates. Users should call
* FLEXIO_I2S_GetReceiveRemainingBytes to poll the transfer status and check whether the FlexIO I2S transfer is finished.
*
* @param base FlexIO I2S peripheral base address.
* @param handle FlexIO I2S DMA handle pointer.
* @param xfer Pointer to DMA transfer structure.
* @retval kStatus_Success Start a FlexIO I2S eDMA receive successfully.
* @retval kStatus_InvalidArgument The input arguments is invalid.
* @retval kStatus_RxBusy FlexIO I2S is busy receiving data.
*/
status_t FLEXIO_I2S_TransferReceiveEDMA(FLEXIO_I2S_Type *base,
flexio_i2s_edma_handle_t *handle,
flexio_i2s_transfer_t *xfer);
/*!
* @brief Aborts a FlexIO I2S transfer using eDMA.
*
* @param base FlexIO I2S peripheral base address.
* @param handle FlexIO I2S DMA handle pointer.
*/
void FLEXIO_I2S_TransferAbortSendEDMA(FLEXIO_I2S_Type *base, flexio_i2s_edma_handle_t *handle);
/*!
* @brief Aborts a FlexIO I2S receive using eDMA.
*
* @param base FlexIO I2S peripheral base address.
* @param handle FlexIO I2S DMA handle pointer.
*/
void FLEXIO_I2S_TransferAbortReceiveEDMA(FLEXIO_I2S_Type *base, flexio_i2s_edma_handle_t *handle);
/*!
* @brief Gets the remaining bytes to be sent.
*
* @param base FlexIO I2S peripheral base address.
* @param handle FlexIO I2S DMA handle pointer.
* @param count Bytes sent.
* @retval kStatus_Success Succeed get the transfer count.
* @retval kStatus_NoTransferInProgress There is not a non-blocking transaction currently in progress.
*/
status_t FLEXIO_I2S_TransferGetSendCountEDMA(FLEXIO_I2S_Type *base, flexio_i2s_edma_handle_t *handle, size_t *count);
/*!
* @brief Get the remaining bytes to be received.
*
* @param base FlexIO I2S peripheral base address.
* @param handle FlexIO I2S DMA handle pointer.
* @param count Bytes received.
* @retval kStatus_Success Succeed get the transfer count.
* @retval kStatus_NoTransferInProgress There is not a non-blocking transaction currently in progress.
*/
status_t FLEXIO_I2S_TransferGetReceiveCountEDMA(FLEXIO_I2S_Type *base, flexio_i2s_edma_handle_t *handle, size_t *count);
/*! @} */
#if defined(__cplusplus)
}
#endif
/*!
* @}
*/
#endif

Some files were not shown because too many files have changed in this diff Show More