TMC6200 SPI With Simple FOC

Hi,
I am planning to use XESC with Simple FOC firmware.
I tested hardware with XESC test firmware and it works ok.MCU can communicate with TMC6200 and i also tested it with VESC firmware for it.
The issue i am having is i cannot communicate with TMC via Simple FOC firmware and can’t use it.
I am a newbie for Simple FOC and SPI protocol, read a lot of documents regarding this. Here is my platformio file:

[env:genericSTM32F405RG]
platform = ststm32
board = genericSTM32F405RG
framework = arduino
lib_deps = 
	askuric/Simple FOC@^2.3.1
	simplefoc/SimpleFOCDrivers@^1.0.5
monitor_speed = 115200
monitor_port= COM3
lib_archive = false
upload_protocol = stlink
build_flags = 
	-DSERIAL_UART_INSTANCE=1
    -DPIN_SERIAL_RX=PB11
    -DPIN_SERIAL_TX=PB10
    -D HSE_VALUE=8000000U

And here is my main.cpp file:


#include "Arduino.h"
#include <SimpleFOC.h>
#include "SimpleFOCDrivers.h"
#include "drivers/tmc6200/TMC6200.hpp"


InlineCurrentSense current_sense  = InlineCurrentSense(0.005, 20, PC2, PC1, PC0);

TMC6200Driver6PWM driver = TMC6200Driver6PWM(PA10, PB15, PA9, PB14, PA8, PB13, PC9, PB5);

BLDCMotor motor = BLDCMotor(8); //FOR HDD MOTOR 

Commander command = Commander(Serial); //OK
void doTarget(char* cmd) { command.scalar(&motor.target, cmd); } //OK
void doLimitCurrent(char* cmd) { command.scalar(&motor.current_limit, cmd); }

int faultIn = PB7; // FAULT OUTPUT OF DRIVER CONNECTED TO PIN PB7 //OK
int ledPin = PB0;  // LED CONNECTED TO DIGITAL PIN PB0 //OK
int faultState = 0; // VARIABLE TO STORE THE DRIVER FAULT STATE //OK
int drive_en = PB5; //TMC6200 DRIVE ENABLE PIN PB5. IT IS USED WHILE SETTING UP WHILE 6PWM DRIVE MODE AND CYCLING IF SOME FAULT IS DETECTED.

/* SPI1 pin defs */
#define P_MISO PB3 //OK
#define P_MOSI PB4 //OK
#define P_SCK PC10 //OK
#define P_SSEL PC9 //OK

SPIClass SPI_1(P_MOSI, P_MISO, P_SCK);

void handleFault()
    {
        
        TMC6200GStatus status = driver.getStatus();
        Serial.print("hasUShorted: "); Serial.println(status.hasUShorted());
        Serial.print("hasVShorted: "); Serial.println(status.hasVShorted());
        Serial.print("hasWShorted: "); Serial.println(status.hasWShorted());
        Serial.print("isUShortedToGround: "); Serial.println(status.isUShortedToGround());
        Serial.print("isUShortedToSupply: "); Serial.println(status.isUShortedToSupply());
        Serial.print("isVShortedToGround: "); Serial.println(status.isVShortedToGround());
        Serial.print("isVShortedToSupply: "); Serial.println(status.isVShortedToSupply());
        Serial.print("isWShortedToGround: "); Serial.println(status.isWShortedToGround());
        Serial.print("isWShortedToSupply: "); Serial.println(status.isWShortedToSupply());
        Serial.print("isOverTemperaturePreWarning: "); Serial.println(status.isOverTemperaturePreWarning());
        Serial.print("isChargePumpUnderVoltage: "); Serial.println(status.isChargePumpUnderVoltage());
        
        // the driver must be cycled to clear the fault
        digitalWrite(drive_en, LOW);
        //delayMicrosockets(1000);
        _delay(1000);
        digitalWrite(drive_en, HIGH);
    }


 
