No Movement detected in InitFOC()

Hi
I have been getting to grips with Simple FOC using an Odrive 3.6 board driving an 11 pole pair drone motor with an AS5047 magnetic position sensor.

After a steep learning curve I got everything working ok using the AS5047 as an incremental encoder , ie A,B,Z inputs. working in all modes including Angle mode.

Problems come when I try to use it with the SPI interface, when the InitFOC function is called the motor does its movement to determine polarity etc but the the function exits saying no movement detected.

I made a seperate test of the encoder using .GetAngle() method called from the main routine and the sensor is working ok.

I dig into the InitFOC code and can see where it reads the encoder during making the calibration move - if I insert a debug message here to display the encoder position it reads 0.0 from the encoder so no movement is detected. So for some reason the GetAngle is working when called from main and not when called from InitFOC.

I tried setting the calibration motor voltage to zero just in case there is some interference from the motor current - and turn the motor by hand during calibration but the encoder still reads zero.

Not sure what I can try next - I did try an earllier version of Simple FOC but no different - I am using latest version 2.3.4

Many thanks for any suggestion

It will be best if you post your code so we can look at it line by line.

Hi
Here is the code - it is a copy paste from the Odrive example in the example hardware on GitHub.

‘/*
Odrive robotics’ hardware is one of the best BLDC motor foc supporting hardware out there.

This is an example code that can be directly uploaded to the Odrive using the SWD programmer. 
This code uses an magnetic spi sensor AS5047 and a BLDC motor with 11 pole pairs connected to the M0 interface of the Odrive. 

This is a short template code and the idea is that you are able to adapt to your needs not to be a complete solution. :D 

*/
#include <SimpleFOC.h>

// Odrive M0 motor pinout
#define M0_INH_A PA8
#define M0_INH_B PA9
#define M0_INH_C PA10
#define M0_INL_A PB13
#define M0_INL_B PB14
#define M0_INL_C PB15
// M0 currnets
#define M0_IB PC0
#define M0_IC PC1
// Odrive M0 encoder pinout
#define M0_ENC_A PB4
#define M0_ENC_B PB5
#define M0_ENC_Z PC9

// Odrive M1 motor pinout
#define M1_INH_A PC6
#define M1_INH_B PC7
#define M1_INH_C PC8
#define M1_INL_A PA7
#define M1_INL_B PB0
#define M1_INL_C PB1
// M0 currnets
#define M1_IB PC2
#define M1_IC PC3
// Odrive M1 encoder pinout
#define M1_ENC_A PB6
#define M1_ENC_B PB7
#define M1_ENC_Z PC15

// M1 & M2 common enable pin
#define EN_GATE PB12

// SPI pinout
#define SPI3_SCL PC10
#define SPI3_MISO PC11
#define SPI3_MOSO PC12

// Motor instance
BLDCMotor motor = BLDCMotor(11);
BLDCDriver6PWM driver = BLDCDriver6PWM(M0_INH_A,M0_INL_A, M0_INH_B,M0_INL_B, M0_INH_C,M0_INL_C, EN_GATE);

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

// low side current sensing define
// 0.0005 Ohm resistor
// gain of 10x
// current sensing on B and C phases, phase A not connected
LowsideCurrentSense current_sense = LowsideCurrentSense(0.0005f, 10.0f, _NC, M0_IB, M0_IC);

// MagneticSensorSPI(int cs, float _cpr, int _angle_register)
// config - SPI config
// cs - SPI chip select pin
//MagneticSensorSPI sensor = MagneticSensorSPI(M0_ENC_A, 14, 0x3FFF);
MagneticSensorSPI sensor = MagneticSensorSPI(AS5147_SPI, M0_ENC_A);
SPIClass SPI_3(SPI3_MOSO, SPI3_MISO, SPI3_SCL);

void setup(){

// use monitoring with serial
Serial.begin(115200);
// enable more verbose output for debugging
// comment out if not needed
SimpleFOCDebug::enable(&Serial);

// pwm frequency to be used [Hz]
driver.pwm_frequency = 20000;
// power supply voltage [V]
driver.voltage_power_supply = 20;
// Max DC voltage allowed - default voltage_power_supply
driver.voltage_limit = 20;
// driver init
driver.init();
// link the motor and the driver
motor.linkDriver(&driver);

// initialise magnetic sensor hardware
sensor.init(&SPI_3);

delay(1000);

// link the motor to the sensor
motor.linkSensor(&sensor);

// control loop type and torque mode
motor.torque_controller = TorqueControlType::voltage;
motor.controller = MotionControlType::torque;

// max voltage allowed for motion control
motor.voltage_limit = 2;
// alignment voltage limit
motor.voltage_sensor_align = 0.5;

// comment out if not needed
motor.useMonitoring(Serial);
motor.monitor_variables = _MON_ANGLE | _MON_CURR_D;
motor.monitor_downsample = 1000;

// add target command T
command.add(‘M’, doMotor, “motor M0”);

// initialise motor
motor.init();

// link the driver
current_sense.linkDriver(&driver);
// init the current sense
current_sense.init();
current_sense.skip_align = true;
motor.linkCurrentSense(&current_sense);
//Serial.println(“TEST SENSOR”);
//Serial.println(sensor.getAngle());
//Serial.println(&sensor->getAngle());

//motor.testsensor();

// init FOC
motor.initFOC();
delay(1000);
}

