3

I'm trying to use an Arduino Due to interface with an ADIS16364 IMU from Analog Devices (product info here) via SPI.

There are two modes for retrieving the measurements from this particular IMU (six 16 bit values, 3 acc, 3 gyros):

  1. The first mode is, if I'm not wrong, the standard one with SPI, in which each successive transfer command retrieves the last data requested and indicates which one should be retrieved next.

  2. The second possibility is a so called "burst mode". For this one you have to request the 0x3E00 register. After that, the IMU will burst out the six measurements (plus a few other bits of information like temperature and supply voltage). From the specs sheet:

enter image description here enter image description here

The problem is, I can not manage to make the Arduino read the data using this burst mode. This is the code I'm using to test the communication:

#include <SPI.h>
#define SerialBT Serial2

short supply, xgyro, ygyro, zgyro, xacc, yacc, zacc, xtemp, ytemp, ztemp, aux;
volatile byte fDataIMUtoRead = 0;
int pauseBetweenTransfers;

void setup() {

  SerialBT.begin(230400);

  pinMode(52, OUTPUT);

  // Configure SPI
  SPI.begin(52);
  SPI.setClockDivider(52, 200); // 84e6/200 = 420kHz
  SPI.setDataMode(52, SPI_MODE3);
  SPI.setBitOrder(52, MSBFIRST);

  // Set sample rate
  float Fs = 1; // Target sampling frequency [Hz]
  float tb = 0.61035 * (Fs >= 12.7009) + 18.921 * (Fs < 12.7009);
  unsigned long tbsel = 0 * (Fs >= 12.7009) + 1 * (Fs < 12.7009);
  unsigned long Ns = (uint16_t) round((1000.0 - tb * Fs) / (tb * Fs));
  float Feff = 1000 / (tb * (Ns + 1));
  SerialBT.print("Selected freq: ");
  SerialBT.println(Feff, DEC);

  digitalWrite(52, LOW);  // Doesn't seem to be necessary
  SPI.transfer16(52, (0L << 15) | (0x36L << 8));                       delayMicroseconds(100);
  SPI.transfer16(52, (1L << 15) | (0x36L << 8) | (tbsel << 7) | Ns );  delayMicroseconds(100);
  SPI.transfer16(52, (0L << 15) | (0x36L << 8));                       delayMicroseconds(100);
  zgyro = SPI.transfer16(52, 0x00);
  digitalWrite(52, HIGH);  

  SerialBT.print("SMPL_PRD = ");
  SerialBT.println(zgyro, HEX);

  attachInterrupt(3, availableIMUData, RISING);
}

void loop() {

if (fDataIMUtoRead) {

SerialBT.print("Loop... ");

// Read values (standard mode)  
pauseBetweenTransfers = 100;
digitalWrite(52, LOW); // Doesn't seem to be necessary

        SPI.transfer16(52, 0x0400, SPI_CONTINUE); delayMicroseconds(pauseBetweenTransfers);
xgyro  = SPI.transfer16(52, 0x0600, SPI_CONTINUE); delayMicroseconds(pauseBetweenTransfers);
ygyro  = SPI.transfer16(52, 0x0800, SPI_CONTINUE); delayMicroseconds(pauseBetweenTransfers);
zgyro  = SPI.transfer16(52, 0x0A00, SPI_CONTINUE); delayMicroseconds(pauseBetweenTransfers);
xacc   = SPI.transfer16(52, 0x0C00, SPI_CONTINUE); delayMicroseconds(pauseBetweenTransfers);
yacc   = SPI.transfer16(52, 0x0E00, SPI_CONTINUE); delayMicroseconds(pauseBetweenTransfers);             
zacc   = SPI.transfer16(52, 0x0000, SPI_CONTINUE);
  
digitalWrite(SS, HIGH);    

/*
// Read values (burst mode)
pauseBetweenTransfers = 5;
digitalWrite(52, LOW);    // Doesn't seem to be necessary 
  
         SPI.transfer16(52, 0x3E00);    delayMicroseconds(pauseBetweenTransfers);  // Request data burst
supply = SPI.transfer16(52, 0x0000, SPI_CONTINUE);  delayMicroseconds(pauseBetweenTransfers);
xgyro  = SPI.transfer16(52, 0x0000, SPI_CONTINUE);  delayMicroseconds(pauseBetweenTransfers);
ygyro  = SPI.transfer16(52, 0x0000, SPI_CONTINUE);  delayMicroseconds(pauseBetweenTransfers);
zgyro  = SPI.transfer16(52, 0x0000, SPI_CONTINUE);  delayMicroseconds(pauseBetweenTransfers);
xacc   = SPI.transfer16(52, 0x0000, SPI_CONTINUE);  delayMicroseconds(pauseBetweenTransfers);
yacc   = SPI.transfer16(52, 0x0000, SPI_CONTINUE);  delayMicroseconds(pauseBetweenTransfers);
zacc   = SPI.transfer16(52, 0x0000, SPI_CONTINUE);  delayMicroseconds(pauseBetweenTransfers);
xtemp  = SPI.transfer16(52, 0x0000, SPI_CONTINUE);  delayMicroseconds(pauseBetweenTransfers);
ytemp  = SPI.transfer16(52, 0x0000, SPI_CONTINUE);  delayMicroseconds(pauseBetweenTransfers);
ztemp  = SPI.transfer16(52, 0x0000);
    
digitalWrite(52, HIGH);     
*/

SerialBT.println(zgyro, DEC); // Print the reading

fDataIMUtoRead = 0; // Reser the "there is new data"-flag

}    

}

