Multiple SPI Slaves Conflict: ADXL-362 and SD Fat

Status
Not open for further replies.

ak12

Member
Hello all,

I am a newcomer to the microcontroller scene and I am very impressed with the Teensy 3.2. This forum has been very helpful as well. I have encountered a frustrating problem: Initializing the SD-Card ruins my Accelerometer data.

Goal: Log Acceleration Data onto SD-Card

I want to record the outputs of a MEMS accelerometer (ADXL-362) of 100 readings/sec onto a microSD card using the Teensy adapter sold on PJRC.

My Teensy 3.2 can properly communicate with either device in isolation. I can Serial.print the correct values with Teensy+ADXL (X=10,Y=-10,Z=1280); and I can successfully Read/Write to the SD card with Teensy+SD adapter. Both devices share the same MISO,MOSI,CLK lines, and have a different CS pin.

However, once I initialize the SD-Card using SD.begin(), my ADXL readings become garbage. If I initialize the SD-card before my accelerometer, I get (X=255,Y=0,Z=0). If I initialize the SD card after the accelerometer, I get (X=-6,000, Y =-7000, Z = -168000). Both very wrong values.

What could be the issue?

It must be a software problem because both SPI-devices behave correctly in isolation. Both the ADXL-362 and the SD-adapter run on SPI_MODE=0. I suspect it's some SPI setting that I am not familiar with.

This link points to a similar problem, where the solution was to separate out each 4 SPI lines between devices because the temperature sensor was using soft_SPI instead of hard-coded SPI pins. But I am using the Teensy's dedicated SPI pins, and don't want to have multiple lines because I will be making a PCB with an Othermill CNC. [Off topic: that thing is great!]

My guess is that I am beginning the SPI twice and thus messing up the settings, seeing how the "order" of initializing SD or ADXL matters. I tried digging through the SdFatBase.cpp and SdSpiTeensy3.cpp but my head started spinning trying to keep track of all the definitions. I don't see where SDfat.begin() initializes the SPI. I am also using a 3rd party arduino library for the ADXL-362 with some custom modifications (below)

Details:
I have the setup as follows:

Teensy Pin 10 <==> SD-Slave Select
Teensy Pin 11 <==> SD-MOSI // ADXL-MOSI
Teensy Pin 12 <==> SD-MISO // ADXL-MISO
Teensy Pin 14 <==> SD-CLK // ADXL-CLK
Teensy Pin 15 <==> ADXL-Slave Select

I have used the alternate Teensy CLK pin of 14 instead of the default 13 because I want 13's LED function. Elsewhere in the forum I see that Paul suggested these CORE_PIN commands, which I put in both my ADXL library and SdSpiTeensy3.cpp in the SD Fat library :
Code:
  CORE_PIN13_CONFIG = PORT_PCR_MUX(1);  //Make SCK =14
  CORE_PIN14_CONFIG = PORT_PCR_DSE | PORT_PCR_MUX(2);//Make SCK =14


Help Request
Has anybody here gotten a MEMS sensor's data correctly saved onto an SD card? I'm a newbie to SPI and I thought it was conceptually simple, but and it's very confusing to me with this talk of "soft" vs "hard" SPI pins, vs bitbanging

TEENSY CODE
Code:
#include <SPI.h>
#include <ADXL362.h>
#include <SdFat.h>

#define VIOLATION_LED 13 //Violation Pin
#define STATUS_LED 6 //Calibration Indicator
#define INIT_SIZE 500

ADXL362 xl;
SdFat SD;
File myFile;

int16_t XValue, YValue, ZValue, Temperature;

unsigned long starttime;
unsigned long runtime;

#define SD_SS 10 //SD Card Slave Select
#define XL_SS 15 //ADXL Slave Select
void setup(){

//Initialize Pins
  pinMode(XL_SS,OUTPUT);
  pinMode(SD_SS,OUTPUT);
  digitalWrite(XL_SS,HIGH);
  digitalWrite(SD_SS,HIGH);
  
 //Start Serial, get signal to start
  Serial.begin(57600);
  delay(1000);
  Serial.println(F("Send any character to start sketch.\n"));
  while (Serial.available() && Serial.read()); // empty buffer
  while (!Serial.available()){
    delay(1500);
  }                
  while (Serial.available() && Serial.read()); // empty buffer again


//  //Start SPI of SD Card (starting SD Card before ADXL = 255, 0, 0)
////----------------------------------------------------------------------------------------  
//  digitalWrite(XL_SS,HIGH);
//  digitalWrite(SD_SS,LOW);
//
// if (!SD.begin(SD_SS)) {
//    Serial.println("SD Card initialization failed!");
//    return;
//  }
//  Serial.println("SD Card initialization done.");
//
////----------------------------------------------------------------------------------------

//Start SPI for ADXL
//----------------------------------------------------------------------------------------  
  digitalWrite(XL_SS,LOW);
  digitalWrite(SD_SS,HIGH);
  xl.begin(XL_SS);           // Setup SPI protocol, issue device soft reset
//  xl.setNoise(ADXL362_NOISE); 
//  xl.setNoise(ADXL362_LOWNOISE); 
  xl.setNoise(ADXL362_ULTRALOWNOISE); 
  xl.setODR(ADXL362_RATE_100); 
  xl.beginMeasure();       // Switch ADXL362 to measure mode  
//---------------------------------------------------------------------------------------- 


//  Start SPI of SD Card (starting SD Card AFTER ADXL = really high numbers)
//----------------------------------------------------------------------------------------  
  digitalWrite(XL_SS,HIGH);
  digitalWrite(SD_SS,LOW);

 if (!SD.begin(SD_SS)) {
    Serial.println("SD Card initialization failed!");
    return;
  }
  Serial.println("SD Card initialization done.");

//----------------------------------------------------------------------------------------  
  starttime = millis();
}

void loop(){
    // read all three axis in burst to ensure all measurements correspond to same sample time
  xl.readXYZTData(XValue, YValue, ZValue, Temperature);  
  runtime = millis()-starttime;
  Serial.print(runtime);
  Serial.print(",");
  Serial.print(XValue);  
  Serial.print(",");
  Serial.print(YValue);  
  Serial.print(",");
  Serial.print(ZValue);  
  Serial.print(",");
  Serial.println(Temperature);
  delay(10);
}

Teensy SdSpiTeensy3.cpp
Code:
/* Arduino SdSpi Library
 * Copyright (C) 2013 by William Greiman
 *
 * This file is part of the Arduino SdSpi Library
 *
 * This Library is free software: you can redistribute it and/or modify
 * it under the terms of the GNU General Public License as published by
 * the Free Software Foundation, either version 3 of the License, or
 * (at your option) any later version.
 *
 * This Library is distributed in the hope that it will be useful,
 * but WITHOUT ANY WARRANTY; without even the implied warranty of
 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
 * GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with the Arduino SdSpi Library.  If not, see
 * <http://www.gnu.org/licenses/>.
 */
#include "SdSpi.h"
#if defined(__arm__) && defined(CORE_TEENSY)
// SPI definitions
#include "kinetis.h"
#ifdef KINETISK
// use 16-bit frame if SPI_USE_8BIT_FRAME is zero
#define SPI_USE_8BIT_FRAME 0
// Limit initial fifo to three entries to avoid fifo overrun
#define SPI_INITIAL_FIFO_DEPTH 3
// define some symbols that are not in mk20dx128.h
#ifndef SPI_SR_RXCTR
#define SPI_SR_RXCTR 0XF0
#endif  // SPI_SR_RXCTR
#ifndef SPI_PUSHR_CONT
#define SPI_PUSHR_CONT 0X80000000
#endif   // SPI_PUSHR_CONT
#ifndef SPI_PUSHR_CTAS
#define SPI_PUSHR_CTAS(n) (((n) & 7) << 28)
#endif  // SPI_PUSHR_CTAS
//------------------------------------------------------------------------------
/**
 * initialize SPI pins
 */
