1
\$\begingroup\$

I am building a scanning tunneling microscope, and I need to connect to a 16 bit ADC and a 16 bit DAC to my microcontroller (Teensy 4.0).

I am focusing on the ADC currently, and I am having a kind of specific problem. I am refencing a blog about STMs and I had to change some of the parts - more specifically I switched from the Teensy 3.1 to the 4.0., which required me to change the SPIFIFO SPI library that the microcontroller was using (built into the Teensy 3.0) to Arduino's SPI.H.
So I rewrote all of the code in Arduino's SPI.h library, and all I am getting back on the serial monitor is a maxed out value for the ADC. The only thing hooked up to the ADCs inputs is a preamp/filter (I cant remember the name for it), but it is not maxing the voltage range for the ADC (16 +- volts, it is currently at 9volts on both leads to the ADC).

This is blog I am refencing, https://dberard.com/home-built-stm/

From here you can get to the wiring diagram I am using along with the original code. Dan's microscope to my understanding works great.

Wiring diagram: https://dberard.com/wp-content/uploads/2015/06/stm_analog4.pdf

I guess my question is, what would cause the ADC to report only maxed values, and how would you troubleshoot this? I think that whatever changes I made to the code is what causes it to behave this way.

Here are some clips of the code that was rewritten (this snip is a library I re-wrote to work with SPI.h for the ADC):

#include "core_pins.h"
#include "Arduino.h"
#include "LTC2326_16.h"
#include "SPI.h"
/**************************************************************************/
/*
 Constructor
*/
/**************************************************************************/
LTC2326_16::LTC2326_16(byte cs, byte cnv, byte busy)
{
 pinMode(cs, OUTPUT);
 pinMode(cnv, OUTPUT);
 pinMode(busy, INPUT);
 digitalWrite(cs, HIGH);
 digitalWrite(cnv, LOW);
 _cs = cs;
 _cnv = cnv;
 _busy = busy;
}
/**************************************************************************/
/*
 Initiate a conversion.
*/
/**************************************************************************/
void LTC2326_16::convert()
{
 digitalWrite(_cnv, HIGH);
}
/**************************************************************************/
/*
 Check whether ADC is busy doing a conversion. Returns true if conversion
 is in progress (BUSY pin is HIGH), false otherwise.
*/
/**************************************************************************/
bool LTC2326_16::busy()
{
 bool status;
 status = (bool)digitalRead(_busy);
 return status;
}
/**************************************************************************/
/*
 Setup the SPI port at 24 MHz.
*/
/**************************************************************************/
void LTC2326_16::begin()
{
 
 
 SPI.begin(); // Initialize SPI
 SPI.beginTransaction(SPISettings(24000000, MSBFIRST, SPI_MODE1)); // Set up the SPI settings (clock speed, data order, SPI mode)
}
/**************************************************************************/
/*
 Read the ADC data register.
*/
/**************************************************************************/
int16_t LTC2326_16::read()
{
 int16_t val;
 digitalWrite(_cnv, LOW); // trigger CNV 
 delayMicroseconds(1);
 val = SPI.transfer16(0); // Read the result from the ADC
 
 return val;
}

This is the controller code:

