Non-Blocking I2C using DMAC

I'm currently investigating using the Direct Memory Access Controller (DMAC) to allow non-blocking I2C data transfers on the Arduino Zero.

The issue with the standard Wire library, is that during I2C bus data transfers the processor idles waiting for the transfer to complete. On faster ARM processors this can take up a lot of processor cycles, simply doing nothing.

One solution is to offload the task of sending or receiving data to the DMAC, thereby freeing up the CPU core for more productive tasks.

I'm currently using a MPU6050 I2C based gyroscope/accelerometer for the test. I can now sucessfully read and write to the device using the DMAC with SERCOM3 in I2C Smart Mode. Once set-up this I2C transfer is running independently of the CPU.

In my test, I'm using DMAC channel 0 to transmit and channel 1 to receive. Both work fine, however during a transmit both the DMAC transfer complete (TCMPL) interrupt (pink trace) and the SERCOM3 master-on-bus (MB) interrupt (dark blue trace) occur after the address has been sent (W:0x68), but before the data (0x75):

The image shows writing to the MPU6050 (at address W:0x68), to set-up the WHO_AM_I register (address 0x75). Reading the MPU6050 (address R:0x68) then returns the data value (0x68).

The problem is that with both the TCMPL and MB interrupts triggering early, how is it possible to find out when the trasmission (of data 0x75) is complete? (It's necessary to know when the I2C bus is free, to then start the read portion of the transaction).

I think that the SERCOM3 was designed this way, so that in normal operation (without the DMAC) the MB interrupt indicates that data needs to be loaded into the I2C data register. As far as the DMAC is concerned, it considers that the transfer's complete the moment it loads the SERCOM3's data register.

The solution for the moment is to add a 20 microsecond delay to account for every byte transmitted. The receive interrupt works perfectly and is generated as the last byte is received.

I'm searching for a possible solution.

Is there something obvious I'm missing? Any help or suggestions would be greatly appreciated.

Here's the code. It simply reads the WHO_AM_I register from the MPU6050:

#define MPU6050_ADDRESS 0x68          // Device address when ADO = 0
#define WHO_AM_I_MPU6050 0x75         // Should return 0x68
enum { WRITE, READ };                 // I2C read and write bits

typedef struct                        // DMAC Descriptor structure
{
  uint16_t btctrl;
  uint16_t btcnt;
  uint32_t srcaddr;
  uint32_t dstaddr;
  uint32_t descaddr;
} dmacdescriptor ;

volatile dmacdescriptor wrb[12] __attribute__ ((aligned (16)));              // Write-back descriptors
dmacdescriptor descriptor_section[12] __attribute__ ((aligned (16)));        // Channel descriptors
dmacdescriptor descriptor __attribute__ ((aligned (16)));                    // Data entry descriptor

volatile boolean dmaDone = false;             // Set the DMAC transfter complete flag
uint8_t subAddress = WHO_AM_I_MPU6050;        // Set the sub address to the WHO_AM_I register in the MPU6050
uint8_t answer;                               // The result returned from the slave device

void setup() 
{
  SerialUSB.begin(115200);                    // Activate the native USB port
  while(!SerialUSB);                          // Wait for the native USB to be ready

  REG_PORT_DIRSET0 = PORT_PA14 | PORT_PA15;   // Activate D2 and D5 as outputs to display interrupt occurence on scope

  // Enable the SCL and SDA lines on SERCOM3
  PORT->Group[g_APinDescription[SCL].ulPort].PINCFG[g_APinDescription[SCL].ulPin].bit.PMUXEN = 1;  
  PORT->Group[g_APinDescription[SDA].ulPort].PINCFG[g_APinDescription[SDA].ulPin].bit.PMUXEN = 1;
  PORT->Group[g_APinDescription[SDA].ulPort].PMUX[g_APinDescription[SDA].ulPin >> 1].reg = PORT_PMUX_PMUXO_C | PORT_PMUX_PMUXE_C;

  // Enable GCLK0 on SERCOM3
  REG_GCLK_CLKCTRL = GCLK_CLKCTRL_CLKEN |              // Enable GCLK0 to SERCOM3
                     GCLK_CLKCTRL_GEN_GCLK0 |          // Select GCLK0
                     GCLK_CLKCTRL_ID_SERCOM3_CORE;     // Feed GCLK0 to SERCOM3
  while (GCLK->STATUS.bit.SYNCBUSY);                   // Wait for synchronization

  NVIC_SetPriority(SERCOM3_IRQn, 0);    // Set the Nested Vector Interrupt Controller (NVIC) priority for SERCOM3 to 0 (highest) 
  NVIC_EnableIRQ(SERCOM3_IRQn);         // Connect SERCOM3 to Nested Vector Interrupt Controller (NVIC)

  SERCOM3->I2CM.CTRLA.reg =  SERCOM_I2CM_CTRLA_MODE(I2C_MASTER_OPERATION);           // Set master mode and enable SCL Clock Stretch mode (stretch after ACK bit)
                            /*SERCOM_I2CM_CTRLA_SCLSM*/ ;
  SERCOM3->I2CM.CTRLB.reg =  SERCOM_I2CM_CTRLB_SMEN /*| SERCOM_I2CM_CTRLB_QCEN*/ ;   // Enable Smart mode
  SERCOM3->I2CM.BAUD.bit.BAUD = SystemCoreClock / (2 * 400000) - 7 ;                 // Set the I2C SCL frequency to 400kHz
  SERCOM3->I2CM.INTENSET.reg |= SERCOM_I2CM_INTENSET_SB | SERCOM_I2CM_INTENSET_MB;

  SERCOM3->I2CM.CTRLA.bit.ENABLE = 1 ;           // Enable the I2C master mode
  while (SERCOM3->I2CM.SYNCBUSY.bit.ENABLE);     // Waiting the enable bit from SYNCBUSY is equal to 0;
  SERCOM3->I2CM.STATUS.bit.BUSSTATE = 0x01 ;     // Setting bus idle mode    
  while (SERCOM3->I2CM.SYNCBUSY.bit.SYSOP);      // Wait the SYSOP bit from SYNCBUSY coming back to 0

  NVIC_SetPriority(DMAC_IRQn, 0);    // Set the Nested Vector Interrupt Controller (NVIC) priority for the DMAC to 0 (highest) 
  NVIC_EnableIRQ(DMAC_IRQn);         // Connect the DMAC to Nested Vector Interrupt Controller (NVIC)
  
  DMAC->BASEADDR.reg = (uint32_t)descriptor_section;                    // Set the DMAC descriptor base address
  DMAC->WRBADDR.reg = (uint32_t)wrb;                                    // Set teh DMAC descriptor write-back address
  DMAC->CTRL.reg = DMAC_CTRL_DMAENABLE | DMAC_CTRL_LVLEN(0xf);          // Enable the DMAC peripheral and set the
 
  DMAC->CHID.reg = DMAC_CHID_ID(0);                                     // Activate DMAC channel 0
  // Set the DMAC level, trigger source and trigger action to beat (trigger for every byte tranmitted)
  DMAC->CHCTRLB.reg = DMAC_CHCTRLB_LVL(0) | DMAC_CHCTRLB_TRIGSRC(SERCOM3_DMAC_ID_TX) | DMAC_CHCTRLB_TRIGACT_BEAT; 
  DMAC->CHINTENSET.reg = DMAC_CHINTENSET_MASK ;                         // Enable all 3 interrupts: SUSP, TCMPL and TERR
  descriptor.descaddr = 0;                                              // Single descriptor
  descriptor.srcaddr = (uint32_t)&subAddress;                           // Set the source address
  descriptor.dstaddr = (uint32_t)&SERCOM3->I2CM.DATA.reg;               // Set the destination address
  descriptor.btcnt = 1;                                                 // Transmit 1 byte of data
  descriptor.btctrl = DMAC_BTCTRL_BEATSIZE_BYTE | DMAC_BTCTRL_VALID;    // Set the data size to 1 byte
  memcpy(&descriptor_section[0], &descriptor, sizeof(dmacdescriptor));  // Copy the descriptor into channel 0's descriptor in SRAM
  
  DMAC->CHID.reg = DMAC_CHID_ID(1);                                     // Activate DMAC channel 1    
  // Set the DMAC level, trigger source and trigger action to beat (trigger for every byte receieved)                                              
  DMAC->CHCTRLB.reg = DMAC_CHCTRLB_LVL(0) | DMAC_CHCTRLB_TRIGSRC(SERCOM3_DMAC_ID_RX) | DMAC_CHCTRLB_TRIGACT_BEAT; 
  DMAC->CHINTENSET.reg = DMAC_CHINTENSET_MASK ;                         // Enable all 3 interrupts: SUSP, TCMPL and TERR
  descriptor.descaddr = 0;                                              // Single descriptor
  descriptor.srcaddr = (uint32_t)&SERCOM3->I2CM.DATA.reg;               // Set the source address
  descriptor.dstaddr = (uint32_t)&answer;                               // Set the destination address
  descriptor.btcnt = 1;                                                 // Receive 1 byte of data
  descriptor.btctrl = DMAC_BTCTRL_BEATSIZE_BYTE /*| DMAC_BTCTRL_DSTINC*/ | DMAC_BTCTRL_VALID;  // Set the data size to 1 byte
  memcpy(&descriptor_section[1], &descriptor, sizeof(dmacdescriptor));  // Copy the descriptor into channel 1's descriptor in SRAM
  
  DMAC->CHID.reg = DMAC_CHID_ID(0);                                     // Activate DMAC channel 0
  DMAC->CHCTRLA.reg |= DMAC_CHCTRLA_ENABLE;                             // Enable DMAC channel 0
  
  SERCOM3->I2CM.ADDR.reg = SERCOM_I2CM_ADDR_LEN(0x01) |                 // Load the I2C slave device address into SERCOM3's ADDR register 
                           SERCOM_I2CM_ADDR_LENEN |
                           SERCOM_I2CM_ADDR_ADDR(MPU6050_ADDRESS << 1 | WRITE);
  while (SERCOM3->I2CM.SYNCBUSY.bit.SYSOP);                             // Wait for sychronization
  while (!dmaDone);           // Wait for the DMAC transfter to complete
  dmaDone = false;            // Reset the DMAC done flag
  delayMicroseconds(20);      // This delay is required as the transfer complete (TCMPL) interrupt is called too early

  DMAC->CHID.reg = DMAC_CHID_ID(1);// Activate DMAC channel 1
  DMAC->CHCTRLA.reg |= DMAC_CHCTRLA_ENABLE; // Enable DMAC channel 1

  SERCOM3->I2CM.ADDR.reg = SERCOM_I2CM_ADDR_LEN(0x01) |                 // Load the I2C slave device address into SERCOM3's ADDR register 
                           SERCOM_I2CM_ADDR_LENEN |
                           SERCOM_I2CM_ADDR_ADDR(MPU6050_ADDRESS << 1 | READ);
  while (SERCOM3->I2CM.SYNCBUSY.bit.SYSOP);
  while (!dmaDone);                                                     // Wait for the DMAC transfer to complete
  SerialUSB.println(answer, HEX);                                       // Output the result from the I2C slave device
}

void loop() {}

void DMAC_Handler()
{
  REG_PORT_OUTSET0 = PORT_PA14;                                         // Turn on D2
  uint8_t activeChannel = DMAC->INTPEND.reg & DMAC_INTPEND_ID_Msk;      // Get DMAC channel number
  DMAC->CHID.reg = DMAC_CHID_ID(activeChannel);                         // Switch to the active DMAC channel
  dmaDone = true;                                                       // Set the DMAC done flag
  DMAC->CHINTFLAG.reg = DMAC_CHINTENCLR_SUSP |                          // Clear DMAC channel the interrupt flags
                        DMAC_CHINTENCLR_TCMPL | 
                        DMAC_CHINTENCLR_TERR; 
  REG_PORT_OUTCLR0 = PORT_PA14;                                         // Turn off D2
}

void SERCOM3_Handler()
{
  REG_PORT_OUTSET0 = PORT_PA15;       // Turn on D5
  SERCOM3->I2CM.INTFLAG.bit.MB = 1;   // Clear the interrupt flag
  SERCOM3->I2CM.INTFLAG.bit.SB = 1;   // Clear the interrupt flag
  REG_PORT_OUTCLR0 = PORT_PA15;       // Turn off D5
}

Ok, I'm beginning to get a handle on the situation.

Transmitting the I2C address followed by two data bytes shows that the SERCOM3's MB (Master-on-Bus) interrupt is called at the beginning of every data byte, while the DMAC's TCMPL (Transmission Complete) interrupt is called only at the beginning of the last data byte to be transmitted.

At an I2C clock speed of 400kHz, this still leaves 20 microsecond before the last data byte of the transmission is complete. SERCOM3 or DMAC interrupts don't appear to offer any hope of indicating when this last data byte has finally been transmitted.

An alternative to simply using the delayMicrosconds(20) function (in the code above), is to wait for the bus to become idle, before starting the next transmission:

while (SERCOM3->I2CM.STATUS.bit.BUSSTATE != 0x1);    // Wait for the bus state to return to IDLE

Even with a 20 microsecond wait at the end of a transmit, this still seems an efficient way of implementing a non-blocking I2C.

I'll package it all up in a small, simple library that'll make it easy to use. I'll make it available shortly on this forum thread.

I've made a start on the I2C_DMAC library.

The issue with non-blocking I2C is the need to usually first write the device's register address, in order to read from it.

With this in mind I've developed the library starting with primitive building blocks that provide independent control over both the initialisation, write and the read portions of the transaction, (again reading the WHO_AM_I register on the MPU6050):

#include <I2C_DMAC.h>

#define MPU6050_ADDRESS 0x68                         // Device address when ADO = 0
#define WHO_AM_I        0x75                         // Should return 0x68

I2C_DMAC i2c;

void setup() 
{
  SerialUSB.begin(115200);                           // Activate the native USB port
  while(!SerialUSB);                                 // Wait for the native USB to be ready

  i2c.begin(400000);                                 // Start I2C bus at 400kHz
  i2c.initWriteRegAddr(MPU6050_ADDRESS, WHO_AM_I);   // Initialise the write DMAC transfer
  i2c.fastWriteRegAddr();                            // Set-up the WHO_AM_I register address
  while(I2C_DMAC::writeBusy);                        // Wait for the write to complete
  i2c.initReadByte();                                // Initialise the read DMAC transfer
  i2c.fastReadByte();                                // Read the WHO_AM_I register contents
  while(I2C_DMAC::readBusy);                         // Wait for the read to complete
  SerialUSB.println(i2c.data, HEX);                  // Output the result
}

void loop() {}

This separates the DMAC initialisation from the read and write functions, to allow faster reading and writing.

The next level combines the DMAC initialisation with each read and write. Here's the same code:

#include <I2C_DMAC.h>

#define MPU6050_ADDRESS 0x68                      // Device address when ADO = 0
#define WHO_AM_I        0x75                      // Should return 0x68

I2C_DMAC i2c;

void setup() 
{
  SerialUSB.begin(115200);                        // Activate the native USB port
  while(!SerialUSB);                              // Wait for the native USB to be ready

  i2c.begin(400000);                              // Start I2C bus at 400kHz
  i2c.writeRegAddr(MPU6050_ADDRESS, WHO_AM_I);    // Set-up the WHO_AM_I register address
  while(I2C_DMAC::writeBusy);                     // Wait for the write to complete
  i2c.readByte();                                 // Read the WHO_AM_I register contents
  while(I2C_DMAC::readBusy);                      // Wait for the read to complete
  SerialUSB.println(i2c.data, HEX);               // Output the result
}

void loop() {}

Finally, there's another layer that blocks (and waits) on the write cycle and therefore only needs to check the readBusy flag. This simplifies the code even further:

#include <I2C_DMAC.h>

#define MPU6050_ADDRESS 0x68          // Device address when ADO = 0
#define WHO_AM_I        0x75          // Should return 0x68

I2C_DMAC i2c;

void setup() 
{
  SerialUSB.begin(115200);                   // Activate the native USB port
  while(!SerialUSB);                         // Wait for the native USB to be ready

  i2c.begin(400000);                         // Start I2C bus at 400kHz
  i2c.readByte(MPU6050_ADDRESS, WHO_AM_I);   // Read the WHO_AM_I register on the MPU6050
  while(I2C_DMAC::readBusy);                 // Wait for I2C transmission to complete
  SerialUSB.println(i2c.data, HEX);          // Output the result
}

void loop() {}

I still need to add error checking and possibly the option of using callback functions.

I've made some modifications. Checking that the I2C bus is IDLE before transmission removes the need to poll the busy flags after each function call.

If a second function call is made before the DMAC has finished it will simply block, until the bus becomes free oncemore.

The following code shows the I2C_DMAC reading gyroscope data from the MPU6050:

#include <I2C_DMAC.h>

#define MPU6050_ADDRESS 0x68                                // Device address when ADO = 0
#define PWR_MGMT_1      0x6B
#define CONFIG          0x1A
#define GYRO_CONFIG     0x1B
#define ACCEL_CONFIG    0x1C
#define GYRO_XOUT_H     0x43

uint8_t data[6];

void setup() 
{
  SerialUSB.begin(115200);                                  // Activate the native USB port
  while(!SerialUSB);                                        // Wait for the native USB to be ready

  I2C.begin(400000);                                        // Start I2C bus at 400kHz
  I2C.writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x01);         // Wake up the MPU6050 device
  delay(100);                                               // Wait for the MPU6050 to settle   
  I2C.writeByte(MPU6050_ADDRESS, CONFIG, 0x4);              // Set the gyro/accel filter to 20Hz  
  I2C.writeByte(MPU6050_ADDRESS, GYRO_CONFIG, 0x1 << 3);    // Set full scale range to +/-500 degrees/s  
  I2C.writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, 0x1 << 3);   // Set full scale range to +/-4g
  I2C.initWriteRegAddr(MPU6050_ADDRESS, GYRO_XOUT_H);       // Set-up DMAC to write to MPU6050 register pointer
  I2C.initReadBytes(data, sizeof(data));                    // Set DMAC to read the data
}