void SdSpi::begin() {
  SIM_SCGC6 |= SIM_SCGC6_SPI0;
}
//------------------------------------------------------------------------------
/**
 * Initialize hardware SPI
 *
 */
void SdSpi::init(uint8_t sckDivisor) {
  uint32_t ctar, ctar0, ctar1;

  if (sckDivisor <= 2) {
    // 1/2 speed
    ctar = SPI_CTAR_DBR | SPI_CTAR_BR(0) | SPI_CTAR_CSSCK(0);
  } else if (sckDivisor <= 4) {
    // 1/4 speed
    ctar = SPI_CTAR_BR(0) | SPI_CTAR_CSSCK(0);
  } else if (sckDivisor <= 8) {
    // 1/8 speed
    ctar = SPI_CTAR_BR(1) | SPI_CTAR_CSSCK(1);
  } else if (sckDivisor <= 12) {
    // 1/12 speed
    ctar = SPI_CTAR_BR(2) | SPI_CTAR_CSSCK(2);
  } else if (sckDivisor <= 16) {
    // 1/16 speed
    ctar = SPI_CTAR_BR(3) | SPI_CTAR_CSSCK(3);
  } else if (sckDivisor <= 32) {
    // 1/32 speed
    ctar = SPI_CTAR_PBR(1) | SPI_CTAR_BR(4) | SPI_CTAR_CSSCK(4);
  } else if (sckDivisor <= 64) {
    // 1/64 speed
    ctar = SPI_CTAR_PBR(1) | SPI_CTAR_BR(5) | SPI_CTAR_CSSCK(5);
  } else {
    // 1/128 speed
    ctar = SPI_CTAR_PBR(1) | SPI_CTAR_BR(6) | SPI_CTAR_CSSCK(6);
  }
  // CTAR0 - 8 bit transfer
  ctar0 = ctar | SPI_CTAR_FMSZ(7);

  // CTAR1 - 16 bit transfer
  ctar1 = ctar | SPI_CTAR_FMSZ(15);

  if (SPI0_CTAR0 != ctar0 || SPI0_CTAR1 != ctar1) {
    SPI0_MCR = SPI_MCR_MSTR | SPI_MCR_MDIS | SPI_MCR_HALT | SPI_MCR_PCSIS(0x1F);
    SPI0_CTAR0 = ctar0;
    SPI0_CTAR1 = ctar1;
  }
  SPI0_MCR = SPI_MCR_MSTR | SPI_MCR_PCSIS(0x1F);
  CORE_PIN11_CONFIG = PORT_PCR_DSE | PORT_PCR_MUX(2);
  CORE_PIN12_CONFIG = PORT_PCR_MUX(2);
  
//   CORE_PIN13_CONFIG = PORT_PCR_DSE | PORT_PCR_MUX(2); //Original SCK = 13 
  CORE_PIN13_CONFIG = PORT_PCR_MUX(1);  //Make SCK =14
  CORE_PIN14_CONFIG = PORT_PCR_DSE | PORT_PCR_MUX(2);//Make SCK =14

}
//------------------------------------------------------------------------------
/** SPI receive a byte */
uint8_t SdSpi::receive() {
  SPI0_MCR |= SPI_MCR_CLR_RXF;
  SPI0_SR = SPI_SR_TCF;
  SPI0_PUSHR = 0xFF;
  while (!(SPI0_SR & SPI_SR_TCF)) {}
  return SPI0_POPR;
}
//------------------------------------------------------------------------------
/** SPI receive multiple bytes */
uint8_t SdSpi::receive(uint8_t* buf, size_t n) {
  // clear any data in RX FIFO
  SPI0_MCR = SPI_MCR_MSTR | SPI_MCR_CLR_RXF | SPI_MCR_PCSIS(0x1F);
#if SPI_USE_8BIT_FRAME
  // initial number of bytes to push into TX FIFO
  int nf = n < SPI_INITIAL_FIFO_DEPTH ? n : SPI_INITIAL_FIFO_DEPTH;
  for (int i = 0; i < nf; i++) {
    SPI0_PUSHR = 0XFF;
  }
  // limit for pushing dummy data into TX FIFO
  uint8_t* limit = buf + n - nf;
  while (buf < limit) {
    while (!(SPI0_SR & SPI_SR_RXCTR)) {}
    SPI0_PUSHR = 0XFF;
    *buf++ = SPI0_POPR;
  }
  // limit for rest of RX data
  limit += nf;
  while (buf < limit) {
    while (!(SPI0_SR & SPI_SR_RXCTR)) {}
    *buf++ = SPI0_POPR;
  }
#else  // SPI_USE_8BIT_FRAME
  // use 16 bit frame to avoid TD delay between frames
  // get one byte if n is odd
  if (n & 1) {
    *buf++ = receive();
    n--;
  }
  // initial number of words to push into TX FIFO
  int nf = n/2 < SPI_INITIAL_FIFO_DEPTH ? n/2 : SPI_INITIAL_FIFO_DEPTH;
  for (int i = 0; i < nf; i++) {
    SPI0_PUSHR = SPI_PUSHR_CONT | SPI_PUSHR_CTAS(1) | 0XFFFF;
  }
  uint8_t* limit = buf + n - 2*nf;
  while (buf < limit) {
    while (!(SPI0_SR & SPI_SR_RXCTR)) {}
    SPI0_PUSHR = SPI_PUSHR_CONT | SPI_PUSHR_CTAS(1) | 0XFFFF;
    uint16_t w = SPI0_POPR;
    *buf++ = w >> 8;
    *buf++ = w & 0XFF;
  }
  // limit for rest of RX data
  limit += 2*nf;
  while (buf < limit) {
    while (!(SPI0_SR & SPI_SR_RXCTR)) {}
    uint16_t w = SPI0_POPR;
    *buf++ = w >> 8;
    *buf++ = w & 0XFF;
  }
#endif  // SPI_USE_8BIT_FRAME
  return 0;
}
//------------------------------------------------------------------------------
/** SPI send a byte */
void SdSpi::send(uint8_t b) {
  SPI0_MCR |= SPI_MCR_CLR_RXF;
  SPI0_SR = SPI_SR_TCF;
  SPI0_PUSHR = b;
  while (!(SPI0_SR & SPI_SR_TCF)) {}
}
//------------------------------------------------------------------------------
/** SPI send multiple bytes */
void SdSpi::send(const uint8_t* buf , size_t n) {
  // clear any data in RX FIFO
  SPI0_MCR = SPI_MCR_MSTR | SPI_MCR_CLR_RXF | SPI_MCR_PCSIS(0x1F);
#if SPI_USE_8BIT_FRAME
  // initial number of bytes to push into TX FIFO
  int nf = n < SPI_INITIAL_FIFO_DEPTH ? n : SPI_INITIAL_FIFO_DEPTH;
  // limit for pushing data into TX fifo
  const uint8_t* limit = buf + n;
  for (int i = 0; i < nf; i++) {
    SPI0_PUSHR = *buf++;
  }
  // write data to TX FIFO
  while (buf < limit) {
    while (!(SPI0_SR & SPI_SR_RXCTR)) {}
    SPI0_PUSHR = *buf++;
    SPI0_POPR;
  }
  // wait for data to be sent
  while (nf) {
    while (!(SPI0_SR & SPI_SR_RXCTR)) {}
    SPI0_POPR;
    nf--;
  }
#else  // SPI_USE_8BIT_FRAME
  // use 16 bit frame to avoid TD delay between frames
  // send one byte if n is odd
  if (n & 1) {
    send(*buf++);
    n--;
  }
  // initial number of words to push into TX FIFO
  int nf = n/2 < SPI_INITIAL_FIFO_DEPTH ? n/2 : SPI_INITIAL_FIFO_DEPTH;
  // limit for pushing data into TX fifo
  const uint8_t* limit = buf + n;
  for (int i = 0; i < nf; i++) {
    uint16_t w = (*buf++) << 8;
    w |= *buf++;
    SPI0_PUSHR = SPI_PUSHR_CONT | SPI_PUSHR_CTAS(1) | w;
  }
  // write data to TX FIFO
  while (buf < limit) {
    uint16_t w = *buf++ << 8;
    w |= *buf++;
    while (!(SPI0_SR & SPI_SR_RXCTR)) {}
    SPI0_PUSHR = SPI_PUSHR_CONT | SPI_PUSHR_CTAS(1) | w;
    SPI0_POPR;
  }
  // wait for data to be sent
  while (nf) {
    while (!(SPI0_SR & SPI_SR_RXCTR)) {}
    SPI0_POPR;
    nf--;
  }
#endif  // SPI_USE_8BIT_FRAME
}
#else  // KINETISK
//==============================================================================
// Use standard SPI library if not KINETISK
#include "SPI.h"
/**
 * Initialize SPI pins.
 */
