Teensy 3.6 + DRV8305

I am trying to control a PMSM motor from texas instruments using the DRV8305 EVM and Teensy 3.6 board using this library.

I tried modifying the code @byDagor used for his Janus Controller project (ESP32 + DRV8305) and using it. That code uses 2.0.1 version of the library. I first tried using that version of the library, but when compiling I get a problem from “_configure3PWM”:

undefined reference to `_configure3PWM(long, int, int, int)’

I also tried with 2.1 version of the library (just in case) and it says:

“simplefoc bldcmotor has no member named command”

If someone can help me with this I would be really helpful.

We’ve had a few issues like this. Teensy isn’t being detected correctly here:

SimpleFOC expects your board to be defining CORE_TEENSY but it is not.

On some IDE’s you need to #include <Arduino.h> for these board but I expect that doesn’t apply.
You could try replacing CORE_TEENSY with TEENSYDUINO or finding some other build flag that has been defined that identifies your board.

I’d like us to get to the bottom of this as there have been a few similar questions.

Hey guys,

There has been a confusion regarding this issue, we had a lot of sensible explanations, but the one that is actually true is that I’ve made an error and forgot to compile the code for Teensy boards in the v2.0.1. :smiley: So in order to make the v2.0.1 work with teensy boards you can just replace the file drivers/hardware_specific/teensy_mcu.cpp from the one in the master branch

This was actually not the issue for this error at least. :smiley:

The v2.1 has a new commander interface and does not use the motor.command() function any more. I would really advise you to go through the library getting strated page to get familliar with the code and the functions that make the simplefoc applications. :smiley:
It can be overwhelming sometimes, that is true but it will help you to understand it better and get the most out of your setup.

Now in terms of the examples. So first you will need to communicate using the SPI to your driver and set up everything that you want to use it with. Either 6PWM or 3PWM mode, current limits and enables it.

6PWM mode is not available on Teensy boards for now :smiley:

You can take the configuration functions @David_Gonzalez wrote for his controller and you can use drv8302 example in the library examples and replace the drv8302 specific code with drv8305 spi configuration calls.

By the way you can also take a look into the NekoGirlChocolate’s class implementation for DRV8301. The DRV8301 and DRV8305 should have more or less the same class to configure your driver!
Once when it is configured you can use it as any other bldc driver in the library.

The important things to take from my code is just the 3xpwm configuration (through SPI) and the fault report (if you want it). My implementation for the DRV8305 is very basic and should be updated in the future, I just did the bare minimum to get a working set-up. :stuck_out_tongue:

Thanks David. I am using your implementation for the DRV setup and fault report.

Hi Antun. I did not get it to work nor with the byDagor example (modifying it to work with Teensy) and changing the “teensy_mcu.cpp” file.

I have also tried using the 2.1 version of the library. I used the DRV8302 example as a reference, adding byDagor’s DRV8305 driver initialization method but I could not make it work.

MOT: Monitor enabled!
MOT: Init
MOT: Enable driver.
MOT: Align sensor.
MOT: Failed to notice movement
MOT: Init FOC failed.

The motor never gets to move, then the alignement can’t be done. I checked the wiring and everything seems correct. I will add the .ino code here if someone wants to check it, just in case. I really don’t know if there is a better way than copy-pasteing the code here. Sorry if this is not they way to do it.

Edit: I remove the code and add a link to a repository I just created with the code.

Hey @xpeedster,

I would suggest you to do this step by step.

  1. test the sensor standalone (you have the codes in the utils examples)
  2. test the open-loop examples (you have the codes in motion_control example)
    Here you will need to add the drv configuration as you added in your code above. Make sure that you enable the driver and that your spi works.
  3. Once when you have 1. and 2. working go to the closed-loop modes.

It should not take long to do all this and it will help you diagnose the problems and be sure what part of the code works and which one doesn’t.

Here are some simplifications of your code to remove unnecessary stuff for now. This code will do the open-loop velocity control. I can not test it really but this should not be too far from something that would work :smiley:

#include <SimpleFOC.h>
#include <SPI.h>

// DRV8302 pins connections
// don't forget to connect the common ground pin
#define INH_A 22
#define INH_B 9
#define INH_C 6

#define cs 24
#define nFAULT 25
#define EN_GATE 26

bool faultTrig = false;

//#####_TIME MANAGEMENT_#####
unsigned long downscale_fault_check = 0;

// Motor instance
BLDCMotor motor = BLDCMotor(4);
BLDCDriver3PWM driver = BLDCDriver3PWM(INH_A, INH_B, INH_C);

// commander interface
Commander command = Commander(Serial);
void onMotor(char* cmd){ command.motor(&motor, cmd); }

void setup() {
  Serial.begin(115200);
  pinMode(nFAULT, INPUT);
  pinMode(EN_GATE, OUTPUT);
  digitalWrite(EN_GATE, LOW);
   
  //SPI start up
  pinMode(cs, OUTPUT);
  digitalWrite(cs, HIGH);
  SPI.begin();
  SPI.setBitOrder(MSBFIRST);
  SPI.setDataMode(SPI_MODE1);

  //Motor driver initialization
  delay(250);
  Serial.println("DRV8305 INIT");
  drv_init();
  delay(500);

  Serial.println("enGate Enabled");
  digitalWrite(EN_GATE, HIGH);
  delay(500);

  // driver config
  // power supply voltage [V]
  driver.voltage_power_supply = 12;
  driver.init();
  // link the motor and the driver
  motor.linkDriver(&driver);

  // set control loop type to be used
  motor.controller = MotionControlType::velocity_openloop;

  // default voltage_power_supply
  motor.voltage_limit = 2;

  // use monitoring with serial for motor init
  motor.useMonitoring(Serial);

  // initialise motor
  motor.init();
  // align encoder and start FOC
  motor.initFOC();

  // set the inital target value
  motor.target = 2; // rad/s

  // define the motor id
  command.add('A', onMotor, "motor");

  Serial.println(F("Motor ready - 2 rad/s initial velocity , 2V voltage limit "));
  
  _delay(1000);
}


void loop() {
  // iterative setting FOC phase voltage
  motor.loopFOC();

  // iterative function setting the outter loop target
  motor.move();

  // user communication
  command.run();

  // Fault check each 1000 loop calls
  if(downscale_fault_check++ > 1000){
    faultStatus();
    downscale_fault_check= 0;
  }
}

//Fault status and manager for the DRV8305
//Datahseet pages 37 and 38
void faultStatus(){
  //Read nFault pin from DRV8305 - LOW == error / HIGH == normal operation
  int fault = digitalRead(nFAULT);
  
  if(fault == LOW && faultTrig == false){
    Serial.println("Fault detected");
    faultTrig = true;
    //Check warning and watchdog reset (Address = 0x1)
    digitalWrite(cs, LOW);
    byte ft1 = SPI.transfer(B10001000);
    byte ft2 = SPI.transfer(B00000000);
    digitalWrite(cs, HIGH);
    Serial.println("Address = 0x1");
    Serial.println(ft1,BIN);
    Serial.println(ft2,BIN);

    //Check OV/VDS Faults (Address = 0x2)
    digitalWrite(cs, LOW);
    byte ft3 = SPI.transfer(B10010000);
    byte ft4 = SPI.transfer(B00000000);
    digitalWrite(cs, HIGH);
    Serial.println("Address = 0x2");
    Serial.println(ft3,BIN);
    Serial.println(ft4,BIN);

    //Check IC Faults (Address = 0x3)
    digitalWrite(cs, LOW);
    byte ft5 = SPI.transfer(B10011000);
    byte ft6 = SPI.transfer(B00000000);
    digitalWrite(cs, HIGH);
    Serial.println("Address = 0x3");
    Serial.println(ft5,BIN);
    Serial.println(ft6,BIN);

    //Check VGS Faults (Address = 0x4)
    digitalWrite(cs, LOW);
    byte ft7 = SPI.transfer(B10100000);
    byte ft8 = SPI.transfer(B00000000);
    digitalWrite(cs, HIGH);
    Serial.println("Address = 0x4");
    Serial.println(ft7,BIN);
    Serial.println(ft8,BIN);
  }
}

//Configure DRV8305 to desired operation mode
void drv_init(){

  //Set to three PWM inputs mode
  digitalWrite(cs, LOW);
  byte resp1 = SPI.transfer(B00111010);
  byte resp2 = SPI.transfer(B10000110);
  digitalWrite(cs, HIGH);

  Serial.println(resp1, BIN);
  Serial.println(resp2, BIN);
  
}
2 Likes

I will go on vacation for almost a month now. I will test it as soon as I am back and let you know how it goes. This will be April 12th.

Thanks a lot for your help!

1 Like

Hi everyone! I am back at my lab and tested what you guys told me. I tested the open-loop configuration and I managed to make it work. It seems that the driver configuration method I was using in the code I sent you does not work. I used an old code I developed a while ago for that purpose and THE MOTOR SPINS!

Thanks a lot for the help. I will let you know any further development of the project.

3 Likes

Hello,I use AS5047P as a encoder. it works on sensor_test-encoder_example(A,B).
open_loop_motor_control also work ,but ,when i chose velocity_control(encoder),it doesn’t work.


MOT:Error:Not found!
MOT:Init FOC failed.

Looks like you are running in abz and the z index search can’t be found. Your original test send to indicator you were using ab (no z).