void loop() 
{ 
  I2C.write();                                              // DMAC write to set MPU6050 register pointer to start of the data
  // Add your concurrent code here...
  while(I2C.writeBusy);                                     // Wait for synchronization 
  I2C.read();
  // Add your concurrent code here...
  while(I2C.readBusy);                                      // Wait for synchronization 
  SerialUSB.print((int16_t)((data[0] << 8) | data[1]));     // Acquire raw gyro values
  SerialUSB.print(F("   "));
  SerialUSB.print((int16_t)((data[2] << 8) | data[3]));
  SerialUSB.print(F("   "));
  SerialUSB.println((int16_t)((data[4] << 8) | data[5]));
}

I've also added a 16-bit address mode to allow communication with I2C EEPROM such as the 24LCxx devices.

This code shows the I2C_DMAC in 16-bit address mode writing and reading data to a 24LC256 I2C EEPROM:

#include <I2C_DMAC.h>

#define EEPROM_ADDRESS 0x50

uint8_t data[] = { 0x01, 0x02, 0x03, 0x04 };

void setup() 
{
  SerialUSB.begin(115200);                    // Initialise the Serial port
  while(!SerialUSB);
  
  I2C.begin(400000, ADDR_16BIT);              // Initialise the I2C bus to 400kHz, 16-bit address mode
  SerialUSB.println(F("Begin Test..."));      // Indicate that the test is beginning
  
  I2C.initWriteBytes(EEPROM_ADDRESS, 0x0000, data, sizeof(data));    // Set-up DMAC to write the data array to EEPROM 
  
  for (uint8_t i = 0; i < sizeof(data); i++)  // Reset the data
  {
    data[i] = 0;
  }
  
  I2C.initWriteRegAddr(EEPROM_ADDRESS, 0x0000);                      // Set the EEPROM address pointer to 0x0000             
  I2C.write();                                                       // Write out the command
  // Add your concurrent code here...
  while(I2C.writeBusy);
  delay(6)                                               // Wait for EEPROM write cycle to complete
  
  I2C.initReadBytes(data, sizeof(data));      // Read the 4 data bytes
  I2C.read();                                 // Read the results
  // Add your concurrent code here...
  while(I2C.readBusy);                        // Wait for synchronization

  for (uint8_t i = 0; i < sizeof(data); i++)                         // Output the data array result
  {
    SerialUSB.println(data[i], HEX);
  }
  SerialUSB.println(F("End Test..."));
}