void SdSpi::begin() {
  SPI.begin();
}
/** Set SPI options for access to SD/SDHC cards.
 *
 * \param[in] divisor SCK clock divider relative to the system clock.
 */
void SdSpi::init(uint8_t divisor) {
  SPI.setBitOrder(MSBFIRST);
  SPI.setDataMode(SPI_MODE0);
#ifndef SPI_CLOCK_DIV128
  SPI.setClockDivider(divisor);
#else  // SPI_CLOCK_DIV128
  int v;
  if (divisor <= 2) {
    v = SPI_CLOCK_DIV2;
  } else  if (divisor <= 4) {
    v = SPI_CLOCK_DIV4;
  } else  if (divisor <= 8) {
    v = SPI_CLOCK_DIV8;
  } else  if (divisor <= 16) {
    v = SPI_CLOCK_DIV16;
  } else  if (divisor <= 32) {
    v = SPI_CLOCK_DIV32;
  } else  if (divisor <= 64) {
    v = SPI_CLOCK_DIV64;
  } else {
    v = SPI_CLOCK_DIV128;
  }
  SPI.setClockDivider(v);
#endif  // SPI_CLOCK_DIV128
}
/** Receive a byte.
 *
 * \return The byte.
 */
uint8_t SdSpi::receive() {
  return SPI.transfer(0XFF);
}
/** Receive multiple bytes.
 *
 * \param[out] buf Buffer to receive the data.
 * \param[in] n Number of bytes to receive.
 *
 * \return Zero for no error or nonzero error code.
 */
uint8_t SdSpi::receive(uint8_t* buf, size_t n) {
  for (size_t i = 0; i < n; i++) {
    buf[i] = SPI.transfer(0XFF);
  }
  return 0;
}
/** Send a byte.
 *
 * \param[in] b Byte to send
 */
void SdSpi::send(uint8_t b) {
  SPI.transfer(b);
}
/** Send multiple bytes.
 *
 * \param[in] buf Buffer for data to be sent.
 * \param[in] n Number of bytes to send.
 */
void SdSpi::send(const uint8_t* buf , size_t n) {
  for (size_t i = 0; i < n; i++) {
    SPI.transfer(buf[i]);
  }
}
#endif  // KINETISK
#endif  // defined(__arm__) && defined(CORE_TEENSY)

ADXL362.CPP

Code:
#include <Arduino.h>
#include <ADXL362.h>
#include <SPI.h>

//#define ADXL362_DEBUG
int16_t slaveSelectPin = 15;
ADXL362::ADXL362() {
}
//
//  begin()
//  Initial SPI setup, soft reset of device
//
void ADXL362::begin(int16_t chipSelectPin) {
	slaveSelectPin = chipSelectPin;
	pinMode(slaveSelectPin, OUTPUT);
	SPI.begin();
	SPI.setDataMode(SPI_MODE0);	//CPHA = CPOL = 0    MODE = 0
  // First reassign pin 13 to Alt1 so that it is not SCK but the LED still works and then reassign pin 14 to SCK
  CORE_PIN13_CONFIG = PORT_PCR_MUX(1);
  CORE_PIN14_CONFIG = PORT_PCR_DSE | PORT_PCR_MUX(2);
	delay(1000);
	// soft reset
	SPIwriteOneRegister(0x1F, 0x52);  // Write to SOFT RESET, "R"
	delay(10);
#ifdef ADXL362_DEBUG
	Serial.println("Soft Reset\n");
#endif
 }
 
//
//  beginMeasure()
//  turn on Measurement mode - required after reset
// 
void ADXL362::beginMeasure() {
	byte temp = SPIreadOneRegister(0x2D);	// read Reg 2D before modifying for measure mode

#ifdef ADXL362_DEBUG
	Serial.print(  "Setting Measurement Mode - Reg 2D before = "); 
	Serial.print(temp); 
#endif

	// turn on measurement mode
	byte tempwrite = temp | 0x02;			// turn on measurement bit in Reg 2D
	SPIwriteOneRegister(0x2D, tempwrite); // Write to POWER_CTL_REG, Measurement Mode
	delay(10);	
  
#ifdef ADXL362_DEBUG
	temp = SPIreadOneRegister(0x2D);
	Serial.print(  ", Reg 2D after = "); 
	Serial.println(temp); 
	Serial.println();
#endif
}

//
// setRange(int sense)
// set the G sensitivity, either ADXL362_2G, ADXL362_4G or ADXL362_8G
// returns true if the register set was successful
//
void ADXL362::setRange(int sense)
{
	byte reg = SPIreadOneRegister(FILTER_CTL);
	reg &= 0x3F; // mask out the sense bits;
	reg |= (sense << RANGE); 
	SPIwriteOneRegister(FILTER_CTL, reg);
}

//
// setMeasureRate(int rate);
// sets the sample rate of the adxl362, pg. 33 of datasheet.
void ADXL362::setSELFTEST(int Val)
{
// 	byte reg = SPIreadOneRegister(SELF_TEST);
// 	reg &= 0xFC;
// 	reg |= (rate << ODR);
	SPIwriteOneRegister(SELF_TEST, Val);
}

//
// setSelfTest(int rate);
// sets the sample rate of the adxl362, pg. 33 of datasheet.
void ADXL362::setODR(int rate)
{
	byte reg = SPIreadOneRegister(FILTER_CTL);
	reg &= 0xFC;
	reg |= (rate << ODR);
	SPIwriteOneRegister(FILTER_CTL, reg);
}

//
// setNoise(int rate);
// sets the sample rate of the adxl362, pg. 33 of datasheet.
void ADXL362::setNoise(int noise)
{
	byte reg = SPIreadOneRegister(POWER_CTL);
	reg &= 0xCF; // mask out the sense bits;
	reg |= (noise << LOW_NOISE);
	SPIwriteOneRegister(POWER_CTL, reg);
}

//
//  readXData(), readYData(), readZData(), readTemp()
//  Read X, Y, Z, and Temp registers
//
int16_t ADXL362::readXData(){
	int16_t XDATA = SPIreadTwoRegisters(0x0E);
	
#ifdef ADXL362_DEBUG
	Serial.print("XDATA = ");
	Serial.println(XDATA);
#endif
	
	return XDATA;
}

int16_t ADXL362::readYData(){
	int16_t YDATA = SPIreadTwoRegisters(0x10);

#ifdef ADXL362_DEBUG
	Serial.print("\tYDATA = "); 
	Serial.println(YDATA);
#endif
	
	return YDATA;
}

int16_t ADXL362::readZData(){
	int16_t ZDATA = SPIreadTwoRegisters(0x12);

#ifdef ADXL362_DEBUG
	Serial.print("\tZDATA = "); 
	Serial.println(ZDATA);
#endif

	return ZDATA;
}

int16_t ADXL362::readTemp(){
	int16_t TEMP = SPIreadTwoRegisters(0x14);

#ifdef ADXL362_DEBUG
	Serial.print("\tTEMP = "); 
	Serial.println(TEMP);
#endif

	return TEMP;
}