// Pin definitions:
#define CS_DAC 20 // DAC chip select pin
#define LDAC 17 // Load DAC pin, not currently used
#define CS_ADC 21 // ADC chip select pin
#define CNV 4 // ADC CNV pin - initiates a conversion
#define BUSY 3 // ADC BUSY pin
#define SERIAL_LED 0 // Indicates serial data transmission
#define TUNNEL_LED 1 // Indicates tunneling
// DAC channel addresses:
#define DAC_CH_X 2
#define DAC_CH_Y 1
#define DAC_CH_Z 0
#define DAC_CH_BIAS 3
// DAC and ADC resolution:
#define DAC_BITS 16 // Actual DAC resolution
#define POSITION_BITS 20 // Sigma-delta resolution
#define ADC_BITS 16
// Default scan settings:
#define SCAN_SIZE 100000 // ~160 nm // Scan size in LSBs
#define IMAGE_PIXELS 512 // Scan size in pixels
#define LINE_RATE 1 // Number of scan lines/second
#define SETPOINT 328 // 1 nA // Tunneling current setpoint in LSBs
#define BIAS 328 // 100 mV // Sample bias in LSBs
#define KP 0 // Proportional gain
#define KI 300000 // Integral gain
// Constants:
#define INVERT_Z true // Inverts the Z output signal from the DAC
#define ENGAGE_SCANNER_STEP_SIZE 50 // Number of LSBs to step the scanner by during engage
#define ENGAGE_MOTOR_STEP_SIZE 1 // Number of steps to move the motor by during engage
#define dt 40 // Time step for scanning and PI control in microseconds
#define DATA_BUFFER_LENGTH 16386 // Number of bytes in each ping-pong buffer for data storage. Need 2 bytes for line number + 16 bytes/pixel.
#define SCAN_COUNTER_LIMIT 0x40000000 // Scan counter counts from -SCAN_COUNTER_LIMIT to SCAN_COUNTER_LIMIT-1
/**************************************************************************/
#include "logTable.h"
#include <SPI.h>
#include "DAC8814.h"
#include "LTC2326_16.h"
/**************************************************************************/
/*
 Variable declarations
*/
/**************************************************************************/
// Scan parameters:
float lineRate = LINE_RATE; // Scan lines per second
unsigned int pixelsPerLine = IMAGE_PIXELS * 2;
unsigned int samplesPerPixel;
int scanSize = SCAN_SIZE; // Size of the scan in LSBs
int bias = BIAS; // Sample bias in LSBs
boolean scanningEnabled = false;
boolean engaged = false;
// Scan counters. Counts from -SCAN_COUNTER_LIMIT to SCAN_COUNTER_LIMIT - 1
// regardless of scan size, then counts back down when the scan direction reverses.
volatile int xCount = -SCAN_COUNTER_LIMIT; // X-axis scan counter
volatile int yCount = -SCAN_COUNTER_LIMIT; // Y-axis scan counter
volatile int dx = 0, dy = 0; // Scan counter increments
// Sample, pixel and line counters:
volatile unsigned int sampleCounter = 0, pixelCounter = 0, lineCounter = 0;
volatile int zAvg = 0, eAvg = 0; // Accumulates Z and error samples for later averaging
// Ping-pong buffers:
byte data1[DATA_BUFFER_LENGTH], data2[DATA_BUFFER_LENGTH]; // Data buffers
volatile boolean fillData1 = true; // Indicates which buffer to fill
volatile boolean sendData = false; // Indicates that data is ready to be sent over USB
boolean serialEnabled = false; // Enables serial transfer of data
// Position variables:
const int MAX_Z = (1 << (POSITION_BITS - 1)) - 1; // Maximum Z value
int xo = 0, yo = 0; // Scan offsets
volatile int x = 0, y = 0, z = 0; // Scanner coordinates in LSBs
// PI variables:
boolean pidEnabled = true; // Setting this to false desiables PI control
int setpoint = SETPOINT, setpointLog; // setpointLog = log(|setpoint|)
int Kp = KP, Ki = KI; // Proportional and integral gains
volatile int16_t input; // ADC input data 
volatile int error = 0; // PID error signal
volatile int64_t iTerm = 0; // Integral term
const int64_t MAX_ITERM = MAX_Z * 0x100000000; // Maximum integral term. Used to prevent windup.
// Sigma-delta variables:
int sigmaX = 0, sigmaY = 0, sigmaZ = 0; // Sigma-delta integrators
const unsigned int shift = POSITION_BITS - DAC_BITS; // Number of bits to increase DAC resolution by using sigma-delta algorithm
// Timers:
IntervalTimer scanTimer;
// Data converters:
DAC8814 dac(CS_DAC, LDAC); // 16-bit quad DAC
LTC2326_16 adc(CS_ADC, CNV, BUSY); // 16-bit ADC
const int MAX_DAC_OUT = (1 << (DAC_BITS - 1)) - 1; // DAC upper bound
const int MIN_DAC_OUT = -(1 << (DAC_BITS - 1)); // DAC lower bound
boolean saturationCompensation = true; // The LTC2326-16 seems to output 0 when its input saturates. This is a temporary fix.
/**************************************************************************/
/*
 Setup
*/
/**************************************************************************/
void setup()
{
 pinMode(SERIAL_LED, OUTPUT);
 pinMode(TUNNEL_LED, OUTPUT);
 digitalWrite(SERIAL_LED, LOW);
 digitalWrite(TUNNEL_LED, LOW);
 // Set the sample bias:
 dac.begin();
 dac.setOutput((uint16_t)(bias + MAX_DAC_OUT + 1), DAC_CH_BIAS);
 
 setpointLog = logTable[abs(SETPOINT)]; // Take the log of the setpoint
 updateStepSizes(); // Compute the scan counter step sizes 
 adc.convert(); // Start an ADC conversion
 // Start the scan/PI/sigma-delta timer:
 scanTimer.priority(0);
 scanTimer.begin(incrementScan, dt);
}
/**************************************************************************/
/*
 Loop
*/
/**************************************************************************/
void loop()
{
 checkSerial(); // Check for incoming serial commands. See "SerialCommands" tab.
 
 // Illuminate tunelling LED if the tunneling current is > setpoint/2:
 if(abs(input) > setpoint >> 1) digitalWriteFast(TUNNEL_LED, HIGH);
 else digitalWriteFast(TUNNEL_LED, LOW); 
 
 // Send data over USB if a line has been scanned and re-scanned:
 if(sendData)
 { 
 if(!fillData1) // Print data1
 {
 data1[0] = (byte)((lineCounter >> 8) & 0xFF); // High byte
 data1[1] = (byte)(lineCounter & 0xFF); // Low byte
 
 if(serialEnabled)
 {
 Serial.println("DATA");
 Serial.write(data1, DATA_BUFFER_LENGTH);
 }
 
 // Uncomment this block to print human-readable data to the serial port:
 
 for(unsigned int i = 0; i < pixelsPerLine * 2; i++) // Loop over pixels
 {
 //un-slash the 2 lines before to get original code 
 Serial.print((int)((int)data1[4*i+2] << 24 | (int)data1[4*i+3] << 16 |(int)data1[4*i+4] << 8 |(int)data1[4*i+5]));
 Serial.print(" ");
 }
 
 }
 else
 {
 data2[0] = (byte)((lineCounter >> 8) & 0xFF); // High byte
 data2[1] = (byte)(lineCounter & 0xFF); // Low byte
 
 if(serialEnabled)
 {
 Serial.println("DATA");
 Serial.write(data2, DATA_BUFFER_LENGTH);
 }
 
 // Uncomment this block to print human-readable data to the serial port:
 
 for(unsigned int i = 0; i < pixelsPerLine * 2; i++) // Loop over pixels
 {
 Serial.print((int)((int)data2[4*i+2] << 24 | (int)data2[4*i+3] << 16 |(int)data2[4*i+4] << 8 |(int)data2[4*i+5]));
 Serial.print(" ");
 }
 
 }
 Serial.println();
 
 sendData = false;
 }
}
/**************************************************************************/
/*
 Increment the scan, perform PI calculations, sigma-delta calculations,
 update the x, y and z DACs, store data in buffers.
*/
/**************************************************************************/
void incrementScan(void) // This interrupt runs in about ~18 us at 96 MHz
{ 
 static int xout, yout, zout;
 static int64_t pTerm;
 
 //////////////////////////////////////////////////////////////////////
 // Increment the scan:
 //////////////////////////////////////////////////////////////////////
 
 if(scanningEnabled)
 {
 if(xCount <= -SCAN_COUNTER_LIMIT || xCount >= SCAN_COUNTER_LIMIT - 1 - dx) dx = -dx; // Reverse at the end of a line
 xCount += dx;
 x = (int)(((int64_t)xCount * (int64_t)scanSize) >> 31) + xo;
 if(yCount <= -SCAN_COUNTER_LIMIT || yCount >= SCAN_COUNTER_LIMIT - 1 - dy) dy = -dy; // Reverse and the end of a scan
 yCount += dy;
 y = (int)(((int64_t)yCount * (int64_t)scanSize) >> 31) + yo;
 if(yCount <= -SCAN_COUNTER_LIMIT) lineCounter = 0; // Just in case the scan and acquisition become desynchronized...
 }
 
 //////////////////////////////////////////////////////////////////////
 // Perform PI calculations:
 //////////////////////////////////////////////////////////////////////
 
 adc.begin(); // Set up the SPI port to communicate with the ADC
 input = adc.read(); // Read the ADC data over SPI
 //Serial.print(input);
 if(saturationCompensation & (input == 0) & (z != -MAX_Z)) input = 32767; // Compensate for the LTC2326-16 saturation issue
 error = logTable[abs((int16_t)input)] - setpointLog; // Negative error = tip too far from sample
 
 if(pidEnabled)
 {
 pTerm = (int64_t)Kp * (int64_t)error;
 iTerm += (int64_t)Ki * (int64_t)error;
 if(iTerm > MAX_ITERM) iTerm = MAX_ITERM; // Constrain the integral term to prevent windup
 else if (iTerm < -MAX_ITERM) iTerm = -MAX_ITERM;
 z = (int)(((pTerm + iTerm) >> 32) & 0xFFFFFFFF);
 z = saturate(z, MAX_Z, -MAX_Z);
 }
 adc.convert(); // Initiate a new conversion. Data will be ready by the next time this interrupt runs. 
 
 
 //////////////////////////////////////////////////////////////////////
 // Perform sigma-delta calculations and update scanner DACs:
 //////////////////////////////////////////////////////////////////////
 
 dac.begin();
 xout = sigmaDelta(x, &sigmaX, shift);
 xout = saturate(xout, MAX_DAC_OUT, MIN_DAC_OUT);
 dac.setOutput((uint16_t)(xout + MAX_DAC_OUT + 1), DAC_CH_X);
 yout = sigmaDelta(y, &sigmaY, shift);
 yout = saturate(yout, MAX_DAC_OUT, MIN_DAC_OUT);
 dac.setOutput((uint16_t)(yout + MAX_DAC_OUT + 1), DAC_CH_Y);
 zout = sigmaDelta(z, &sigmaZ, shift);
 if(INVERT_Z) zout = -zout;
 zout = saturate(zout, MAX_DAC_OUT, MIN_DAC_OUT);
 dac.setOutput((uint16_t)(zout + MAX_DAC_OUT + 1), DAC_CH_Z);
 
 //////////////////////////////////////////////////////////////////////
 // Store data in buffer arrays and update counters:
 //////////////////////////////////////////////////////////////////////
 
 if(scanningEnabled)
 {
 zAvg += z; // Accumulate data for averaging
 eAvg += error;
 sampleCounter++;
 
 if(sampleCounter >= samplesPerPixel) // If enough samples have been acquired for one pixel
 {
 unsigned int indexZ = (pixelCounter << 2) + 2; // Index for Z data point in data buffer
 unsigned int indexE = indexZ + (pixelsPerLine << 2); // Index for error data point in data buffer
 
 zAvg = zAvg / (int)samplesPerPixel; // Compute the average of acquired samples
 eAvg = eAvg / (int)samplesPerPixel;
 
 if(fillData1)
 {
 data1[indexZ] = (byte)((zAvg >> 24) & 0xFF); // High byte Z
 data1[indexZ + 1] = (byte)((zAvg >> 16) & 0xFF);
 data1[indexZ + 2] = (byte)((zAvg >> 8) & 0xFF);
 data1[indexZ + 3] = (byte)(zAvg & 0xFF); // Low byte Z
 data1[indexE] = (byte)((eAvg >> 24) & 0xFF); // High byte E
 data1[indexE + 1] = (byte)((eAvg >> 16) & 0xFF);
 data1[indexE + 2] = (byte)((eAvg >> 8) & 0xFF);
 data1[indexE + 3] = (byte)(eAvg & 0xFF); // Low byte E
 }
 else
 {
 data2[indexZ] = (byte)((zAvg >> 24) & 0xFF); // High byte Z
 data2[indexZ + 1] = (byte)((zAvg >> 16) & 0xFF);
 data2[indexZ + 2] = (byte)((zAvg >> 8) & 0xFF);
 data2[indexZ + 3] = (byte)(zAvg & 0xFF); // Low byte Z
 data2[indexE] = (byte)((eAvg >> 24) & 0xFF); // High byte E
 data2[indexE + 1] = (byte)((eAvg >> 16) & 0xFF);
 data2[indexE + 2] = (byte)((eAvg >> 8) & 0xFF);
 data2[indexE + 3] = (byte)(eAvg & 0xFF); // Low byte E
 }
 pixelCounter++; 
 sampleCounter = 0;
 zAvg = 0;
 eAvg = 0;
 
 if(pixelCounter >= pixelsPerLine)
 {
 pixelCounter = 0;
 fillData1 = !fillData1;
 sendData = true;
 lineCounter++;
 if(lineCounter >= pixelsPerLine)
 {
 lineCounter = 0;
 }
 }
 }
 }
}
/**************************************************************************/
/*
 Sigma delta. Used to produce a PWM output between LSBs of a DAC to 
 effectively increase its resolution. The DAC output must be low-pass 
 filtered to smooth out the PWM.
 
 Based on Tim Wescott's example here:
 http://www.embedded.com/design/configurable-systems/4006431/Sigma-delta-techniques-extend-DAC-resolution
*/
/**************************************************************************/
int sigmaDelta(int in, int *sigma, unsigned int shift)
{
 int out;
 
 *sigma += in; // Add desired input to sigma-delta integrator
 out = *sigma >> shift; // Truncate to the number of actual DAC bits
 *sigma -= out << shift; // Shift the DAC output value and subtract it from the integrator
 return out;
}
 