void loop() {}

Over the next day (or two) I'll add callback functions and error checking.

Ok, the first version of the I2C_DMAC library is complete. Please find a copy of the library as a zip file below. I'll also post it on Github in due course.

The I2C_DMAC library allows non-blocking and/or blocking communication over the I2C bus. It's currently only designed for the Arduino Zero as the bus master.

It uses the I2C in Smart Mode in conjuction with the SAMD21's Direct Memory Access Controller (DMAC). Smart mode configures the I2C bus for completely autonomous operation, while the DMAC moves data from memory to the I2C bus and vice-versa, but without direct intervention from the CPU.

Tests show that even during blocking transfers, the I2C_DMAC library marginally out performs the standard Wire library. This is probably due to the fact that it's completely clocked using hardware.

Non-blocking operation allows the I2C data transfer to occur in parallel to the CPU. The CPU's sketch checks at a later point in the program to see if the transfer is complete. It's the parallel nature of the operation that can provide a significant performance enhancement over blocking code. On my Arduino Zero based Falcon 1 flight controller, using the I2C_DMAC library with non-blocking code provides at least a 25% increase in loop() time frequency performance over the standard Wire library.

Installation

Simply un-zip the file below and place the DMAC and I2C_DMAC directories in your ...Arduino/libraries folder. The Arduino folder is the one where your sketches are usually located.