void ADXL362::readXYZTData(int16_t &XData, int16_t &YData, int16_t &ZData, int16_t &Temperature){
	  // burst SPI read
	  // A burst read of all three axis is required to guarantee all measurements correspond to same sample time
	  digitalWrite(slaveSelectPin, LOW);
	  SPI.transfer(0x0B);  // read instruction
	  SPI.transfer(0x0E);  // Start at XData Reg
	  XData = SPI.transfer(0x00);
	  XData = XData + (SPI.transfer(0x00) << 8);
	  YData = SPI.transfer(0x00);
	  YData = YData + (SPI.transfer(0x00) << 8);
	  ZData = SPI.transfer(0x00);
	  ZData = ZData + (SPI.transfer(0x00) << 8);
	  Temperature = SPI.transfer(0x00);
	  Temperature = Temperature + (SPI.transfer(0x00) << 8);
	  digitalWrite(slaveSelectPin, HIGH);
  
#ifdef ADXL362_DEBUG
	Serial.print("XDATA = "); Serial.print(XData); 
	Serial.print("\tYDATA = "); Serial.print(YData); 
	Serial.print("\tZDATA = "); Serial.print(ZData); 
	Serial.print("\tTemperature = "); Serial.println(Temperature);
#endif
}

void ADXL362::setupDCActivityInterrupt(int16_t threshold, byte time){
	//  Setup motion and time thresholds
	SPIwriteTwoRegisters(0x20, threshold);
	SPIwriteOneRegister(0x22, time);

	// turn on activity interrupt
	byte ACT_INACT_CTL_Reg = SPIreadOneRegister(0x27);  // Read current reg value
	ACT_INACT_CTL_Reg = ACT_INACT_CTL_Reg | (0x01);     // turn on bit 1, ACT_EN  
	SPIwriteOneRegister(0x27, ACT_INACT_CTL_Reg);       // Write new reg value 
	ACT_INACT_CTL_Reg = SPIreadOneRegister(0x27);       // Verify properly written

#ifdef ADXL362_DEBUG
	Serial.print("DC Activity Threshold set to ");  	Serial.print(SPIreadTwoRegisters(0x20));
	Serial.print(", Time threshold set to ");  		Serial.print(SPIreadOneRegister(0x22)); 
	Serial.print(", ACT_INACT_CTL Register is ");  	Serial.println(ACT_INACT_CTL_Reg, HEX);
#endif
}

void ADXL362::setupACActivityInterrupt(int16_t threshold, byte time){
	//  Setup motion and time thresholds
	SPIwriteTwoRegisters(0x20, threshold);
	SPIwriteOneRegister(0x22, time);
  
	// turn on activity interrupt
	byte ACT_INACT_CTL_Reg = SPIreadOneRegister(0x27);  // Read current reg value
	ACT_INACT_CTL_Reg = ACT_INACT_CTL_Reg | (0x03);     // turn on bit 2 and 1, ACT_AC_DCB, ACT_EN  
	SPIwriteOneRegister(0x27, ACT_INACT_CTL_Reg);       // Write new reg value 
	ACT_INACT_CTL_Reg = SPIreadOneRegister(0x27);       // Verify properly written

#ifdef ADXL362_DEBUG
	Serial.print("AC Activity Threshold set to ");  	Serial.print(SPIreadTwoRegisters(0x20));
	Serial.print(", Time Activity set to ");  		Serial.print(SPIreadOneRegister(0x22));  
	Serial.print(", ACT_INACT_CTL Register is ");  Serial.println(ACT_INACT_CTL_Reg, HEX);
#endif
}

void ADXL362::setupDCInactivityInterrupt(int16_t threshold, int16_t time){
	// Setup motion and time thresholds
	SPIwriteTwoRegisters(0x23, threshold);
	SPIwriteTwoRegisters(0x25, time);

	// turn on inactivity interrupt
	byte ACT_INACT_CTL_Reg = SPIreadOneRegister(0x27);   // Read current reg value 
	ACT_INACT_CTL_Reg = ACT_INACT_CTL_Reg | (0x04);      // turn on bit 3, INACT_EN  
	SPIwriteOneRegister(0x27, ACT_INACT_CTL_Reg);        // Write new reg value 
	ACT_INACT_CTL_Reg = SPIreadOneRegister(0x27);        // Verify properly written

#ifdef ADXL362_DEBUG
	Serial.print("DC Inactivity Threshold set to ");  Serial.print(SPIreadTwoRegisters(0x23));
	Serial.print(", Time Inactivity set to ");  Serial.print(SPIreadTwoRegisters(0x25));
	Serial.print(", ACT_INACT_CTL Register is ");  Serial.println(ACT_INACT_CTL_Reg, HEX);
#endif
}

void ADXL362::setupACInactivityInterrupt(int16_t threshold, int16_t time){
	//  Setup motion and time thresholds
	SPIwriteTwoRegisters(0x23, threshold);
	SPIwriteTwoRegisters(0x25, time);
 
	// turn on inactivity interrupt
	byte ACT_INACT_CTL_Reg = SPIreadOneRegister(0x27);   // Read current reg value
	ACT_INACT_CTL_Reg = ACT_INACT_CTL_Reg | (0x0C);      // turn on bit 3 and 4, INACT_AC_DCB, INACT_EN  
	SPIwriteOneRegister(0x27, ACT_INACT_CTL_Reg);        // Write new reg value 
	ACT_INACT_CTL_Reg = SPIreadOneRegister(0x27);        // Verify properly written

#ifdef ADXL362_DEBUG
	Serial.print("AC Inactivity Threshold set to ");  Serial.print(SPIreadTwoRegisters(0x23));
	Serial.print(", Time Inactivity set to ");  Serial.print(SPIreadTwoRegisters(0x25)); 
	Serial.print(", ACT_INACT_CTL Register is ");  Serial.println(ACT_INACT_CTL_Reg, HEX);
#endif
}

void ADXL362::checkAllControlRegs(){
	//byte filterCntlReg = SPIreadOneRegister(0x2C);
	//byte ODR = filterCntlReg & 0x07;  Serial.print("ODR = ");  Serial.println(ODR, HEX);
	//byte ACT_INACT_CTL_Reg = SPIreadOneRegister(0x27);      Serial.print("ACT_INACT_CTL_Reg = "); Serial.println(ACT_INACT_CTL_Reg, HEX);
	digitalWrite(slaveSelectPin, LOW);
	SPI.transfer(0x0B);  // read instruction
	SPI.transfer(0x20);  // Start burst read at Reg 20
#ifdef ADXL362_DEBUG
	Serial.println("Start Burst Read of all Control Regs - Library version 6-5-2014:");
	Serial.print("Reg 20 = "); 	Serial.println(SPI.transfer(0x00), HEX);
	Serial.print("Reg 21 = "); 	Serial.println(SPI.transfer(0x00), HEX);
	Serial.print("Reg 22 = "); 	Serial.println(SPI.transfer(0x00), HEX);
	Serial.print("Reg 23 = "); 	Serial.println(SPI.transfer(0x00), HEX);
	Serial.print("Reg 24 = "); 	Serial.println(SPI.transfer(0x00), HEX);
	Serial.print("Reg 25 = "); 	Serial.println(SPI.transfer(0x00), HEX);
	Serial.print("Reg 26 = "); 	Serial.println(SPI.transfer(0x00), HEX);
	Serial.print("Reg 27 = "); 	Serial.println(SPI.transfer(0x00), HEX);
	Serial.print("Reg 28 = "); 	Serial.println(SPI.transfer(0x00), HEX);
	Serial.print("Reg 29 = "); 	Serial.println(SPI.transfer(0x00), HEX);
	Serial.print("Reg 2A = "); 	Serial.println(SPI.transfer(0x00), HEX);
	Serial.print("Reg 2B = "); 	Serial.println(SPI.transfer(0x00), HEX);
	Serial.print("Reg 2C = "); 	Serial.println(SPI.transfer(0x00), HEX);
	Serial.print("Reg 2D = "); 	Serial.println(SPI.transfer(0x00), HEX);
	Serial.print("Reg 2E = "); 	Serial.println(SPI.transfer(0x00), HEX);
#endif
	digitalWrite(slaveSelectPin, HIGH);
}

