MOT: Init not possible, driver not initialized. Teensy4.0

I’m running a teensy 4.0, DRV8302, and AS5048A in 3PWM mode it seems flawless in all modes, so far anyway. However once I switch over to 6PWM, and change the M_PWM output accordingly, after an error free compilation and upload, I get the error message “MOT: Init not possible, driver not initialized”.

I’m wired as per the example:
BLDCDriver6PWM driver = BLDCDriver6PWM(2,3, 6,9, 8,7);

Any clues?.

Hmm this is interesting.

Do you have any other output in the serial. The simplefoc debugging in the driver initialisation whould be on by default so you should be able to see much more info when the driver is initialising if you enable debugging before you call driver.init().

You can do this either by setting up the motor monitor before the driver.init() call:

Serial.begin(115200); 
motor.useMonitoring(Serial);
...
driver.init();

Of by enabling debugging directly:

SimpleFOCDebug::enable(&Serial);
...
driver.init();

This should give you a bit more info when driver is initialising. If it fails it will tell you why ;D

However this will not solve the issue :smiley:
Which library version are you using? We are supporting teensy 4.0 6PWM from the version v2.3.0, from the last release.

No luck with adding the serial before the driver.init. The error messages have not changed, I Had motor.useMonitoring(Serial); and tried SimpleFOCDebug::enable(&Serial);

For 6PWM the serial output is:

MOT: Monitor enabled!
MOT: Init not possible, driver not initialized
MOT: Align sensor.
MOT: Failed to notice movement

I’m using v2.3.0

Could I have a hardware error, wiring to to wrong pins?

#include <arduino.h>
#include <SimpleKalmanFilter.h>
#include <SimpleFOC.h>
#include <SimpleFOCDrivers.h>
#include "encoders/as5048a/MagneticSensorAS5048A.h"

#define   SENSOR1_CS 10 // some digital pin that you're using as the nCS pin
#define   INH_A 2
#define   INL_A 3
#define   INH_B 6
#define   INL_B 9
#define   INH_C 8
#define   INL_C 7
#define   EN_GATE 4
#define   M_PWM 1
#define   M_OC 0
#define   OC_ADJ 5
#define   NFAULT 14
#define   NOCTW  15

#define IOUTA A6
#define IOUTB A7
#define IOUTC A8

#define CONTROL_LOOP_PERIOD 2000  // msec
#define K 20/0.065            // spring coefficient;N/m
#define B 0.2  * K            //damping coefficient N/m/sec
#define MASS 7                // in kg
#define LIMIT 0.065           // meters
#define MIDWAY 0.1          // meters from endstop
#define FRICTION 1            //newtons
#define MM_REV 0.008          //mm
#define COMMANDED_VEL_LIMIT 0.15    //m/sec

// angle set point variable
float sensor_initial_position = 0;
float target_angle = 0;
int   servoinitialized = 0;
float posangle = 0;
float negangle = 0;
int   servo_direction = 0;
float servo_midpoint = 0;
float total_force = 0;
float acce = 0;
float velo = 0;
float dist = 0;
float real_position = 0;
float servo_position = 0;
float spring_force = 0;
float damping_force = 0;
float filtered_force = 0;
float dt = 0;
float dt1 = 0;
float friction = 0;  //newtons
float linear_position = 0; //meters
float current_magnitude = 0;


//print buffer
char buff[1024];
//simulation variables
float trim_position = 0;

IntervalTimer find_midpoint_timer;
IntervalTimer serialprinttimer;
IntervalTimer force_control_loop_timer;

SimpleKalmanFilter forceFilter(2, 2, 0.1);
SimpleKalmanFilter velocityFilter(2, 2, 0.1);

//sensor instance
MagneticSensorAS5048A sensor1(SENSOR1_CS);

// motor instance
BLDCMotor motor = BLDCMotor(4);

// driver instance
// BLDCDriver6PWM(pwmA_H, pwmA_L, pwmB_H,pwmB_L, pwmC_H, pwmC_L)
BLDCDriver6PWM driver = BLDCDriver6PWM(2,3, 6,9, 8,7, EN_GATE);
//BLDCDriver3PWM driver = BLDCDriver3PWM(2, 6, 8, EN_GATE);

// DRV8302 board has 0.005Ohm shunt resistors and the gain of 12.22 V/V
LowsideCurrentSense cs = LowsideCurrentSense(0.005f, 12.22f, IOUTA, IOUTB, IOUTC);

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