/**************************************************************************/
/*
 Saturate a value if it falls outside of max or min
*/
/**************************************************************************/
int saturate(int val, int max, int min)
{
 if(val > max) val = max;
 else if (val < min) val = min;
 return val;
}
/**************************************************************************/
/*
 This function updates scan stepsizes without changing the scan direction.
*/
/**************************************************************************/
void updateStepSizes()
{
 unsigned int new_samplesPerPixel = (unsigned int)(1000000.0f / (lineRate * (float)dt * (float)pixelsPerLine));
 int new_dx = (SCAN_COUNTER_LIMIT - 1)/ ((int)new_samplesPerPixel * (int)pixelsPerLine) * 4;
 int new_dy = new_dx / (int)pixelsPerLine;
 
 noInterrupts();
 samplesPerPixel = new_samplesPerPixel;
 if(dx > 0) dx = new_dx;
 else dx = -new_dx;
 if(dy > 0) dy = new_dy;
 else dy = -new_dy;
 interrupts();
}
/**************************************************************************/
/*
 Move the scanner to the scan start position.
*/
/**************************************************************************/
void resetScan()
{
 int xStart = -(scanSize >> 1) + xo;
 int yStart = -(scanSize >> 1) + yo;
 
 scanningEnabled = false; // disable scanning
 
 // Reset counters etc:
 noInterrupts();
 xCount = -SCAN_COUNTER_LIMIT;
 yCount = -SCAN_COUNTER_LIMIT;
 dx = 0;
 dy = 0;
 updateStepSizes(); // Re-calculate step sizes
 sampleCounter = 0;
 pixelCounter = 0;
 lineCounter = 0;
 zAvg = 0;
 eAvg = 0;
 fillData1 = true;
 interrupts();
 
 // Move to start position:
 moveTip(xStart, yStart);
}
/**************************************************************************/
/*
 Move from (x,y) to (xf,yf). The tip moves at the current scanning speed.
*/
/**************************************************************************/
void moveTip(int xf, int yf)
{
 int stepSize = abs((int)(((int64_t)dx * (int64_t)scanSize) >> 31));
 
 scanningEnabled = false;
 
 while (x > xf) {
 x -= stepSize;
 waitTimeStep(); // Wait for incrementScan() to update the DAC
 }
 while (x < xf) {
 x += stepSize;
 waitTimeStep();
 }
 while (y > yf) {
 y -= stepSize;
 waitTimeStep();
 }
 while (y < yf) {
 y += stepSize;
 waitTimeStep();
 }
}
/**************************************************************************/
/*
 Wait for on time interval dt.
*/
/**************************************************************************/
void waitTimeStep()
{
 unsigned int t = micros();
 while (micros() - t <= dt)
 {
 // Wait...
 }
}
/**************************************************************************/
/*
 Currently, this function only starts the scan and enables the Z feedback
 loop. For use with manual coarse approach. Will be replaced later with 
 a motorized approach function.
*/
/**************************************************************************/
boolean engage()
{
 scanningEnabled = true;
 engaged = true;
 pidEnabled = true;
 return true;
}
/**************************************************************************/
/*
 Retracts the scanner without using the approach motor. This function 
 only moves the scanner Z-axis, not the approach motor.
*/
/**************************************************************************/
void retract()
{
 scanningEnabled = false;
 pidEnabled = false;
 engaged = false;
 z = MAX_Z; // Fully retract the Z-piezo
 digitalWrite(TUNNEL_LED, LOW);
}