void setup() { 

// use monitoring with the BLDCMotor
Serial.begin(115200); //OK 
Serial.println("TESTING SERIAL");
SPI_1.begin();
delay(1000);

// driver init
Serial.println("INITIATING DRIVER");
delay(1000);

driver.init();
delay(1000);

Serial.println("DRIVER INITED");
delay(1000);


pinMode(faultIn, INPUT); 
pinMode(ledPin, OUTPUT); 

// pwm frequency to be used [Hz]
driver.pwm_frequency = 20000; //OK
// power supply voltage [V]
driver.voltage_power_supply = 12; //OK
// Max DC voltage allowed - default voltage_power_supply
driver.voltage_limit = 15; //OK

driver.dead_zone = 0.05; 

driver.setCurrentSenseGain(TMC6200_AmplificationGain::_10); 

driver.setCurrentSenseAmplifierState(false); 
driver.setDriverStrength(TMC6200_DRVStrength::Weak);

attachInterrupt(digitalPinToInterrupt(faultIn), handleFault, RISING); 


// link the driver with the current sense
current_sense.linkDriver(&driver);
// init current sense
current_sense.init();

//Validating the TMC6200 SPI Connection
//You can validate the SPI connection by checking the value of VERSION field in IOIN register. The value should be 0x10.
if(driver.getInputs().VERSION != TMC6200_VERSION){
        // something is wrong with the spi connection
        Serial.println("SPI CONNECTION IS NOT WORKING!!!");
    }


Serial.println("Motor ready!"); //OK
Serial.println("Set target velocity [rad/s]"); //OK
delay(1000);

// limiting motor movements
motor.phase_resistance = 2.2; // [Ohm] //OK
motor.current_limit = 2;   // [Amps] - if phase resistance defined //OK
motor.velocity_limit = 5; // [rad/s] cca 50rpm //OK

// link the motor to the driver
motor.linkDriver(&driver); //OK
// link driver and the current sense
  
// link the motor to current sense
motor.linkCurrentSense(&current_sense);

// set control loop type to be used
//motor.controller = MotionControlType::velocity;
motor.controller = MotionControlType::velocity_openloop; 
// initialize motor
motor.init(); 
//motor.initFOC();
// add target command T
command.add('T', doTarget, "target velocity"); 
command.add('C', doLimitCurrent, "current limit");

motor.foc_modulation = FOCModulationType::SinePWM;

// limiting voltage 
motor.voltage_limit = 3;   // Volts
// or current  - if phase resistance provided
motor.current_limit = 0.5; // Amps

}


void loop() {


faultState = digitalRead(faultIn);

if (faultState == HIGH)
digitalWrite(ledPin, HIGH);
else
digitalWrite(ledPin, LOW);

// velocity control loop function
// setting the target velocity or 2rad/s
motor.move(); //OK

//motor.monitor();
command.run();


}

I tested it many times and cannot fix it. Triple checked my pin configs.MCU never talks to TMC driver. Since i couldn’t find any examples i used README on github library to generate main.cpp. Could someone point me in right direction?

Hi @whitepawn , welcome to SimpleFOC!

Please try the following:

Set the SPI_1 to the driver via the init method, otherwise it will be using the standard “SPI” object:
driver.init(&SPI_1);

And please move the driver.init to be after this line: driver.dead_zone = 0.05;
So that the basic parameters are set on the driver before you init it…

Let me know if that changes anything…

@runger

Thanks for welcome and reply.

I added &SPI_1 and moved driver init line after dead zone:

But it freezes i think because “Motor ready!” is not printed on serial:

Any thougts?

@whitepawn

Hey,

The xESC isnt using the hardware SPI peripheral, the pins used dont support it.

They are emulating SPI through software, you can take a look at their exmaple here:

that is the reason your spi connection is failing,

you can use a library such as SoftSPI, and it should be seamless since that library extends the SPIClass class, so you would be able to pass your instance into the init() and continue normally from there.

Ive actually used SoftSPI while writing the TMC6200Driver for SimpleOFC, so im certain it works, however I remember fiddling around with the SPIModes, i dont exactly rememeber …