void loop(){

// foc loop
motor.loopFOC();
// motion control
motor.move();
// monitoring
// motor.monitor();
// user communication
command.run();
sensor.update();
//Serial.println(motor.shaft_angle);

//Serial.print(“\t”);
//Serial.println(sensor.getAngle());

}

Here is the messages from the diagnostic

MOT: Enable driver.

STM32-DRV: Stopping timer 1

STM32-DRV: Stopping timer 1

STM32-DRV: Stopping timer 1

STM32-DRV: Stopping timer 1

STM32-DRV: Stopping timer 1

STM32-DRV: Stopping timer 1

STM32-DRV: Syncronising timers! Timer no. 1

STM32-DRV: Restarting timer 1

MOT: Align sensor.

MOT: Failed to notice movement

MOT: Init FOC failed.

If I enable the Serial.println(sensor.getAngle()); in main then the position is read ok

.77

0.77

0.77

Hi @Servo-man ,

Is it possible the driver channels are mixed up and you’re using channel 1 when you want to be using channel 0?

Is there an enable pin you should be switching on? Or is it possible that at 2V its just not enough to move the motor?

You should remove the sensor.update() from the main loop, it is already called for you in loopFOC().

Hi @runger
Thankyou for replying
I am pretty sure I am using channel 0 - the motor is connected to channel 0 , the motor is defined with channel 0 pins and the encoder is linked to the motor.

The motor is definately moving during the alignment procedure - the encoder just doesn’t give a reading/see any movement

I have been experimenting and find that the first time InitFOC is run then the alignment fails due to no movement detected even though the motor moves. If I then call the InitFOC a second time - this time there is no movement - however if during this second attempt I move the motor by hand then the InitFOC sees the movement and completes - probably with wrong data but still its a step forward. So there seems to be some reason why the sensor is not working the first time initFOC runs???
My head is fried so I will look further into it tommorrow. I now have the InitFOC in the main loop along with a motor.init() so I can repeat the problem over and over and maybe get a scope on the SPI bus to see if there is any sign of life.
Seems strange as I am sure I am not the first to use this encoder with STM32 though I did find some similar threads on this forum which had no solution at the end??

So I have made some progress but not solved yet.

I have added the code below to loop

void loop(){

// foc loop
// motor.loopFOC();
// motion control
//motor.move();
// monitoring
//motor.useMonitoring(Serial);
//motor.monitor();
// user communication
// command.run();
motor.init();
delay(1000);
motor.initFOC();
delay(1000);
motor.initFOC();
delay(5000);
}

I have a scope on the CLK and MISO lines of the SPI bus to the encoder

During the first execution of InitFOC() the motor moves , I can see each time the encoder is being read on the scope , the CLK is as expected but the MISO data signal is only rising to about 1.4v , my guess this is below the logic threshold so data is read as zero

On the second execution of InitFOC() the motor does not move (some flag must be set by the first attempt) but the encoder is still being read, however this time the MISO data signal is rising to the full 3.3v level.

So something is holding down the MISO signal first time round.

I have tried with the motor phases not connected in case it is an electrical noise issue but makes no difference , except of course the motor won’t move.

Need to understand how the SPI pins are configured by the code - i.e where is the pin configured as an input , is is possible the first time the pin is set to be an output and only the second time is it correctly configured as an input???
Can any pins on STM32F4 be used for SPI , I could try a different pin for MISO??

I have a theory that the problem may be a conflict on the SPI bus. The bus is shared between the encoder and also the two driver chips for the Mosfets. In the sample program from the hardware examples the chip select pins for the driver chips are not defined - maybe this is leading to some unpredictable behaviour ?? I will define these pins and set them high. Will try out tommorrow.

That’s a very likely sounding theory. Other chips on the same SPI bus should definitely have their CS lines pulled high.

So I put in a define for the two pins that act as chip select for the driver chips on SPI bus and set them high.
Now the motor aligns ok , however new problem has come that the angle reading from the encoder is jumping about. I can run the motor in torque mode though you can hear the noise in the motor. In velocity mode is hopeless motor jumps about.
Scoping SPI shows the chip select is blipping high during the read cycle which probably screws up the data??? Don’t know why yet.

The noisy signal seemed to be intermittent so I rewired everything and is working good now must have been a bad connection. Working well in Angle mode

So origional problem was lack of definition of SPI pins for driver chips.