void setup() {

  Serial.begin(115200);
  delay(1000);
  motor.useMonitoring(Serial);

  // DRV8302 specific code
  // M_OC  - enable over-current protection
  pinMode(M_OC,OUTPUT);
  digitalWrite(M_OC,LOW);
  // M_PWM  - enable 3pwm mode
  //pinMode(M_PWM,OUTPUT);
  //digitalWrite(M_PWM,HIGH);
  //or 6PWM mode
  pinMode(M_PWM,OUTPUT);
  digitalWrite(M_PWM,LOW);

  // OD_ADJ - set the maximum over-current limit possible
  // Better option would be to use voltage divisor to set exact value
  pinMode(OC_ADJ,OUTPUT);
  digitalWrite(OC_ADJ,HIGH);

  // configure driver
  // pwm frequency to be used [Hz]
  driver.pwm_frequency = 30000;
  driver.voltage_power_supply = 24;

  driver.init();

  motor.linkDriver(&driver);

  // initialize sensor hardware
  sensor1.init();
  motor.linkSensor(&sensor1);

  // link current sense and the driver
  cs.linkDriver(&driver);

    // align voltage
  motor.voltage_sensor_align = 2.0;

  // choose FOC modulation
  motor.foc_modulation = FOCModulationType::SinePWM;
  motor.torque_controller = TorqueControlType::voltage;
  motor.controller = MotionControlType::torque;

  // controller configuration based on the control type 

 // velocity loop PID
motor.PID_velocity.P = 0.2;
motor.PID_velocity.I = 0.0;
motor.PID_velocity.D = 0.0;
motor.PID_velocity.output_ramp = 1000.0;
motor.PID_velocity.limit = 12.0;
// Low pass filtering time constant 
motor.LPF_velocity.Tf = 0.05;
// angle loop PID
motor.P_angle.P = 20.0;
motor.P_angle.I = 0.0;
motor.P_angle.D = 0.0;
motor.P_angle.output_ramp = 0.0;
motor.P_angle.limit = 200.0;
// Low pass filtering time constant 
motor.LPF_angle.Tf = 0.05;
// current q loop PID 
motor.PID_current_q.P = 2.0;
motor.PID_current_q.I = 0.0;
motor.PID_current_q.D = 0.0;
motor.PID_current_q.output_ramp = 0.0;
motor.PID_current_q.limit = 12.0;
// Low pass filtering time constant 
motor.LPF_current_q.Tf = 0.05;
// current d loop PID
motor.PID_current_d.P = 2.0;
motor.PID_current_d.I = 0.0;
motor.PID_current_d.D = 0.0;
motor.PID_current_d.output_ramp = 0.0;
motor.PID_current_d.limit = 12.0;
// Low pass filtering time constant 
motor.LPF_current_d.Tf = 0.05;
// Limits 
motor.velocity_limit = 200.0;
motor.voltage_limit = 12.0;
motor.current_limit = 3.0;

motor.motion_downsample = 10;

  // use monitoring with serial for motor init
  //motor.monitor_variables = _MON_TARGET | _MON_VOLT_Q | _MON_VOLT_D | _MON_CURR_Q | _MON_CURR_D | _MON_VEL | _MON_ANGLE;
  // monitoring port

  // comment out if not needed
  //motor.useMonitoring(Serial);

  // initialize motor
  motor.init();

  cs.init();
  //cs.skip_align = true;
  // driver 8302 has inverted gains on all channels
  cs.gain_a *= -1;
  cs.gain_b *= -1;
  cs.gain_c *= -1;
  motor.linkCurrentSense(&cs);

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

  // set the initial target value
  motor.enable();

  // define the motor id
  //char motor_id = 'M';
  command.add('M', doMotor, "motor");

  dt1 = 1000000 / CONTROL_LOOP_PERIOD; //integration timer
  
  _delay(1000);

  servo_midpoint = 2 * PI * MIDWAY/MM_REV;  //radians
  find_midpoint_timer.begin(find_midpoint, 1000);
}

Hey,

This one:

MOT: Init not possible, driver not initialized

indicates the pins used are not the right ones for 6-PWM… Unfortunately I don’t really use the Teensy yet, so I can’t give you guidance on which ones to use.

Thanks Runger, unfortunately that leave me a little stuck. The pins I use are straight out of the teensy examples Teensy 4.x support for 6pwm. I am using a Teensy 4.0 not a 4.1, could this be it?

Hey @Carl,

I’ve gone through the teensy code and we did have a big bug in the code that would make setting the pwm in real-time not possible and in term driving motors. So the bug has been fixed in the dev branch.

If you use that code you should be able to run the motor. However, in your case there might be some other errors in play. If you do not see any output when you use debugging then it might be that you are not even initialising the driver at all. I do not own a teensy 4.0, only 4.1 so I am not sure if its specific to 4.0 or it is something else.
Could you please try using the dev branch code, this might be the solution to your issue. If it’s not then we’ll have to do some more in-depth debugging.

Cheers,
Antun

1 Like