2 Likes

@Yaseen_Twati Many many thanks for reply.I installed library from here and modified code as below: (I assume SoftSPI library is the right one.)
resim

It compiled without error and i flashed it. Happily it doesn’t “freeze” now but SPI connection seems doesn’t work.

By any chance do you have example codes for changing SPI modes?Or could you look up if which one worked for you best?

Thanks again.

EDIT:In TMC datasheet page 20 i found this:


Tried with data mode 3 but still no luck.(I also tried mode 0, 1 and 2.Same result.)
resim

hmmm, weird
you dont happen to have a logic analyzer do you ? even one of those cheap ones, that helps alot with debugging such problems …

perhaps lets try going at this one step at the time, are you able to try the exmaple code provided by xESC and check if the IC version is read correctly ?

also lets try solving the connection issue seperatly from SimpleFOC motor initialization since thats not gona work without the spi connection working first.

Try this code

#include <Arduino.h>

#include "Arduino.h"
#include <SimpleFOC.h>
#include "SimpleFOCDrivers.h"
#include "drivers/tmc6200/TMC6200.hpp"
#include "SoftSPI.hpp"

const int TMC_MISO = PB3;
const int TMC_MOSI = PB4;
const int TMC_SCK = PC10;
const int TMC_CS = PC9;


TMC6200Driver tmcDriver = TMC6200Driver(TMC_CS);

SoftSPI tmcSPI(TMC_MOSI, TMC_MISO, TMC_SCK);

void setup()
{
  Serial.begin(115200);
  Serial.println("Driver TEST");

  tmcSPI.setDataMode(SPI_MODE3);
  tmcSPI.begin();

  tmcDriver.init(&SPI);
}

void loop()
{
  if (tmcDriver.getInputs().VERSION != TMC6200_VERSION)
  {
    Serial.println("Correct TMC6200 Version Found");
  }
  else
  {
    Serial.println("Failed to find TMC6200");
  }

  delay(750);
}

Thanks for reply.
I have a cheap CY7C68013A USB Logic Analyzer and 2 Osciloscopes but due to XESC hardware design there are no Test Points or soldering place (MCU and TMC pins are very tiny to solder some cables.) so i ditched that idea. :face_with_diagonal_mouth:

I also considered cutting existing SoftSPI pins on PCB and re-wiring Hardware SPI pins to TMC, but again it is a delicate soldering job.

I tested my board with XESC test firmware ,MCU finds TMC chip id which is 0x10 and passes test but i believe xesc test firmware uses TMC API which i couldn’t understand and couldn’t implement in SimpleFOC code.

Today I also modded hardware for TMC Standalone configuration. My understanding from TMC datasheet if we pull SPE pin to GND TMC will work on standalone mode. If we pull SPE pin to 3.3v it will work on SPI mode. So i lifted 25th pin (SPE) from TMC ic and soldered a cable and pulled it to GND. Now I can change modes.

Your code always gives “Correct TMC6200 Version Found” whether if i powered on TMC or not. I am not sure why it prints correct version found but if i switch to xesc test firmware it works without issues.(If esc is powered up i can see 0x10, if i power down it it is 0xFF.)

Here is my “clean” SPI tester code from xesc test firmware:

#include "Arduino.h"
#include <SimpleFOC.h>
#include "SimpleFOCDrivers.h"
#include "drivers/tmc6200/TMC6200.hpp"
//#include "SoftSPI.h"
//#include <SoftwareSpiMaster.h>
//#include "tmc/ic/TMC6200/TMC6200.h"

extern "C"
{
#include <tmc/ic/TMC6200/TMC6200.h>
}

#define PIN_TMC_MISO PB3
#define PIN_TMC_MOSI PB4
#define PIN_TMC_SCK PC10
#define PIN_TMC_NCS PC9
#define PIN_TMC_ENABLE PB5