// Basic SPI routines to simplify code
// read and write one register
byte ADXL362::SPIreadOneRegister(byte regAddress){
	byte regValue = 0;
  
	digitalWrite(slaveSelectPin, LOW);
	SPI.transfer(0x0B);  // read instruction
	SPI.transfer(regAddress);
	regValue = SPI.transfer(0x00);
	digitalWrite(slaveSelectPin, HIGH);

	return regValue;
}

void ADXL362::SPIwriteOneRegister(byte regAddress, byte regValue){
  
	digitalWrite(slaveSelectPin, LOW);
	SPI.transfer(0x0A);  // write instruction
	SPI.transfer(regAddress);
	SPI.transfer(regValue);
	digitalWrite(slaveSelectPin, HIGH);
}

int16_t ADXL362::SPIreadTwoRegisters(byte regAddress){
	int16_t twoRegValue = 0;
  
	digitalWrite(slaveSelectPin, LOW);
	SPI.transfer(0x0B);  // read instruction
	SPI.transfer(regAddress);  
	twoRegValue = SPI.transfer(0x00);
	twoRegValue = twoRegValue + (SPI.transfer(0x00) << 8);
	digitalWrite(slaveSelectPin, HIGH);

	return twoRegValue;
}  

void ADXL362::SPIwriteTwoRegisters(byte regAddress, int16_t twoRegValue){
	byte twoRegValueH = twoRegValue >> 8;
	byte twoRegValueL = twoRegValue;
  
	digitalWrite(slaveSelectPin, LOW);
	SPI.transfer(0x0A);  // write instruction
	SPI.transfer(regAddress);  
	SPI.transfer(twoRegValueL);
	SPI.transfer(twoRegValueH);
	digitalWrite(slaveSelectPin, HIGH);
}
ADXL362.H
Code:
#include "Arduino.h"

#ifndef ADXL362_h
#define ADXL362_h

#define FILTER_CTL 0x2C
#define POWER_CTL 0x2D
#define SELF_TEST 0x2E

#define RANGE 6
#define ODR 0
#define LOW_NOISE 4

#define ADXL362_2G 0
#define ADXL362_4G 1
#define ADXL362_8G 2

#define ADXL362_NOISE 0
#define ADXL362_LOWNOISE 1
#define ADXL362_ULTRALOWNOISE 2

#define ADXL362_RATE_12_5 0 // 12.5 Hz
#define ADXL362_RATE_25   1 // 25 Hz
#define ADXL362_RATE_50   2 // 50 Hz
#define ADXL362_RATE_100  3 // 100 Hz (reset default)
#define ADXL362_RATE_200  4 // 200 Hz
#define ADXL362_RATE_400  7 // 400 Hz

class ADXL362
{
public:

	ADXL362();
	
	//
	// Basic Device control and readback functions
	//
	void begin(int16_t chipSelectPin = 10); 		
	void beginMeasure(); 
	int16_t readXData();
	int16_t readYData();
	int16_t readZData();
	void readXYZTData(int16_t &XData, int16_t &YData, int16_t &ZData, int16_t &Temperature);
	int16_t readTemp();
	void setRange(int sense);
	void setODR(int rate);
	void setNoise(int rate);
	void setSELFTEST(int val);
	
	//
	// Activity/Inactivity interrupt functions
	//
	void setupDCActivityInterrupt(int16_t threshold, byte time);	
	void setupDCInactivityInterrupt(int16_t threshold, int16_t time);
    void setupACActivityInterrupt(int16_t threshold, byte time);
	void setupACInactivityInterrupt(int16_t threshold, int16_t time);
	
	// TODO: 
	// void mapINT1
	// void mapINT2
	// void autoSleep
	// void activityInterruptControl
	//		- Activity, Inactivity, Both
	//		- Referenced, Absolute
	//		- Free Fall, Linked Mode, Loop Mode
	
	void checkAllControlRegs();
	
	//remove:
	byte SPIreadOneRegister(byte regAddress);
private:
	//  Low-level SPI control, to simplify overall coding
	//byte SPIreadOneRegister(byte regAddress);
	void SPIwriteOneRegister(byte regAddress, byte regValue);
	int16_t  SPIreadTwoRegisters(byte regAddress);
	void SPIwriteTwoRegisters(byte regAddress, int16_t twoRegValue);
	
};

#endif
 
Haven't gone through all your code yet, but I would suggest using the standard SD library for now to make sure all your hardware connections are correct. The only thing that stands out to me in your code is that you're not using the SPI.beginTransaction() and SPI.endTransaction() in your ADXL362 library. If you only use SPI.transfer() you may not be sending anything, and you may have the SPI hardware configured incorrectly for whichever peripheral you are trying to talk to.
 
Hmmm.. actually, I took another look and there's quite a few problems here. I would really recommend using the much simpler SPI and SD libraries. They will simplify your code greatly. But a couple things I've noticed so far, about the SCK on pin 14, that's fine, I do that all the time, but you have to call it before SPI.begin(). And you can do this using SPI.setSCK(14) instead of the CORE_PIN... calls. In addition, you are calling SPI.begin() in multiple places, which I think is okay, but unnecessary, and most importantly, you're not calling SPI.beginTransaction() anywhere! First thing for you to do is check out some of the example sketches using the SPI and SD libraries, then go from there. Good luck!
 
Try a weakish pullup resistor on the slave select lines (between the line and 3.3v).
A value of 10k should do.

Alternatively, on your slave select initialisation pins, use:
Code:
pinMode(<pin>, INPUT_PULLUP);

I always prefer the hardware method though; can save a lot of time and effort (and money in a commercial setting) if you mess with your code and lose the pullups for whatever reason.
 
Thanks to both! I used a 20K pullup resistor on both CS pins and that solved the problem. To think 15 hours over 2 days all solved with a 10cent resistor, over something I probably should have known beforehand... knowledge is indeed quite valuable.

Capricorn, I did end up using the SD library instead of SD-Fat, but the ADXL library does have a SPI.transfer function in the readXYZ function :)

Now I'm running into the speed limitation of SD library to log data at 100 entries/sec, but that problem is more well-defined!

Try a weakish pullup resistor on the slave select lines (between the line and 3.3v).
A value of 10k should do.

Alternatively, on your slave select initialisation pins, use:
Code:
pinMode(<pin>, INPUT_PULLUP);

I always prefer the hardware method though; can save a lot of time and effort (and money in a commercial setting) if you mess with your code and lose the pullups for whatever reason.
 
