fsl_lpi2c.c
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2015, Freescale Semiconductor, Inc.
3  * Copyright 2016-2020 NXP
4  * All rights reserved.
5  *
6  * SPDX-License-Identifier: BSD-3-Clause
7  */
8 
9 #include "fsl_lpi2c.h"
10 #include <stdlib.h>
11 #include <string.h>
12 
13 /*******************************************************************************
14  * Definitions
15  ******************************************************************************/
16 
17 /* Component ID definition, used by tools. */
18 #ifndef FSL_COMPONENT_ID
19 #define FSL_COMPONENT_ID "platform.drivers.lpi2c"
20 #endif
21 
23 enum
24 {
29 
34 
38 
42 
47 
50 };
51 
52 /* ! @brief LPI2C master fifo commands. */
53 enum
54 {
59 };
60 
66 enum
67 {
70 };
71 
73 enum
74 {
81 };
82 
84 typedef void (*lpi2c_master_isr_t)(LPI2C_Type *base, lpi2c_master_handle_t *handle);
85 
87 typedef void (*lpi2c_slave_isr_t)(LPI2C_Type *base, lpi2c_slave_handle_t *handle);
88 
89 /*******************************************************************************
90  * Prototypes
91  ******************************************************************************/
92 
93 /* Not static so it can be used from fsl_lpi2c_edma.c. */
94 uint32_t LPI2C_GetInstance(LPI2C_Type *base);
95 
96 static uint32_t LPI2C_GetCyclesForWidth(uint32_t sourceClock_Hz,
97  uint32_t width_ns,
98  uint32_t maxCycles,
99  uint32_t prescaler);
100 
102 
103 static status_t LPI2C_RunTransferStateMachine(LPI2C_Type *base, lpi2c_master_handle_t *handle, bool *isDone);
104 
106 
107 static status_t LPI2C_SlaveCheckAndClearError(LPI2C_Type *base, uint32_t flags);
108 
109 static void LPI2C_CommonIRQHandler(LPI2C_Type *base, uint32_t instance);
110 
111 /*******************************************************************************
112  * Variables
113  ******************************************************************************/
114 
117 
119 static IRQn_Type const kLpi2cIrqs[] = LPI2C_IRQS;
120 
121 #if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
122 
124 
125 #if defined(LPI2C_PERIPH_CLOCKS)
126 
127 static const clock_ip_name_t kLpi2cPeriphClocks[] = LPI2C_PERIPH_CLOCKS;
128 #endif
129 
130 #endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
131 
134 
137 
140 
143 
144 /*******************************************************************************
145  * Code
146  ******************************************************************************/
147 
158 {
159  uint32_t instance;
160  for (instance = 0U; instance < ARRAY_SIZE(kLpi2cBases); ++instance)
161  {
162  if (kLpi2cBases[instance] == base)
163  {
164  break;
165  }
166  }
167 
168  assert(instance < ARRAY_SIZE(kLpi2cBases));
169  return instance;
170 }
171 
179 static uint32_t LPI2C_GetCyclesForWidth(uint32_t sourceClock_Hz,
180  uint32_t width_ns,
181  uint32_t maxCycles,
182  uint32_t prescaler)
183 {
184  assert(sourceClock_Hz > 0U);
185  assert(prescaler > 0U);
186 
187  uint32_t busCycle_ns = 1000000U / (sourceClock_Hz / prescaler / 1000U);
188  uint32_t cycles = 0U;
189 
190  /* Search for the cycle count just below the desired glitch width. */
191  while ((((cycles + 1U) * busCycle_ns) < width_ns) && (cycles + 1U < maxCycles))
192  {
193  ++cycles;
194  }
195 
196  /* If we end up with zero cycles, then set the filter to a single cycle unless the */
197  /* bus clock is greater than 10x the desired glitch width. */
198  if ((cycles == 0U) && (busCycle_ns <= (width_ns * 10U)))
199  {
200  cycles = 1U;
201  }
202 
203  return cycles;
204 }
205 
216 /* Not static so it can be used from fsl_lpi2c_edma.c. */
218 {
219  status_t result = kStatus_Success;
220 
221  /* Check for error. These errors cause a stop to automatically be sent. We must */
222  /* clear the errors before a new transfer can start. */
223  status &= (uint32_t)kMasterErrorFlags;
224  if (0U != status)
225  {
226  /* Select the correct error code. Ordered by severity, with bus issues first. */
227  if (0U != (status & (uint32_t)kLPI2C_MasterPinLowTimeoutFlag))
228  {
230  }
231  else if (0U != (status & (uint32_t)kLPI2C_MasterArbitrationLostFlag))
232  {
234  }
235  else if (0U != (status & (uint32_t)kLPI2C_MasterNackDetectFlag))
236  {
237  result = kStatus_LPI2C_Nak;
238  }
239  else if (0U != (status & (uint32_t)kLPI2C_MasterFifoErrFlag))
240  {
241  result = kStatus_LPI2C_FifoError;
242  }
243  else
244  {
245  ; /* Intentional empty */
246  }
247 
248  /* Clear the flags. */
249  LPI2C_MasterClearStatusFlags(base, status);
250 
251  /* Reset fifos. These flags clear automatically. */
253  }
254  else
255  {
256  ; /* Intentional empty */
257  }
258 
259  return result;
260 }
261 
272 {
273  uint32_t status;
274  size_t txCount;
275  size_t txFifoSize = (size_t)FSL_FEATURE_LPI2C_FIFO_SIZEn(base);
276 
277 #if I2C_RETRY_TIMES
278  uint32_t waitTimes = I2C_RETRY_TIMES;
279 #endif
280  do
281  {
282  status_t result;
283 
284  /* Get the number of words in the tx fifo and compute empty slots. */
285  LPI2C_MasterGetFifoCounts(base, NULL, &txCount);
286  txCount = txFifoSize - txCount;
287 
288  /* Check for error flags. */
289  status = LPI2C_MasterGetStatusFlags(base);
290  result = LPI2C_MasterCheckAndClearError(base, status);
291  if (kStatus_Success != result)
292  {
293  return result;
294  }
295 #if I2C_RETRY_TIMES
296  } while ((0U == txCount) && (0U != --waitTimes));
297 
298  if (0U == waitTimes)
299  {
300  return kStatus_LPI2C_Timeout;
301  }
302 #else
303  } while (0U == txCount);
304 #endif
305 
306  return kStatus_Success;
307 }
308 
318 /* Not static so it can be used from fsl_lpi2c_edma.c. */
320 {
322 
323  uint32_t status = LPI2C_MasterGetStatusFlags(base);
324  if ((0U != (status & (uint32_t)kLPI2C_MasterBusBusyFlag)) && (0U == (status & (uint32_t)kLPI2C_MasterBusyFlag)))
325  {
326  ret = kStatus_LPI2C_Busy;
327  }
328 
329  return ret;
330 }
331 
357 {
358  /* Initializes the configure structure to zero. */
359  (void)memset(masterConfig, 0, sizeof(*masterConfig));
360 
361  masterConfig->enableMaster = true;
362  masterConfig->debugEnable = false;
363  masterConfig->enableDoze = true;
364  masterConfig->ignoreAck = false;
365  masterConfig->pinConfig = kLPI2C_2PinOpenDrain;
366  masterConfig->baudRate_Hz = 100000U;
367  masterConfig->busIdleTimeout_ns = 0U;
368  masterConfig->pinLowTimeout_ns = 0U;
369  masterConfig->sdaGlitchFilterWidth_ns = 0U;
370  masterConfig->sclGlitchFilterWidth_ns = 0U;
371  masterConfig->hostRequest.enable = false;
374 }
375 
389 void LPI2C_MasterInit(LPI2C_Type *base, const lpi2c_master_config_t *masterConfig, uint32_t sourceClock_Hz)
390 {
391  uint32_t prescaler;
392  uint32_t cycles;
393  uint32_t cfgr2;
394  uint32_t value;
395 
396 #if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
397 
398  uint32_t instance = LPI2C_GetInstance(base);
399 
400  /* Ungate the clock. */
401  CLOCK_EnableClock(kLpi2cClocks[instance]);
402 #if defined(LPI2C_PERIPH_CLOCKS)
403  /* Ungate the functional clock in initialize function. */
404  CLOCK_EnableClock(kLpi2cPeriphClocks[instance]);
405 #endif
406 
407 #endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
408 
409  /* Reset peripheral before configuring it. */
410  LPI2C_MasterReset(base);
411 
412  /* Doze bit: 0 is enable, 1 is disable */
413  base->MCR = LPI2C_MCR_DBGEN(masterConfig->debugEnable) | LPI2C_MCR_DOZEN(!(masterConfig->enableDoze));
414 
415  /* host request */
416  value = base->MCFGR0;
418  value |= LPI2C_MCFGR0_HREN(masterConfig->hostRequest.enable) |
419  LPI2C_MCFGR0_HRPOL(masterConfig->hostRequest.polarity) |
420  LPI2C_MCFGR0_HRSEL(masterConfig->hostRequest.source);
421  base->MCFGR0 = value;
422 
423  /* pin config and ignore ack */
424  value = base->MCFGR1;
426  value |= LPI2C_MCFGR1_PINCFG(masterConfig->pinConfig);
427  value |= LPI2C_MCFGR1_IGNACK(masterConfig->ignoreAck);
428  base->MCFGR1 = value;
429 
431 
432  LPI2C_MasterSetBaudRate(base, sourceClock_Hz, masterConfig->baudRate_Hz);
433 
434  /* Configure glitch filters and bus idle and pin low timeouts. */
436  cfgr2 = base->MCFGR2;
437  if (0U != (masterConfig->busIdleTimeout_ns))
438  {
439  cycles = LPI2C_GetCyclesForWidth(sourceClock_Hz, masterConfig->busIdleTimeout_ns,
441  cfgr2 &= ~LPI2C_MCFGR2_BUSIDLE_MASK;
442  cfgr2 |= LPI2C_MCFGR2_BUSIDLE(cycles);
443  }
444  if (0U != (masterConfig->sdaGlitchFilterWidth_ns))
445  {
446  cycles = LPI2C_GetCyclesForWidth(sourceClock_Hz, masterConfig->sdaGlitchFilterWidth_ns,
448  cfgr2 &= ~LPI2C_MCFGR2_FILTSDA_MASK;
449  cfgr2 |= LPI2C_MCFGR2_FILTSDA(cycles);
450  }
451  if (0U != masterConfig->sclGlitchFilterWidth_ns)
452  {
453  cycles = LPI2C_GetCyclesForWidth(sourceClock_Hz, masterConfig->sclGlitchFilterWidth_ns,
455  cfgr2 &= ~LPI2C_MCFGR2_FILTSCL_MASK;
456  cfgr2 |= LPI2C_MCFGR2_FILTSCL(cycles);
457  }
458  base->MCFGR2 = cfgr2;
459  if (0U != masterConfig->pinLowTimeout_ns)
460  {
461  cycles = LPI2C_GetCyclesForWidth(sourceClock_Hz, masterConfig->pinLowTimeout_ns / 256U,
463  base->MCFGR3 = (base->MCFGR3 & ~LPI2C_MCFGR3_PINLOW_MASK) | LPI2C_MCFGR3_PINLOW(cycles);
464  }
465 
466  LPI2C_MasterEnable(base, masterConfig->enableMaster);
467 }
468 
478 {
479  /* Restore to reset state. */
480  LPI2C_MasterReset(base);
481 
482 #if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
483 
484  uint32_t instance = LPI2C_GetInstance(base);
485 
486  /* Gate clock. */
487  CLOCK_DisableClock(kLpi2cClocks[instance]);
488 #if defined(LPI2C_PERIPH_CLOCKS)
489  /* Gate the functional clock. */
490  CLOCK_DisableClock(kLpi2cPeriphClocks[instance]);
491 #endif
492 
493 #endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
494 }
495 
503 {
504  /* Disable master mode. */
505  bool wasEnabled = (0U != ((base->MCR & LPI2C_MCR_MEN_MASK) >> LPI2C_MCR_MEN_SHIFT));
506  LPI2C_MasterEnable(base, false);
507 
508  base->MCFGR1 = (base->MCFGR1 & ~LPI2C_MCFGR1_MATCFG_MASK) | LPI2C_MCFGR1_MATCFG(config->matchMode);
509  base->MCFGR0 = (base->MCFGR0 & ~LPI2C_MCFGR0_RDMO_MASK) | LPI2C_MCFGR0_RDMO(config->rxDataMatchOnly);
510  base->MDMR = LPI2C_MDMR_MATCH0(config->match0) | LPI2C_MDMR_MATCH1(config->match1);
511 
512  /* Restore master mode. */
513  if (wasEnabled)
514  {
515  LPI2C_MasterEnable(base, true);
516  }
517 }
518 
533 void LPI2C_MasterSetBaudRate(LPI2C_Type *base, uint32_t sourceClock_Hz, uint32_t baudRate_Hz)
534 {
535  uint32_t prescale = 0U;
536  uint32_t bestPre = 0U;
537  uint32_t bestClkHi = 0U;
538  uint32_t absError = 0U;
539  uint32_t bestError = 0xffffffffu;
540  uint32_t value;
541  uint32_t clkHiCycle;
542  uint32_t computedRate;
543  uint32_t i;
544  bool wasEnabled;
545 
546  /* Disable master mode. */
547  wasEnabled = (0U != ((base->MCR & LPI2C_MCR_MEN_MASK) >> LPI2C_MCR_MEN_SHIFT));
548  LPI2C_MasterEnable(base, false);
549 
550  /* Baud rate = (sourceClock_Hz/2^prescale)/(CLKLO+1+CLKHI+1 + ROUNDDOWN((2+FILTSCL)/2^prescale) */
551  /* Assume CLKLO = 2*CLKHI, SETHOLD = CLKHI, DATAVD = CLKHI/2. */
552  for (prescale = 1U; prescale <= 128U; prescale = 2U * prescale)
553  {
554  if (bestError == 0U)
555  {
556  break;
557  }
558 
559  for (clkHiCycle = 1U; clkHiCycle < 32U; clkHiCycle++)
560  {
561  if (clkHiCycle == 1U)
562  {
563  computedRate = (sourceClock_Hz / prescale) / (1U + 3U + 2U + 2U / prescale);
564  }
565  else
566  {
567  computedRate = (sourceClock_Hz / prescale) / (3U * clkHiCycle + 2U + 2U / prescale);
568  }
569 
570  absError = baudRate_Hz > computedRate ? baudRate_Hz - computedRate : computedRate - baudRate_Hz;
571 
572  if (absError < bestError)
573  {
574  bestPre = prescale;
575  bestClkHi = clkHiCycle;
576  bestError = absError;
577 
578  /* If the error is 0, then we can stop searching because we won't find a better match. */
579  if (absError == 0U)
580  {
581  break;
582  }
583  }
584  }
585  }
586 
587  /* Standard, fast, fast mode plus and ultra-fast transfers. */
588  value = LPI2C_MCCR0_CLKHI(bestClkHi);
589 
590  if (bestClkHi < 2U)
591  {
592  value |= (uint32_t)(LPI2C_MCCR0_CLKLO(3UL) | LPI2C_MCCR0_SETHOLD(2UL) | LPI2C_MCCR0_DATAVD(1UL));
593  }
594  else
595  {
596  value |=
597  LPI2C_MCCR0_CLKLO(2UL * bestClkHi) | LPI2C_MCCR0_SETHOLD(bestClkHi) | LPI2C_MCCR0_DATAVD(bestClkHi / 2UL);
598  }
599 
600  base->MCCR0 = value;
601 
602  for (i = 0U; i < 8U; i++)
603  {
604  if (bestPre == (1UL << i))
605  {
606  bestPre = i;
607  break;
608  }
609  }
610  base->MCFGR1 = (base->MCFGR1 & ~LPI2C_MCFGR1_PRESCALE_MASK) | LPI2C_MCFGR1_PRESCALE(bestPre);
611 
612  /* Restore master mode. */
613  if (wasEnabled)
614  {
615  LPI2C_MasterEnable(base, true);
616  }
617 }
618 
635 {
636  /* Return an error if the bus is already in use not by us. */
637  status_t result = LPI2C_CheckForBusyBus(base);
638  if (kStatus_Success != result)
639  {
640  return result;
641  }
642 
643  /* Clear all flags. */
645 
646  /* Turn off auto-stop option. */
648 
649  /* Wait until there is room in the fifo. */
650  result = LPI2C_MasterWaitForTxReady(base);
651  if (kStatus_Success != result)
652  {
653  return result;
654  }
655 
656  /* Issue start command. */
657  base->MTDR = (uint32_t)kStartCmd | (((uint32_t)address << 1U) | (uint32_t)dir);
658 
659  return kStatus_Success;
660 }
661 
676 {
677  /* Wait until there is room in the fifo. */
678  status_t result = LPI2C_MasterWaitForTxReady(base);
679  if (kStatus_Success != result)
680  {
681  return result;
682  }
683 
684  /* Send the STOP signal */
685  base->MTDR = (uint32_t)kStopCmd;
686 
687 /* Wait for the stop detected flag to set, indicating the transfer has completed on the bus. */
688 /* Also check for errors while waiting. */
689 #if I2C_RETRY_TIMES
690  uint32_t waitTimes = I2C_RETRY_TIMES;
691 #endif
692 
693 #if I2C_RETRY_TIMES
694  while ((result == kStatus_Success) && (0U != --waitTimes))
695 #else
696  while (result == kStatus_Success)
697 #endif
698  {
699  uint32_t status = LPI2C_MasterGetStatusFlags(base);
700 
701  /* Check for error flags. */
702  result = LPI2C_MasterCheckAndClearError(base, status);
703 
704  /* Check if the stop was sent successfully. */
705  if ((0U != (status & (uint32_t)kLPI2C_MasterStopDetectFlag)) &&
706  (0U != (status & (uint32_t)kLPI2C_MasterTxReadyFlag)))
707  {
709  break;
710  }
711  }
712 
713 #if I2C_RETRY_TIMES
714  if (0U == waitTimes)
715  {
716  return kStatus_LPI2C_Timeout;
717  }
718 #endif
719 
720  return result;
721 }
722 
736 status_t LPI2C_MasterReceive(LPI2C_Type *base, void *rxBuff, size_t rxSize)
737 {
738  status_t result;
739  uint8_t *buf;
740 #if I2C_RETRY_TIMES
741  uint32_t waitTimes;
742 #endif
743 
744  assert(NULL != rxBuff);
745 
746  /* Handle empty read. */
747  if (rxSize == 0U)
748  {
749  return kStatus_Success;
750  }
751 
752  /* Wait until there is room in the command fifo. */
753  result = LPI2C_MasterWaitForTxReady(base);
754  if (kStatus_Success != result)
755  {
756  return result;
757  }
758 
759  /* Issue command to receive data. */
760  base->MTDR = ((uint32_t)kRxDataCmd) | LPI2C_MTDR_DATA(rxSize - 1U);
761 
762  /* Receive data */
763  buf = (uint8_t *)rxBuff;
764  while (0U != (rxSize--))
765  {
766 #if I2C_RETRY_TIMES
767  waitTimes = I2C_RETRY_TIMES;
768 #endif
769  /* Read LPI2C receive fifo register. The register includes a flag to indicate whether */
770  /* the FIFO is empty, so we can both get the data and check if we need to keep reading */
771  /* using a single register read. */
772  uint32_t value;
773  do
774  {
775  /* Check for errors. */
777  if (kStatus_Success != result)
778  {
779  return result;
780  }
781 
782  value = base->MRDR;
783 #if I2C_RETRY_TIMES
784  } while ((0U != (value & LPI2C_MRDR_RXEMPTY_MASK)) && (0U != --waitTimes));
785  if (0U == waitTimes)
786  {
787  return kStatus_LPI2C_Timeout;
788  }
789 #else
790  } while (0U != (value & LPI2C_MRDR_RXEMPTY_MASK));
791 #endif
792 
793  *buf++ = (uint8_t)(value & LPI2C_MRDR_DATA_MASK);
794  }
795 
796  return kStatus_Success;
797 }
798 
816 status_t LPI2C_MasterSend(LPI2C_Type *base, void *txBuff, size_t txSize)
817 {
818  uint8_t *buf = (uint8_t *)txBuff;
819 
820  assert(NULL != txBuff);
821 
822  /* Send data buffer */
823  while (0U != (txSize--))
824  {
825  /* Wait until there is room in the fifo. This also checks for errors. */
826  status_t result = LPI2C_MasterWaitForTxReady(base);
827  if (kStatus_Success != result)
828  {
829  return result;
830  }
831 
832  /* Write byte into LPI2C master data register. */
833  base->MTDR = *buf++;
834  }
835 
836  return kStatus_Success;
837 }
838 
855 {
856  status_t result = kStatus_Success;
857  uint16_t commandBuffer[7];
858  uint32_t cmdCount = 0U;
859 
860  assert(NULL != transfer);
861  assert(transfer->subaddressSize <= sizeof(transfer->subaddress));
862 
863  /* Return an error if the bus is already in use not by us. */
864  result = LPI2C_CheckForBusyBus(base);
865  if (kStatus_Success != result)
866  {
867  return result;
868  }
869 
870  /* Clear all flags. */
872 
873  /* Turn off auto-stop option. */
875 
876  lpi2c_direction_t direction = (0U != transfer->subaddressSize) ? kLPI2C_Write : transfer->direction;
877  if (0U == (transfer->flags & (uint32_t)kLPI2C_TransferNoStartFlag))
878  {
879  commandBuffer[cmdCount++] =
880  (uint16_t)kStartCmd | (uint16_t)((uint16_t)((uint16_t)transfer->slaveAddress << 1U) | (uint16_t)direction);
881  }
882 
883  /* Subaddress, MSB first. */
884  if (0U != transfer->subaddressSize)
885  {
886  uint32_t subaddressRemaining = transfer->subaddressSize;
887  while (0U != subaddressRemaining--)
888  {
889  uint8_t subaddressByte = (uint8_t)((transfer->subaddress >> (8U * subaddressRemaining)) & 0xffU);
890  commandBuffer[cmdCount++] = subaddressByte;
891  }
892  }
893 
894  /* Reads need special handling. */
895  if ((0U != transfer->dataSize) && (transfer->direction == kLPI2C_Read))
896  {
897  /* Need to send repeated start if switching directions to read. */
898  if (direction == kLPI2C_Write)
899  {
900  commandBuffer[cmdCount++] =
901  (uint16_t)kStartCmd |
902  (uint16_t)((uint16_t)((uint16_t)transfer->slaveAddress << 1U) | (uint16_t)kLPI2C_Read);
903  }
904  }
905 
906  /* Send command buffer */
907  uint32_t index = 0U;
908  while (0U != cmdCount--)
909  {
910  /* Wait until there is room in the fifo. This also checks for errors. */
911  result = LPI2C_MasterWaitForTxReady(base);
912  if (kStatus_Success != result)
913  {
914  return result;
915  }
916 
917  /* Write byte into LPI2C master data register. */
918  base->MTDR = commandBuffer[index];
919  index++;
920  }
921 
922  /* Transmit data. */
923  if ((transfer->direction == kLPI2C_Write) && (transfer->dataSize > 0U))
924  {
925  /* Send Data. */
926  result = LPI2C_MasterSend(base, transfer->data, transfer->dataSize);
927  }
928 
929  /* Receive Data. */
930  if ((transfer->direction == kLPI2C_Read) && (transfer->dataSize > 0U))
931  {
932  result = LPI2C_MasterReceive(base, transfer->data, transfer->dataSize);
933  }
934 
935  if (kStatus_Success != result)
936  {
937  return result;
938  }
939 
940  if ((transfer->flags & (uint32_t)kLPI2C_TransferNoStopFlag) == 0U)
941  {
942  result = LPI2C_MasterStop(base);
943  }
944 
945  return result;
946 }
947 
966  lpi2c_master_handle_t *handle,
968  void *userData)
969 {
970  uint32_t instance;
971 
972  assert(NULL != handle);
973 
974  /* Clear out the handle. */
975  (void)memset(handle, 0, sizeof(*handle));
976 
977  /* Look up instance number */
978  instance = LPI2C_GetInstance(base);
979 
980  /* Save base and instance. */
981  handle->completionCallback = callback;
982  handle->userData = userData;
983 
984  /* Save this handle for IRQ use. */
985  s_lpi2cMasterHandle[instance] = handle;
986 
987  /* Set irq handler. */
989 
990  /* Clear internal IRQ enables and enable NVIC IRQ. */
992 
993  /* Enable NVIC IRQ, this only enables the IRQ directly connected to the NVIC.
994  In some cases the LPI2C IRQ is configured through INTMUX, user needs to enable
995  INTMUX IRQ in application code. */
996  (void)EnableIRQ(kLpi2cIrqs[instance]);
997 }
998 
1010 {
1011  uint32_t status;
1012  status_t result = kStatus_Success;
1014  size_t txCount;
1015  size_t rxCount;
1016  size_t txFifoSize = (size_t)FSL_FEATURE_LPI2C_FIFO_SIZEn(base);
1017  bool state_complete = false;
1018  uint16_t sendval;
1019 
1020  /* Set default isDone return value. */
1021  *isDone = false;
1022 
1023  /* Check for errors. */
1024  status = LPI2C_MasterGetStatusFlags(base);
1025  /* For the last byte, nack flag is expected.
1026  Do not check and clear kLPI2C_MasterNackDetectFlag for the last byte,
1027  in case FIFO is emptied when stop command has not been sent. */
1028  if (handle->remainingBytes == 0U)
1029  {
1030  status &= ~(uint32_t)kLPI2C_MasterNackDetectFlag;
1031  }
1032  result = LPI2C_MasterCheckAndClearError(base, status);
1033  if (kStatus_Success != result)
1034  {
1035  return result;
1036  }
1037 
1038  /* Get pointer to private data. */
1039  xfer = &handle->transfer;
1040 
1041  /* Get fifo counts and compute room in tx fifo. */
1042  LPI2C_MasterGetFifoCounts(base, &rxCount, &txCount);
1043  txCount = txFifoSize - txCount;
1044 
1045  while (!state_complete)
1046  {
1047  /* Execute the state. */
1048  switch (handle->state)
1049  {
1050  case (uint8_t)kSendCommandState:
1051  /* Make sure there is room in the tx fifo for the next command. */
1052  if (0U == txCount--)
1053  {
1054  state_complete = true;
1055  break;
1056  }
1057 
1058  /* Issue command. buf is a uint8_t* pointing at the uint16 command array. */
1059  sendval = ((uint16_t)(*handle->buf)) | ((uint16_t)(*(handle->buf + 1U)) << 8U);
1060  base->MTDR = sendval;
1061  handle->buf++;
1062  handle->buf++;
1063 
1064  /* Count down until all commands are sent. */
1065  if (--handle->remainingBytes == 0U)
1066  {
1067  /* Choose next state and set up buffer pointer and count. */
1068  if (0U != xfer->dataSize)
1069  {
1070  /* Either a send or receive transfer is next. */
1071  handle->state = (uint8_t)kTransferDataState;
1072  handle->buf = (uint8_t *)xfer->data;
1073  handle->remainingBytes = (uint16_t)xfer->dataSize;
1074  if (xfer->direction == kLPI2C_Read)
1075  {
1076  /* Disable TX interrupt */
1078  }
1079  }
1080  else
1081  {
1082  /* No transfer, so move to stop state. */
1083  handle->state = (uint8_t)kStopState;
1084  }
1085  }
1086  break;
1087 
1088  case (uint8_t)kIssueReadCommandState:
1089  /* Make sure there is room in the tx fifo for the read command. */
1090  if (0U == txCount--)
1091  {
1092  state_complete = true;
1093  break;
1094  }
1095 
1096  base->MTDR = (uint32_t)kRxDataCmd | LPI2C_MTDR_DATA(xfer->dataSize - 1U);
1097 
1098  /* Move to transfer state. */
1099  handle->state = (uint8_t)kTransferDataState;
1100  if (xfer->direction == kLPI2C_Read)
1101  {
1102  /* Disable TX interrupt */
1104  }
1105  break;
1106 
1107  case (uint8_t)kTransferDataState:
1108  if (xfer->direction == kLPI2C_Write)
1109  {
1110  /* Make sure there is room in the tx fifo. */
1111  if (0U == txCount--)
1112  {
1113  state_complete = true;
1114  break;
1115  }
1116 
1117  /* Put byte to send in fifo. */
1118  base->MTDR = *(handle->buf)++;
1119  }
1120  else
1121  {
1122  /* XXX handle receive sizes > 256, use kIssueReadCommandState */
1123  /* Make sure there is data in the rx fifo. */
1124  if (0U == rxCount--)
1125  {
1126  state_complete = true;
1127  break;
1128  }
1129 
1130  /* Read byte from fifo. */
1131  *(handle->buf)++ = (uint8_t)(base->MRDR & LPI2C_MRDR_DATA_MASK);
1132  }
1133 
1134  /* Move to stop when the transfer is done. */
1135  if (--handle->remainingBytes == 0U)
1136  {
1137  if (xfer->direction == kLPI2C_Write)
1138  {
1139  state_complete = true;
1140  }
1141  handle->state = (uint8_t)kStopState;
1142  }
1143  break;
1144 
1145  case (uint8_t)kStopState:
1146  /* Only issue a stop transition if the caller requested it. */
1147  if ((xfer->flags & (uint32_t)kLPI2C_TransferNoStopFlag) == 0U)
1148  {
1149  /* Make sure there is room in the tx fifo for the stop command. */
1150  if (0U == txCount--)
1151  {
1152  state_complete = true;
1153  break;
1154  }
1155 
1156  base->MTDR = (uint32_t)kStopCmd;
1157  }
1158  else
1159  {
1160  /* Caller doesn't want to send a stop, so we're done now. */
1161  *isDone = true;
1162  state_complete = true;
1163  break;
1164  }
1165  handle->state = (uint8_t)kWaitForCompletionState;
1166  break;
1167 
1168  case (uint8_t)kWaitForCompletionState:
1169  /* We stay in this state until the stop state is detected. */
1170  if (0U != (status & (uint32_t)kLPI2C_MasterStopDetectFlag))
1171  {
1172  *isDone = true;
1173  }
1174  state_complete = true;
1175  break;
1176  default:
1177  assert(false);
1178  break;
1179  }
1180  }
1181  return result;
1182 }
1183 
1189 {
1190  lpi2c_master_transfer_t *xfer = &handle->transfer;
1191 
1192  /* Handle no start option. */
1193  if (0U != (xfer->flags & (uint32_t)kLPI2C_TransferNoStartFlag))
1194  {
1195  if (xfer->direction == kLPI2C_Read)
1196  {
1197  /* Need to issue read command first. */
1198  handle->state = (uint8_t)kIssueReadCommandState;
1199  }
1200  else
1201  {
1202  /* Start immediately in the data transfer state. */
1203  handle->state = (uint8_t)kTransferDataState;
1204  }
1205 
1206  handle->buf = (uint8_t *)xfer->data;
1207  handle->remainingBytes = (uint16_t)xfer->dataSize;
1208  }
1209  else
1210  {
1211  uint16_t *cmd = (uint16_t *)&handle->commandBuffer;
1212  uint32_t cmdCount = 0U;
1213 
1214  /* Initial direction depends on whether a subaddress was provided, and of course the actual */
1215  /* data transfer direction. */
1216  lpi2c_direction_t direction = (0U != xfer->subaddressSize) ? kLPI2C_Write : xfer->direction;
1217 
1218  /* Start command. */
1219  cmd[cmdCount++] =
1220  (uint16_t)kStartCmd | (uint16_t)((uint16_t)((uint16_t)xfer->slaveAddress << 1U) | (uint16_t)direction);
1221 
1222  /* Subaddress, MSB first. */
1223  if (0U != xfer->subaddressSize)
1224  {
1225  uint32_t subaddressRemaining = xfer->subaddressSize;
1226  while (0U != (subaddressRemaining--))
1227  {
1228  uint8_t subaddressByte = (uint8_t)((xfer->subaddress >> (8U * subaddressRemaining)) & 0xffU);
1229  cmd[cmdCount++] = subaddressByte;
1230  }
1231  }
1232 
1233  /* Reads need special handling. */
1234  if ((0U != xfer->dataSize) && (xfer->direction == kLPI2C_Read))
1235  {
1236  /* Need to send repeated start if switching directions to read. */
1237  if (direction == kLPI2C_Write)
1238  {
1239  cmd[cmdCount++] = (uint16_t)kStartCmd |
1240  (uint16_t)((uint16_t)((uint16_t)xfer->slaveAddress << 1U) | (uint16_t)kLPI2C_Read);
1241  }
1242 
1243  /* Read command. */
1244  cmd[cmdCount++] = (uint16_t)((uint32_t)kRxDataCmd | LPI2C_MTDR_DATA(xfer->dataSize - 1U));
1245  }
1246 
1247  /* Set up state machine for transferring the commands. */
1248  handle->state = (uint8_t)kSendCommandState;
1249  handle->remainingBytes = (uint16_t)cmdCount;
1250  handle->buf = (uint8_t *)&handle->commandBuffer;
1251  }
1252 }
1253 
1265  lpi2c_master_handle_t *handle,
1266  lpi2c_master_transfer_t *transfer)
1267 {
1268  status_t result;
1269 
1270  assert(NULL != handle);
1271  assert(NULL != transfer);
1272  assert(transfer->subaddressSize <= sizeof(transfer->subaddress));
1273 
1274  /* Return busy if another transaction is in progress. */
1275  if (handle->state != (uint8_t)kIdleState)
1276  {
1277  return kStatus_LPI2C_Busy;
1278  }
1279 
1280  /* Return an error if the bus is already in use not by us. */
1281  result = LPI2C_CheckForBusyBus(base);
1282  if (kStatus_Success != result)
1283  {
1284  return result;
1285  }
1286 
1287  /* Disable LPI2C IRQ sources while we configure stuff. */
1289 
1290  /* Reset FIFO in case there are data. */
1292 
1293  /* Save transfer into handle. */
1294  handle->transfer = *transfer;
1295 
1296  /* Generate commands to send. */
1298 
1299  /* Clear all flags. */
1301 
1302  /* Turn off auto-stop option. */
1304 
1305  /* Enable LPI2C internal IRQ sources. NVIC IRQ was enabled in CreateHandle() */
1307 
1308  return result;
1309 }
1310 
1320 {
1321  assert(NULL != handle);
1322 
1323  if (NULL == count)
1324  {
1325  return kStatus_InvalidArgument;
1326  }
1327 
1328  /* Catch when there is not an active transfer. */
1329  if (handle->state == (uint8_t)kIdleState)
1330  {
1331  *count = 0;
1333  }
1334 
1335  uint8_t state;
1336  uint16_t remainingBytes;
1337  uint32_t dataSize;
1338 
1339  /* Cache some fields with IRQs disabled. This ensures all field values */
1340  /* are synchronized with each other during an ongoing transfer. */
1341  uint32_t irqs = LPI2C_MasterGetEnabledInterrupts(base);
1342  LPI2C_MasterDisableInterrupts(base, irqs);
1343  state = handle->state;
1344  remainingBytes = handle->remainingBytes;
1345  dataSize = handle->transfer.dataSize;
1346  LPI2C_MasterEnableInterrupts(base, irqs);
1347 
1348  /* Get transfer count based on current transfer state. */
1349  switch (state)
1350  {
1351  case (uint8_t)kIdleState:
1352  case (uint8_t)kSendCommandState:
1353  case (
1354  uint8_t)kIssueReadCommandState: /* XXX return correct value for this state when >256 reads are supported */
1355  *count = 0;
1356  break;
1357 
1358  case (uint8_t)kTransferDataState:
1359  *count = dataSize - remainingBytes;
1360  break;
1361 
1362  case (uint8_t)kStopState:
1363  case (uint8_t)kWaitForCompletionState:
1364  default:
1365  *count = dataSize;
1366  break;
1367  }
1368 
1369  return kStatus_Success;
1370 }
1371 
1384 {
1385  if (handle->state != (uint8_t)kIdleState)
1386  {
1387  /* Disable internal IRQ enables. */
1389 
1390  /* Reset fifos. */
1392 
1393  /* Send a stop command to finalize the transfer. */
1394  base->MTDR = (uint32_t)kStopCmd;
1395 
1396  /* Reset handle. */
1397  handle->state = (uint8_t)kIdleState;
1398  }
1399 }
1400 
1409 {
1410  bool isDone = false;
1411  status_t result;
1412  size_t txCount;
1413 
1414  /* Don't do anything if we don't have a valid handle. */
1415  if (NULL == handle)
1416  {
1417  return;
1418  }
1419 
1420  if (handle->state == (uint8_t)kIdleState)
1421  {
1422  return;
1423  }
1424 
1425  result = LPI2C_RunTransferStateMachine(base, handle, &isDone);
1426 
1427  if ((result != kStatus_Success) || isDone)
1428  {
1429  /* Handle error, terminate xfer */
1430  if (result != kStatus_Success)
1431  {
1432  LPI2C_MasterTransferAbort(base, handle);
1433  }
1434  /* Check whether there is data in tx FIFO not sent out, is there is then the last transfer was NACKed by slave
1435  */
1436  LPI2C_MasterGetFifoCounts(base, NULL, &txCount);
1437  if (txCount != 0U)
1438  {
1439  result = kStatus_LPI2C_Nak;
1440  /* Reset fifos. */
1442  /* Send a stop command to finalize the transfer. */
1443  base->MTDR = (uint32_t)kStopCmd;
1444  }
1445  /* Disable internal IRQ enables. */
1447 
1448  /* Set handle to idle state. */
1449  handle->state = (uint8_t)kIdleState;
1450 
1451  /* Invoke callback. */
1452  if (NULL != handle->completionCallback)
1453  {
1454  handle->completionCallback(base, handle, result, handle->userData);
1455  }
1456  }
1457 }
1458 
1491 {
1492  /* Initializes the configure structure to zero. */
1493  (void)memset(slaveConfig, 0, sizeof(*slaveConfig));
1494 
1495  slaveConfig->enableSlave = true;
1496  slaveConfig->address0 = 0U;
1497  slaveConfig->address1 = 0U;
1498  slaveConfig->addressMatchMode = kLPI2C_MatchAddress0;
1499  slaveConfig->filterDozeEnable = true;
1500  slaveConfig->filterEnable = true;
1501  slaveConfig->enableGeneralCall = false;
1502  slaveConfig->sclStall.enableAck = false;
1503  slaveConfig->sclStall.enableTx = true;
1504  slaveConfig->sclStall.enableRx = true;
1505  slaveConfig->sclStall.enableAddress = false;
1506  slaveConfig->ignoreAck = false;
1507  slaveConfig->enableReceivedAddressRead = false;
1508  slaveConfig->sdaGlitchFilterWidth_ns = 0U; /* TODO determine default width values */
1509  slaveConfig->sclGlitchFilterWidth_ns = 0U;
1510  slaveConfig->dataValidDelay_ns = 0U;
1511  slaveConfig->clockHoldTime_ns = 0U;
1512 }
1513 
1526 void LPI2C_SlaveInit(LPI2C_Type *base, const lpi2c_slave_config_t *slaveConfig, uint32_t sourceClock_Hz)
1527 {
1528  uint32_t tmpCycle;
1529 
1530 #if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
1531 
1532  uint32_t instance = LPI2C_GetInstance(base);
1533 
1534  /* Ungate the clock. */
1535  CLOCK_EnableClock(kLpi2cClocks[instance]);
1536 #if defined(LPI2C_PERIPH_CLOCKS)
1537  /* Ungate the functional clock in initialize function. */
1538  CLOCK_EnableClock(kLpi2cPeriphClocks[instance]);
1539 #endif
1540 
1541 #endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
1542 
1543  /* Restore to reset conditions. */
1544  LPI2C_SlaveReset(base);
1545 
1546  /* Configure peripheral. */
1547  base->SAMR = LPI2C_SAMR_ADDR0(slaveConfig->address0) | LPI2C_SAMR_ADDR1(slaveConfig->address1);
1548 
1549  base->SCFGR1 =
1550  LPI2C_SCFGR1_ADDRCFG(slaveConfig->addressMatchMode) | LPI2C_SCFGR1_IGNACK(slaveConfig->ignoreAck) |
1553  LPI2C_SCFGR1_RXSTALL(slaveConfig->sclStall.enableRx) |
1555 
1556  tmpCycle =
1559  tmpCycle |=
1563  sourceClock_Hz, slaveConfig->dataValidDelay_ns, (LPI2C_SCFGR2_DATAVD_MASK >> LPI2C_SCFGR2_DATAVD_SHIFT), 1U));
1564 
1566  sourceClock_Hz, slaveConfig->clockHoldTime_ns,
1568 
1569  /* Save SCR to last so we don't enable slave until it is configured */
1570  base->SCR = LPI2C_SCR_FILTDZ(slaveConfig->filterDozeEnable) | LPI2C_SCR_FILTEN(slaveConfig->filterEnable) |
1571  LPI2C_SCR_SEN(slaveConfig->enableSlave);
1572 }
1573 
1583 {
1584  LPI2C_SlaveReset(base);
1585 
1586 #if !(defined(FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL) && FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL)
1587 
1588  uint32_t instance = LPI2C_GetInstance(base);
1589 
1590  /* Gate the clock. */
1591  CLOCK_DisableClock(kLpi2cClocks[instance]);
1592 
1593 #if defined(LPI2C_PERIPH_CLOCKS)
1594  /* Gate the functional clock. */
1595  CLOCK_DisableClock(kLpi2cPeriphClocks[instance]);
1596 #endif
1597 
1598 #endif /* FSL_SDK_DISABLE_DRIVER_CLOCK_CONTROL */
1599 }
1600 
1610 {
1611  status_t result = kStatus_Success;
1612 
1613  flags &= (uint32_t)kSlaveErrorFlags;
1614  if (0U != flags)
1615  {
1616  if (0U != (flags & (uint32_t)kLPI2C_SlaveBitErrFlag))
1617  {
1618  result = kStatus_LPI2C_BitError;
1619  }
1620  else if (0U != (flags & (uint32_t)kLPI2C_SlaveFifoErrFlag))
1621  {
1622  result = kStatus_LPI2C_FifoError;
1623  }
1624  else
1625  {
1626  ; /* Intentional empty */
1627  }
1628 
1629  /* Clear the errors. */
1630  LPI2C_SlaveClearStatusFlags(base, flags);
1631  }
1632  else
1633  {
1634  ; /* Intentional empty */
1635  }
1636 
1637  return result;
1638 }
1639 
1649 status_t LPI2C_SlaveSend(LPI2C_Type *base, void *txBuff, size_t txSize, size_t *actualTxSize)
1650 {
1651  uint8_t *buf = (uint8_t *)txBuff;
1652  size_t remaining = txSize;
1653 
1654  assert(NULL != txBuff);
1655 
1656 #if I2C_RETRY_TIMES
1657  uint32_t waitTimes = I2C_RETRY_TIMES;
1658 #endif
1659 
1660  /* Clear stop flag. */
1663 
1664  while (0U != remaining)
1665  {
1666  uint32_t flags;
1667  status_t result;
1668 
1669  /* Wait until we can transmit. */
1670  do
1671  {
1672  /* Check for errors */
1673  flags = LPI2C_SlaveGetStatusFlags(base);
1674  result = LPI2C_SlaveCheckAndClearError(base, flags);
1675  if (kStatus_Success != result)
1676  {
1677  if (NULL != actualTxSize)
1678  {
1679  *actualTxSize = txSize - remaining;
1680  }
1681  return result;
1682  }
1683 #if I2C_RETRY_TIMES
1684  } while ((0U == (flags & ((uint32_t)kLPI2C_SlaveTxReadyFlag | (uint32_t)kLPI2C_SlaveStopDetectFlag |
1685  (uint32_t)kLPI2C_SlaveRepeatedStartDetectFlag))) &&
1686  (0U != --waitTimes));
1687  if (0U == waitTimes)
1688  {
1689  return kStatus_LPI2C_Timeout;
1690  }
1691 #else
1692  } while (0U == (flags & ((uint32_t)kLPI2C_SlaveTxReadyFlag | (uint32_t)kLPI2C_SlaveStopDetectFlag |
1694 #endif
1695 
1696  /* Send a byte. */
1697  if (0U != (flags & (uint32_t)kLPI2C_SlaveTxReadyFlag))
1698  {
1699  base->STDR = *buf++;
1700  --remaining;
1701  }
1702 
1703  /* Exit loop if we see a stop or restart in transfer*/
1704  if ((0U != (flags & ((uint32_t)kLPI2C_SlaveStopDetectFlag | (uint32_t)kLPI2C_SlaveRepeatedStartDetectFlag))) &&
1705  (remaining != 0U))
1706  {
1709  break;
1710  }
1711  }
1712 
1713  if (NULL != actualTxSize)
1714  {
1715  *actualTxSize = txSize - remaining;
1716  }
1717 
1718  return kStatus_Success;
1719 }
1720 
1730 status_t LPI2C_SlaveReceive(LPI2C_Type *base, void *rxBuff, size_t rxSize, size_t *actualRxSize)
1731 {
1732  uint8_t *buf = (uint8_t *)rxBuff;
1733  size_t remaining = rxSize;
1734 
1735  assert(NULL != rxBuff);
1736 
1737 #if I2C_RETRY_TIMES
1738  uint32_t waitTimes = I2C_RETRY_TIMES;
1739 #endif
1740 
1741  /* Clear stop flag. */
1744 
1745  while (0U != remaining)
1746  {
1747  uint32_t flags;
1748  status_t result;
1749 
1750  /* Wait until we can receive. */
1751  do
1752  {
1753  /* Check for errors */
1754  flags = LPI2C_SlaveGetStatusFlags(base);
1755  result = LPI2C_SlaveCheckAndClearError(base, flags);
1756  if (kStatus_Success != result)
1757  {
1758  if (NULL != actualRxSize)
1759  {
1760  *actualRxSize = rxSize - remaining;
1761  }
1762  return result;
1763  }
1764 #if I2C_RETRY_TIMES
1765  } while ((0U == (flags & ((uint32_t)kLPI2C_SlaveRxReadyFlag | (uint32_t)kLPI2C_SlaveStopDetectFlag |
1766  (uint32_t)kLPI2C_SlaveRepeatedStartDetectFlag))) &&
1767  (0U != --waitTimes));
1768  if (0U == waitTimes)
1769  {
1770  return kStatus_LPI2C_Timeout;
1771  }
1772 #else
1773  } while (0U == (flags & ((uint32_t)kLPI2C_SlaveRxReadyFlag | (uint32_t)kLPI2C_SlaveStopDetectFlag |
1775 #endif
1776 
1777  /* Receive a byte. */
1778  if (0U != (flags & (uint32_t)kLPI2C_SlaveRxReadyFlag))
1779  {
1780  *buf++ = (uint8_t)(base->SRDR & LPI2C_SRDR_DATA_MASK);
1781  --remaining;
1782  }
1783 
1784  /* Exit loop if we see a stop or restart */
1785  if ((0U != (flags & ((uint32_t)kLPI2C_SlaveStopDetectFlag | (uint32_t)kLPI2C_SlaveRepeatedStartDetectFlag))) &&
1786  (remaining != 0U))
1787  {
1790  break;
1791  }
1792  }
1793 
1794  if (NULL != actualRxSize)
1795  {
1796  *actualRxSize = rxSize - remaining;
1797  }
1798 
1799  return kStatus_Success;
1800 }
1801 
1819  lpi2c_slave_handle_t *handle,
1821  void *userData)
1822 {
1823  uint32_t instance;
1824 
1825  assert(NULL != handle);
1826 
1827  /* Clear out the handle. */
1828  (void)memset(handle, 0, sizeof(*handle));
1829 
1830  /* Look up instance number */
1831  instance = LPI2C_GetInstance(base);
1832 
1833  /* Save base and instance. */
1834  handle->callback = callback;
1835  handle->userData = userData;
1836 
1837  /* Save this handle for IRQ use. */
1838  s_lpi2cSlaveHandle[instance] = handle;
1839 
1840  /* Set irq handler. */
1842 
1843  /* Clear internal IRQ enables and enable NVIC IRQ. */
1845  (void)EnableIRQ(kLpi2cIrqs[instance]);
1846 
1847  /* Nack by default. */
1848  base->STAR = LPI2C_STAR_TXNACK_MASK;
1849 }
1850 
1876 {
1877  uint32_t status;
1878 
1879  assert(NULL != handle);
1880 
1881  /* Return busy if another transaction is in progress. */
1882  if (handle->isBusy)
1883  {
1884  return kStatus_LPI2C_Busy;
1885  }
1886 
1887  /* Return an error if the bus is already in use not by us. */
1888  status = LPI2C_SlaveGetStatusFlags(base);
1889  if ((0U != (status & (uint32_t)kLPI2C_SlaveBusBusyFlag)) && (0U == (status & (uint32_t)kLPI2C_SlaveBusyFlag)))
1890  {
1891  return kStatus_LPI2C_Busy;
1892  }
1893 
1894  /* Disable LPI2C IRQ sources while we configure stuff. */
1896 
1897  /* Clear transfer in handle. */
1898  (void)memset(&handle->transfer, 0, sizeof(handle->transfer));
1899 
1900  /* Record that we're busy. */
1901  handle->isBusy = true;
1902 
1903  /* Set up event mask. tx and rx are always enabled. */
1904  handle->eventMask = eventMask | (uint32_t)kLPI2C_SlaveTransmitEvent | (uint32_t)kLPI2C_SlaveReceiveEvent;
1905 
1906  /* Ack by default. */
1907  base->STAR = 0U;
1908 
1909  /* Clear all flags. */
1911 
1912  /* Enable LPI2C internal IRQ sources. NVIC IRQ was enabled in CreateHandle() */
1914 
1915  return kStatus_Success;
1916 }
1917 
1928 {
1929  assert(NULL != handle);
1930 
1931  if (count == NULL)
1932  {
1933  return kStatus_InvalidArgument;
1934  }
1935 
1936  /* Catch when there is not an active transfer. */
1937  if (!handle->isBusy)
1938  {
1939  *count = 0;
1941  }
1942 
1943  /* For an active transfer, just return the count from the handle. */
1944  *count = handle->transferredCount;
1945 
1946  return kStatus_Success;
1947 }
1948 
1958 {
1959  assert(NULL != handle);
1960 
1961  /* Return idle if no transaction is in progress. */
1962  if (handle->isBusy)
1963  {
1964  /* Disable LPI2C IRQ sources. */
1966 
1967  /* Nack by default. */
1968  base->STAR = LPI2C_STAR_TXNACK_MASK;
1969 
1970  /* Reset transfer info. */
1971  (void)memset(&handle->transfer, 0, sizeof(handle->transfer));
1972 
1973  /* We're no longer busy. */
1974  handle->isBusy = false;
1975  }
1976 }
1977 
1986 {
1987  uint32_t flags;
1988  lpi2c_slave_transfer_t *xfer;
1989 
1990  /* Check for a valid handle in case of a spurious interrupt. */
1991  if (NULL == handle)
1992  {
1993  return;
1994  }
1995 
1996  xfer = &handle->transfer;
1997 
1998  /* Get status flags. */
1999  flags = LPI2C_SlaveGetStatusFlags(base);
2000 
2001  if (0U != (flags & ((uint32_t)kLPI2C_SlaveBitErrFlag | (uint32_t)kLPI2C_SlaveFifoErrFlag)))
2002  {
2004  xfer->completionStatus = LPI2C_SlaveCheckAndClearError(base, flags);
2005 
2006  if ((0U != (handle->eventMask & (uint32_t)kLPI2C_SlaveCompletionEvent)) && (NULL != handle->callback))
2007  {
2008  handle->callback(base, xfer, handle->userData);
2009  }
2010  return;
2011  }
2012  if (0U != (flags & (((uint32_t)kLPI2C_SlaveRepeatedStartDetectFlag) | ((uint32_t)kLPI2C_SlaveStopDetectFlag))))
2013  {
2014  xfer->event = (0U != (flags & (uint32_t)kLPI2C_SlaveRepeatedStartDetectFlag)) ? kLPI2C_SlaveRepeatedStartEvent :
2016  xfer->receivedAddress = 0U;
2018  xfer->transferredCount = handle->transferredCount;
2019 
2020  if (xfer->event == kLPI2C_SlaveCompletionEvent)
2021  {
2022  handle->isBusy = false;
2023  }
2024 
2025  if (handle->wasTransmit)
2026  {
2027  /* Subtract one from the transmit count to offset the fact that LPI2C asserts the */
2028  /* tx flag before it sees the nack from the master-receiver, thus causing one more */
2029  /* count that the master actually receives. */
2030  --xfer->transferredCount;
2031  handle->wasTransmit = false;
2032  }
2033 
2034  /* Clear the flag. */
2036  base, flags & ((uint32_t)kLPI2C_SlaveRepeatedStartDetectFlag | (uint32_t)kLPI2C_SlaveStopDetectFlag));
2037 
2038  /* Revert to sending an Ack by default, in case we sent a Nack for receive. */
2039  base->STAR = 0U;
2040 
2041  if ((0U != (handle->eventMask & (uint32_t)xfer->event)) && (NULL != handle->callback))
2042  {
2043  handle->callback(base, xfer, handle->userData);
2044  }
2045 
2046  /* Clean up transfer info on completion, after the callback has been invoked. */
2047  (void)memset(&handle->transfer, 0, sizeof(handle->transfer));
2048  }
2049  if (0U != (flags & (uint32_t)kLPI2C_SlaveAddressValidFlag))
2050  {
2052  xfer->receivedAddress = (uint8_t)(base->SASR & LPI2C_SASR_RADDR_MASK);
2053 
2054  /* Update handle status to busy because slave is addressed. */
2055  handle->isBusy = true;
2056  if ((0U != (handle->eventMask & (uint32_t)kLPI2C_SlaveAddressMatchEvent)) && (NULL != handle->callback))
2057  {
2058  handle->callback(base, xfer, handle->userData);
2059  }
2060  }
2061  if (0U != (flags & (uint32_t)kLPI2C_SlaveTransmitAckFlag))
2062  {
2064 
2065  if ((0U != (handle->eventMask & (uint32_t)kLPI2C_SlaveTransmitAckEvent)) && (NULL != handle->callback))
2066  {
2067  handle->callback(base, xfer, handle->userData);
2068  }
2069  }
2070 
2071  /* Handle transmit and receive. */
2072  if (0U != (flags & (uint32_t)kLPI2C_SlaveTxReadyFlag))
2073  {
2074  handle->wasTransmit = true;
2075 
2076  /* If we're out of data, invoke callback to get more. */
2077  if ((NULL == xfer->data) || (0U == xfer->dataSize))
2078  {
2080  if (NULL != handle->callback)
2081  {
2082  handle->callback(base, xfer, handle->userData);
2083  }
2084 
2085  /* Clear the transferred count now that we have a new buffer. */
2086  handle->transferredCount = 0U;
2087  }
2088 
2089  /* Transmit a byte. */
2090  if ((NULL != xfer->data) && (0U != xfer->dataSize))
2091  {
2092  base->STDR = *xfer->data++;
2093  --xfer->dataSize;
2094  ++handle->transferredCount;
2095  }
2096  }
2097  if (0U != (flags & (uint32_t)kLPI2C_SlaveRxReadyFlag))
2098  {
2099  /* If we're out of room in the buffer, invoke callback to get another. */
2100  if ((NULL == xfer->data) || (0U == xfer->dataSize))
2101  {
2103  if (NULL != handle->callback)
2104  {
2105  handle->callback(base, xfer, handle->userData);
2106  }
2107 
2108  /* Clear the transferred count now that we have a new buffer. */
2109  handle->transferredCount = 0U;
2110  }
2111 
2112  /* Receive a byte. */
2113  if ((NULL != xfer->data) && (0U != xfer->dataSize))
2114  {
2115  *xfer->data++ = (uint8_t)base->SRDR;
2116  --xfer->dataSize;
2117  ++handle->transferredCount;
2118  }
2119  else
2120  {
2121  /* We don't have any room to receive more data, so send a nack. */
2122  base->STAR = LPI2C_STAR_TXNACK_MASK;
2123  }
2124  }
2125 }
2126 
2127 #if !(defined(FSL_FEATURE_I2C_HAS_NO_IRQ) && FSL_FEATURE_I2C_HAS_NO_IRQ)
2128 
2138 static void LPI2C_CommonIRQHandler(LPI2C_Type *base, uint32_t instance)
2139 {
2140  /* Check for master IRQ. */
2141  if ((0U != (base->MCR & LPI2C_MCR_MEN_MASK)) && (NULL != s_lpi2cMasterIsr))
2142  {
2143  /* Master mode. */
2144  s_lpi2cMasterIsr(base, s_lpi2cMasterHandle[instance]);
2145  }
2146 
2147  /* Check for slave IRQ. */
2148  if ((0U != (base->SCR & LPI2C_SCR_SEN_MASK)) && (NULL != s_lpi2cSlaveIsr))
2149  {
2150  /* Slave mode. */
2151  s_lpi2cSlaveIsr(base, s_lpi2cSlaveHandle[instance]);
2152  }
2154 }
2155 #endif
2156 
2157 #if defined(LPI2C0)
2158 /* Implementation of LPI2C0 handler named in startup code. */
2159 void LPI2C0_DriverIRQHandler(void)
2160 {
2161  LPI2C_CommonIRQHandler(LPI2C0, 0U);
2162 }
2163 #endif
2164 
2165 #if defined(LPI2C1)
2166 /* Implementation of LPI2C1 handler named in startup code. */
2167 void LPI2C1_DriverIRQHandler(void)
2168 {
2170 }
2171 #endif
2172 
2173 #if defined(LPI2C2)
2174 /* Implementation of LPI2C2 handler named in startup code. */
2175 void LPI2C2_DriverIRQHandler(void)
2176 {
2178 }
2179 #endif
2180 
2181 #if defined(LPI2C3)
2182 /* Implementation of LPI2C3 handler named in startup code. */
2183 void LPI2C3_DriverIRQHandler(void)
2184 {
2186 }
2187 #endif
2188 
2189 #if defined(LPI2C4)
2190 /* Implementation of LPI2C4 handler named in startup code. */
2191 void LPI2C4_DriverIRQHandler(void)
2192 {
2194 }
2195 #endif
2196 
2197 #if defined(LPI2C5)
2198 /* Implementation of LPI2C5 handler named in startup code. */
2199 void LPI2C5_DriverIRQHandler(void)
2200 {
2201  LPI2C_CommonIRQHandler(LPI2C5, 5U);
2202 }
2203 #endif
2204 
2205 #if defined(LPI2C6)
2206 /* Implementation of LPI2C6 handler named in startup code. */
2207 void LPI2C6_DriverIRQHandler(void)
2208 {
2209  LPI2C_CommonIRQHandler(LPI2C6, 6U);
2210 }
2211 #endif
2212 
2213 #if defined(CM4_0__LPI2C)
2214 /* Implementation of CM4_0__LPI2C handler named in startup code. */
2215 void M4_0_LPI2C_DriverIRQHandler(void)
2216 {
2217  LPI2C_CommonIRQHandler(CM4_0__LPI2C, LPI2C_GetInstance(CM4_0__LPI2C));
2218 }
2219 #endif
2220 
2221 #if defined(CM4__LPI2C)
2222 /* Implementation of CM4__LPI2C handler named in startup code. */
2223 void M4_LPI2C_DriverIRQHandler(void)
2224 {
2225  LPI2C_CommonIRQHandler(CM4__LPI2C, LPI2C_GetInstance(CM4__LPI2C));
2226 }
2227 #endif
2228 
2229 #if defined(CM4_1__LPI2C)
2230 /* Implementation of CM4_1__LPI2C handler named in startup code. */
2231 void M4_1_LPI2C_DriverIRQHandler(void)
2232 {
2233  LPI2C_CommonIRQHandler(CM4_1__LPI2C, LPI2C_GetInstance(CM4_1__LPI2C));
2234 }
2235 #endif
2236 
2237 #if defined(DMA__LPI2C0)
2238 /* Implementation of DMA__LPI2C0 handler named in startup code. */
2239 void DMA_I2C0_INT_DriverIRQHandler(void)
2240 {
2241  LPI2C_CommonIRQHandler(DMA__LPI2C0, LPI2C_GetInstance(DMA__LPI2C0));
2242 }
2243 #endif
2244 
2245 #if defined(DMA__LPI2C1)
2246 /* Implementation of DMA__LPI2C1 handler named in startup code. */
2247 void DMA_I2C1_INT_DriverIRQHandler(void)
2248 {
2249  LPI2C_CommonIRQHandler(DMA__LPI2C1, LPI2C_GetInstance(DMA__LPI2C1));
2250 }
2251 #endif
2252 
2253 #if defined(DMA__LPI2C2)
2254 /* Implementation of DMA__LPI2C2 handler named in startup code. */
2255 void DMA_I2C2_INT_DriverIRQHandler(void)
2256 {
2257  LPI2C_CommonIRQHandler(DMA__LPI2C2, LPI2C_GetInstance(DMA__LPI2C2));
2258 }
2259 #endif
2260 
2261 #if defined(DMA__LPI2C3)
2262 /* Implementation of DMA__LPI2C3 handler named in startup code. */
2263 void DMA_I2C3_INT_DriverIRQHandler(void)
2264 {
2265  LPI2C_CommonIRQHandler(DMA__LPI2C3, LPI2C_GetInstance(DMA__LPI2C3));
2266 }
2267 #endif
2268 
2269 #if defined(DMA__LPI2C4)
2270 /* Implementation of DMA__LPI2C3 handler named in startup code. */
2271 void DMA_I2C4_INT_DriverIRQHandler(void)
2272 {
2273  LPI2C_CommonIRQHandler(DMA__LPI2C4, LPI2C_GetInstance(DMA__LPI2C4));
2274 }
2275 #endif
2276 
2277 #if defined(ADMA__LPI2C0)
2278 /* Implementation of DMA__LPI2C0 handler named in startup code. */
2279 void ADMA_I2C0_INT_DriverIRQHandler(void)
2280 {
2281  LPI2C_CommonIRQHandler(ADMA__LPI2C0, LPI2C_GetInstance(ADMA__LPI2C0));
2282 }
2283 #endif
2284 
2285 #if defined(ADMA__LPI2C1)
2286 /* Implementation of DMA__LPI2C1 handler named in startup code. */
2287 void ADMA_I2C1_INT_DriverIRQHandler(void)
2288 {
2289  LPI2C_CommonIRQHandler(ADMA__LPI2C1, LPI2C_GetInstance(ADMA__LPI2C1));
2290 }
2291 #endif
2292 
2293 #if defined(ADMA__LPI2C2)
2294 /* Implementation of DMA__LPI2C2 handler named in startup code. */
2295 void ADMA_I2C2_INT_DriverIRQHandler(void)
2296 {
2297  LPI2C_CommonIRQHandler(ADMA__LPI2C2, LPI2C_GetInstance(ADMA__LPI2C2));
2298 }
2299 #endif
2300 
2301 #if defined(ADMA__LPI2C3)
2302 /* Implementation of DMA__LPI2C3 handler named in startup code. */
2303 void ADMA_I2C3_INT_DriverIRQHandler(void)
2304 {
2305  LPI2C_CommonIRQHandler(ADMA__LPI2C3, LPI2C_GetInstance(ADMA__LPI2C3));
2306 }
2307 #endif
2308 
2309 #if defined(ADMA__LPI2C4)
2310 /* Implementation of DMA__LPI2C3 handler named in startup code. */
2311 void ADMA_I2C4_INT_DriverIRQHandler(void)
2312 {
2313  LPI2C_CommonIRQHandler(ADMA__LPI2C4, LPI2C_GetInstance(ADMA__LPI2C4));
2314 }
2315 #endif
LPI2C_SCR_FILTDZ
#define LPI2C_SCR_FILTDZ(x)
Definition: MIMXRT1052.h:25681
LPI2C_MCCR0_DATAVD
#define LPI2C_MCCR0_DATAVD(x)
Definition: MIMXRT1052.h:25559
LPI2C_MCFGR1_PRESCALE_MASK
#define LPI2C_MCFGR1_PRESCALE_MASK
Definition: MIMXRT1052.h:25434
_lpi2c_master_handle::remainingBytes
uint16_t remainingBytes
Definition: fsl_lpi2c.h:239
LPI2C_SlaveGetStatusFlags
static uint32_t LPI2C_SlaveGetStatusFlags(LPI2C_Type *base)
Gets the LPI2C slave status flags.
Definition: fsl_lpi2c.h:1008
_lpi2c_master_config::hostRequest
struct _lpi2c_master_config::@353 hostRequest
LPI2C_Type::SCFGR1
__IO uint32_t SCFGR1
Definition: MIMXRT1052.h:25124
LPI2C_InitTransferStateMachine
static void LPI2C_InitTransferStateMachine(lpi2c_master_handle_t *handle)
Prepares the transfer state machine and fills in the command buffer.
Definition: fsl_lpi2c.c:1188
LPI2C_MCFGR0_RDMO_MASK
#define LPI2C_MCFGR0_RDMO_MASK
Definition: MIMXRT1052.h:25423
LPI2C_MasterGetDefaultConfig
void LPI2C_MasterGetDefaultConfig(lpi2c_master_config_t *masterConfig)
Provides a default configuration for the LPI2C master peripheral.
Definition: fsl_lpi2c.c:356
LPI2C_IRQS
#define LPI2C_IRQS
Definition: MIMXRT1052.h:26127
kStatus_InvalidArgument
@ kStatus_InvalidArgument
Definition: fsl_common.h:183
_lpi2c_slave_config::enableSlave
bool enableSlave
Definition: fsl_lpi2c.h:304
LPI2C_Type::MCFGR0
__IO uint32_t MCFGR0
Definition: MIMXRT1052.h:25102
LPI2C_Type::MDMR
__IO uint32_t MDMR
Definition: MIMXRT1052.h:25107
kWaitForCompletionState
@ kWaitForCompletionState
Definition: fsl_lpi2c.c:80
_lpi2c_master_transfer::data
void * data
Definition: fsl_lpi2c.h:228
kLPI2C_SlaveFifoErrFlag
@ kLPI2C_SlaveFifoErrFlag
Definition: fsl_lpi2c.h:277
_lpi2c_slave_handle::transfer
lpi2c_slave_transfer_t transfer
Definition: fsl_lpi2c.h:392
_lpi2c_master_config::pinLowTimeout_ns
uint32_t pinLowTimeout_ns
Definition: fsl_lpi2c.h:146
LPI2C_SCFGR2_FILTSCL_SHIFT
#define LPI2C_SCFGR2_FILTSCL_SHIFT
Definition: MIMXRT1052.h:26015
LPI2C_Type::MCR
__IO uint32_t MCR
Definition: MIMXRT1052.h:25098
lpi2c_direction_t
enum _lpi2c_direction lpi2c_direction_t
Direction of master and slave transfers.
_lpi2c_master_config::source
lpi2c_host_request_source_t source
Definition: fsl_lpi2c.h:152
LPI2C_MCFGR1_PINCFG
#define LPI2C_MCFGR1_PINCFG(x)
Definition: MIMXRT1052.h:25493
_lpi2c_master_config::baudRate_Hz
uint32_t baudRate_Hz
Definition: fsl_lpi2c.h:144
LPI2C_SlaveDeinit
void LPI2C_SlaveDeinit(LPI2C_Type *base)
Deinitializes the LPI2C slave peripheral.
Definition: fsl_lpi2c.c:1582
s_lpi2cMasterIsr
static lpi2c_master_isr_t s_lpi2cMasterIsr
Pointer to master IRQ handler for each instance.
Definition: fsl_lpi2c.c:133
_lpi2c_master_config::pinConfig
lpi2c_master_pin_config_t pinConfig
Definition: fsl_lpi2c.h:143
_lpi2c_master_transfer::subaddress
uint32_t subaddress
Definition: fsl_lpi2c.h:226
LPI2C_SCFGR1_RXCFG
#define LPI2C_SCFGR1_RXCFG(x)
Definition: MIMXRT1052.h:25972
LPI2C3
#define LPI2C3
Definition: MIMXRT1052.h:26117
_lpi2c_slave_config::addressMatchMode
lpi2c_slave_address_match_t addressMatchMode
Definition: fsl_lpi2c.h:307
NULL
#define NULL
Definition: porcupine/demo/c/dr_libs/tests/external/miniaudio/extras/speex_resampler/thirdparty/resample.c:92
LPI2C_MCFGR0_HRSEL_MASK
#define LPI2C_MCFGR0_HRSEL_MASK
Definition: MIMXRT1052.h:25409
kLPI2C_2PinOpenDrain
@ kLPI2C_2PinOpenDrain
Definition: fsl_lpi2c.h:101
kMasterErrorFlags
@ kMasterErrorFlags
Definition: fsl_lpi2c.c:36
LPI2C_SlaveReset
static void LPI2C_SlaveReset(LPI2C_Type *base)
Performs a software reset of the LPI2C slave peripheral.
Definition: fsl_lpi2c.h:974
_lpi2c_slave_transfer::receivedAddress
uint8_t receivedAddress
Definition: fsl_lpi2c.h:363
LPI2C_SCFGR2_DATAVD_SHIFT
#define LPI2C_SCFGR2_DATAVD_SHIFT
Definition: MIMXRT1052.h:26010
LPI2C_MCFGR2_FILTSDA_SHIFT
#define LPI2C_MCFGR2_FILTSDA_SHIFT
Definition: MIMXRT1052.h:25509
_lpi2c_slave_config::filterDozeEnable
bool filterDozeEnable
Definition: fsl_lpi2c.h:308
lpi2c_slave_transfer_callback_t
void(* lpi2c_slave_transfer_callback_t)(LPI2C_Type *base, lpi2c_slave_transfer_t *transfer, void *userData)
Slave event callback function pointer type.
Definition: fsl_lpi2c.h:384
LPI2C_MasterEnableInterrupts
static void LPI2C_MasterEnableInterrupts(LPI2C_Type *base, uint32_t interruptMask)
Enables the LPI2C master interrupt requests.
Definition: fsl_lpi2c.h:570
LPI2C_Type::SAMR
__IO uint32_t SAMR
Definition: MIMXRT1052.h:25127
LPI2C_MRDR_RXEMPTY_MASK
#define LPI2C_MRDR_RXEMPTY_MASK
Definition: MIMXRT1052.h:25643
LPI2C_MCFGR1_PINCFG_MASK
#define LPI2C_MCFGR1_PINCFG_MASK
Definition: MIMXRT1052.h:25481
LPI2C_MCFGR1_IGNACK
#define LPI2C_MCFGR1_IGNACK(x)
Definition: MIMXRT1052.h:25460
LPI2C_MCFGR1_PRESCALE
#define LPI2C_MCFGR1_PRESCALE(x)
Definition: MIMXRT1052.h:25446
LPI2C_CLOCKS
#define LPI2C_CLOCKS
Clock ip name array for LPI2C.
Definition: fsl_clock.h:277
_lpi2c_slave_handle::wasTransmit
bool wasTransmit
Definition: fsl_lpi2c.h:394
kLPI2C_SlaveTransmitAckEvent
@ kLPI2C_SlaveTransmitAckEvent
Definition: fsl_lpi2c.h:350
LPI2C_SCFGR1_IGNACK
#define LPI2C_SCFGR1_IGNACK(x)
Definition: MIMXRT1052.h:25979
kLPI2C_MasterArbitrationLostFlag
@ kLPI2C_MasterArbitrationLostFlag
Definition: fsl_lpi2c.h:83
LPI2C_SlaveTransferHandleIRQ
void LPI2C_SlaveTransferHandleIRQ(LPI2C_Type *base, lpi2c_slave_handle_t *handle)
Reusable routine to handle slave interrupts.
Definition: fsl_lpi2c.c:1985
LPI2C_SCFGR1_ADDRCFG
#define LPI2C_SCFGR1_ADDRCFG(x)
Definition: MIMXRT1052.h:25999
kLPI2C_SlaveStopDetectFlag
@ kLPI2C_SlaveStopDetectFlag
Definition: fsl_lpi2c.h:275
LPI2C_Type::MCCR0
__IO uint32_t MCCR0
Definition: MIMXRT1052.h:25109
LPI2C_Type::SASR
__I uint32_t SASR
Definition: MIMXRT1052.h:25129
LPI2C_MasterStart
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.
Definition: fsl_lpi2c.c:634
LPI2C_SCFGR2_DATAVD
#define LPI2C_SCFGR2_DATAVD(x)
Definition: MIMXRT1052.h:26013
LPI2C_MCR_DOZEN
#define LPI2C_MCR_DOZEN(x)
Definition: MIMXRT1052.h:25203
LPI2C_MasterReceive
status_t LPI2C_MasterReceive(LPI2C_Type *base, void *rxBuff, size_t rxSize)
Performs a polling receive transfer on the I2C bus.
Definition: fsl_lpi2c.c:736
LPI2C_MasterDeinit
void LPI2C_MasterDeinit(LPI2C_Type *base)
Deinitializes the LPI2C master peripheral.
Definition: fsl_lpi2c.c:477
LPI2C_CheckForBusyBus
status_t LPI2C_CheckForBusyBus(LPI2C_Type *base)
Make sure the bus isn't already busy.
Definition: fsl_lpi2c.c:319
kStatus_NoTransferInProgress
@ kStatus_NoTransferInProgress
Definition: fsl_common.h:185
_lpi2c_slave_config::enableAck
bool enableAck
Definition: fsl_lpi2c.h:313
LPI2C_MasterTransferCreateHandle
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.
Definition: fsl_lpi2c.c:965
_lpi2c_master_transfer::slaveAddress
uint16_t slaveAddress
Definition: fsl_lpi2c.h:224
LPI2C_MCFGR0_HRPOL
#define LPI2C_MCFGR0_HRPOL(x)
Definition: MIMXRT1052.h:25408
LPI2C_SCFGR1_ACKSTALL
#define LPI2C_SCFGR1_ACKSTALL(x)
Definition: MIMXRT1052.h:25942
LPI2C_SCFGR2_CLKHOLD
#define LPI2C_SCFGR2_CLKHOLD(x)
Definition: MIMXRT1052.h:26008
LPI2C_RunTransferStateMachine
static status_t LPI2C_RunTransferStateMachine(LPI2C_Type *base, lpi2c_master_handle_t *handle, bool *isDone)
Execute states until FIFOs are exhausted.
Definition: fsl_lpi2c.c:1009
LPI2C_Type::MCFGR1
__IO uint32_t MCFGR1
Definition: MIMXRT1052.h:25103
_lpi2c_master_config::sclGlitchFilterWidth_ns
uint8_t sclGlitchFilterWidth_ns
Definition: fsl_lpi2c.h:148
_lpi2c_slave_config::enableAddress
bool enableAddress
Definition: fsl_lpi2c.h:323
LPI2C_MCFGR2_BUSIDLE_MASK
#define LPI2C_MCFGR2_BUSIDLE_MASK
Definition: MIMXRT1052.h:25498
kLPI2C_SlaveRepeatedStartDetectFlag
@ kLPI2C_SlaveRepeatedStartDetectFlag
Definition: fsl_lpi2c.h:274
kIdleState
@ kIdleState
Definition: fsl_lpi2c.c:75
LPI2C_SCFGR1_GCEN
#define LPI2C_SCFGR1_GCEN(x)
Definition: MIMXRT1052.h:25949
kLPI2C_SlaveRepeatedStartEvent
@ kLPI2C_SlaveRepeatedStartEvent
Definition: fsl_lpi2c.h:351
kLPI2C_MasterPinLowTimeoutFlag
@ kLPI2C_MasterPinLowTimeoutFlag
Definition: fsl_lpi2c.h:85
kStatus_LPI2C_FifoError
@ kStatus_LPI2C_FifoError
Definition: fsl_lpi2c.h:41
LPI2C_STAR_TXNACK_MASK
#define LPI2C_STAR_TXNACK_MASK
Definition: MIMXRT1052.h:26058
LPI2C_MCR_DBGEN
#define LPI2C_MCR_DBGEN(x)
Definition: MIMXRT1052.h:25210
LPI2C_SlaveGetDefaultConfig
void LPI2C_SlaveGetDefaultConfig(lpi2c_slave_config_t *slaveConfig)
Provides a default configuration for the LPI2C slave peripheral.
Definition: fsl_lpi2c.c:1490
LPI2C_SAMR_ADDR0
#define LPI2C_SAMR_ADDR0(x)
Definition: MIMXRT1052.h:26032
LPI2C_MCFGR2_BUSIDLE
#define LPI2C_MCFGR2_BUSIDLE(x)
Definition: MIMXRT1052.h:25502
LPI2C_Type::MTDR
__O uint32_t MTDR
Definition: MIMXRT1052.h:25115
_lpi2c_slave_config::dataValidDelay_ns
uint32_t dataValidDelay_ns
Definition: fsl_lpi2c.h:329
kDefaultRxWatermark
@ kDefaultRxWatermark
Definition: fsl_lpi2c.c:69
_lpi2c_master_config::sdaGlitchFilterWidth_ns
uint8_t sdaGlitchFilterWidth_ns
Definition: fsl_lpi2c.h:147
LPI2C_MasterSetBaudRate
void LPI2C_MasterSetBaudRate(LPI2C_Type *base, uint32_t sourceClock_Hz, uint32_t baudRate_Hz)
Sets the I2C bus frequency for master transactions.
Definition: fsl_lpi2c.c:533
_lpi2c_master_config
Structure with settings to initialize the LPI2C master module.
Definition: fsl_lpi2c.h:137
kLPI2C_MasterFifoErrFlag
@ kLPI2C_MasterFifoErrFlag
Definition: fsl_lpi2c.h:84
LPI2C_MCFGR0_RDMO
#define LPI2C_MCFGR0_RDMO(x)
Definition: MIMXRT1052.h:25429
kLPI2C_MasterNackDetectFlag
@ kLPI2C_MasterNackDetectFlag
Definition: fsl_lpi2c.h:82
kLPI2C_MasterDataMatchFlag
@ kLPI2C_MasterDataMatchFlag
Definition: fsl_lpi2c.h:86
kLPI2C_SlaveRxReadyFlag
@ kLPI2C_SlaveRxReadyFlag
Definition: fsl_lpi2c.h:271
kLPI2C_SlaveTransmitAckFlag
@ kLPI2C_SlaveTransmitAckFlag
Definition: fsl_lpi2c.h:273
_lpi2c_master_handle::transfer
lpi2c_master_transfer_t transfer
Definition: fsl_lpi2c.h:242
LPI2C_MCFGR0_HRSEL
#define LPI2C_MCFGR0_HRSEL(x)
Definition: MIMXRT1052.h:25415
kStatus_LPI2C_Timeout
@ kStatus_LPI2C_Timeout
Definition: fsl_lpi2c.h:49
I2C_RETRY_TIMES
#define I2C_RETRY_TIMES
Retry times for waiting flag.
Definition: fsl_lpi2c.h:32
_lpi2c_master_handle::buf
uint8_t * buf
Definition: fsl_lpi2c.h:240
kStatus_LPI2C_ArbitrationLost
@ kStatus_LPI2C_ArbitrationLost
Definition: fsl_lpi2c.h:43
LPI2C_SCFGR2_FILTSCL_MASK
#define LPI2C_SCFGR2_FILTSCL_MASK
Definition: MIMXRT1052.h:26014
kDefaultTxWatermark
@ kDefaultTxWatermark
Definition: fsl_lpi2c.c:68
kLPI2C_MasterBusBusyFlag
@ kLPI2C_MasterBusBusyFlag
Definition: fsl_lpi2c.h:88
LPI2C_MDMR_MATCH0
#define LPI2C_MDMR_MATCH0(x)
Definition: MIMXRT1052.h:25530
_lpi2c_slave_config::address1
uint8_t address1
Definition: fsl_lpi2c.h:306
s_lpi2cSlaveHandle
static lpi2c_slave_handle_t * s_lpi2cSlaveHandle[ARRAY_SIZE(kLpi2cBases)]
Pointers to slave handles for each instance.
Definition: fsl_lpi2c.c:142
_lpi2c_master_handle
Driver handle for master non-blocking APIs.
Definition: fsl_lpi2c.h:236
FSL_FEATURE_LPI2C_FIFO_SIZEn
#define FSL_FEATURE_LPI2C_FIFO_SIZEn(x)
Definition: MIMXRT1052_features.h:391
LPI2C_MCFGR3_PINLOW
#define LPI2C_MCFGR3_PINLOW(x)
Definition: MIMXRT1052.h:25521
kStartCmd
@ kStartCmd
Definition: fsl_lpi2c.c:58
LPI2C_MCFGR3_PINLOW_MASK
#define LPI2C_MCFGR3_PINLOW_MASK
Definition: MIMXRT1052.h:25517
_lpi2c_slave_config::enableGeneralCall
bool enableGeneralCall
Definition: fsl_lpi2c.h:310
LPI2C_MasterCheckAndClearError
status_t LPI2C_MasterCheckAndClearError(LPI2C_Type *base, uint32_t status)
Convert provided flags to status code, and clear any errors if present.
Definition: fsl_lpi2c.c:217
LPI2C1
#define LPI2C1
Definition: MIMXRT1052.h:26109
_lpi2c_slave_config::ignoreAck
bool ignoreAck
Definition: fsl_lpi2c.h:325
kTransferDataState
@ kTransferDataState
Definition: fsl_lpi2c.c:78
LPI2C_GetCyclesForWidth
static uint32_t LPI2C_GetCyclesForWidth(uint32_t sourceClock_Hz, uint32_t width_ns, uint32_t maxCycles, uint32_t prescaler)
Computes a cycle count for a given time in nanoseconds.
Definition: fsl_lpi2c.c:179
_lpi2c_slave_handle::transferredCount
uint32_t transferredCount
Definition: fsl_lpi2c.h:396
LPI2C_SCFGR2_CLKHOLD_SHIFT
#define LPI2C_SCFGR2_CLKHOLD_SHIFT
Definition: MIMXRT1052.h:26005
LPI2C4
#define LPI2C4
Definition: MIMXRT1052.h:26121
kLPI2C_MasterBusyFlag
@ kLPI2C_MasterBusyFlag
Definition: fsl_lpi2c.h:87
_lpi2c_slave_config::enableTx
bool enableTx
Definition: fsl_lpi2c.h:319
LPI2C_MCFGR1_MATCFG_MASK
#define LPI2C_MCFGR1_MATCFG_MASK
Definition: MIMXRT1052.h:25468
kStopCmd
@ kStopCmd
Definition: fsl_lpi2c.c:57
LPI2C_MTDR_CMD
#define LPI2C_MTDR_CMD(x)
Definition: MIMXRT1052.h:25633
LPI2C_MCR_MEN_MASK
#define LPI2C_MCR_MEN_MASK
Definition: MIMXRT1052.h:25183
kLPI2C_SlaveBitErrFlag
@ kLPI2C_SlaveBitErrFlag
Definition: fsl_lpi2c.h:276
LPI2C_Type::SRDR
__I uint32_t SRDR
Definition: MIMXRT1052.h:25134
kLPI2C_SlaveCompletionEvent
@ kLPI2C_SlaveCompletionEvent
Definition: fsl_lpi2c.h:352
kLPI2C_SlaveAddressValidFlag
@ kLPI2C_SlaveAddressValidFlag
Definition: fsl_lpi2c.h:272
LPI2C_SlaveReceive
status_t LPI2C_SlaveReceive(LPI2C_Type *base, void *rxBuff, size_t rxSize, size_t *actualRxSize)
Performs a polling receive transfer on the I2C bus.
Definition: fsl_lpi2c.c:1730
kLpi2cBases
static LPI2C_Type *const kLpi2cBases[]
Array to map LPI2C instance number to base pointer.
Definition: fsl_lpi2c.c:116
_lpi2c_slave_transfer::dataSize
size_t dataSize
Definition: fsl_lpi2c.h:365
LPI2C_MCFGR0_HREN_MASK
#define LPI2C_MCFGR0_HREN_MASK
Definition: MIMXRT1052.h:25395
SDK_ISR_EXIT_BARRIER
#define SDK_ISR_EXIT_BARRIER
Definition: fsl_common.h:250
LPI2C_MasterTransferHandleIRQ
void LPI2C_MasterTransferHandleIRQ(LPI2C_Type *base, lpi2c_master_handle_t *handle)
Reusable routine to handle master interrupts.
Definition: fsl_lpi2c.c:1408
kLPI2C_MatchAddress0
@ kLPI2C_MatchAddress0
Definition: fsl_lpi2c.h:288
kLPI2C_Read
@ kLPI2C_Read
Definition: fsl_lpi2c.h:95
LPI2C_MCFGR1_MATCFG
#define LPI2C_MCFGR1_MATCFG(x)
Definition: MIMXRT1052.h:25480
_lpi2c_slave_config::address0
uint8_t address0
Definition: fsl_lpi2c.h:305
kLPI2C_MasterRxReadyFlag
@ kLPI2C_MasterRxReadyFlag
Definition: fsl_lpi2c.h:79
kLPI2C_Write
@ kLPI2C_Write
Definition: fsl_lpi2c.h:94
kStatus_LPI2C_BitError
@ kStatus_LPI2C_BitError
Definition: fsl_lpi2c.h:42
kLPI2C_TransferNoStartFlag
@ kLPI2C_TransferNoStartFlag
Definition: fsl_lpi2c.h:210
LPI2C_SAMR_ADDR1
#define LPI2C_SAMR_ADDR1(x)
Definition: MIMXRT1052.h:26037
kLPI2C_SlaveBusyFlag
@ kLPI2C_SlaveBusyFlag
Definition: fsl_lpi2c.h:281
ARRAY_SIZE
#define ARRAY_SIZE(x)
Computes the number of elements in an array.
Definition: fsl_common.h:211
LPI2C_SlaveTransferCreateHandle
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.
Definition: fsl_lpi2c.c:1818
kLpi2cClocks
static const clock_ip_name_t kLpi2cClocks[]
Array to map LPI2C instance number to clock gate enum.
Definition: fsl_lpi2c.c:123
kLPI2C_MasterStopDetectFlag
@ kLPI2C_MasterStopDetectFlag
Definition: fsl_lpi2c.h:81
LPI2C_BASE_PTRS
#define LPI2C_BASE_PTRS
Definition: MIMXRT1052.h:26125
_lpi2c_slave_config::filterEnable
bool filterEnable
Definition: fsl_lpi2c.h:309
_lpi2c_slave_config::sclGlitchFilterWidth_ns
uint32_t sclGlitchFilterWidth_ns
Definition: fsl_lpi2c.h:328
LPI2C_MasterClearStatusFlags
static void LPI2C_MasterClearStatusFlags(LPI2C_Type *base, uint32_t statusMask)
Clears the LPI2C master status flag state.
Definition: fsl_lpi2c.h:550
LPI2C_MCFGR2_FILTSCL_MASK
#define LPI2C_MCFGR2_FILTSCL_MASK
Definition: MIMXRT1052.h:25503
IRQn_Type
IRQn_Type
STM32F4XX Interrupt Number Definition, according to the selected device in Library_configuration_sect...
Definition: stm32f407xx.h:66
LPI2C_SCFGR1_TXDSTALL
#define LPI2C_SCFGR1_TXDSTALL(x)
Definition: MIMXRT1052.h:25935
kLPI2C_HostRequestExternalPin
@ kLPI2C_HostRequestExternalPin
Definition: fsl_lpi2c.h:117
LPI2C_MCFGR2_BUSIDLE_SHIFT
#define LPI2C_MCFGR2_BUSIDLE_SHIFT
Definition: MIMXRT1052.h:25499
count
size_t count
Definition: porcupine/demo/c/dr_libs/tests/external/miniaudio/tests/test_common/ma_test_common.c:31
_lpi2c_master_handle::completionCallback
lpi2c_master_transfer_callback_t completionCallback
Definition: fsl_lpi2c.h:243
_lpi2c_slave_transfer::transferredCount
size_t transferredCount
Definition: fsl_lpi2c.h:368
kSlaveErrorFlags
@ kSlaveErrorFlags
Definition: fsl_lpi2c.c:49
_lpi2c_master_transfer::direction
lpi2c_direction_t direction
Definition: fsl_lpi2c.h:225
kLPI2C_SlaveReceiveEvent
@ kLPI2C_SlaveReceiveEvent
Definition: fsl_lpi2c.h:348
LPI2C_SlaveInit
void LPI2C_SlaveInit(LPI2C_Type *base, const lpi2c_slave_config_t *slaveConfig, uint32_t sourceClock_Hz)
Initializes the LPI2C slave peripheral.
Definition: fsl_lpi2c.c:1526
kStatus_LPI2C_Nak
@ kStatus_LPI2C_Nak
Definition: fsl_lpi2c.h:40
LPI2C_MCFGR1_AUTOSTOP_MASK
#define LPI2C_MCFGR1_AUTOSTOP_MASK
Definition: MIMXRT1052.h:25447
LPI2C_SlaveEnableInterrupts
static void LPI2C_SlaveEnableInterrupts(LPI2C_Type *base, uint32_t interruptMask)
Enables the LPI2C slave interrupt requests.
Definition: fsl_lpi2c.h:1050
LPI2C_MDMR_MATCH1
#define LPI2C_MDMR_MATCH1(x)
Definition: MIMXRT1052.h:25535
LPI2C_SRDR_DATA_MASK
#define LPI2C_SRDR_DATA_MASK
Definition: MIMXRT1052.h:26078
_lpi2c_master_config::enableMaster
bool enableMaster
Definition: fsl_lpi2c.h:139
LPI2C_SlaveCheckAndClearError
static status_t LPI2C_SlaveCheckAndClearError(LPI2C_Type *base, uint32_t flags)
Convert provided flags to status code, and clear any errors if present.
Definition: fsl_lpi2c.c:1609
LPI2C_MCFGR0_HRPOL_MASK
#define LPI2C_MCFGR0_HRPOL_MASK
Definition: MIMXRT1052.h:25402
_lpi2c_master_config::busIdleTimeout_ns
uint32_t busIdleTimeout_ns
Definition: fsl_lpi2c.h:145
LPI2C_Type::STAR
__IO uint32_t STAR
Definition: MIMXRT1052.h:25130
LPI2C_SCFGR2_CLKHOLD_MASK
#define LPI2C_SCFGR2_CLKHOLD_MASK
Definition: MIMXRT1052.h:26004
LPI2C_Type::SCR
__IO uint32_t SCR
Definition: MIMXRT1052.h:25119
LPI2C_MRDR_DATA_MASK
#define LPI2C_MRDR_DATA_MASK
Definition: MIMXRT1052.h:25638
_lpi2c_slave_config::enableRx
bool enableRx
Definition: fsl_lpi2c.h:321
LPI2C_MCR_RRF_MASK
#define LPI2C_MCR_RRF_MASK
Definition: MIMXRT1052.h:25218
_lpi2c_slave_handle::userData
void * userData
Definition: fsl_lpi2c.h:398
_lpi2c_slave_handle::isBusy
bool isBusy
Definition: fsl_lpi2c.h:393
LPI2C_MasterGetEnabledInterrupts
static uint32_t LPI2C_MasterGetEnabledInterrupts(LPI2C_Type *base)
Returns the set of currently enabled LPI2C master interrupt requests.
Definition: fsl_lpi2c.h:597
LPI2C_MCFGR2_FILTSCL_SHIFT
#define LPI2C_MCFGR2_FILTSCL_SHIFT
Definition: MIMXRT1052.h:25504
kLPI2C_MasterTxReadyFlag
@ kLPI2C_MasterTxReadyFlag
Definition: fsl_lpi2c.h:78
CLOCK_EnableClock
static void CLOCK_EnableClock(clock_ip_name_t name)
Enable the clock for specific IP.
Definition: fsl_clock.h:1059
_lpi2c_slave_config::clockHoldTime_ns
uint32_t clockHoldTime_ns
Definition: fsl_lpi2c.h:330
_lpi2c_slave_handle
LPI2C slave handle structure.
Definition: fsl_lpi2c.h:390
_lpi2c_slave_config
Structure with settings to initialize the LPI2C slave module.
Definition: fsl_lpi2c.h:302
LPI2C_MasterSetWatermarks
static void LPI2C_MasterSetWatermarks(LPI2C_Type *base, size_t txWords, size_t rxWords)
Sets the watermarks for LPI2C master FIFOs.
Definition: fsl_lpi2c.h:657
LPI2C_SCR_SEN_MASK
#define LPI2C_SCR_SEN_MASK
Definition: MIMXRT1052.h:25654
_lpi2c_master_handle::userData
void * userData
Definition: fsl_lpi2c.h:244
LPI2C_MasterReset
static void LPI2C_MasterReset(LPI2C_Type *base)
Performs a software reset.
Definition: fsl_lpi2c.h:491
LPI2C_SCR_FILTEN
#define LPI2C_SCR_FILTEN(x)
Definition: MIMXRT1052.h:25674
_lpi2c_slave_config::sclStall
struct _lpi2c_slave_config::@354 sclStall
LPI2C_Type::SCFGR2
__IO uint32_t SCFGR2
Definition: MIMXRT1052.h:25125
LPI2C_SCFGR2_FILTSDA
#define LPI2C_SCFGR2_FILTSDA(x)
Definition: MIMXRT1052.h:26023
LPI2C_GetInstance
uint32_t LPI2C_GetInstance(LPI2C_Type *base)
Returns an instance number given a base address.
Definition: fsl_lpi2c.c:157
kLPI2C_HostRequestPinActiveHigh
@ kLPI2C_HostRequestPinActiveHigh
Definition: fsl_lpi2c.h:125
s_lpi2cMasterHandle
static lpi2c_master_handle_t * s_lpi2cMasterHandle[ARRAY_SIZE(kLpi2cBases)]
Pointers to master handles for each instance.
Definition: fsl_lpi2c.c:136
LPI2C_MasterGetFifoCounts
static void LPI2C_MasterGetFifoCounts(LPI2C_Type *base, size_t *rxCount, size_t *txCount)
Gets the current number of words in the LPI2C master FIFOs.
Definition: fsl_lpi2c.h:671
LPI2C_Type
Definition: MIMXRT1052.h:25094
LPI2C_SlaveClearStatusFlags
static void LPI2C_SlaveClearStatusFlags(LPI2C_Type *base, uint32_t statusMask)
Clears the LPI2C status flag state.
Definition: fsl_lpi2c.h:1030
_lpi2c_master_transfer::dataSize
size_t dataSize
Definition: fsl_lpi2c.h:229
LPI2C_Type::MCFGR2
__IO uint32_t MCFGR2
Definition: MIMXRT1052.h:25104
kMasterClearFlags
@ kMasterClearFlags
Definition: fsl_lpi2c.c:26
kTxDataCmd
@ kTxDataCmd
Definition: fsl_lpi2c.c:55
kLPI2C_SlaveBusBusyFlag
@ kLPI2C_SlaveBusBusyFlag
Definition: fsl_lpi2c.h:282
_lpi2c_master_config::polarity
lpi2c_host_request_polarity_t polarity
Definition: fsl_lpi2c.h:153
LPI2C_MasterTransferNonBlocking
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.
Definition: fsl_lpi2c.c:1264
LPI2C_SCFGR1_RXSTALL
#define LPI2C_SCFGR1_RXSTALL(x)
Definition: MIMXRT1052.h:25928
LPI2C_MCFGR2_FILTSDA
#define LPI2C_MCFGR2_FILTSDA(x)
Definition: MIMXRT1052.h:25512
LPI2C_MasterTransferGetCount
status_t LPI2C_MasterTransferGetCount(LPI2C_Type *base, lpi2c_master_handle_t *handle, size_t *count)
Returns number of bytes transferred so far.
Definition: fsl_lpi2c.c:1319
_lpi2c_master_config::debugEnable
bool debugEnable
Definition: fsl_lpi2c.h:141
_lpi2c_slave_handle::eventMask
uint32_t eventMask
Definition: fsl_lpi2c.h:395
LPI2C_MasterWaitForTxReady
static status_t LPI2C_MasterWaitForTxReady(LPI2C_Type *base)
Wait until there is room in the tx fifo.
Definition: fsl_lpi2c.c:271
_lpi2c_match_config
LPI2C master data match configuration structure.
Definition: fsl_lpi2c.h:174
LPI2C_MasterSend
status_t LPI2C_MasterSend(LPI2C_Type *base, void *txBuff, size_t txSize)
Performs a polling send transfer on the I2C bus.
Definition: fsl_lpi2c.c:816
kSlaveIrqFlags
@ kSlaveIrqFlags
Definition: fsl_lpi2c.c:44
LPI2C_SlaveSend
status_t LPI2C_SlaveSend(LPI2C_Type *base, void *txBuff, size_t txSize, size_t *actualTxSize)
Performs a polling send transfer on the I2C bus.
Definition: fsl_lpi2c.c:1649
EnableIRQ
static status_t EnableIRQ(IRQn_Type interrupt)
Enable specific interrupt.
Definition: fsl_common.h:484
LPI2C_MasterDisableInterrupts
static void LPI2C_MasterDisableInterrupts(LPI2C_Type *base, uint32_t interruptMask)
Disables the LPI2C master interrupt requests.
Definition: fsl_lpi2c.h:585
LPI2C_MCR_MEN_SHIFT
#define LPI2C_MCR_MEN_SHIFT
Definition: MIMXRT1052.h:25184
LPI2C_SCR_SEN
#define LPI2C_SCR_SEN(x)
Definition: MIMXRT1052.h:25660
_lpi2c_master_handle::state
uint8_t state
Definition: fsl_lpi2c.h:238
kLPI2C_SlaveTransmitEvent
@ kLPI2C_SlaveTransmitEvent
Definition: fsl_lpi2c.h:346
LPI2C_SlaveTransferGetCount
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.
Definition: fsl_lpi2c.c:1927
_lpi2c_slave_config::enableReceivedAddressRead
bool enableReceivedAddressRead
Definition: fsl_lpi2c.h:326
s_lpi2cSlaveIsr
static lpi2c_slave_isr_t s_lpi2cSlaveIsr
Pointer to slave IRQ handler for each instance.
Definition: fsl_lpi2c.c:139
CLOCK_DisableClock
static void CLOCK_DisableClock(clock_ip_name_t name)
Disable the clock for specific IP.
Definition: fsl_clock.h:1069
LPI2C_MTDR_DATA
#define LPI2C_MTDR_DATA(x)
Definition: MIMXRT1052.h:25620
kLPI2C_SlaveTxReadyFlag
@ kLPI2C_SlaveTxReadyFlag
Definition: fsl_lpi2c.h:270
_lpi2c_master_config::enable
bool enable
Definition: fsl_lpi2c.h:151
LPI2C_MCFGR1_IGNACK_MASK
#define LPI2C_MCFGR1_IGNACK_MASK
Definition: MIMXRT1052.h:25454
LPI2C_MasterConfigureDataMatch
void LPI2C_MasterConfigureDataMatch(LPI2C_Type *base, const lpi2c_data_match_config_t *config)
Configures LPI2C master data match feature.
Definition: fsl_lpi2c.c:502
fsl_lpi2c.h
LPI2C_MasterStop
status_t LPI2C_MasterStop(LPI2C_Type *base)
Sends a STOP signal on the I2C bus.
Definition: fsl_lpi2c.c:675
_lpi2c_slave_transfer::completionStatus
status_t completionStatus
Definition: fsl_lpi2c.h:366
kSendCommandState
@ kSendCommandState
Definition: fsl_lpi2c.c:76
LPI2C_MCFGR2_FILTSDA_MASK
#define LPI2C_MCFGR2_FILTSDA_MASK
Definition: MIMXRT1052.h:25508
LPI2C_MCFGR0_HREN
#define LPI2C_MCFGR0_HREN(x)
Definition: MIMXRT1052.h:25401
LPI2C_Type::MCFGR3
__IO uint32_t MCFGR3
Definition: MIMXRT1052.h:25105
_lpi2c_master_handle::commandBuffer
uint16_t commandBuffer[7]
Definition: fsl_lpi2c.h:241
_lpi2c_master_config::enableDoze
bool enableDoze
Definition: fsl_lpi2c.h:140
LPI2C_SASR_RADDR_MASK
#define LPI2C_SASR_RADDR_MASK
Definition: MIMXRT1052.h:26042
LPI2C_MasterTransferAbort
void LPI2C_MasterTransferAbort(LPI2C_Type *base, lpi2c_master_handle_t *handle)
Terminates a non-blocking LPI2C master transmission early.
Definition: fsl_lpi2c.c:1383
LPI2C_SCFGR2_FILTSDA_SHIFT
#define LPI2C_SCFGR2_FILTSDA_SHIFT
Definition: MIMXRT1052.h:26020
lpi2c_slave_isr_t
void(* lpi2c_slave_isr_t)(LPI2C_Type *base, lpi2c_slave_handle_t *handle)
Typedef for slave interrupt handler.
Definition: fsl_lpi2c.c:87
LPI2C_CommonIRQHandler
static void LPI2C_CommonIRQHandler(LPI2C_Type *base, uint32_t instance)
Shared IRQ handler that can call both master and slave ISRs.
Definition: fsl_lpi2c.c:2138
kLPI2C_TransferNoStopFlag
@ kLPI2C_TransferNoStopFlag
Definition: fsl_lpi2c.h:212
_lpi2c_slave_transfer::event
lpi2c_slave_transfer_event_t event
Definition: fsl_lpi2c.h:362
LPI2C_Type::STDR
__O uint32_t STDR
Definition: MIMXRT1052.h:25132
LPI2C_MasterTransferBlocking
status_t LPI2C_MasterTransferBlocking(LPI2C_Type *base, lpi2c_master_transfer_t *transfer)
Performs a master polling transfer on the I2C bus.
Definition: fsl_lpi2c.c:854
config
static sai_transceiver_t config
Definition: imxrt1050/imxrt1050-evkb/source/pv_audio_rec.c:75
LPI2C_MCFGR2_FILTSCL
#define LPI2C_MCFGR2_FILTSCL(x)
Definition: MIMXRT1052.h:25507
kLPI2C_MasterEndOfPacketFlag
@ kLPI2C_MasterEndOfPacketFlag
Definition: fsl_lpi2c.h:80
LPI2C_SlaveDisableInterrupts
static void LPI2C_SlaveDisableInterrupts(LPI2C_Type *base, uint32_t interruptMask)
Disables the LPI2C slave interrupt requests.
Definition: fsl_lpi2c.h:1065
clock_ip_name_t
enum _clock_ip_name clock_ip_name_t
CCM CCGR gate control for each module independently.
LPI2C_SCFGR1_ADRSTALL
#define LPI2C_SCFGR1_ADRSTALL(x)
Definition: MIMXRT1052.h:25921
LPI2C_MCCR0_CLKHI
#define LPI2C_MCCR0_CLKHI(x)
Definition: MIMXRT1052.h:25549
kLpi2cIrqs
static const IRQn_Type kLpi2cIrqs[]
Array to map LPI2C instance number to IRQ number.
Definition: fsl_lpi2c.c:119
LPI2C_MCR_RTF_MASK
#define LPI2C_MCR_RTF_MASK
Definition: MIMXRT1052.h:25211
cmd
string cmd
LPI2C_MasterInit
void LPI2C_MasterInit(LPI2C_Type *base, const lpi2c_master_config_t *masterConfig, uint32_t sourceClock_Hz)
Initializes the LPI2C master peripheral.
Definition: fsl_lpi2c.c:389
kMasterIrqFlags
@ kMasterIrqFlags
Definition: fsl_lpi2c.c:31
_lpi2c_slave_transfer
LPI2C slave transfer structure.
Definition: fsl_lpi2c.h:360
_lpi2c_master_transfer::flags
uint32_t flags
Definition: fsl_lpi2c.h:222
LPI2C_MasterEnable
static void LPI2C_MasterEnable(LPI2C_Type *base, bool enable)
Enables or disables the LPI2C module as master.
Definition: fsl_lpi2c.h:503
_lpi2c_slave_transfer::data
uint8_t * data
Definition: fsl_lpi2c.h:364
LPI2C_SCFGR2_FILTSDA_MASK
#define LPI2C_SCFGR2_FILTSDA_MASK
Definition: MIMXRT1052.h:26019
kSlaveClearFlags
@ kSlaveClearFlags
Definition: fsl_lpi2c.c:40
LPI2C_Type::MRDR
__I uint32_t MRDR
Definition: MIMXRT1052.h:25117
status_t
int32_t status_t
Type used for all status and error return values.
Definition: fsl_common.h:189
_lpi2c_master_transfer::subaddressSize
size_t subaddressSize
Definition: fsl_lpi2c.h:227
LPI2C_MCCR0_SETHOLD
#define LPI2C_MCCR0_SETHOLD(x)
Definition: MIMXRT1052.h:25554
lpi2c_master_transfer_callback_t
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.
Definition: fsl_lpi2c.h:196
LPI2C_MasterGetStatusFlags
static uint32_t LPI2C_MasterGetStatusFlags(LPI2C_Type *base)
Gets the LPI2C master status flags.
Definition: fsl_lpi2c.h:525
kLPI2C_SlaveAddressMatchEvent
@ kLPI2C_SlaveAddressMatchEvent
Definition: fsl_lpi2c.h:345
kStatus_Success
@ kStatus_Success
Definition: fsl_common.h:179
_lpi2c_slave_handle::callback
lpi2c_slave_transfer_callback_t callback
Definition: fsl_lpi2c.h:397
kStopState
@ kStopState
Definition: fsl_lpi2c.c:79
kIssueReadCommandState
@ kIssueReadCommandState
Definition: fsl_lpi2c.c:77
kStatus_LPI2C_PinLowTimeout
@ kStatus_LPI2C_PinLowTimeout
Definition: fsl_lpi2c.h:44
LPI2C_MCCR0_CLKLO
#define LPI2C_MCCR0_CLKLO(x)
Definition: MIMXRT1052.h:25544
LPI2C_SlaveTransferAbort
void LPI2C_SlaveTransferAbort(LPI2C_Type *base, lpi2c_slave_handle_t *handle)
Aborts the slave non-blocking transfers.
Definition: fsl_lpi2c.c:1957
_lpi2c_master_transfer
Non-blocking transfer descriptor structure.
Definition: fsl_lpi2c.h:220
_lpi2c_slave_config::sdaGlitchFilterWidth_ns
uint32_t sdaGlitchFilterWidth_ns
Definition: fsl_lpi2c.h:327
kStatus_LPI2C_Busy
@ kStatus_LPI2C_Busy
Definition: fsl_lpi2c.h:38
_lpi2c_master_config::ignoreAck
bool ignoreAck
Definition: fsl_lpi2c.h:142
LPI2C_SlaveTransferNonBlocking
status_t LPI2C_SlaveTransferNonBlocking(LPI2C_Type *base, lpi2c_slave_handle_t *handle, uint32_t eventMask)
Starts accepting slave transfers.
Definition: fsl_lpi2c.c:1875
kRxDataCmd
@ kRxDataCmd
Definition: fsl_lpi2c.c:56
LPI2C2
#define LPI2C2
Definition: MIMXRT1052.h:26113
LPI2C_MCFGR1_PRESCALE_SHIFT
#define LPI2C_MCFGR1_PRESCALE_SHIFT
Definition: MIMXRT1052.h:25435
LPI2C_SCFGR2_DATAVD_MASK
#define LPI2C_SCFGR2_DATAVD_MASK
Definition: MIMXRT1052.h:26009
lpi2c_master_isr_t
void(* lpi2c_master_isr_t)(LPI2C_Type *base, lpi2c_master_handle_t *handle)
Typedef for master interrupt handler.
Definition: fsl_lpi2c.c:84
LPI2C_SCFGR2_FILTSCL
#define LPI2C_SCFGR2_FILTSCL(x)
Definition: MIMXRT1052.h:26018


picovoice_driver
Author(s):
autogenerated on Fri Apr 1 2022 02:13:56