Usage

Simply include the I2C_DMAC.h file the beginning of the sketch:

#include <I2C_DMAC.h>

The I2C_DMAC object is created (instantiated) automatically and the oject can be called using the I2C prefix, for example:

I2C.begin();

The I2C_DMAC library's functions operate in the following way:

The "init" functions simply set up the DMAC prior to transfer, while the "read" and "write" functions do the actual transmission.

All the other read and write functions are just a combination of the these three base level operations.

The write functions allow for the transmission of the device address, plus the following options:

Device Address->Data->Data Count (bytes)
Device Address->8-bit Register Address
Device Address->16-bit Register Address
Device Address->8-bit Register Address->1 Byte Data
Device Address->8-bit Register Address->Data->Data Count (bytes)
Device Address->16-bit Register Address->1 Byte Data
Device Address->16-bit Register Address->Data->Data Count (bytes)

The 8-bit register address is used to access most small I2C devices, such as sensors, while the 16-bit resgister address can be used to access I2C EEPROM devices.

The read functions allow for the transmission of the device address, plus the reception of the following options:

Device Address->1 Byte Data
Device Address->Data->Data Count (bytes)

Single bytes of data are handled by the library, meaning that you can simply enter constants as a single byte of data without having to allocate any memory. This is useful for configuring an I2C device.

