twi.c
Go to the documentation of this file.
1 /*
2  twi.c - TWI/I2C library for Wiring & Arduino
3  Copyright (c) 2006 Nicholas Zambetti. All right reserved.
4 
5  This library is free software; you can redistribute it and/or
6  modify it under the terms of the GNU Lesser General Public
7  License as published by the Free Software Foundation; either
8  version 2.1 of the License, or (at your option) any later version.
9 
10  This library is distributed in the hope that it will be useful,
11  but WITHOUT ANY WARRANTY; without even the implied warranty of
12  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
13  Lesser General Public License for more details.
14 
15  You should have received a copy of the GNU Lesser General Public
16  License along with this library; if not, write to the Free Software
17  Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
18 
19  Modified 2012 by Todd Krein (todd@krein.org) to implement repeated starts
20 */
21 
22 #include <math.h>
23 #include <stdlib.h>
24 #include <inttypes.h>
25 #include <avr/io.h>
26 #include <avr/interrupt.h>
27 #include <compat/twi.h>
28 #include "Arduino.h" // for digitalWrite
29 
30 #ifndef cbi
31 #define cbi(sfr, bit) (_SFR_BYTE(sfr) &= ~_BV(bit))
32 #endif
33 
34 #ifndef sbi
35 #define sbi(sfr, bit) (_SFR_BYTE(sfr) |= _BV(bit))
36 #endif
37 
38 #include "pins_arduino.h"
39 #include "twi.h"
40 
41 static volatile uint8_t twi_state;
42 static volatile uint8_t twi_slarw;
43 static volatile uint8_t twi_sendStop; // should the transaction end with a stop
44 static volatile uint8_t twi_inRepStart; // in the middle of a repeated start
45 
47 static void (*twi_onSlaveReceive)(uint8_t*, int);
48 
50 static volatile uint8_t twi_masterBufferIndex;
51 static volatile uint8_t twi_masterBufferLength;
52 
54 static volatile uint8_t twi_txBufferIndex;
55 static volatile uint8_t twi_txBufferLength;
56 
58 static volatile uint8_t twi_rxBufferIndex;
59 
60 static volatile uint8_t twi_error;
61 
62 /*
63  * Function twi_init
64  * Desc readys twi pins and sets twi bitrate
65  * Input none
66  * Output none
67  */
68 void twi_init(void)
69 {
70  // initialize state
72  twi_sendStop = true; // default value
73  twi_inRepStart = false;
74 
75  // activate internal pullups for twi.
76  digitalWrite(SDA, 1);
77  digitalWrite(SCL, 1);
78 
79  // initialize twi prescaler and bit rate
80  cbi(TWSR, TWPS0);
81  cbi(TWSR, TWPS1);
82  TWBR = ((F_CPU / TWI_FREQ) - 16) / 2;
83 
84  /* twi bit rate formula from atmega128 manual pg 204
85  SCL Frequency = CPU Clock Frequency / (16 + (2 * TWBR))
86  note: TWBR should be 10 or higher for master mode
87  It is 72 for a 16mhz Wiring board with 100kHz TWI */
88 
89  // enable twi module, acks, and twi interrupt
90  TWCR = _BV(TWEN) | _BV(TWIE) | _BV(TWEA);
91 }
92 
93 /*
94  * Function twi_disable
95  * Desc disables twi pins
96  * Input none
97  * Output none
98  */
99 void twi_disable(void)
100 {
101  // disable twi module, acks, and twi interrupt
102  TWCR &= ~(_BV(TWEN) | _BV(TWIE) | _BV(TWEA));
103 
104  // deactivate internal pullups for twi.
105  digitalWrite(SDA, 0);
106  digitalWrite(SCL, 0);
107 }
108 
109 /*
110  * Function twi_slaveInit
111  * Desc sets slave address and enables interrupt
112  * Input none
113  * Output none
114  */
115 void twi_setAddress(uint8_t address)
116 {
117  // set twi slave address (skip over TWGCE bit)
118  TWAR = address << 1;
119 }
120 
121 /*
122  * Function twi_setClock
123  * Desc sets twi bit rate
124  * Input Clock Frequency
125  * Output none
126  */
127 void twi_setFrequency(uint32_t frequency)
128 {
129  TWBR = ((F_CPU / frequency) - 16) / 2;
130 
131  /* twi bit rate formula from atmega128 manual pg 204
132  SCL Frequency = CPU Clock Frequency / (16 + (2 * TWBR))
133  note: TWBR should be 10 or higher for master mode
134  It is 72 for a 16mhz Wiring board with 100kHz TWI */
135 }
136 
137 /*
138  * Function twi_readFrom
139  * Desc attempts to become twi bus master and read a
140  * series of bytes from a device on the bus
141  * Input address: 7bit i2c device address
142  * data: pointer to byte array
143  * length: number of bytes to read into array
144  * sendStop: Boolean indicating whether to send a stop at the end
145  * Output number of bytes read
146  */
147 uint8_t twi_readFrom(uint8_t address, uint8_t* data, uint8_t length, uint8_t sendStop)
148 {
149  uint8_t i;
150 
151  // ensure data will fit into buffer
152  if(TWI_BUFFER_LENGTH < length){
153  return 0;
154  }
155 
156  // wait until twi is ready, become master receiver
157  while(TWI_READY != twi_state){
158  continue;
159  }
160  twi_state = TWI_MRX;
161  twi_sendStop = sendStop;
162  // reset error state (0xFF.. no error occured)
163  twi_error = 0xFF;
164 
165  // initialize buffer iteration vars
167  twi_masterBufferLength = length-1; // This is not intuitive, read on...
168  // On receive, the previously configured ACK/NACK setting is transmitted in
169  // response to the received byte before the interrupt is signalled.
170  // Therefor we must actually set NACK when the _next_ to last byte is
171  // received, causing that NACK to be sent in response to receiving the last
172  // expected byte of data.
173 
174  // build sla+w, slave device address + w bit
175  twi_slarw = TW_READ;
176  twi_slarw |= address << 1;
177 
178  if (true == twi_inRepStart) {
179  // if we're in the repeated start state, then we've already sent the start,
180  // (@@@ we hope), and the TWI statemachine is just waiting for the address byte.
181  // We need to remove ourselves from the repeated start state before we enable interrupts,
182  // since the ISR is ASYNC, and we could get confused if we hit the ISR before cleaning
183  // up. Also, don't enable the START interrupt. There may be one pending from the
184  // repeated start that we sent ourselves, and that would really confuse things.
185  twi_inRepStart = false; // remember, we're dealing with an ASYNC ISR
186  do {
187  TWDR = twi_slarw;
188  } while(TWCR & _BV(TWWC));
189  TWCR = _BV(TWINT) | _BV(TWEA) | _BV(TWEN) | _BV(TWIE); // enable INTs, but not START
190  }
191  else
192  // send start condition
193  TWCR = _BV(TWEN) | _BV(TWIE) | _BV(TWEA) | _BV(TWINT) | _BV(TWSTA);
194 
195  // wait for read operation to complete
196  while(TWI_MRX == twi_state){
197  continue;
198  }
199 
200  if (twi_masterBufferIndex < length)
201  length = twi_masterBufferIndex;
202 
203  // copy twi buffer to data
204  for(i = 0; i < length; ++i){
205  data[i] = twi_masterBuffer[i];
206  }
207 
208  return length;
209 }
210 
211 /*
212  * Function twi_writeTo
213  * Desc attempts to become twi bus master and write a
214  * series of bytes to a device on the bus
215  * Input address: 7bit i2c device address
216  * data: pointer to byte array
217  * length: number of bytes in array
218  * wait: boolean indicating to wait for write or not
219  * sendStop: boolean indicating whether or not to send a stop at the end
220  * Output 0 .. success
221  * 1 .. length to long for buffer
222  * 2 .. address send, NACK received
223  * 3 .. data send, NACK received
224  * 4 .. other twi error (lost bus arbitration, bus error, ..)
225  */
226 uint8_t twi_writeTo(uint8_t address, uint8_t* data, uint8_t length, uint8_t wait, uint8_t sendStop)
227 {
228  uint8_t i;
229 
230  // ensure data will fit into buffer
231  if(TWI_BUFFER_LENGTH < length){
232  return 1;
233  }
234 
235  // wait until twi is ready, become master transmitter
236  while(TWI_READY != twi_state){
237  continue;
238  }
239  twi_state = TWI_MTX;
240  twi_sendStop = sendStop;
241  // reset error state (0xFF.. no error occured)
242  twi_error = 0xFF;
243 
244  // initialize buffer iteration vars
246  twi_masterBufferLength = length;
247 
248  // copy data to twi buffer
249  for(i = 0; i < length; ++i){
250  twi_masterBuffer[i] = data[i];
251  }
252 
253  // build sla+w, slave device address + w bit
254  twi_slarw = TW_WRITE;
255  twi_slarw |= address << 1;
256 
257  // if we're in a repeated start, then we've already sent the START
258  // in the ISR. Don't do it again.
259  //
260  if (true == twi_inRepStart) {
261  // if we're in the repeated start state, then we've already sent the start,
262  // (@@@ we hope), and the TWI statemachine is just waiting for the address byte.
263  // We need to remove ourselves from the repeated start state before we enable interrupts,
264  // since the ISR is ASYNC, and we could get confused if we hit the ISR before cleaning
265  // up. Also, don't enable the START interrupt. There may be one pending from the
266  // repeated start that we sent outselves, and that would really confuse things.
267  twi_inRepStart = false; // remember, we're dealing with an ASYNC ISR
268  do {
269  TWDR = twi_slarw;
270  } while(TWCR & _BV(TWWC));
271  TWCR = _BV(TWINT) | _BV(TWEA) | _BV(TWEN) | _BV(TWIE); // enable INTs, but not START
272  }
273  else
274  // send start condition
275  TWCR = _BV(TWINT) | _BV(TWEA) | _BV(TWEN) | _BV(TWIE) | _BV(TWSTA); // enable INTs
276 
277  // wait for write operation to complete
278  while(wait && (TWI_MTX == twi_state)){
279  continue;
280  }
281 
282  if (twi_error == 0xFF)
283  return 0; // success
284  else if (twi_error == TW_MT_SLA_NACK)
285  return 2; // error: address send, nack received
286  else if (twi_error == TW_MT_DATA_NACK)
287  return 3; // error: data send, nack received
288  else
289  return 4; // other twi error
290 }
291 
292 /*
293  * Function twi_transmit
294  * Desc fills slave tx buffer with data
295  * must be called in slave tx event callback
296  * Input data: pointer to byte array
297  * length: number of bytes in array
298  * Output 1 length too long for buffer
299  * 2 not slave transmitter
300  * 0 ok
301  */
302 uint8_t twi_transmit(const uint8_t* data, uint8_t length)
303 {
304  uint8_t i;
305 
306  // ensure data will fit into buffer
307  if(TWI_BUFFER_LENGTH < (twi_txBufferLength+length)){
308  return 1;
309  }
310 
311  // ensure we are currently a slave transmitter
312  if(TWI_STX != twi_state){
313  return 2;
314  }
315 
316  // set length and copy data into tx buffer
317  for(i = 0; i < length; ++i){
318  twi_txBuffer[twi_txBufferLength+i] = data[i];
319  }
320  twi_txBufferLength += length;
321 
322  return 0;
323 }
324 
325 /*
326  * Function twi_attachSlaveRxEvent
327  * Desc sets function called before a slave read operation
328  * Input function: callback function to use
329  * Output none
330  */
331 void twi_attachSlaveRxEvent( void (*function)(uint8_t*, int) )
332 {
333  twi_onSlaveReceive = function;
334 }
335 
336 /*
337  * Function twi_attachSlaveTxEvent
338  * Desc sets function called before a slave write operation
339  * Input function: callback function to use
340  * Output none
341  */
342 void twi_attachSlaveTxEvent( void (*function)(void) )
343 {
344  twi_onSlaveTransmit = function;
345 }
346 
347 /*
348  * Function twi_reply
349  * Desc sends byte or readys receive line
350  * Input ack: byte indicating to ack or to nack
351  * Output none
352  */
353 void twi_reply(uint8_t ack)
354 {
355  // transmit master read ready signal, with or without ack
356  if(ack){
357  TWCR = _BV(TWEN) | _BV(TWIE) | _BV(TWINT) | _BV(TWEA);
358  }else{
359  TWCR = _BV(TWEN) | _BV(TWIE) | _BV(TWINT);
360  }
361 }
362 
363 /*
364  * Function twi_stop
365  * Desc relinquishes bus master status
366  * Input none
367  * Output none
368  */
369 void twi_stop(void)
370 {
371  // send stop condition
372  TWCR = _BV(TWEN) | _BV(TWIE) | _BV(TWEA) | _BV(TWINT) | _BV(TWSTO);
373 
374  // wait for stop condition to be exectued on bus
375  // TWINT is not set after a stop condition!
376  while(TWCR & _BV(TWSTO)){
377  continue;
378  }
379 
380  // update twi state
382 }
383 
384 /*
385  * Function twi_releaseBus
386  * Desc releases bus control
387  * Input none
388  * Output none
389  */
390 void twi_releaseBus(void)
391 {
392  // release bus
393  TWCR = _BV(TWEN) | _BV(TWIE) | _BV(TWEA) | _BV(TWINT);
394 
395  // update twi state
397 }
398 
399 ISR(TWI_vect)
400 {
401  switch(TW_STATUS){
402  // All Master
403  case TW_START: // sent start condition
404  case TW_REP_START: // sent repeated start condition
405  // copy device address and r/w bit to output register and ack
406  TWDR = twi_slarw;
407  twi_reply(1);
408  break;
409 
410  // Master Transmitter
411  case TW_MT_SLA_ACK: // slave receiver acked address
412  case TW_MT_DATA_ACK: // slave receiver acked data
413  // if there is data to send, send it, otherwise stop
415  // copy data to output register and ack
417  twi_reply(1);
418  }else{
419  if (twi_sendStop)
420  twi_stop();
421  else {
422  twi_inRepStart = true; // we're gonna send the START
423  // don't enable the interrupt. We'll generate the start, but we
424  // avoid handling the interrupt until we're in the next transaction,
425  // at the point where we would normally issue the start.
426  TWCR = _BV(TWINT) | _BV(TWSTA)| _BV(TWEN) ;
428  }
429  }
430  break;
431  case TW_MT_SLA_NACK: // address sent, nack received
432  twi_error = TW_MT_SLA_NACK;
433  twi_stop();
434  break;
435  case TW_MT_DATA_NACK: // data sent, nack received
436  twi_error = TW_MT_DATA_NACK;
437  twi_stop();
438  break;
439  case TW_MT_ARB_LOST: // lost bus arbitration
440  twi_error = TW_MT_ARB_LOST;
441  twi_releaseBus();
442  break;
443 
444  // Master Receiver
445  case TW_MR_DATA_ACK: // data received, ack sent
446  // put byte into buffer
448  case TW_MR_SLA_ACK: // address sent, ack received
449  // ack if more bytes are expected, otherwise nack
451  twi_reply(1);
452  }else{
453  twi_reply(0);
454  }
455  break;
456  case TW_MR_DATA_NACK: // data received, nack sent
457  // put final byte into buffer
459  if (twi_sendStop)
460  twi_stop();
461  else {
462  twi_inRepStart = true; // we're gonna send the START
463  // don't enable the interrupt. We'll generate the start, but we
464  // avoid handling the interrupt until we're in the next transaction,
465  // at the point where we would normally issue the start.
466  TWCR = _BV(TWINT) | _BV(TWSTA)| _BV(TWEN) ;
468  }
469  break;
470  case TW_MR_SLA_NACK: // address sent, nack received
471  twi_stop();
472  break;
473  // TW_MR_ARB_LOST handled by TW_MT_ARB_LOST case
474 
475  // Slave Receiver
476  case TW_SR_SLA_ACK: // addressed, returned ack
477  case TW_SR_GCALL_ACK: // addressed generally, returned ack
478  case TW_SR_ARB_LOST_SLA_ACK: // lost arbitration, returned ack
479  case TW_SR_ARB_LOST_GCALL_ACK: // lost arbitration, returned ack
480  // enter slave receiver mode
481  twi_state = TWI_SRX;
482  // indicate that rx buffer can be overwritten and ack
483  twi_rxBufferIndex = 0;
484  twi_reply(1);
485  break;
486  case TW_SR_DATA_ACK: // data received, returned ack
487  case TW_SR_GCALL_DATA_ACK: // data received generally, returned ack
488  // if there is still room in the rx buffer
490  // put byte in buffer and ack
492  twi_reply(1);
493  }else{
494  // otherwise nack
495  twi_reply(0);
496  }
497  break;
498  case TW_SR_STOP: // stop or repeated start condition received
499  // ack future responses and leave slave receiver state
500  twi_releaseBus();
501  // put a null char after data if there's room
504  }
505  // callback to user defined callback
507  // since we submit rx buffer to "wire" library, we can reset it
508  twi_rxBufferIndex = 0;
509  break;
510  case TW_SR_DATA_NACK: // data received, returned nack
511  case TW_SR_GCALL_DATA_NACK: // data received generally, returned nack
512  // nack back at master
513  twi_reply(0);
514  break;
515 
516  // Slave Transmitter
517  case TW_ST_SLA_ACK: // addressed, returned ack
518  case TW_ST_ARB_LOST_SLA_ACK: // arbitration lost, returned ack
519  // enter slave transmitter mode
520  twi_state = TWI_STX;
521  // ready the tx buffer index for iteration
522  twi_txBufferIndex = 0;
523  // set tx buffer length to be zero, to verify if user changes it
524  twi_txBufferLength = 0;
525  // request for txBuffer to be filled and length to be set
526  // note: user must call twi_transmit(bytes, length) to do this
528  // if they didn't change buffer & length, initialize it
529  if(0 == twi_txBufferLength){
530  twi_txBufferLength = 1;
531  twi_txBuffer[0] = 0x00;
532  }
533  // transmit first byte from buffer, fall
534  case TW_ST_DATA_ACK: // byte sent, ack returned
535  // copy data to output register
537  // if there is more to send, ack, otherwise nack
539  twi_reply(1);
540  }else{
541  twi_reply(0);
542  }
543  break;
544  case TW_ST_DATA_NACK: // received nack, we are done
545  case TW_ST_LAST_DATA: // received ack, but we are done already!
546  // ack future responses
547  twi_reply(1);
548  // leave slave receiver state
550  break;
551 
552  // All
553  case TW_NO_INFO: // no state information
554  break;
555  case TW_BUS_ERROR: // bus error, illegal stop/start
556  twi_error = TW_BUS_ERROR;
557  twi_stop();
558  break;
559  }
560 }
561 
GLuint GLsizei GLsizei * length
void twi_disable(void)
Definition: twi.c:99
void twi_releaseBus(void)
Definition: twi.c:390
#define TWI_FREQ
Definition: twi.h:28
static const uint8_t SCL
GLvoid *typedef void(GLAPIENTRY *PFNGLGETVERTEXATTRIBDVPROC)(GLuint
void twi_init(void)
Definition: twi.c:68
void twi_attachSlaveRxEvent(void(*function)(uint8_t *, int))
Definition: twi.c:331
#define TWI_MTX
Definition: twi.h:37
uint8_t twi_transmit(const uint8_t *data, uint8_t length)
Definition: twi.c:302
static volatile uint8_t twi_txBufferLength
Definition: twi.c:55
ISR(TWI_vect)
Definition: twi.c:399
static volatile uint8_t twi_rxBufferIndex
Definition: twi.c:58
static void(* twi_onSlaveReceive)(uint8_t *, int)
Definition: twi.c:47
static volatile uint8_t twi_state
Definition: twi.c:41
void twi_setAddress(uint8_t address)
Definition: twi.c:115
void twi_setFrequency(uint32_t frequency)
Definition: twi.c:127
uint8_t twi_readFrom(uint8_t address, uint8_t *data, uint8_t length, uint8_t sendStop)
Definition: twi.c:147
unsigned int uint32_t
static const uint8_t SDA
#define TWI_MRX
Definition: twi.h:36
static volatile uint8_t twi_slarw
Definition: twi.c:42
void twi_stop(void)
Definition: twi.c:369
static uint8_t twi_rxBuffer[TWI_BUFFER_LENGTH]
Definition: twi.c:57
static uint8_t twi_txBuffer[TWI_BUFFER_LENGTH]
Definition: twi.c:53
#define TWI_BUFFER_LENGTH
Definition: twi.h:32
static void(* twi_onSlaveTransmit)(void)
Definition: twi.c:46
#define TWI_SRX
Definition: twi.h:38
GLint GLenum GLsizei GLint GLsizei const GLvoid * data
static volatile uint8_t twi_masterBufferLength
Definition: twi.c:51
typedef int(WINAPI *PFNWGLRELEASEPBUFFERDCARBPROC)(HPBUFFERARB hPbuffer
GLuint address
static volatile uint8_t twi_inRepStart
Definition: twi.c:44
#define TWI_READY
Definition: twi.h:35
static volatile uint8_t twi_txBufferIndex
Definition: twi.c:54
void twi_reply(uint8_t ack)
Definition: twi.c:353
#define cbi(sfr, bit)
Definition: twi.c:31
void digitalWrite(uint8_t, uint8_t)
static volatile uint8_t twi_sendStop
Definition: twi.c:43
uint8_t twi_writeTo(uint8_t address, uint8_t *data, uint8_t length, uint8_t wait, uint8_t sendStop)
Definition: twi.c:226
static uint8_t twi_masterBuffer[TWI_BUFFER_LENGTH]
Definition: twi.c:49
#define TWI_STX
Definition: twi.h:39
static volatile uint8_t twi_masterBufferIndex
Definition: twi.c:50
void twi_attachSlaveTxEvent(void(*function)(void))
Definition: twi.c:342
static volatile uint8_t twi_error
Definition: twi.c:60


arduino_daq
Author(s):
autogenerated on Mon Jun 10 2019 12:46:03