lastly this is the serial command code

void checkSerial()
{
 
 String serialString;
 
 if(Serial.available() > 0)
 {
 for(int i = 0; i < 2; i++) // Accepts 2 char commands
 {
 delay(1); // This seems to be necessary, not sure why
 char inChar = Serial.read();
 serialString += inChar;
 }
 }
 serialCommand(serialString);
 serialString = "";
}
/**************************************************************************/
void serialCommand(String str)
{
 
 String command = "00";
 
 if (str.length() > 0)
 { 
 // Get the first 2 characters of str and store them in command:
 for(int i = 0; i < 2; i++)
 {
 command[i] = str[i];
 }
 
 
 if(command == "SE") // Enable serial communications
 {
 Serial.begin(115200); // original is 115200
 Serial.println("SE");
 serialEnabled = true;
 digitalWriteFast(SERIAL_LED, HIGH);
 }
 
 
 else if(command == "SD") // Disable serial communications
 {
 serialEnabled = false;
 Serial.flush();
 Serial.end();
 digitalWriteFast(SERIAL_LED, LOW);
 } 
 
 
 else if(command == "SS") // Scan size in LSBs
 {
 boolean scanningEnabledOnCommand = scanningEnabled;
 int new_scanSize = Serial.parseInt();
 int xNew, yNew;
 
 // Calculate position to move to:
 xNew = (int)(((float)(x - xo) * (float)new_scanSize) / (float)scanSize) + xo;
 yNew = (int)(((float)(y - yo) * (float)new_scanSize) / (float)scanSize) + yo;
 
 scanningEnabled = false; // Pause the scan
 
 if(new_scanSize > scanSize) // Update scanSize, then move
 {
 scanSize = new_scanSize;
 moveTip(xNew, yNew);
 }
 else // Move, then update scanSize
 {
 moveTip(xNew, yNew);
 scanSize = new_scanSize;
 }
 if(scanningEnabledOnCommand) scanningEnabled = true; // Resume scanning
 }
 
 
 else if(command == "IP") // Image pixels
 { 
 boolean scanningEnabledOnCommand = scanningEnabled;
 pixelsPerLine = Serial.parseInt() * 2;
 resetScan();
 if(scanningEnabledOnCommand) scanningEnabled = true;
 }
 
 
 else if(command == "LR") // Line rate in Hz
 {
 boolean scanningEnabledOnCommand = scanningEnabled;
 lineRate = (float)Serial.parseInt() / 100.0f; // Line rate is multiplied by 100 for the transmission
 while(pixelCounter != 0); // Wait for the scanner to finish scanning a line
 scanningEnabled = false; // Pause the scan
 updateStepSizes();
 if(scanningEnabledOnCommand) scanningEnabled = true; // Resume scan
 }
 
 
 else if(command == "XO") // X-offset
 {
 boolean scanningEnabledOnCommand = scanningEnabled;
 int previous_xo = xo;
 int new_xo = Serial.parseInt();
 scanningEnabled = false; // Pause the scan
 xo = new_xo;
 moveTip(x - previous_xo + xo, y); // Move over by (xo, yo)
 if(scanningEnabledOnCommand) scanningEnabled = true; // Resume scan
 } 
 
 
 else if(command == "YO") // Y-offset
 {
 boolean scanningEnabledOnCommand = scanningEnabled;
 int previous_yo = yo;
 int new_yo = Serial.parseInt();
 scanningEnabled = false;
 yo = new_yo;
 moveTip(x, y - previous_yo + yo);
 if(scanningEnabledOnCommand) scanningEnabled = true;
 } 
 
 
 else if(command == "SP") // Setpoint in LSBs
 {
 setpoint = Serial.parseInt();
 setpointLog = logTable[abs(setpoint)]; 
 } 
 
 
 else if(command == "SB") // Sample bias in LSBs
 {
 bias = Serial.parseInt();
 noInterrupts();
 dac.setOutput((uint16_t)(bias + 32768), DAC_CH_BIAS); // Set the sample bias
 interrupts(); 
 }
 
 
 else if(command == "KP") // P gain
 {
 Kp = Serial.parseInt(); 
 } 
 
 
 else if(command == "KI") // I gain
 {
 Ki = Serial.parseInt() * dt; 
 }
 
 
 else if(command == "EN") // Enable scanning
 {
 resetScan();
 scanningEnabled = true; 
 } 
 
 
 else if(command == "DL") // Disable scanning
 {
 scanningEnabled = false; 
 } 
 
 
 else if(command == "TE") // Tip engage
 { 
 engage(); 
 } 
 
 
 else if(command == "TR") // Tip retract
 { 
 retract(); 
 }
 }
}
SnappyRiffs
1,3801 gold badge5 silver badges29 bronze badges
asked Jan 27 at 0:53
\$\endgroup\$
3
  • 1
    \$\begingroup\$ Move the pinMode() and digitalWrite() code from the LTC2326_16::LTC2326_16() construct and move those code into the LTC2326_16::begin() method, this might not the only issue as you only show us the partial of the library. BTW, don't post code as an image, post it as a code block in text. \$\endgroup\$ Commented Jan 27 at 1:18
  • 1
    \$\begingroup\$ SPI.beginTransactin() and SPI.endTransaction() should be part of SPI.transfer() to form the basic transactional SPI communication, your current code might work if you only has one SPI device on the bus, but it won't work for multiple SPI communication because SPI.beginTransaction() hold up the SPI bus exclusively. \$\endgroup\$ Commented Jan 27 at 1:23
  • \$\begingroup\$ sorry about that, I reformatted the code and added the other parts that mesh with the library. \$\endgroup\$ Commented Jan 27 at 1:50

