twihs.c
Go to the documentation of this file.
1 
33 /*
34  * Support and FAQ: visit <a href="https://www.microchip.com/support/">Microchip Support</a>
35  */
36 
37 #include "twihs.h"
38 
40 
41 #ifdef __cplusplus
42 extern "C" {
43 #endif
44 
45 
71 /* Low level time limit of I2C Fast Mode. */
72 #define LOW_LEVEL_TIME_LIMIT 384000
73 #define I2C_FAST_MODE_SPEED 400000
74 #define TWIHS_CLK_DIVIDER 2
75 #define TWIHS_CLK_CALC_ARGU 3
76 #define TWIHS_CLK_DIV_MAX 0xFF
77 #define TWIHS_CLK_DIV_MIN 7
78 
85 {
86  /* Set Master Disable bit and Slave Disable bit */
87  p_twihs->TWIHS_CR = TWIHS_CR_MSDIS;
88  p_twihs->TWIHS_CR = TWIHS_CR_SVDIS;
89 
90  /* Set Master Enable bit */
91  p_twihs->TWIHS_CR = TWIHS_CR_MSEN;
92 }
93 
100 {
101  /* Set Master Disable bit */
102  p_twihs->TWIHS_CR = TWIHS_CR_MSDIS;
103 }
104 
113 uint32_t twihs_master_init(Twihs *p_twihs, const twihs_options_t *p_opt)
114 {
115  uint32_t status = TWIHS_SUCCESS;
116 
117  /* Disable TWIHS interrupts */
118  p_twihs->TWIHS_IDR = ~0UL;
119 
120  /* Dummy read in status register */
121  p_twihs->TWIHS_SR;
122 
123  /* Reset TWIHS peripheral */
124  twihs_reset(p_twihs);
125 
126  twihs_enable_master_mode(p_twihs);
127 
128  /* Select the speed */
129  if (twihs_set_speed(p_twihs, p_opt->speed, p_opt->master_clk) == FAIL) {
130  /* The desired speed setting is rejected */
131  status = TWIHS_INVALID_ARGUMENT;
132  }
133 
134  return status;
135 }
136 
147 uint32_t twihs_set_speed(Twihs *p_twihs, uint32_t ul_speed, uint32_t ul_mck)
148 {
149  uint32_t ckdiv = 0;
150  uint32_t c_lh_div;
151  uint32_t cldiv, chdiv;
152 
153  /* High-Speed can be only used in slave mode, 400k is the max speed allowed for master */
154  if (ul_speed > I2C_FAST_MODE_SPEED) {
155  return FAIL;
156  }
157 
158  /* Low level time not less than 1.3us of I2C Fast Mode. */
159  if (ul_speed > LOW_LEVEL_TIME_LIMIT) {
160  /* Low level of time fixed for 1.3us. */
162  chdiv = ul_mck / ((ul_speed + (ul_speed - LOW_LEVEL_TIME_LIMIT)) * TWIHS_CLK_DIVIDER) - TWIHS_CLK_CALC_ARGU;
163 
164  /* cldiv must fit in 8 bits, ckdiv must fit in 3 bits */
165  while ((cldiv > TWIHS_CLK_DIV_MAX) && (ckdiv < TWIHS_CLK_DIV_MIN)) {
166  /* Increase clock divider */
167  ckdiv++;
168  /* Divide cldiv value */
169  cldiv /= TWIHS_CLK_DIVIDER;
170  }
171  /* chdiv must fit in 8 bits, ckdiv must fit in 3 bits */
172  while ((chdiv > TWIHS_CLK_DIV_MAX) && (ckdiv < TWIHS_CLK_DIV_MIN)) {
173  /* Increase clock divider */
174  ckdiv++;
175  /* Divide cldiv value */
176  chdiv /= TWIHS_CLK_DIVIDER;
177  }
178 
179  /* set clock waveform generator register */
180  p_twihs->TWIHS_CWGR =
181  TWIHS_CWGR_CLDIV(cldiv) | TWIHS_CWGR_CHDIV(chdiv) |
182  TWIHS_CWGR_CKDIV(ckdiv);
183  } else {
184  c_lh_div = ul_mck / (ul_speed * TWIHS_CLK_DIVIDER) - TWIHS_CLK_CALC_ARGU;
185 
186  /* cldiv must fit in 8 bits, ckdiv must fit in 3 bits */
187  while ((c_lh_div > TWIHS_CLK_DIV_MAX) && (ckdiv < TWIHS_CLK_DIV_MIN)) {
188  /* Increase clock divider */
189  ckdiv++;
190  /* Divide cldiv value */
191  c_lh_div /= TWIHS_CLK_DIVIDER;
192  }
193 
194  /* set clock waveform generator register */
195  p_twihs->TWIHS_CWGR =
196  TWIHS_CWGR_CLDIV(c_lh_div) | TWIHS_CWGR_CHDIV(c_lh_div) |
197  TWIHS_CWGR_CKDIV(ckdiv);
198  }
199 
200  return PASS;
201 }
202 
211 uint32_t twihs_probe(Twihs *p_twihs, uint8_t uc_slave_addr)
212 {
213  twihs_packet_t packet;
214  uint8_t data = 0;
215 
216  /* Data to send */
217  packet.buffer = &data;
218  /* Data length */
219  packet.length = 1;
220  /* Slave chip address */
221  packet.chip = (uint32_t) uc_slave_addr;
222  /* Internal chip address */
223  packet.addr[0] = 0;
224  /* Address length */
225  packet.addr_length = 0;
226 
227  /* Perform a master write access */
228  return (twihs_master_write(p_twihs, &packet));
229 }
230 
231 
241 static uint32_t twihs_mk_addr(const uint8_t *addr, int len)
242 {
243  uint32_t val;
244 
245  if (len == 0)
246  return 0;
247 
248  val = addr[0];
249  if (len > 1) {
250  val <<= 8;
251  val |= addr[1];
252  }
253  if (len > 2) {
254  val <<= 8;
255  val |= addr[2];
256  }
257  return val;
258 }
259 
270 uint32_t twihs_master_read(Twihs *p_twihs, twihs_packet_t *p_packet)
271 {
272  uint32_t status, cnt = p_packet->length;
273  uint8_t *buffer = p_packet->buffer;
274  uint32_t timeout = TWIHS_TIMEOUT;
275 
276  /* Check argument */
277  if (cnt == 0) {
278  return TWIHS_INVALID_ARGUMENT;
279  }
280 
281  /* Set read mode, slave address and 3 internal address byte lengths */
282  p_twihs->TWIHS_MMR = 0;
283  p_twihs->TWIHS_MMR = TWIHS_MMR_MREAD | TWIHS_MMR_DADR(p_packet->chip) |
284  ((p_packet->addr_length << TWIHS_MMR_IADRSZ_Pos) &
286 
287  /* Set internal address for remote chip */
288  p_twihs->TWIHS_IADR = 0;
289  p_twihs->TWIHS_IADR = twihs_mk_addr(p_packet->addr, p_packet->addr_length);
290 
291  /* Send a START Condition */
292  p_twihs->TWIHS_CR = TWIHS_CR_START;
293 
294  while (cnt > 0) {
295  status = p_twihs->TWIHS_SR;
296  if (status & TWIHS_SR_NACK) {
297  return TWIHS_RECEIVE_NACK;
298  }
299  if (!timeout--) {
300  return TWIHS_ERROR_TIMEOUT;
301  }
302  /* Last byte ? */
303  if (cnt == 1) {
304  p_twihs->TWIHS_CR = TWIHS_CR_STOP;
305  }
306 
307  if (!(status & TWIHS_SR_RXRDY)) {
308  continue;
309  }
310  *buffer++ = p_twihs->TWIHS_RHR;
311 
312  cnt--;
313  timeout = TWIHS_TIMEOUT;
314  }
315 
316  while (!(p_twihs->TWIHS_SR & TWIHS_SR_TXCOMP)) {
317  }
318 
319  p_twihs->TWIHS_SR;
320 
321  return TWIHS_SUCCESS;
322 }
323 
334 uint32_t twihs_master_write(Twihs *p_twihs, twihs_packet_t *p_packet)
335 {
336  uint32_t status, cnt = p_packet->length;
337  uint8_t *buffer = p_packet->buffer;
338 
339  /* Check argument */
340  if (cnt == 0) {
341  return TWIHS_INVALID_ARGUMENT;
342  }
343 
344  /* Set write mode, slave address and 3 internal address byte lengths */
345  p_twihs->TWIHS_MMR = 0;
346  p_twihs->TWIHS_MMR = TWIHS_MMR_DADR(p_packet->chip) |
347  ((p_packet->addr_length << TWIHS_MMR_IADRSZ_Pos) &
349 
350  /* Set internal address for remote chip */
351  p_twihs->TWIHS_IADR = 0;
352  p_twihs->TWIHS_IADR = twihs_mk_addr(p_packet->addr, p_packet->addr_length);
353 
354  /* Send all bytes */
355  while (cnt > 0) {
356  status = p_twihs->TWIHS_SR;
357  if (status & TWIHS_SR_NACK) {
358  return TWIHS_RECEIVE_NACK;
359  }
360 
361  if (!(status & TWIHS_SR_TXRDY)) {
362  continue;
363  }
364  p_twihs->TWIHS_THR = *buffer++;
365 
366  cnt--;
367  }
368 
369  while (1) {
370  status = p_twihs->TWIHS_SR;
371  if (status & TWIHS_SR_NACK) {
372  return TWIHS_RECEIVE_NACK;
373  }
374 
375  if (status & TWIHS_SR_TXRDY) {
376  break;
377  }
378  }
379 
380  p_twihs->TWIHS_CR = TWIHS_CR_STOP;
381 
382  while (!(p_twihs->TWIHS_SR & TWIHS_SR_TXCOMP)) {
383  }
384 
385  return TWIHS_SUCCESS;
386 }
387 
394 void twihs_enable_interrupt(Twihs *p_twihs, uint32_t ul_sources)
395 {
396  /* Enable the specified interrupts */
397  p_twihs->TWIHS_IER = ul_sources;
398 }
399 
406 void twihs_disable_interrupt(Twihs *p_twihs, uint32_t ul_sources)
407 {
408  /* Disable the specified interrupts */
409  p_twihs->TWIHS_IDR = ul_sources;
410  /* Dummy read */
411  p_twihs->TWIHS_SR;
412 }
413 
422 {
423  return p_twihs->TWIHS_SR;
424 }
425 
433 uint32_t twihs_get_interrupt_mask(Twihs *p_twihs)
434 {
435  return p_twihs->TWIHS_IMR;
436 }
437 
445 uint8_t twihs_read_byte(Twihs *p_twihs)
446 {
447  return p_twihs->TWIHS_RHR;
448 }
449 
456 void twihs_write_byte(Twihs *p_twihs, uint8_t uc_byte)
457 {
458  p_twihs->TWIHS_THR = uc_byte;
459 }
460 
467 {
468  /* Set Master Disable bit and Slave Disable bit */
469  p_twihs->TWIHS_CR = TWIHS_CR_MSDIS;
470  p_twihs->TWIHS_CR = TWIHS_CR_SVDIS;
471 
472  /* Set Slave Enable bit */
473  p_twihs->TWIHS_CR = TWIHS_CR_SVEN;
474 }
475 
482 {
483  /* Set Slave Disable bit */
484  p_twihs->TWIHS_CR = TWIHS_CR_SVDIS;
485 }
486 
493 void twihs_slave_init(Twihs *p_twihs, uint32_t ul_device_addr)
494 {
495  /* Disable TWIHS interrupts */
496  p_twihs->TWIHS_IDR = ~0UL;
497  p_twihs->TWIHS_SR;
498 
499  /* Reset TWIHS */
500  twihs_reset(p_twihs);
501 
502  /* Set slave address in slave mode */
503  p_twihs->TWIHS_SMR = TWIHS_SMR_SADR(ul_device_addr);
504 
505  /* Enable slave mode */
506  twihs_enable_slave_mode(p_twihs);
507 }
508 
515 void twihs_set_slave_addr(Twihs *p_twihs, uint32_t ul_device_addr)
516 {
517  /* Set slave address */
518  p_twihs->TWIHS_SMR = TWIHS_SMR_SADR(ul_device_addr);
519 }
520 
531 uint32_t twihs_slave_read(Twihs *p_twihs, uint8_t *p_data)
532 {
533  uint32_t status, cnt = 0;
534 
535  do {
536  status = p_twihs->TWIHS_SR;
537  if (status & TWIHS_SR_SVACC) {
538  if (!(status & (TWIHS_SR_GACC | TWIHS_SR_SVREAD)) &&
539  (status & TWIHS_SR_RXRDY)) {
540  *p_data++ = (uint8_t) p_twihs->TWIHS_RHR;
541  cnt++;
542  }
543  } else if ((status & (TWIHS_SR_EOSACC | TWIHS_SR_TXCOMP))
545  break;
546  }
547  } while (1);
548 
549  return cnt;
550 }
551 
562 uint32_t twihs_slave_write(Twihs *p_twihs, uint8_t *p_data)
563 {
564  uint32_t status, cnt = 0;
565 
566  do {
567  status = p_twihs->TWIHS_SR;
568  if (status & TWIHS_SR_SVACC) {
569  if (!(status & (TWIHS_SR_GACC | TWIHS_SR_NACK)) &&
570  ((status & (TWIHS_SR_SVREAD | TWIHS_SR_TXRDY))
572  p_twihs->TWIHS_THR = *p_data++;
573  cnt++;
574  }
575  } else if ((status & (TWIHS_SR_EOSACC | TWIHS_SR_TXCOMP))
577  break;
578  }
579  } while (1);
580 
581  return cnt;
582 }
583 
589 void twihs_reset(Twihs *p_twihs)
590 {
591  /* Set SWRST bit to reset TWIHS peripheral */
592  p_twihs->TWIHS_CR = TWIHS_CR_SWRST;
593  p_twihs->TWIHS_RHR;
594 }
595 
596 #if !(SAMV70 || SAMV71 || SAME70 || SAMS70)
597 
604 Pdc *twihs_get_pdc_base(Twihs *p_twihs)
605 {
606  Pdc *p_pdc_base = NULL;
607 
608  if (p_twihs == TWI0) {
609  p_pdc_base = PDC_TWI0;
610  } else {
611  Assert(false);
612  }
613 
614  return p_pdc_base;
615 }
616 #endif
617 
624 void twihs_set_write_protection(Twihs *p_twihs, bool flag)
625 {
626  if (flag) {
628  } else {
630  }
631 }
632 
639 void twihs_read_write_protection_status(Twihs *p_twihs, uint32_t *p_status)
640 {
641  *p_status = p_twihs->TWIHS_WPSR;
642 }
643 
650 void twihs_smbus_set_timing(Twihs *p_twihs, uint32_t ul_timing)
651 {
652  p_twihs->TWIHS_SMBTR = ul_timing;;
653 }
654 
655 #if !(SAMV70 || SAMV71 || SAME70 || SAMS70)
656 
662 void twihs_set_alternative_command(Twihs *p_twihs, uint32_t ul_alt_cmd)
663 {
664  p_twihs->TWIHS_ACR = ul_alt_cmd;;
665 }
666 #endif
667 
674 void twihs_set_filter(Twihs *p_twihs, uint32_t ul_filter)
675 {
676  p_twihs->TWIHS_FILTR = ul_filter;;
677 }
678 
686 void twihs_mask_slave_addr(Twihs *p_twihs, uint32_t ul_mask)
687 {
688  p_twihs->TWIHS_SMR |= TWIHS_SMR_MASK(ul_mask);
689 }
690 
691 #if (SAMG53 || SAMG54 || SAMV70 || SAMV71 || SAME70 || SAMS70)
692 
705 void twihs_set_sleepwalking(Twihs *p_twihs,
706  uint32_t ul_matching_addr1, bool flag1,
707  uint32_t ul_matching_addr2, bool flag2,
708  uint32_t ul_matching_addr3, bool flag3,
709  uint32_t ul_matching_data, bool flag)
710 {
711  uint32_t temp = 0;
712 
713  if (flag1) {
714  temp |= TWIHS_SWMR_SADR1(ul_matching_addr1);
715  }
716 
717  if (flag2) {
718  temp |= TWIHS_SWMR_SADR2(ul_matching_addr2);
719  }
720 
721  if (flag3) {
722  temp |= TWIHS_SWMR_SADR3(ul_matching_addr3);
723  }
724 
725  if (flag) {
726  temp |= TWIHS_SWMR_DATAM(ul_matching_data);
727  }
728 
729  p_twihs->TWIHS_SWMR = temp;
730 }
731 #endif
732 
733 
735 
736 #ifdef __cplusplus
737 }
738 #endif
739 
740 
#define TWIHS_SR_TXRDY
(TWIHS_SR) Transmit Holding Register Ready (cleared by writing TWIHS_THR)
void * buffer
Where to find the data to be transferred.
#define I2C_FAST_MODE_SPEED
Definition: twihs.c:73
__IO uint32_t TWIHS_SMBTR
(Twihs Offset: 0x38) SMBus Timing Register
void twihs_write_byte(Twihs *p_twihs, uint8_t uc_byte)
Sends a byte of data to one of the TWIHS slaves on the bus.
Definition: twihs.c:456
#define TWIHS_CR_MSDIS
(TWIHS_CR) TWIHS Master Mode Disabled
__I uint32_t TWIHS_SR
(Twihs Offset: 0x20) Status Register
#define TWIHS_CR_STOP
(TWIHS_CR) Send a STOP Condition
uint8_t twihs_read_byte(Twihs *p_twihs)
Reads a byte from the TWIHS bus.
Definition: twihs.c:445
void twihs_set_filter(Twihs *p_twihs, uint32_t ul_filter)
Set the filter for TWIHS.
Definition: twihs.c:674
__I uint32_t TWIHS_RHR
(Twihs Offset: 0x30) Receive Holding Register
void twihs_read_write_protection_status(Twihs *p_twihs, uint32_t *p_status)
Read the write protection status.
Definition: twihs.c:639
__I uint32_t TWIHS_IMR
(Twihs Offset: 0x2C) Interrupt Mask Register
Information concerning the data transmission.
__O uint32_t TWIHS_IER
(Twihs Offset: 0x24) Interrupt Enable Register
#define FAIL
Definition: compiler.h:429
void twihs_slave_init(Twihs *p_twihs, uint32_t ul_device_addr)
Initialize TWIHS slave mode.
Definition: twihs.c:493
void twihs_set_write_protection(Twihs *p_twihs, bool flag)
Enables/Disables write protection mode.
Definition: twihs.c:624
static uint32_t twihs_mk_addr(const uint8_t *addr, int len)
Definition: twihs.c:241
uint32_t master_clk
MCK for TWIHS.
void twihs_set_slave_addr(Twihs *p_twihs, uint32_t ul_device_addr)
Set TWIHS slave address.
Definition: twihs.c:515
uint32_t addr_length
Length of the TWIHS data address segment (1-3 bytes).
#define TWIHS_TIMEOUT
__O uint32_t TWIHS_CR
(Twihs Offset: 0x00) Control Register
__IO uint32_t TWIHS_CWGR
(Twihs Offset: 0x10) Clock Waveform Generator Register
#define TWIHS_SWMR_SADR1(value)
#define TWIHS_WPMR_WPKEY_PASSWD
(TWIHS_WPMR) Writing any other value in this field aborts the write operation of the WPEN bit...
#define TWIHS_CWGR_CLDIV(value)
#define NULL
Definition: nm_bsp.h:52
__IO uint32_t TWIHS_SWMR
(Twihs Offset: 0x4C) SleepWalking Matching Register
#define TWIHS_SR_NACK
(TWIHS_SR) Not Acknowledged (cleared on read)
#define TWIHS_MMR_IADRSZ_Msk
(TWIHS_MMR) Internal Device Address Size
uint32_t twihs_probe(Twihs *p_twihs, uint8_t uc_slave_addr)
Test if a chip answers a given I2C address.
Definition: twihs.c:211
uint32_t twihs_set_speed(Twihs *p_twihs, uint32_t ul_speed, uint32_t ul_mck)
Set the I2C bus speed in conjunction with the clock frequency.
Definition: twihs.c:147
uint32_t twihs_master_init(Twihs *p_twihs, const twihs_options_t *p_opt)
Initialize TWIHS master mode.
Definition: twihs.c:113
#define TWIHS_SR_TXCOMP
(TWIHS_SR) Transmission Completed (cleared by writing TWIHS_THR)
__IO uint32_t TWIHS_SMR
(Twihs Offset: 0x08) Slave Mode Register
#define TWIHS_CR_SVDIS
(TWIHS_CR) TWIHS Slave Mode Disabled
#define TWIHS_WPMR_WPEN
(TWIHS_WPMR) Write Protection Enable
void twihs_enable_interrupt(Twihs *p_twihs, uint32_t ul_sources)
Enable TWIHS interrupts.
Definition: twihs.c:394
uint32_t twihs_get_interrupt_mask(Twihs *p_twihs)
Read TWIHS interrupt mask.
Definition: twihs.c:433
#define TWIHS_CR_START
(TWIHS_CR) Send a START Condition
__O uint32_t TWIHS_THR
(Twihs Offset: 0x34) Transmit Holding Register
#define TWIHS_CR_SWRST
(TWIHS_CR) Software Reset
#define TWIHS_SR_EOSACC
(TWIHS_SR) End Of Slave Access (cleared on read)
void twihs_reset(Twihs *p_twihs)
Reset TWIHS.
Definition: twihs.c:589
uint32_t twihs_get_interrupt_status(Twihs *p_twihs)
Get TWIHS interrupt status.
Definition: twihs.c:421
#define TWIHS_SR_GACC
(TWIHS_SR) General Call Access (cleared on read)
#define LOW_LEVEL_TIME_LIMIT
Definition: twihs.c:72
#define TWIHS_SR_SVREAD
(TWIHS_SR) Slave Read
#define TWIHS_RECEIVE_NACK
Two-Wire Interface High Speed (TWIHS) driver for SAM.
__IO uint32_t TWIHS_MMR
(Twihs Offset: 0x04) Master Mode Register
__I uint32_t TWIHS_WPSR
(Twihs Offset: 0xE8) Write Protection Status Register
uint32_t twihs_slave_read(Twihs *p_twihs, uint8_t *p_data)
Read data from master.
Definition: twihs.c:531
#define TWIHS_CWGR_CHDIV(value)
__IO uint32_t TWIHS_WPMR
(Twihs Offset: 0xE4) Write Protection Mode Register
#define TWIHS_ERROR_TIMEOUT
#define TWIHS_CLK_DIV_MIN
Definition: twihs.c:77
#define TWIHS_CR_MSEN
(TWIHS_CR) TWIHS Master Mode Enabled
#define TWIHS_SWMR_DATAM(value)
Twihs hardware registers.
USBInterfaceDescriptor data
#define PASS
Definition: compiler.h:428
uint32_t length
How many bytes do we want to transfer.
#define TWIHS_SWMR_SADR3(value)
__IO uint32_t TWIHS_IADR
(Twihs Offset: 0x0C) Internal Address Register
#define TWIHS_SWMR_SADR2(value)
void twihs_smbus_set_timing(Twihs *p_twihs, uint32_t ul_timing)
Set the prescaler, TLOW:SEXT, TLOW:MEXT and clock high max cycles for SMBUS mode. ...
Definition: twihs.c:650
#define TWIHS_INVALID_ARGUMENT
uint32_t twihs_master_read(Twihs *p_twihs, twihs_packet_t *p_packet)
Read multiple bytes from a TWIHS compatible slave device.
Definition: twihs.c:270
__O uint32_t TWIHS_IDR
(Twihs Offset: 0x28) Interrupt Disable Register
uint32_t twihs_slave_write(Twihs *p_twihs, uint8_t *p_data)
Write data to TWIHS bus.
Definition: twihs.c:562
void twihs_set_alternative_command(Twihs *p_twihs, uint32_t ul_alt_cmd)
Set length/direction/PEC for alternative command mode.
Definition: twihs.c:662
uint8_t chip
TWIHS chip address to communicate with.
void twihs_disable_slave_mode(Twihs *p_twihs)
Disable TWIHS slave mode.
Definition: twihs.c:481
#define TWIHS_CR_SVEN
(TWIHS_CR) TWIHS Slave Mode Enabled
#define TWIHS_CLK_CALC_ARGU
Definition: twihs.c:75
uint32_t speed
The baud rate of the TWIHS bus.
void twihs_disable_interrupt(Twihs *p_twihs, uint32_t ul_sources)
Disable TWIHS interrupts.
Definition: twihs.c:406
__IO uint32_t TWIHS_FILTR
(Twihs Offset: 0x44) Filter Register
void twihs_enable_slave_mode(Twihs *p_twihs)
Enable TWIHS slave mode.
Definition: twihs.c:466
#define TWIHS_SR_RXRDY
(TWIHS_SR) Receive Holding Register Ready (cleared by reading TWIHS_RHR)
Input parameters when initializing the TWIHS module mode.
#define TWIHS_MMR_MREAD
(TWIHS_MMR) Master Read Direction
uint32_t twihs_master_write(Twihs *p_twihs, twihs_packet_t *p_packet)
Write multiple bytes to a TWIHS compatible slave device.
Definition: twihs.c:334
Pdc * twihs_get_pdc_base(Twihs *p_twihs)
Get TWIHS PDC base address.
Definition: twihs.c:604
#define TWIHS_SUCCESS
Return codes for TWIHS APIs.
#define Assert(expr)
This macro is used to test fatal errors.
Definition: compiler.h:196
uint8_t addr[3]
TWIHS address/commands to issue to the other chip (node).
#define TWIHS_CWGR_CKDIV(value)
#define TWIHS_SR_SVACC
(TWIHS_SR) Slave Access
void twihs_disable_master_mode(Twihs *p_twihs)
Disable TWIHS master mode.
Definition: twihs.c:99
#define TWIHS_CLK_DIV_MAX
Definition: twihs.c:76
#define TWIHS_CLK_DIVIDER
Definition: twihs.c:74
void twihs_enable_master_mode(Twihs *p_twihs)
Enable TWIHS master mode.
Definition: twihs.c:84
void twihs_mask_slave_addr(Twihs *p_twihs, uint32_t ul_mask)
A mask can be applied on the slave device address in slave mode in order to allow multiple address an...
Definition: twihs.c:686


inertial_sense_ros
Author(s):
autogenerated on Sun Feb 28 2021 03:17:58