A block of data can be a simple array and needs to be declared and "in scope" for the duration of the transfer. The block data size is limited to 255 bytes of data, (including the register address length). This limitation in imposed by the hardware.

Note that the I2C_DMAC doesn't use a ring buffer like the standard Wire library, it simply allows you to send and receive data from memory already allocated in your program. This also makes it more efficient as it isn't necessary to pull data off the ring buffer, the data is instead transfer directly to where you specify.

By default the DMAC uses channel 0 to write and 1 to read, but it's possible to select your DMAC channels of choice (0-11). It's also possible to set the priority level (0 lowest-3 highest). This is only necessary if you're using the DMAC channels for other purposes as well.

It's possible to initialise the DMAC only one time and then continuouly call the read() and write() functions in the loop() to initiate multiple transfers. In other words it isn't necessary to set-up the DMAC each time if you're doing a repeated operation.

To allow the sketch to check if the DMAC read or write operation is complete it's necessary to poll the respective busy flags:

while(I2C.busyWrite);

It's also possible to allocate callback functions that are executed when a read or write has completed, or when an error occurs.

The DMAC_Handler() and SERCOM3_Handler are provided as weak linker symbols allowing them to be overriden in your sketch for inclusion of your own handler functions, should that be necessary.

Here's a list of the available functions, it looks quite daunting, but trust me it's pretty easy to use and the differing (overloaded) functions are just there to handle various situations you may encounter, (see the examples included in the zip file):