void setup() {
	SerialUSB.begin(115200);
    pinMode(PIN_TMC_MOSI, OUTPUT);
    pinMode(PIN_TMC_SCK, OUTPUT);
    pinMode(PIN_TMC_NCS, OUTPUT);
    pinMode(PIN_TMC_ENABLE, OUTPUT);
    digitalWrite(PIN_TMC_ENABLE, HIGH);
    digitalWrite(PIN_TMC_SCK, HIGH);
    digitalWrite(PIN_TMC_NCS, HIGH);

    pinMode(PB0, OUTPUT);

    for (int i = 0; i < 10; i++)
    {
        digitalWrite(PB0, HIGH);
        delay(100);
        digitalWrite(PB0, LOW);
        delay(100);
    }

}

void spiDelay()
{
    delay(1);
}



void waitForEnter(bool dots = false) {
    SerialUSB.println("Press enter to continue");
    while (1) {
        if (dots) {
            SerialUSB.print(".");
        }
        unsigned long started = millis();
        while (millis() - started < 1000 && !SerialUSB.available()) {
        }
        if (SerialUSB.available()) {
            while (SerialUSB.available()) {
                SerialUSB.read();
            }
            break;
        }
    }
}



uint8_t transfer(uint8_t value)
{
    uint8_t readValue = 0;

    for (uint8_t i = 0; i < 8; ++i)
    {
        digitalWrite(PIN_TMC_MOSI, (bool)(value >> 7));

        value <<= 1;

        digitalWrite(PIN_TMC_SCK, LOW);

        spiDelay();

        digitalWrite(PIN_TMC_SCK, HIGH);
        readValue <<= 1;
        if (digitalRead(PIN_TMC_MISO))
        {
            digitalWrite(PB0, HIGH);
            readValue |= 1;
        }
        else
        {
            digitalWrite(PB0, LOW);
        }
        spiDelay();
    }
    return readValue;

    
}

void loop() {
    digitalWrite(PC10, HIGH);
    spiDelay();
    digitalWrite(PC9, LOW);
    spiDelay();

    SerialUSB.println("Trying to connect to TMC6200");

    digitalWrite(PIN_TMC_SCK, HIGH);
    spiDelay();
    digitalWrite(PIN_TMC_NCS, LOW);
    spiDelay();

    // delayMicroseconds(100);
    uint32_t request = TMC6200_IOIN_OUTPUT;
    uint32_t ic_version = (tmc6200_readInt(0, request) & TMC6200_VERSION_MASK) >> TMC6200_VERSION_SHIFT;
    SerialUSB.print("IC version: 0x");
    SerialUSB.println(ic_version, HEX);
    SerialUSB.println("(expected value = 0x10)");
    if (ic_version == 0x10)
    {
        SerialUSB.println("--> OK");
        waitForEnter();
    }
    else
    {
        SerialUSB.println("--> NOT OK!!!");
        delay(1000);
        return;
    }
delay(1000);

}

extern "C"
{
    uint8_t tmc6200_readwriteByte(uint8_t motor, uint8_t data, uint8_t lastTransfer)
    {
        digitalWrite(PIN_TMC_NCS, LOW);
        spiDelay();
        uint8_t rx = transfer(data);

        if (lastTransfer)
        {
            digitalWrite(PIN_TMC_NCS, HIGH);
        }
        return rx;
    }
}

How can i implement TMC-API to SimpleFOC code? Because it seems i am out of options with current XESC hardware.

Any thoughts?

@whitepawn

I completly forgot that the XESC was so small and attaching the logic analyzer would be hard to do.

also my bad, in my code im checking that it “!= TMC6200_VERSION”, which seems to be always the case, thats why its always saying its correct, while in reality its always incorrect.

i beilive something is wrong with the way SoftSPI works in our use case,
what i would try to do is to modify its transfer function to be the same as the one from the xesc exmaple code and give it a try,

depending on the time i have available today/tomorrow
ill pull out my TMC6200 board and give it a try and get back to you on my findings

1 Like

@Yaseen_Twati

Did you had a chance to test your board?