void availableIMUData() {
fDataIMUtoRead = 1; // Set the "there is new data"-flag }

The standard way to communicate seems to work without any problem, provided that I set the right delays after each transfer16 command. But I'm not able to make the Arduino read the data in burst mode (commented in the code above).

So does anybody have any ideas on how to make the Arduino retrieve the readings in this burst mode? I understand this is a tricky unless you have (had) access to the same hardware, but any suggestion will be welcome.

Thanks a lot.

2
  • 1
    You seem to be correct about everything said, so far as I can tell. I would put a scope on the signals and make sure they look okay.
    – timemage
    Jun 8, 2021 at 12:12
  • Thanks timemage. Unfortunately I have no scope. Only a cheap logic analayzer, which wasn't of much help Jun 9, 2021 at 10:11

1 Answer 1

3

First of all, this may not related to your question, but you are using old SPI methods setClockDivider(), setDataMode(), and setBitOrder() that has been deprecated since 2014. It is recommend to use use transactional SPI APIs which I have some explanation here.

Why I actually need those delays?

If you read page 6 of ADIS16364 datasheet, there is a tSTALL time between each data transmission that could be as long as 75uS (when operating on Low Power mode), this value can be much lower if you operate on Normal or Bust mode.

why this combination of delays with the 200 clock divider?

The clock divide set the clock used for the SPI SCLK rate, for Due a clock divide of 200 means 84,000,000 / 200 = 420,000Hz, Why this rate? again, you have to look into datasheet, on page 6 table 2, max fsck is 2MHz for Normal mode, and 1MHz for Bust mode, and only 300kHz at Low Power mode.

Shouldn't this be done automatically by the SPI library?

This is a wrong perception, SPI library do nothing than handling the communication. All the timing requirements are component/chip specific, and therefore if you want to communicate with the chip at SPI communication level, you will have to deal with all the timing requirements yourself. Most of the people in the Arduino community get used of using some pre-written library which was written by someone who care to read the datasheet and provide high level abstract API so that users don't need to deal with all the timing.

Any ideas on how to make the Arduino retrieve the readings in this burst mode?

Update

As suggested by the datasheet, "To start a burst read sequence, set DIN = 0x3E00", what this means is that you need to WRITE into the register 0x3E00 first to setup the burst mode. Fig 11. of the datasheet indicate that a WRITE operation would have a set most significant bit to 1, so you will need to send 0x3E00 | 0x8000 or 0xAE00 for writing into register 0x3E00. What you did is basically reading form 0x3E00, not writing into 0x3E00.

I re-read the datasheet and you are right, it should be okay to just send out 0x3E00. I never use an Arduino Due before, but I realised that the SPI.transfer16() might send out the 0x00 first instead of 0x3E. I modified the code to send out two bytes 0x3E and 0x00 separately using SPI.transfer()

I don't have the IMU, but I think the follow code should works for bust mode:

SPI.beginTransaction(SPISettings(1000000, MSBFIRST, SPI_MODE3));    //initialises SPI clock speed, mode and bit order
digitalWrite(SS, LOW);              // adjust this as per your chip select pin
SPI.transfer(0x3E);
SPI.transfer(0x00);
delayMicroseconds(1);               //bust mode only 1uS required as per datasheet
xgyro_out = SPI.transfer16(0x0000);
delayMicroseconds(1);
ygyro_out = SPI.transfer16(0x0000);  
delayMicroseconds(1);
zgyro_out = SPI.transfer16(0x0000);  
delayMicroseconds(1);
xaccl_out = SPI.transfer16(0x0000);  
delayMicroseconds(1);
yaccl_out = SPI.transfer16(0x0000);  
delayMicroseconds(1);
zaccl_out = SPI.transfer16(0x0000);  
delayMicroseconds(1);
data16    = SPI.transfer16(0x0000);  
delayMicroseconds(1);
data16    = SPI.transfer16(0x0000);  
delayMicroseconds(1);
data16    = SPI.transfer16(0x0000);  
delayMicroseconds(1);
data16    = SPI.transfer16(0x0000);  
delayMicroseconds(1);
digitalWrite(SS, HIGH);   // deselect slave
SPI.endTransaction();
7
  • Thanks for you detailed reply, hcheung. Your indication to WRITE to the 0x3e00 seemed to be the key, but it didn't solve the problem. After checking the specs sheet again, on page 12, end of first paragraph of the second column: "Reading the GLOB_CMD register (DIN = 0x3E00) starts the burst read sequence." So SPI.transfer16(0x3E00) should actually do the job, if I get it right. Any other ideas? Jun 9, 2021 at 10:22
  • I use the old syntax for SPI communication because I just wasn't able to make the new SPI.beginTransaction command work. No idea what I'm doing wrong. The old one seems to be working fine, though (unless you see any reason this should be preventing the burst mode to work) Jun 9, 2021 at 10:23
  • I just discovered yesterday that with sample rates as high as 150 Hz the IMU still works in low-power mode, which explains the high delays needed, as you suggest. Jun 9, 2021 at 10:23
  • 1
    You are right, it should be okay to just send a read cmd to 0x3E00. Please see my update answer and also the change of the code to send out two bytes (0x3E, 0x00) separately. Please try, I think it should work.
    – hcheung
    Jun 9, 2021 at 11:26
  • 1
    The old APIs still work even though it is deprecated as long as your SPI bus do not have multiple SPI devices on it. The SPI.begintransaction is designed to allow multiple devices to operate with each has its own configuration settings.
    – hcheung
    Jun 9, 2021 at 11:34

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge that you have read and understand our privacy policy and code of conduct.

Not the answer you're looking for? Browse other questions tagged or ask your own question.