1 Answer 1

1
\$\begingroup\$

Other than my comments on the Library construct and the transactional SPI, your latest posted code has the incorrect trigger of CNV in LTC2326_16::read() with digitalWrite(_cnv, LOW);. Based on the datasheet, ADC conversion is triggered by rising edge of CNV pin.

Based on the schematic, the circuit uses CS_ADC, so the timing diagram for the SPI should based on "Figure 11 Normal Mode with Multiple Devices Sharing CNV, SCK, and SDO" of datasheet.

I re-write your LTC2326_16 library based on my understanding of the timing diagram (not test as I don't have a LTC2326_16).

LTC2326_16 timing diagram with 4-wire SPI

#include "core_pins.h"
#include "Arduino.h"
#include "LTC2326_16.h"
#include "SPI.h"
/**************************************************************************/
/*
 Constructor
*/
/**************************************************************************/
LTC2326_16::LTC2326_16(byte cs, byte cnv, byte busy)
{
 _cs = cs;
 _cnv = cnv;
 _busy = busy;
}
/**************************************************************************/
/*
 Initiate a conversion.
*/
/**************************************************************************/
void LTC2326_16::convert()
{
 digitalWrite(_cnv, HIGH);
}
/**************************************************************************/
/*
 Check whether ADC is busy doing a conversion. Returns true if conversion
 is in progress (BUSY pin is HIGH), false otherwise.
*/
/**************************************************************************/
bool LTC2326_16::busy()
{
 return digitalRead(_busy);
}
/**************************************************************************/
/*
 Setup the SPI port at 24 MHz.
*/
/**************************************************************************/
void LTC2326_16::begin()
{
 digitalWrite(_cs, HIGH);
 pinMode(_cs, OUTPUT);
 digitalWrite(_cnv, LOW);
 pinMode(_cnv, OUTPUT);
 pinMode(_busy, INPUT);
 SPI.begin(); // Initialize SPI
}
/**************************************************************************/
/*
 Read the ADC data register.
*/
/**************************************************************************/
int16_t LTC2326_16::read()
{
 digitalWrite(_cnv, HIGH); // raising edge trigger CNV 
 while (busy()); // wait if busy line is high
 digitalWrite(_cs, LOW); // enable chip select
 SPI.beginTransaction(SPISettings(24000000, MSBFIRST, SPI_MODE1)); // Set up the SPI settings (clock speed, data order, SPI mode)
 int16_t val = SPI.transfer16(0); // Read the result from the ADC
 SPI.endTranaction();
 digitalWrite(_cs, HIGH); // release chip select
 digitalWrite(_cnv, LOW); // conversion completed
 return val;
}
answered Jan 27 at 7:49
\$\endgroup\$
1
  • \$\begingroup\$ hello, sorry about the late reply, but I have been busy with school currently, thank you for your time helping me with this! i finally managed to get something that wasn't a zero but its still not working but i think i it has something to do with the busy pin, because my spi indicator no longer lights up when i implemented your code and i could only communicate with my teensy once i slashed out the while (busy());. any ways thanks again for yor help! hopefully i am able to continue from here. \$\endgroup\$ Commented Jan 31 at 1:08

Your Answer

Draft saved
Draft discarded

Sign up or log in

Sign up using Google
Sign up using Email and Password

Post as a guest

Required, but never shown

Post as a guest

Required, but never shown

By clicking "Post Your Answer", you agree to our terms of service and acknowledge you have read our privacy policy.

Start asking to get answers

Find the answer to your question by asking.

Ask question

Explore related questions

See similar questions with these tags.