//
// Configuration functions
//
void begin(); // Begin with 100kHz I2C bus clock speed and 8-bit register address mode
void begin(uint32_t baudrate); // Begin with specified baud rate and 8-bit register address mode
void begin(uint32_t baudrate, uint8_t regAddrMode); // Begin with specified baud rate and register address mode
void end(); // Tear down and tidy up resources
void setClock(uint32_t baudrate); // Set the I2C bus clock speed to the specified baud rate
void setWriteChannel(uint8_t channel); // Set the DMAC write channel number (0 - 11), default 0
void setReadChannel(uint8_t channel); // Set the DMAC read channel number (0 - 11), default 1
void setPriority(uint8_t priority); // Set the priority level for both read and write DMAC channels (0 - 3), default 0
void setRegAddrMode(uint8_t regAddrMode); // Set the register address mode REG_ADDR_8BIT or REG_ADDR_16BIT

//
// DMAC Configuration functions
//
void initWriteBytes(uint8_t devAddress, uint8_t* data, uint8_t count); // Initialise DMAC to send data, (no register address)
void initWriteBytes(uint8_t devAddress, uint16_t regAddress, uint8_t* data, uint8_t count); // Initialise DMAC to send register address + data
void initWriteByte(uint8_t devAddress, uint16_t regAddress, uint8_t data); // Initialise DMAC to send register address + 1 data byte
void initWriteRegAddr(uint8_t devAddress, uint16_t regAddress); // Initialise DMAC to send register address, (no data)
void initReadBytes(uint8_t devAddress, uint8_t* data, uint8_t count); // Initialise DMAC to receive data
void initReadByte(uint8_t devAddress); // Initialise DMAC to receive 1 data byte

//
// Data transmission functions
//
uint8_t getData(); // Retrieve the received data byte
void write(); // Transmit on I2C bus
void read(); // Receive on I2C bus
void writeBytes(uint8_t devAddress, uint16_t regAddress, uint8_t* data, uint8_t count); // Transmit data to the I2C device's register address
void writeByte(uint8_t devAddress, uint16_t regAddress, uint8_t data); // Transmit 1 data byte to the I2C device's register address
void writeRegAddr(uint8_t devAddress, uint16_t regAddress); // Write the register address to the I2C device
void readBytes(uint8_t devAddress, uint8_t* data, uint8_t count); // Receive data from the I2C device
void readByte(uint8_t devAddress); // Receive 1 data byte from the I2C device
void readBytes(uint8_t devAddress, uint16_t regAddress, uint8_t* data, uint8_t count); // Receive data from the I2C device's register address
void readByte(uint8_t devAddress, uint16_t regAddress); // Receive a byte from the I2C device's register address

//
// Callback functions
//
void attachWriteCallback(voidFuncPtr callback); // Attach a DMAC write callback function
void attachReadCallback(voidFuncPtr callback); // Attach a DMAC read callback function
void attachDmacErrorCallback(voidFuncPtr callback); // Attach a DMAC error callback function
void attachSercom3ErrorCallback(voidFuncPtr callback); // Attach a SERCOM3 error callback function
void detachWriteCallback(); // Detach the DMAC write callback function
void detachReadCallback(); // Detach the DMAC read callback function
void detachDmacErrorCallback(); // Detach the DAMC error callback function
void detachSercom3ErrorCallback(); // Detach the SERCOM3 error callback function

//
// Interrupt handler functions
//
static void DMAC_IrqHandler(); // DMAC interrupt handler function
static void SERCOM3_IrqHandler(); // SERCOM3 interrupt handler function

//
// Read and write busy flags
//
volatile boolean writeBusy; // Write busy flag - indicates write transfer in progress
volatile boolean readBusy; // Read busy flag - indicates read transfer in progress

I2C_DMAC Library.zip (13.2 KB)

Also, please find attached an I2C_DMAC EEPROM library.

Again, just drop the ExtEEPROM3 and the EEPROMAnything4 directories into your ...Arduino/libraries folder.

To use, include the following .h files:

#include <I2C_DMAC.h>
#include <ExtEERPOM3.h>
#include <EEPROM_Anything4.h>

This library allows you to use the 24LCXX I2C external EEPROM in conjuction with the I2C_DMAC library. The code does block, but it uses modified EEPROM_Anything functions to allow you seamlessly read and write entire data structures to and from memory.

Example code is included in the zip file.

ExtEEPROM Library.zip (2.86 KB)

For those that want to look at the code, I've posted it to the Github repository: GitHub - MartinL1/I2C_DMAC: Arduino Zero (SAMD21/SAMD51) based non-blocking I2C library using the DMAC..

Pretty awesome work. Have you tried using your code on any of the other SERCOMs? I'm going to be rearrange the pin usage on my project and probably not using SERCOM3 for I2C.

Hi dlabun,

I was thinking of adding I2C support for port pins: PA08 and PA09 as well, as I know these are used by the Arduino MKR series.

I believe these I2C pins will also be used on the Adafruit's forthcoming SAMD51 based Metro M4 board, which I also intend to support.

Which I2C pins did you have in mind for your project?

I'm currently substantially redesigning the I2C_DMAC library (V1.1.0), so that it'll be more closely aligned with the Arduino core code, but still backwards compatible with the first version (V1.0.0).