That's great to hear.
(For anyone who stumbles across this thread wondering why pullups are required: http://www.dorkbotpdx.org/blog/paul/better_spi_bus_design_in_3_steps)

We may be able to provide help with writing the data more efficiently, if you can provide us with the sketch you're using?
The datasheet for the chip suggests you can get readings at up to 400Hz by setting the ODR correctly, but your initialization routine (in the code you initially provided) is only setting it to 100 using the library function.
Code:
   xl.setODR(ADXL362_RATE_100);
 
Last edited:
Thanks Cosford. It's nice to see that there are strangers out there willing to help out other strangers :)

I misspoke that I'm having trouble writing the data fast enough. More accurately, every ~20th data reading gets slightly corrupted when I have the SD card writing data. The X value jumps from -20ish to +16. The Y,Z,Temp seem fine.

Also, when I tried to use the trick here to speed up the writing, I get those erroneously positive measurements 1 out of every ~2 measurements, instead of 1 out of every 20 or so.

Maybe it has to do with my unsophisticated way of getting 100 readings a second? I am simply applying a 10 ms delay between reads, instead of synchronizing with the Accelerometer. My guess is that I'm messing up some synchronization with the delays. Eventually I want to run this off a few Alkaline AA batteries, and plan to implement a sleep-wake cycle/FIFO buffer writing to greatly reduce my power consumption like post #9 here



Serial Output of Read-Write: Initialize SD card, and write to file. (Erroneous values bolded)
Code:
0,-20,-13,1216,600
10,-16,-13,1212,600
20,-20,-15,1216,600
31,-20,-13,1217,600
41,-17,-15,1216,600
51,-16,-13,1216,598
61,-18,-16,1216,600
71,-20,-13,1216,600
[B]83,16,-16,1217,600
[/B]93,-17,-13,1216,600
103,-17,-16,1216,600
114,-18,-16,1216,600
124,-18,-13,1216,601
134,-17,-16,1216,599
144,-17,-15,1217,598
154,-17,-13,1216,600
164,-17,-15,1216,600
174,-18,-15,1216,600
184,-17,-16,1219,600
194,-17,-16,1216,599
204,-16,-13,1217,600
214,-16,-16,1216,600
224,-20,-15,1219,600
235,-20,-16,1219,600
245,-16,-13,1217,600
255,-18,-13,1214,600
265,-18,-15,1215,599
275,-20,-16,1215,599
285,-17,-16,1212,599
295,-20,-13,1216,600
305,-18,-15,1216,600
315,-20,-13,1216,599
[B]329,19,-16,1216,600
[/B]339,-15,-15,1215,600
349,-20,-16,1215,599
359,-23,-15,1216,600
369,-18,-16,1216,600
379,-18,-13,1216,600
389,-18,-14,1216,600
399,-18,-15,1215,600
409,-16,-13,1217,600
419,-18,-16,1215,600
429,-18,-16,1216,600
439,-18,-16,1216,600
450,-16,-13,1215,600
460,-18,-16,1216,600
470,-20,-15,1219,600
480,-16,-16,1214,600
490,-16,-13,1215,599
500,-18,-13,1216,600
510,-18,-15,1216,598
520,-18,-15,1216,599
530,-20,-16,1216,600
540,-17,-16,1215,600
550,-18,-15,1215,600
[B]562,19,-15,1223,600
[/B]572,-16,-16,1219,599
582,-23,-13,1219,599
592,-20,-13,1216,598
602,-16,-15,1216,599
612,-16,-13,1216,600
622,-16,-16,1216,600
633,-20,-15,1219,599
643,-18,-16,1216,600
653,-17,-15,1215,600
663,-18,-16,1216,600
673,-18,-16,1216,600
683,-16,-13,1217,600
693,-20,-13,1215,600
703,-20,-12,1216,600
713,-18,-16,1216,600
723,-20,-16,1216,600
733,-20,-15,1219,599
743,-15,-15,1215,599
753,-20,-15,1217,600
764,-18,-12,1215,599
774,-20,-15,1216,599
784,-20,-13,1216,599
[B]795,16,-16,1216,600
[/B]805,-17,-16,1219,598
815,-20,-15,1216,600
826,-20,-13,1216,598
836,-20,-15,1217,600
846,-20,-13,1216,600
856,-17,-16,1217,599
866,-17,-13,1216,600
876,-18,-16,1216,600
886,-16,-16,1212,599
896,-18,-15,1216,599
906,-17,-13,1216,599
916,-18,-13,1215,600
926,-17,-16,1216,598
936,-20,-15,1217,600
947,-18,-15,1216,600
957,-17,-16,1217,600
967,-20,-15,1215,599
977,-20,-15,1216,600
987,-16,-13,1216,599
997,-18,-15,1216,600
1007,-18,-16,1216,600
1017,-18,-16,1216,600
[B]1029,16,-16,1209,604
[/B]1039,-16,-16,1215,600
1049,-16,-15,1217,599
1059,-18,-15,1216,600
1069,-18,-13,1214,600
1079,-20,-15,1216,600
1089,-20,-15,1217,599
1099,-18,-16,1216,600
1109,-16,-15,1216,599
1119,-18,-16,1216,600
1130,-16,-12,1214,600
1140,-17,-16,1216,600
1150,-20,-16,1216,600
1160,-18,-16,1216,600
1170,-20,-13,1216,600
1180,-20,-16,1216,600
1190,-16,-13,1217,600
1200,-18,-15,1216,600
1210,-20,-16,1216,600
1220,-18,-16,1216,600
1230,-18,-16,1216,600
1240,-18,-15,1216,600
1251,-18,-15,1216,599
[B]1262,17,-15,1217,599
[/B]1272,-16,-16,1217,600
1282,-20,-16,1216,600
1292,-20,-13,1217,600
1302,-20,-13,1219,600
1312,-16,-13,1215,600
1323,-18,-15,1216,600
1333,-18,-13,1215,600
1343,-19,-16,1216,600
1353,-20,-13,1214,600
1363,-17,-13,1216,599
1373,-17,-16,1216,600
1383,-17,-15,1216,599
1393,-16,-13,1215,600
1403,-18,-15,1215,599
1413,-20,-13,1216,600
1423,-16,-13,1215,600
1433,-17,-15,1216,600
1444,-17,-15,1216,599
1454,-16,-13,1216,601
1464,-16,-16,1216,599
1474,-18,-15,1219,600
1485,16,-15,1208,599
1495,-16,-13,1209,598
1506,-20,-13,1219,600
1516,-17,-13,1214,600
1526,-18,-13,1216,600
1536,-17,-15,1216,600
1546,-18,-16,1216,600
1556,-20,-13,1214,600
1566,-20,-16,1216,600
1576,-17,-13,1216,599
1586,-16,-16,1216,600
1596,-16,-13,1217,598
1606,-18,-13,1216,599
1616,-18,-16,1216,600
1627,-20,-16,1216,600
1637,-20,-16,1216,600
1647,-16,-13,1216,600
1657,-18,-15,1216,599
1667,-17,-16,1216,600
1677,-18,-17,1216,600
1687,-17,-16,1216,600
1697,-17,-15,1216,600
[B]1709,19,-13,1223,600
[/B]1719,-16,-16,1216,600
1729,-20,-15,1217,600
1739,-18,-16,1217,600
1749,-20,-16,1216,600
1759,-20,-15,1216,600
1769,-17,-16,1216,600
1779,-17,-16,1216,599
1789,-18,-17,1216,600
1799,-18,-13,1216,600
1810,-18,-16,1217,600
1820,-16,-15,1216,600
1830,-17,-16,1219,600
1840,-18,-13,1216,599
1850,-20,-16,1216,600
1860,-17,-16,1217,600
1870,-16,-15,1216,600
1880,-16,-15,1215,600
1890,-16,-16,1216,599
1900,-17,-15,1216,598
1910,-17,-15,1216,600
1920,-20,-16,1219,599
1931,-16,-13,1216,600
[B]1942,15,-15,1216,600
[/B]1952,-18,-16,1216,600
1962,-20,-16,1216,601
1972,-16,-13,1214,600
1982,-17,-15,1216,600
1993,-16,-12,1216,600
2003,-18,-15,1219,601
2013,-18,-15,1216,600
2023,-20,-13,1214,600
2033,-17,-16,1217,599
2043,-20,-15,1216,600
2053,-18,-16,1217,600
2063,-17,-15,1216,600
2073,-17,-16,1217,600
2083,-17,-13,1217,600
2093,-18,-12,1215,600
2103,-18,-10,1215,600
2114,-20,-15,1216,600
2124,-18,-16,1215,600
2134,-18,-15,1215,600
2144,-17,-16,1219,600
2154,-18,-16,1216,600
[B]2165,15,-16,1212,600
[/B]2176,-18,-16,1216,600
2186,-21,-16,1219,600
2196,-20,-16,1216,600
2206,-20,-15,1215,600
2216,-16,-15,1219,600
2226,-16,-17,1216,600
2236,-16,-16,1215,600
2246,-18,-16,1216,599
2256,-18,-15,1216,600
2266,-17,-15,1215,599
2276,-16,-16,1216,596
2286,-16,-16,1216,600
2297,-18,-16,1216,600
2307,-17,-16,1216,598
2317,-17,-15,1217,598
2327,-18,-13,1215,600
2337,-20,-15,1219,599
2347,-20,-10,1217,600
2357,-20,-15,1216,600
2367,-18,-15,1215,599
2377,-20,-15,1216,600
[B]2392,14,-13,1219,600
[/B]2403,-18,-13,1216,599
2413,-17,-13,1216,600
2423,-20,-16,1216,600
2433,-18,-15,1216,600
2443,-18,-13,1216,599
2453,-20,-15,1216,600
2463,-16,-16,1217,600
2473,-20,-16,1217,600
2483,-16,-13,1216,600
2493,-17,-13,1214,600
2503,-18,-16,1219,600
...

Serial Output of Read-Only: No SD card initialized, nothing written to file.
Code:
0,16,-18,1311,604
10,-32,-20,1217,604
20,-20,-13,1216,606
30,-20,-9,1216,604
40,-17,-13,1215,604
50,-17,-13,1216,604
60,-20,-16,1219,604
70,-18,-13,1215,604
80,-23,-13,1216,601
90,-20,-16,1216,604
100,-21,-16,1216,604
110,-20,-15,1216,604
120,-17,-13,1216,604
130,-20,-13,1216,604
140,-20,-13,1216,606
150,-20,-15,1216,604
161,-20,-12,1216,606
171,-20,-15,1216,604
181,-20,-13,1216,601
191,-20,-16,1216,604
201,-18,-13,1215,604
211,-20,-16,1215,604
221,-20,-16,1216,604
231,-18,-13,1217,604
241,-18,-15,1216,604
251,-16,-16,1219,601
261,-20,-10,1217,604
271,-20,-13,1216,604
281,-20,-16,1216,604
291,-20,-13,1216,604
301,-20,-15,1216,603
311,-20,-10,1216,604
321,-20,-16,1216,606
331,-20,-13,1217,604
341,-20,-13,1216,604
352,-20,-13,1216,604
362,-20,-13,1216,603
372,-20,-16,1217,604
382,-20,-15,1216,604
392,-20,-16,1216,604
402,-18,-13,1216,604
412,-20,-13,1217,606
422,-18,-13,1215,604
432,-20,-16,1216,603
442,-23,-15,1216,606
452,-20,-15,1216,604
462,-20,-13,1219,603
472,-20,-13,1219,603
482,-23,-15,1217,601
492,-20,-13,1216,604
502,-20,-13,1216,603
512,-20,-13,1216,603
522,-20,-13,1217,604
533,-18,-16,1216,604
543,-17,-16,1216,601
553,-18,-16,1216,607
563,-23,-16,1216,604
573,-17,-12,1216,604
583,-16,-13,1215,604
593,-20,-16,1216,603
603,-18,-9,1216,604
613,-20,-13,1215,606
623,-20,-12,1217,601
633,-17,-13,1216,601
643,-21,-13,1216,603
653,-20,-15,1215,601
663,-20,-13,1216,604
673,-18,-14,1217,606
683,-20,-15,1216,604
693,-18,-15,1216,603
703,-20,-13,1216,601
713,-20,-13,1216,604
724,-20,-13,1216,604
734,-18,-13,1216,604
744,-18,-16,1216,604
754,-17,-13,1216,601
764,-18,-16,1215,604
774,-20,-15,1217,604
784,-18,-13,1216,604
794,-20,-15,1216,604
804,-18,-15,1216,606
814,-20,-13,1216,603
824,-20,-15,1216,604
834,-18,-16,1216,606
844,-20,-15,1216,603
854,-20,-16,1219,604
864,-20,-13,1217,604
874,-20,-13,1217,606
884,-21,-10,1216,603
894,-23,-13,1216,604
905,-20,-15,1216,604
915,-20,-15,1216,604
925,-24,-13,1216,604
935,-20,-13,1212,604
945,-21,-16,1216,606
955,-20,-13,1216,603
965,-17,-13,1217,606
975,-20,-13,1219,601
985,-17,-13,1216,603
995,-18,-13,1216,604
1005,-18,-13,1216,604
1015,-18,-15,1216,603
1025,-20,-16,1219,604
1035,-18,-15,1217,603
1045,-18,-13,1216,604
1055,-20,-16,1215,607
1065,-18,-13,1214,603
1075,-18,-10,1216,604
1085,-20,-15,1214,606
1096,-17,-13,1216,604
1106,-20,-13,1216,604
1116,-17,-13,1216,604
1126,-20,-16,1216,604
1136,-20,-15,1217,604
1146,-21,-16,1216,604
1156,-20,-16,1216,604
1166,-21,-13,1216,604
1176,-17,-13,1216,603
1186,-18,-15,1216,604
1196,-20,-16,1219,603
1206,-18,-13,1216,603
1216,-20,-16,1216,604
1226,-18,-15,1215,604
1236,-18,-10,1216,603
1246,-17,-13,1216,603
1256,-18,-16,1216,604
1266,-20,-13,1216,604
1277,-20,-13,1216,604
1287,-23,-15,1216,604
1297,-20,-16,1215,603
1307,-18,-10,1216,604
1317,-18,-16,1216,603
1327,-18,-15,1219,604
1337,-18,-16,1217,604
1347,-17,-13,1216,604
1357,-20,-12,1216,604
1367,-18,-15,1216,607
1377,-18,-13,1216,604
1387,-20,-10,1216,604
1397,-18,-13,1216,603
1407,-20,-13,1216,603
1417,-20,-15,1216,604
1427,-23,-16,1217,604
1437,-20,-15,1215,604
1447,-20,-16,1216,604
1458,-18,-13,1216,604
1468,-18,-13,1217,603
1478,-21,-13,1217,603
1488,-20,-15,1214,604
1498,-18,-15,1216,604
1508,-20,-13,1215,606
1518,-20,-12,1215,606
1528,-16,-13,1216,603
1538,-16,-15,1216,604
1548,-20,-15,1216,604
1558,-18,-13,1216,604
1568,-20,-14,1216,604
1578,-18,-13,1216,604
1588,-21,-13,1217,606
1598,-20,-15,1219,604
1608,-16,-15,1216,603
1618,-20,-15,1216,603
1628,-18,-13,1216,608
1639,-17,-16,1217,604
1649,-20,-16,1216,604
1659,-20,-15,1216,604
1669,-20,-10,1216,604
1679,-16,-13,1216,604
1689,-21,-12,1216,603
1699,-20,-16,1217,604
1709,-18,-15,1217,606
1719,-20,-13,1217,603
1729,-17,-13,1214,604
1739,-20,-15,1216,606
1749,-18,-13,1216,604
1759,-20,-15,1216,607
1769,-17,-13,1216,601
1779,-17,-13,1217,604
1789,-18,-13,1219,601
1799,-18,-13,1216,604
1809,-20,-15,1215,604
1819,-20,-13,1216,604
1830,-20,-13,1215,601
1840,-18,-13,1216,606
1850,-20,-10,1217,604
1860,-20,-15,1216,604
1870,-20,-15,1215,604
1880,-20,-13,1216,606
1890,-17,-13,1219,604
1900,-21,-13,1219,604
1910,-20,-16,1216,604
1920,-17,-10,1216,603
1930,-20,-15,1216,604
1940,-21,-15,1215,604
1950,-20,-16,1216,604
1960,-20,-15,1216,604
1970,-20,-16,1216,604
1980,-23,-15,1216,604
1990,-18,-16,1215,604
2000,-18,-15,1216,606
2011,-20,-12,1217,607
2021,-17,-9,1216,604
2031,-17,-13,1216,604
2041,-17,-13,1217,604
2051,-20,-13,1216,603
2061,-20,-18,1219,604
2071,-21,-16,1212,606
2081,-17,-15,1214,604
2091,-16,-13,1216,603
2101,-20,-13,1215,601
2111,-20,-13,1215,604
2121,-18,-15,1216,601
2131,-16,-15,1216,604
2141,-18,-13,1215,603
2151,-20,-15,1219,604
2161,-20,-15,1219,604
2171,-20,-13,1215,606
2181,-20,-15,1216,606
2192,-16,-15,1216,606
2202,-17,-13,1216,603
2212,-20,-12,1215,604
2222,-20,-15,1212,603
2232,-21,-15,1216,606
2242,-20,-15,1215,608
2252,-20,-13,1216,606
2262,-20,-15,1216,603
2272,-20,-13,1215,604
2282,-20,-13,1216,604
2292,-18,-16,1216,604
2302,-21,-13,1219,603
2312,-20,-12,1214,606
2322,-20,-10,1215,604
2332,-16,-10,1215,603
2342,-20,-15,1216,606
2352,-16,-13,1216,604
2362,-20,-15,1215,604
2372,-18,-13,1215,604
2383,-17,-13,1216,604
2393,-18,-13,1216,604
2403,-17,-13,1219,603
2413,-20,-15,1216,604
2423,-17,-13,1216,604
2433,-20,-13,1216,604
2443,-20,-15,1216,607
2453,-18,-12,1217,604
2463,-18,-16,1219,604
2473,-18,-16,1215,600
2483,-20,-13,1216,604
2493,-23,-13,1216,604
2503,-18,-15,1216,604
...

ADXL362_ReadSave.ino (I comment out the File-writing lines to get the Read-Only version)
Code:
#include <SPI.h>
#include <ADXL362.h>
#include <SD.h>

#define SD_SS 10 //SD Card Slave Select
#define XL_SS 15 //ADXL Slave Select
#define VIOLATION_LED 13 //Violation Pin
#define STATUS_LED 6 //Calibration Indicator
#define INIT_SIZE 500

ADXL362 xl;
//SdFat SD;
File myFile;

int16_t XValue, YValue, ZValue, Temperature;

unsigned long starttime;
unsigned long runtime;


void setup(){

//Initialize Pins
  pinMode(XL_SS,OUTPUT);
  pinMode(SD_SS,OUTPUT);
  digitalWrite(XL_SS,HIGH);
  digitalWrite(SD_SS,HIGH);
  
 //Start Serial, get signal to start
  Serial.begin(57600);
  delay(1000);
  Serial.println(F("Send any character to start sketch.\n"));
  while (Serial.available() && Serial.read()); // empty buffer
  while (!Serial.available()){
    delay(1500);
  }                
  while (Serial.available() && Serial.read()); // empty buffer again


// Initialize SD Card
//----------------------------------------------------------------------------------------  
  digitalWrite(XL_SS,HIGH);
  digitalWrite(SD_SS,LOW);

 if (!SD.begin(SD_SS)) {
    Serial.println("SD Card initialization failed!");
    return;
  }
  Serial.println("SD Card initialization done.");

////----------------------------------------------------------------------------------------

//Initialize ADXL
//----------------------------------------------------------------------------------------  
  digitalWrite(XL_SS,LOW);
  digitalWrite(SD_SS,HIGH);
  xl.begin(XL_SS);           // Setup SPI protocol, issue device soft reset
//  xl.setNoise(ADXL362_NOISE); 
//  xl.setNoise(ADXL362_LOWNOISE); 
  xl.setNoise(ADXL362_ULTRALOWNOISE); 
  xl.setODR(ADXL362_RATE_100); 
  xl.beginMeasure();       // Switch ADXL362 to measure mode  
  
//---------------------------------------------------------------------------------------- 

// Open a File
 myFile = SD.open("Data.txt", FILE_WRITE);
//myFile = SD.open("Data2.TXT", O_CREAT | O_WRITE);
  // if the file opened okay, write to it:
  if (myFile) {
    Serial.println("Writing to SD card...");
    myFile.println("Time,X,Y,Z,Temp");
//    myFile.flush();
  } else {
    // if the file didn't open, print an error:
    Serial.println("error opening data.txt");
    delay(9000000);
  }
  delay(100);

 //---------------------------------------------------------------------------------------- 

  digitalWrite(SD_SS,HIGH); //Only one CS allowed
  starttime = millis();
}

void loop(){
    // read all three axis in burst to ensure all measurements correspond to same sample time

  xl.readXYZTData(XValue, YValue, ZValue, Temperature);  
  runtime = millis()-starttime;
  
  digitalWriteFast(SD_SS,LOW); //Only one CS allowed
  myFile.print(runtime);
  myFile.print(",");
  myFile.print(XValue);  
  myFile.print(",");
  myFile.print(YValue);  
  myFile.print(",");
  myFile.print(ZValue);  
  myFile.print(",");
  myFile.println(Temperature);
//  myFile.flush();
  digitalWriteFast(SD_SS,HIGH); //Only one CS allowed  
//  
  Serial.print(runtime);
  Serial.print(",");
  Serial.print(XValue);  
  Serial.print(",");
  Serial.print(YValue);  
  Serial.print(",");
  Serial.print(ZValue);  
  Serial.print(",");
  Serial.println(Temperature);

  if(runtime > 5000){
    myFile.close();
    Serial.println("Done!");
    delay(900000);
  }
  
  delay(10);
}
 
Last edited:
That's great to hear.
(For anyone who stumbles across this thread wondering why pullups are required: http://www.dorkbotpdx.org/blog/paul/better_spi_bus_design_in_3_steps)

We may be able to provide help with writing the data more efficiently, if you can provide us with the sketch you're using?
The datasheet for the chip suggests you can get readings at up to 400Hz by setting the ODR correctly, but your initialization routine (in the code you initially provided) is only setting it to 100 using the library function.
Code:
   xl.setODR(ADXL362_RATE_100);

The link provided would have been very helpful to me a few days ago! Thanks for sharing and hope others in my predicament see it.
 
Increasing the ADXL sampling rate to 200Hz and Teensy reading with 100Hz (10 ms delay) eliminates the problematic values, but I'm throwing away half my data, and some power. Sampling and reading at both 200 Hz (5ms), I see those problem values again.

My intuition is that the ADXL has a recovery time between updating its values and being ready for interrogation. Because I'm not synchronizing updates and interrogations, I might be periodically catching it at the wrong time. By forcing the reads update at 1/2x the sampling rate, it's mathematically impossible to catch a read during this update time.

The ADXL-362 has an external interrupt pin that I imagine for these exact conditions ... time to learn!

Not ideal, but works for now.
 
Increasing the ADXL sampling rate to 200Hz and Teensy reading with 100Hz (10 ms delay) eliminates the problematic values, but I'm throwing away half my data, and some power. Sampling and reading at both 200 Hz (5ms), I see those problem values again.

My intuition is that the ADXL has a recovery time between updating its values and being ready for interrogation. Because I'm not synchronizing updates and interrogations, I might be periodically catching it at the wrong time. By forcing the reads update at 1/2x the sampling rate, it's mathematically impossible to catch a read during this update time.

The ADXL-362 has an external interrupt pin that I imagine for these exact conditions ... time to learn!

Not ideal, but works for now.

By the sounds of it, you're on the right tracks. A quick look, (ctrl-f is a wondrous tool) shows up table 12 on page 25 of the datasheet (http://www.analog.com/media/en/technical-documentation/data-sheets/ADXL362.pdf), which presents one option - to read the status register and check a new reading is ready.
You can also use the FIFO mode of the chip to log data and fetch the contents of the last 512 samples all at once from the FIFO. Otherwise, there's options for triggering a reading at a specific time, or you can just set up an interrupt so that you can see when new data is ready by reading the logic signal from that pin. Endless options for this chip!
 
Status
Not open for further replies.
Back
Top