Go to the documentation of this file.
27 #define FSL_LPI2C_DRIVER_VERSION (MAKE_VERSION(2, 1, 11))
31 #ifndef I2C_RETRY_TIMES
32 #define I2C_RETRY_TIMES 0U
407 #if defined(__cplusplus)
552 base->
MSR = statusMask;
572 base->
MIER |= interruptMask;
587 base->
MIER &= ~interruptMask;
627 return (uint32_t)&base->
MTDR;
638 return (uint32_t)&base->
MRDR;
1032 base->
SSR = statusMask;
1052 base->
SIER |= interruptMask;
1067 base->
SIER &= ~interruptMask;
1262 #if defined(__cplusplus)
_lpi2c_master_transfer_flags
Transfer option flags.
static uint32_t LPI2C_SlaveGetStatusFlags(LPI2C_Type *base)
Gets the LPI2C slave status flags.
@ kLPI2C_2PinOpenDrainWithSeparateSlave
struct _lpi2c_master_config lpi2c_master_config_t
Structure with settings to initialize the LPI2C master module.
struct _lpi2c_master_config::@353 hostRequest
#define LPI2C_MCR_RST_MASK
_lpi2c_data_match_config_mode
LPI2C master data match configuration modes.
void LPI2C_MasterGetDefaultConfig(lpi2c_master_config_t *masterConfig)
Provides a default configuration for the LPI2C master peripheral.
#define LPI2C_MSR_PLTF_MASK
enum _lpi2c_host_request_source lpi2c_host_request_source_t
LPI2C master host request selection.
@ kLPI2C_SlaveFifoErrFlag
lpi2c_slave_transfer_t transfer
#define LPI2C_SSR_BBF_MASK
uint32_t pinLowTimeout_ns
enum _lpi2c_direction lpi2c_direction_t
Direction of master and slave transfers.
void LPI2C_SlaveDeinit(LPI2C_Type *base)
Deinitializes the LPI2C slave peripheral.
lpi2c_master_pin_config_t pinConfig
lpi2c_slave_address_match_t addressMatchMode
static void LPI2C_SlaveReset(LPI2C_Type *base)
Performs a software reset of the LPI2C slave peripheral.
@ kLPI2C_1stWordEqualsM0And2ndWordEqualsM1
static bool LPI2C_SlaveGetBusIdleState(LPI2C_Type *base)
Returns whether the bus is idle.
@ kLPI2C_SlaveAddressMatch1Flag
void(* lpi2c_slave_transfer_callback_t)(LPI2C_Type *base, lpi2c_slave_transfer_t *transfer, void *userData)
Slave event callback function pointer type.
static void LPI2C_MasterEnableInterrupts(LPI2C_Type *base, uint32_t interruptMask)
Enables the LPI2C master interrupt requests.
struct _lpi2c_slave_config lpi2c_slave_config_t
Structure with settings to initialize the LPI2C slave module.
@ kLPI2C_SlaveTransmitAckEvent
@ kLPI2C_MasterArbitrationLostFlag
void LPI2C_SlaveTransferHandleIRQ(LPI2C_Type *base, lpi2c_slave_handle_t *handle)
Reusable routine to handle slave interrupts.
@ kLPI2C_SlaveStopDetectFlag
status_t LPI2C_MasterStart(LPI2C_Type *base, uint8_t address, lpi2c_direction_t dir)
Sends a START signal and slave address on the I2C bus.
#define LPI2C_SSR_AM0F_MASK
@ kLPI2C_SlaveAddressMatch0Flag
status_t LPI2C_MasterReceive(LPI2C_Type *base, void *rxBuff, size_t rxSize)
Performs a polling receive transfer on the I2C bus.
_lpi2c_host_request_polarity
LPI2C master host request pin polarity configuration.
void LPI2C_MasterDeinit(LPI2C_Type *base)
Deinitializes the LPI2C master peripheral.
@ kLPI2C_1stWordEqualsM0OrM1
#define LPI2C_MFCR_TXWATER(x)
status_t LPI2C_CheckForBusyBus(LPI2C_Type *base)
Make sure the bus isn't already busy.
lpi2c_data_match_config_mode_t matchMode
#define LPI2C_MSR_BBF_SHIFT
enum _lpi2c_master_pin_config lpi2c_master_pin_config_t
LPI2C pin configuration.
void LPI2C_MasterTransferCreateHandle(LPI2C_Type *base, lpi2c_master_handle_t *handle, lpi2c_master_transfer_callback_t callback, void *userData)
Creates a new handle for the LPI2C master non-blocking APIs.
#define LPI2C_STAR_TXNACK(x)
#define LPI2C_SDER_RDDE_MASK
uint8_t sclGlitchFilterWidth_ns
#define LPI2C_MSR_EPF_MASK
@ kLPI2C_SlaveRepeatedStartDetectFlag
@ kLPI2C_SlaveRepeatedStartEvent
static void LPI2C_SlaveTransmitAck(LPI2C_Type *base, bool ackOrNack)
Transmits either an ACK or NAK on the I2C bus in response to a byte from the master.
@ kLPI2C_MasterPinLowTimeoutFlag
@ kStatus_LPI2C_FifoError
#define LPI2C_SSR_AM1F_MASK
#define LPI2C_MDER_RDDE(x)
#define LPI2C_MFCR_RXWATER(x)
void LPI2C_SlaveGetDefaultConfig(lpi2c_slave_config_t *slaveConfig)
Provides a default configuration for the LPI2C slave peripheral.
@ kLPI2C_AnyWordEqualsM0OrM1
enum _lpi2c_slave_transfer_event lpi2c_slave_transfer_event_t
Set of events sent to the callback for non blocking slave transfers.
uint32_t dataValidDelay_ns
uint8_t sdaGlitchFilterWidth_ns
void LPI2C_MasterSetBaudRate(LPI2C_Type *base, uint32_t sourceClock_Hz, uint32_t baudRate_Hz)
Sets the I2C bus frequency for master transactions.
Structure with settings to initialize the LPI2C master module.
@ kLPI2C_MasterFifoErrFlag
@ kLPI2C_MasterNackDetectFlag
@ kLPI2C_MasterDataMatchFlag
@ kLPI2C_SlaveRxReadyFlag
@ kLPI2C_SlaveTransmitAckFlag
lpi2c_master_transfer_t transfer
#define LPI2C_SSR_BBF_SHIFT
@ kLPI2C_TransferRepeatedStartFlag
@ kStatus_LPI2C_ArbitrationLost
#define LPI2C_MSR_NDF_MASK
static void LPI2C_SlaveEnable(LPI2C_Type *base, bool enable)
Enables or disables the LPI2C module as slave.
@ kLPI2C_MasterBusBusyFlag
Driver handle for master non-blocking APIs.
#define LPI2C_SSR_TDF_MASK
status_t LPI2C_MasterCheckAndClearError(LPI2C_Type *base, uint32_t status)
Convert provided flags to status code, and clear any errors if present.
@ kLPI2C_HostRequestInputTrigger
uint32_t transferredCount
#define LPI2C_MFSR_TXCOUNT_MASK
#define LPI2C_MCR_MEN_MASK
struct _lpi2c_match_config lpi2c_data_match_config_t
LPI2C master data match configuration structure.
#define MAKE_STATUS(group, code)
Construct a status code value from a group and code number.
@ kLPI2C_SlaveCompletionEvent
@ kLPI2C_SlaveAddressValidFlag
status_t LPI2C_SlaveReceive(LPI2C_Type *base, void *rxBuff, size_t rxSize, size_t *actualRxSize)
Performs a polling receive transfer on the I2C bus.
static void LPI2C_SlaveEnableDMA(LPI2C_Type *base, bool enableAddressValid, bool enableRx, bool enableTx)
Enables or disables the LPI2C slave peripheral DMA requests.
void LPI2C_MasterTransferHandleIRQ(LPI2C_Type *base, lpi2c_master_handle_t *handle)
Reusable routine to handle master interrupts.
@ kLPI2C_MasterRxReadyFlag
@ kLPI2C_1stWordAndM1EqualsM0AndM1
#define LPI2C_SCR_RST_MASK
@ kLPI2C_TransferNoStartFlag
@ kStatus_LPI2C_NoTransferInProgress
static uint32_t LPI2C_SlaveGetReceivedAddress(LPI2C_Type *base)
Returns the slave address sent by the I2C master.
void LPI2C_SlaveTransferCreateHandle(LPI2C_Type *base, lpi2c_slave_handle_t *handle, lpi2c_slave_transfer_callback_t callback, void *userData)
Creates a new handle for the LPI2C slave non-blocking APIs.
@ kLPI2C_MasterStopDetectFlag
@ kLPI2C_4PinPushPullWithInvertedOutput
#define LPI2C_SDER_RDDE(x)
uint32_t sclGlitchFilterWidth_ns
#define LPI2C_SSR_BEF_MASK
#define LPI2C_MSR_TDF_MASK
static void LPI2C_MasterClearStatusFlags(LPI2C_Type *base, uint32_t statusMask)
Clears the LPI2C master status flag state.
static uint32_t LPI2C_SlaveGetEnabledInterrupts(LPI2C_Type *base)
Returns the set of currently enabled LPI2C slave interrupt requests.
@ kLPI2C_HostRequestExternalPin
lpi2c_master_transfer_callback_t completionCallback
static status_t LPI2C_MasterRepeatedStart(LPI2C_Type *base, uint8_t address, lpi2c_direction_t dir)
Sends a repeated START signal and slave address on the I2C bus.
static bool LPI2C_MasterGetBusIdleState(LPI2C_Type *base)
Returns whether the bus is idle.
lpi2c_direction_t direction
@ kLPI2C_SlaveReceiveEvent
#define LPI2C_SSR_RSF_MASK
#define LPI2C_MSR_ALF_MASK
void LPI2C_SlaveInit(LPI2C_Type *base, const lpi2c_slave_config_t *slaveConfig, uint32_t sourceClock_Hz)
Initializes the LPI2C slave peripheral.
static void LPI2C_SlaveEnableInterrupts(LPI2C_Type *base, uint32_t interruptMask)
Enables the LPI2C slave interrupt requests.
uint32_t busIdleTimeout_ns
#define LPI2C_MSR_RDF_MASK
@ kLPI2C_2PinOutputOnlyWithSeparateSlave
static uint32_t LPI2C_MasterGetEnabledInterrupts(LPI2C_Type *base)
Returns the set of currently enabled LPI2C master interrupt requests.
_lpi2c_host_request_source
LPI2C master host request selection.
@ kLPI2C_MasterTxReadyFlag
enum _lpi2c_host_request_polarity lpi2c_host_request_polarity_t
LPI2C master host request pin polarity configuration.
uint32_t clockHoldTime_ns
LPI2C slave handle structure.
Structure with settings to initialize the LPI2C slave module.
static void LPI2C_MasterSetWatermarks(LPI2C_Type *base, size_t txWords, size_t rxWords)
Sets the watermarks for LPI2C master FIFOs.
#define LPI2C_SCR_SEN_MASK
static void LPI2C_MasterReset(LPI2C_Type *base)
Performs a software reset.
struct _lpi2c_slave_transfer lpi2c_slave_transfer_t
LPI2C slave transfer structure.
struct _lpi2c_slave_config::@354 sclStall
#define LPI2C_MFSR_TXCOUNT_SHIFT
@ kLPI2C_HostRequestPinActiveHigh
#define LPI2C_MFSR_RXCOUNT_SHIFT
static void LPI2C_MasterGetFifoCounts(LPI2C_Type *base, size_t *rxCount, size_t *txCount)
Gets the current number of words in the LPI2C master FIFOs.
@ kLPI2C_2PinPushPullWithSeparateSlave
_lpi2c_direction
Direction of master and slave transfers.
static void LPI2C_SlaveClearStatusFlags(LPI2C_Type *base, uint32_t statusMask)
Clears the LPI2C status flag state.
#define LPI2C_MSR_DMF_MASK
#define LPI2C_SSR_TAF_MASK
@ kLPI2C_SlaveBusBusyFlag
#define LPI2C_MSR_SDF_MASK
@ kLPI2C_AnyWordEqualsM0AndNextWordEqualsM1
status_t LPI2C_MasterTransferNonBlocking(LPI2C_Type *base, lpi2c_master_handle_t *handle, lpi2c_master_transfer_t *transfer)
Performs a non-blocking transaction on the I2C bus.
status_t LPI2C_MasterTransferGetCount(LPI2C_Type *base, lpi2c_master_handle_t *handle, size_t *count)
Returns number of bytes transferred so far.
LPI2C master data match configuration structure.
status_t LPI2C_MasterSend(LPI2C_Type *base, void *txBuff, size_t txSize)
Performs a polling send transfer on the I2C bus.
#define LPI2C_SDER_TDDE(x)
#define LPI2C_MSR_MBF_MASK
status_t LPI2C_SlaveSend(LPI2C_Type *base, void *txBuff, size_t txSize, size_t *actualTxSize)
Performs a polling send transfer on the I2C bus.
@ kStatus_LPI2C_DmaRequestFail
#define LPI2C_MDER_TDDE(x)
static void LPI2C_MasterDisableInterrupts(LPI2C_Type *base, uint32_t interruptMask)
Disables the LPI2C master interrupt requests.
#define LPI2C_MFSR_RXCOUNT_MASK
enum _lpi2c_data_match_config_mode lpi2c_data_match_config_mode_t
LPI2C master data match configuration modes.
@ kLPI2C_SlaveTransmitEvent
status_t LPI2C_SlaveTransferGetCount(LPI2C_Type *base, lpi2c_slave_handle_t *handle, size_t *count)
Gets the slave transfer status during a non-blocking transfer.
bool enableReceivedAddressRead
static uint32_t LPI2C_MasterGetRxFifoAddress(LPI2C_Type *base)
Gets LPI2C master receive data register address for DMA transfer.
#define LPI2C_SSR_GCF_MASK
#define LPI2C_SDER_AVDE(x)
@ kLPI2C_SlaveTxReadyFlag
void LPI2C_MasterConfigureDataMatch(LPI2C_Type *base, const lpi2c_data_match_config_t *config)
Configures LPI2C master data match feature.
status_t LPI2C_MasterStop(LPI2C_Type *base)
Sends a STOP signal on the I2C bus.
_lpi2c_slave_flags
LPI2C slave peripheral flags.
status_t completionStatus
uint16_t commandBuffer[7]
#define LPI2C_SASR_RADDR_MASK
#define LPI2C_MSR_FEF_MASK
@ kLPI2C_AnyWordAndM1EqualsM0AndM1
void LPI2C_MasterTransferAbort(LPI2C_Type *base, lpi2c_master_handle_t *handle)
Terminates a non-blocking LPI2C master transmission early.
static void LPI2C_MasterEnableDMA(LPI2C_Type *base, bool enableTx, bool enableRx)
Enables or disables LPI2C master DMA requests.
@ kLPI2C_TransferDefaultFlag
@ kLPI2C_TransferNoStopFlag
lpi2c_slave_transfer_event_t event
status_t LPI2C_MasterTransferBlocking(LPI2C_Type *base, lpi2c_master_transfer_t *transfer)
Performs a master polling transfer on the I2C bus.
_lpi2c_slave_address_match
LPI2C slave address match options.
static sai_transceiver_t config
@ kLPI2C_MasterEndOfPacketFlag
static void LPI2C_SlaveDisableInterrupts(LPI2C_Type *base, uint32_t interruptMask)
Disables the LPI2C slave interrupt requests.
#define LPI2C_SSR_FEF_MASK
#define LPI2C_SDER_AVDE_MASK
static uint32_t LPI2C_MasterGetTxFifoAddress(LPI2C_Type *base)
Gets LPI2C master transmit data register address for DMA transfer.
void LPI2C_MasterInit(LPI2C_Type *base, const lpi2c_master_config_t *masterConfig, uint32_t sourceClock_Hz)
Initializes the LPI2C master peripheral.
LPI2C slave transfer structure.
static void LPI2C_MasterEnable(LPI2C_Type *base, bool enable)
Enables or disables the LPI2C module as master.
#define LPI2C_SSR_SDF_MASK
lpi2c_host_request_polarity_t polarity
#define LPI2C_SSR_AVF_MASK
#define LPI2C_MSR_BBF_MASK
_lpi2c_slave_transfer_event
Set of events sent to the callback for non blocking slave transfers.
int32_t status_t
Type used for all status and error return values.
@ kLPI2C_MatchAddress0ThroughAddress1
_lpi2c_master_pin_config
LPI2C pin configuration.
void(* lpi2c_master_transfer_callback_t)(LPI2C_Type *base, lpi2c_master_handle_t *handle, status_t completionStatus, void *userData)
Master completion callback function pointer type.
#define LPI2C_SSR_RDF_MASK
static uint32_t LPI2C_MasterGetStatusFlags(LPI2C_Type *base)
Gets the LPI2C master status flags.
@ kLPI2C_SlaveAddressMatchEvent
#define LPI2C_SDER_TDDE_MASK
lpi2c_slave_transfer_callback_t callback
@ kStatus_LPI2C_PinLowTimeout
enum _lpi2c_slave_address_match lpi2c_slave_address_match_t
LPI2C slave address match options.
@ kLPI2C_HostRequestPinActiveLow
void LPI2C_SlaveTransferAbort(LPI2C_Type *base, lpi2c_slave_handle_t *handle)
Aborts the slave non-blocking transfers.
@ kLPI2C_SlaveGeneralCallFlag
Non-blocking transfer descriptor structure.
uint32_t sdaGlitchFilterWidth_ns
status_t LPI2C_SlaveTransferNonBlocking(LPI2C_Type *base, lpi2c_slave_handle_t *handle, uint32_t eventMask)
Starts accepting slave transfers.
lpi2c_host_request_source_t source
#define LPI2C_SSR_SBF_MASK
@ kLPI2C_MatchAddress0OrAddress1