By default new I2C_DMAC will take its I2C SCL and SDA pins from the "variant.h" and "variant.cpp" configuration files. This will provide compatibility with both the Arduino Zero and MKR series of boards.

The library will also handle multiple instances of the I2C bus, provided the other buses communicate on different DMAC read and write channels.

Work on the SAMD21 is complete, however it's the SAMD51 that's making me fight every inch of the way.

While the SAMD51's SERCOM is identical to the SAMD21's, the DMAC is very different with the transmission complete (TMCPL) flag occuring much later (than the SAMD21's). This is currently causing timing issues with the code that I'm working on resolving.

I'll post the new version on Github when it's ready.

Ok, version V1.1.0 of the I2C_DMAC library is ready and available on Github: GitHub - MartinL1/I2C_DMAC: Arduino Zero (SAMD21/SAMD51) based non-blocking I2C library using the DMAC..

The new library in additon to the Arduino Zero, now supports the Arduino MKR series (untested) and the SAMD51 using Adafruit's Metro/Feather M4 core code (tested).

It also supports multiple I2C instances. An example sketch "MPU6050_Gyroscope_V2.ino" that reads the raw gyroscope data from two gyroscopes on separate I2C ports, is also included.

Here's the "MPU6050_Gyroscope_V2.ino" example code, using two MPU6050 gyroscope/accelerometer devices.

The first device is on the standard SCL/SDL pins, the second on D3 and D4, (use D2 instead of D4 if you're using the Arduino M0 Pro or M0):

#include <I2C_DMAC.h>
#include <wiring_private.h>

#define MPU6050_ADDRESS 0x68                                // Device address when ADO = 0
#define PWR_MGMT_1      0x6B
#define CONFIG          0x1A
#define GYRO_CONFIG     0x1B
#define ACCEL_CONFIG    0x1C
#define GYRO_XOUT_H     0x43

uint8_t data[6];
uint8_t data1[6];

I2C_DMAC I2C1(&sercom2, 4, 3);                              // Create (instantiate) a second I2C1 object with sercom2, on pins D3 and D4

void setup() 
{
  SerialUSB.begin(115200);                                  // Activate the native USB port
  while(!SerialUSB);                                        // Wait for the native USB to be ready
  
  I2C.begin(400000);                                        // Start I2C bus at 400kHz          
  I2C.writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x01);         // Wake up the MPU6050 device
  delay(100);                                               // Wait for the MPU6050 to settle   
  I2C.writeByte(MPU6050_ADDRESS, CONFIG, 0x4);              // Set the gyro/accel filter to 20Hz  
  I2C.writeByte(MPU6050_ADDRESS, GYRO_CONFIG, 0x1 << 3);    // Set full scale range to +/-500 degrees/s 
  I2C.writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, 0x1 << 3);   // Set full scale range to +/-4g
  I2C.initWriteRegAddr(MPU6050_ADDRESS, GYRO_XOUT_H);       // Set-up DMAC to write to MPU6050 register pointer
  I2C.initReadBytes(MPU6050_ADDRESS, data, sizeof(data));   // Set DMAC to read the data
  I2C.attachReadCallback(gyro1Callback);                    // Attach a read callback function to I2C
  
  I2C1.begin(400000);                                       // Start I2C bus at 400kHz 
  pinPeripheral(3, PIO_SERCOM_ALT);                         // Assign D3 to SERCOM2 I2C SDA
  pinPeripheral(4, PIO_SERCOM_ALT);                         // Assign D4 to SERCOM2 I2C SCL
  I2C1.setWriteChannel(2);                                  // Set the I2C1 DMAC write channel to 2
  I2C1.setReadChannel(3);                                   // Set the I2C1 DMAC read channel to 3
  I2C1.writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x01);        // Wake up the MPU6050 device
  delay(100);                                               // Wait for the MPU6050 to settle   
  I2C1.writeByte(MPU6050_ADDRESS, CONFIG, 0x4);             // Set the gyro/accel filter to 20Hz  
  I2C1.writeByte(MPU6050_ADDRESS, GYRO_CONFIG, 0x1 << 3);   // Set full scale range to +/-500 degrees/s  
  I2C1.writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, 0x1 << 3);  // Set full scale range to +/-4g
  I2C1.initWriteRegAddr(MPU6050_ADDRESS, GYRO_XOUT_H);      // Set-up DMAC to write to MPU6050 register pointer
  I2C1.initReadBytes(MPU6050_ADDRESS, data1, sizeof(data1));// Set DMAC to read the data
  I2C1.attachReadCallback(gyro2Callback);                   // Attach a read callback function to I2C1
}

void loop() 
{ 
  I2C.write();                                              // DMAC write to set MPU6050 register pointer to start of the data
  // Add your concurrent code here...
  while(I2C.writeBusy);                                     // Wait for synchronization 
  I2C.read();
  // Add your concurrent code here...
  while(I2C.readBusy);                                      // Wait for synchronization 
  //SerialUSB.print(F("Gyro 1: "));                           // Acquire raw gyro values from MPU6050 device 1
  SerialUSB.print((int16_t)((data[0] << 8) | data[1]));     
  SerialUSB.print(F("   "));
  SerialUSB.print((int16_t)((data[2] << 8) | data[3]));
  SerialUSB.print(F("   "));
  SerialUSB.println((int16_t)((data[4] << 8) | data[5]));

  I2C1.write();                                              // DMAC write to set MPU6050 register pointer to start of the data
  // Add your concurrent code here...
  while(I2C1.writeBusy);                                     // Wait for synchronization 
  I2C1.read();
  // Add your concurrent code here...
  while(I2C1.readBusy);                                      // Wait for synchronization 
  //SerialUSB.print(F("Gyro 2: "));                            // Acquire raw gyro values from MPU6050 device 2
  SerialUSB.print((int16_t)((data1[0] << 8) | data1[1]));    
  SerialUSB.print(F("   "));
  SerialUSB.print((int16_t)((data1[2] << 8) | data1[3]));
  SerialUSB.print(F("   "));
  SerialUSB.println((int16_t)((data1[4] << 8) | data1[5]));
}

void gyro1Callback()
{
  SerialUSB.print(F("Gyro 1: "));
}

void gyro2Callback()
{
  SerialUSB.print(F("Gyro 2: "));
}

The callbacks functions are optional and are implemented for demonstration purposes only.

Updated both the DMAC and I2C_DMAC files (V1.1.2), to allow I2C_DMAC library to be used in conjunction with other code and/or libraries on the remaining DMAC channels.

This version is now available on Github: GitHub - MartinL1/I2C_DMAC: Arduino Zero (SAMD21/SAMD51) based non-blocking I2C library using the DMAC..

Updated the I2C_DMAC library files (V1.1.3) to fix an issue, whereby successive calls to the writeByte() function caused it to override the previous (writeByte) function's data.

This one slipped through the net while testing the I2C_DMAC library on the MPU6050 gyro/accelerometer, as it only affected the device's filter settings, it wasn't immediately apparent.

Anyway, this bug's now been fixed.

Another update. This brings the I2C_DMAC library to version V1.1.4.

The latest change is to allow the DMAC to resume normal operation in the event of a NACK (Not Acknowledge) being received too early during communication.

This typically happens when an attempt is made to communicate with an I2C device that is absent from bus. It might be an optional device that can be plugged in, but your sketch might need to detect if the device is present or not.

The solution was like trying to find a needle in a haystack.

On receiving an early NACK the sercom's ERROR interrupt flag is raised, but the problem was that afterwards the DMAC wouldn't restart. The solution, (after countless trial and error attempts), was to manually disable the DMAC read and write channels in sercom's ISR. Unfortunately however, this wasn't documented in the SAMD21 datasheet. After simply disabling the read and write channels the DMAC resumes normal operation oncemore.

Now on V1.1.5, this activates the SAMD21/SAMD51's internal pull-up resistors and increases the pins' driver strength.

This increases the I2C pins' current sinking ability on the SAMD21 from 3mA to 10mA max. and on the SAMD51 from 2mA to 8mA max.

Just tested the V1.1.5 of I2C_DMAC library on my SAMD21 based flight contoller.

It fetches the MPU6050's gyroscope and accelerometer data for the next cycle on I2C bus, while simultaneously performing the current loop calculations. The two theads of operation are then synchronized in the next cycle when the new data are ready. This is then repeated as the sketch loops.

In this instance the I2C_DMAC library provides a 25% increase in performance (looptime) over the standard Wire library, although (as expected) there wasn't really any noticable improvement in the flight characteristics, flying a 550mm (span) tricopter with 490Hz PWM to the ESCs, (a set-up that some would consider prehistoric by today's standards).

Still great fun though.

Thank you for providing this Non-Blocking I2C library! I am attempting to use it in my project.

I have a question, however. I was hoping that your library would be tolerant of a slave holding the I2C bus low. The Arduino Wire library locks up in endTransmission in this condition which is unacceptable. The Arduino code can not lock up forever because of a bad piece of hardware!

While your library doesn't seem to lock up when a slave has the bus held low, it does lock up when the slave releases the bus. I don't suppose you know off the top of your head where this lockup would be occurring in your driver?

FWIW, I solved the problem by finding the places you had while loops pending on a hardware bit, and adding a way for them to break out. For example:

    const int TIMEOUT = 10;
    timeout = TIMEOUT;
    while (sercom->I2CM.SYNCBUSY.bit.SYSOP && --timeout);                    // Wait for synchronization

The methods then return whether a timeout occurred or not. If they timeout, I call I2C.begin() again. That's my method of solving the problem in a few hours without really understanding the code :slight_smile: I'd appreciate what you have to say about a more elegant solution.

Maybe you haven't run into the need for this in your projects yet, but trust me...some day when you have a design with a dozen i2c slaves, and 1000 PCBs made for this design, you're going to find it unacceptable for the processor to halt forever because one slave is holding SCL low.