Test SimpleFOClibrary + SimpleFOCMini + RP2040-Zero + 2804 + AS5600

Good morning,
And congratulations to all the developers for this superb work :slight_smile:

My test setup:
BLDC Motor 2804 + AS5600 ==> MKS YT2804
https://uk.aliexpress.com/item/1005005065257355.html

Driver FOC ==> SimpleFOCMini (China… sorry)

MicroController ==> RP2040-Zero

First test with version 2.3.0 ==> adc error impossible to compile…

Second test with the github “dev” version, everything is ok :slight_smile:

The current test code for SimpleFOCStudio not optimized, I will add a video when everything is ready.

#include <Arduino.h>
#include <Wire.h> // penser a changer pins I2C dans setup !
#include <SimpleFOC.h>

#define SIMPLEFOC_PWM_ACTIVE_HIGH true

int OUT1 = 29; // pin out1
int OUT2 = 28; // pin out2
int OUT3 = 27; // pin out3
int MOTOR_ENABLE = 26; // pin enable

float MotorResInOhms = 8.6;
float MotorInAmps = 0.240;  // 180 M-Amps
float PowerInVolts = 12;
float SensorOffset = 0;
int MOTORE_POLE_NB = 7; // 7 Nombre de poles du BLDC
float MOTOR_KV_RATING = 320; // motor.KV_rating = MOTOR_KV_RATING;  rpm/volt - default not set

// BLDC motor & driver instance
BLDCMotor motor = BLDCMotor(MOTORE_POLE_NB); // Nombre de pôles du moteur
BLDCDriver3PWM driver = BLDCDriver3PWM(OUT1, OUT2, OUT3, MOTOR_ENABLE); //  3 phases + enable

// magnetic sensor instance - MagneticSensorI2C
//MagneticSensorI2C sensor = MagneticSensorI2C(AS5600_I2C);
MagneticSensorI2C sensor = MagneticSensorI2C(0x36, 12, 0x0E, 4);

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


//▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬setup▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬
void setup() {
  // use monitoring with serial
  Serial.begin(115200);
  delay(500);

  //▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬sensor_config▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬
  // initialise magnetic sensor hardware
  Wire.setClock(1000000); // Try calling Wire.setClock(400000) or 1000000 or 3400000 to speed up the i2c bus.
  Wire.setSDA(0); // pin SDA
  Wire.setSCL(1); // pin SCL
  Wire.begin();
  delay(500);

  // providing
  // sensor.min_elapsed_time = 0.0001; // 0.0001 ==> 100us by default ==>  10000 Hz ==> 10Khz
  sensor.init(&Wire);

  //▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬driver_config▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬
  // power supply voltage [V]
  driver.voltage_power_supply = PowerInVolts;

  // Max DC voltage allowed
  driver.voltage_limit = PowerInVolts;

  // pwm frequency to be used [Hz]
  // for atmega328 fixed to 32kHz
  // esp32/stm32/teensy configurable
  driver.pwm_frequency = 100000; // 100000

  // init driver
  if (driver.init())  Serial.println("Driver init success!");
  else {
    Serial.println("Driver init failed!");
    return;
  }

  //▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬motor_config▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬

  // link the motor to the sensor
  motor.linkSensor(&sensor);
  // choose FOC modulation
  // FOCModulationType::SinePWM;
  motor.foc_modulation = FOCModulationType::SinePWM; //  SinePWM SpaceVectorPWM

  // link the motor and the driver
  motor.linkDriver(&driver);

  // set torque mode to be used
  // TorqueControlType::voltage    ( default )
  // TorqueControlType::dc_current
  // TorqueControlType::foc_current
  motor.torque_controller = TorqueControlType::voltage;

  // Closed-Loop control
  //SimpleFOClibrary gives you the choice of using 3 different Closed-Loop control strategies:
  // set motion control loop to be used
  // MotionControlType::torque
  // MotionControlType::velocity
  // MotionControlType::angle
  motor.controller = MotionControlType::angle;

  // contoller configuration
  // default parameters in defaults.h

  // velocity PI controller parameters
  motor.PID_velocity.P = 0.2f; // 0.2f 0.8f
  motor.PID_velocity.I = 20.0f; // 20
  motor.PID_velocity.D = 0.001; // 0.001 / 0

  // jerk control using voltage voltage ramp
  // default value is 300 volts per sec  ~ 0.3V per millisecond
  motor.PID_velocity.output_ramp = 1000; // 1000

  // setting the limits
  //  maximal velocity of the position control
  motor.velocity_limit = 20; // rad/s - default 20 (limite vitesse & 6 vitese est lent mais ok)

  // velocity low pass filtering time constant
  // the lower the less filtered
  motor.LPF_velocity.Tf = 0.6f; // 0.01f

  // https://docs.simplefoc.com/cheetsheet/options_reference

  // angle PID controller
  // default P=20
  motor.P_angle.P = 10.0f; // 6 20  80 (faible amortis l'arrêt)
  motor.P_angle.I = 0;  // 0 usually only P controller is enough
  motor.P_angle.D = 0;  // 0 usually only P controller is enough
  // acceleration control using output ramp
  // this variable is in rad/s^2 and sets the limit of acceleration
  motor.P_angle.output_ramp = 10000; // 10000 // default 1e6 rad/s^2

  // angle low pass filtering
  // default 0 - disabled
  // use only for very noisy position sensors - try to avoid and keep the values very small
  motor.LPF_angle.Tf = 0.0001; // default 0

  // sensor offset [rad]
  motor.sensor_offset = SensorOffset; // default 0 rad (dcaler offset 0 sur capteur/encodeur=

  // limiting voltage
  motor.voltage_limit = PowerInVolts;   // limiting Voltage Volts

  // Global current limit. Limits Q-axis current.
  motor.current_limit = MotorInAmps; // 180 M-Amps

  // motor phase resistance [Ohms]
  motor.phase_resistance = MotorResInOhms; //

  // motor KV rating [rpm/V]
  //KV = velocity_at_one_volt * 30/pi
  motor.KV_rating = MOTOR_KV_RATING; // rpm/volt - default not set

  //▬▬▬▬▬▬▬▬Velocity PID controller output limit. Set to limit velocity to this maximum.
  // ATTENTION volts ou amps ???
  // https://community.simplefoc.com/t/setting-current-limits-in-main-loop/1972/2
  motor.PID_velocity.limit = 12;

  // aligning voltage [V]
  motor.voltage_sensor_align = 6; // default 3V
  // incremental encoder index search velocity [rad/s]
  motor.velocity_index_search = 3; // default 1 rad/s

  // Set to values > 1 to reduce how often move() is executed compared to loopFOC().
  // On fast MCUs it makes sense to reduce how often move() gets called.
  motor.motion_downsample = 0;

  motor.sensor_direction = Direction::CCW; // CW or CCW

  // initialize motor
  motor.init();

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

  // https://github.com/simplefoc/Arduino-FOC/blob/dev/src/common/defaults.h
  // https://docs.simplefoc.com/commander_interface
  // https://docs.simplefoc.com/commander_motor
  // https://docs.simplefoc.com/commander_target

  // https://docs.simplefoc.com/studio
  // add the motor to the commander interface
  // The letter (here 'M') you will provide to the SimpleFOCStudio
  //command.add('M', doMotor, "My motor motion");
  command.add('M', doMotor, "motor");
  command.decimal_places = 4; // default 3 (moi 4)
  // tell the motor to use the monitoring
  motor.useMonitoring(Serial);
  motor.monitor_downsample = 0; // 0 = disable monitor at first - optional

  _delay(1000);
} // End_setup
//▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬End_setup▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬


//▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬loop▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬
void loop() {
  // main FOC algorithm function
  motor.loopFOC();

  // Motion control function
  // velocity, position or voltage (defined in motor.controller)
  // this function can be run at much lower frequency than loopFOC() function
  // You can also use motor.move() and set the motor.target in the code

  // Motion control function
  motor.move();

  //Serial.print(String(sensor.getAngle()) + "\t" + String(sensor.getVelocity()) + "\t" + String(((sensor.getAngle()-motor.sensor_offset)*180/_PI)) + "\n");

  // function intended to be used with serial plotter to monitor motor variables
  // significantly slowing the execution down!!!!
  motor.monitor();

  // user communication
  command.run();
} // End_loop
//▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬End_loop▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬

I would reduce the sensor align voltages, that could overheat your motor. Also the
MagneticSensorI2C(0x36, 12, 0x0E, 4)

line, I think I might have had to change that, there is an error with one of the examples on that line. The E needs to be a C or something, I forget.

In general it is more advisable to get the motor working open loop at low voltage, and get the sensor reading reliably, first.

These sensors benefit seriously from the “calibration” procedure. Much better energy efficiency is obtained as motor timing is better.

Also there are a number of other details like the direction pin, some as5600 sensor boards need to have that grounded, that sort of thing is what the other testing stages is for. To check all wiring etc. However it looks promising. Exactly how did you attach the magnet to the motor? I printed a little magnet holder and that worked well for the magnet that usually comes with these sensors.

Hello Anthony,
Thank you for your tips :slight_smile:
The motor I use is sold with magnet attached and support for AS5600
But you are right I also use 3D printing if I need to fix
I still have a lot of settings to discover to hope to use suimpleFOC correctly

Hello,

It’s starting to work fine :slight_smile:

I still have to familiarize myself with all the possibilities of SimpleFOC

There is still a little vibration when stopped in “Angle” mode

The current code

/*
  Encodeur Magnétique ==> AS5600
  Moteur BLDC ==> MKS YT2804
  Driver FOC ==> SimpleFOCMini (China... sorry)
  MicroControleur ==> RP2040-Zero
  https://www.waveshare.com/wiki/RP2040-Zero
  https://www.waveshare.com/wiki/RP2040-ZeroWS2812B
  WS2812B GPIO16

  https://docs.simplefoc.com/citing

  https://github.com/earlephilhower/arduino-pico
  https://github.com/MrYsLab/NeoPixelConnect

*/
#include <Arduino.h>
#include <NeoPixelConnect.h>
#include <Wire.h> // penser a changer pins I2C dans setup !
#include <SimpleFOC.h>

#define SIMPLEFOC_PWM_ACTIVE_HIGH true

int OUT1 = 29; // pin out1
int OUT2 = 28; // pin out2
int OUT3 = 27; // pin out3
int MOTOR_ENABLE = 26; // pin enable

float MotorResInOhms = 2.6; //
float MotorInAmps = 1.0;  // 180 M-Amps
float PowerInVolts = 12;
float SensorOffset = 0.60;
int MOTORE_POLE_NB = 7; // 7 Nombre de poles du BLDC
float MOTOR_KV_RATING = 320; // 432.14; // motor.KV_rating = MOTOR_KV_RATING;  rpm/volt - default not set

// BLDC motor & driver instance
BLDCMotor motor = BLDCMotor(MOTORE_POLE_NB); // ??????? Nombre de pôles du moteur
BLDCDriver3PWM driver = BLDCDriver3PWM(OUT1, OUT2, OUT3, MOTOR_ENABLE); // ??????? 3 phases + enable

// magnetic sensor instance - MagneticSensorI2C
MagneticSensorI2C sensor = MagneticSensorI2C(AS5600_I2C);
//MagneticSensorI2C sensor = MagneticSensorI2C(0x36, 12, 0x0E, 4);

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

#define MAXIMUM_NUM_NEOPIXELS 1
int NeoPixelPin = 16;
int Intensity = 200;
NeoPixelConnect p(NeoPixelPin, MAXIMUM_NUM_NEOPIXELS, pio0, 0);

//▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬setup▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬
void setup() {
  // Led
  p.neoPixelFill(0, Intensity, 0, true);
  p.neoPixelClear(true);

  // use monitoring with serial
  Serial.begin(115200);
  delay(500);

  //▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬sensor_config▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬
  // initialise magnetic sensor hardware
  Wire.setClock(1000000); // Try calling Wire.setClock(400000) or 1000000 or 3400000 to speed up the i2c bus.
  Wire.setSDA(0); // pin SDA
  Wire.setSCL(1); // pin SCL
  Wire.begin();
  delay(500);

  // providing
  // sensor.min_elapsed_time = 0.0001; // 0.0001 ==> 100us by default ==>  10000 Hz ==> 10Khz
  sensor.init(&Wire);

  //▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬driver_config▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬
  // power supply voltage [V]
  driver.voltage_power_supply = PowerInVolts;

  // Max DC voltage allowed
  driver.voltage_limit = PowerInVolts;

  // pwm frequency to be used [Hz]
  // for atmega328 fixed to 32kHz
  // esp32/stm32/teensy configurable
  driver.pwm_frequency = 100000; // 100000

  // init driver
  if (driver.init())  Serial.println("Driver init success!");
  else {
    Serial.println("Driver init failed!");
    return;
  }

  //▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬motor_config▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬

  // link the motor to the sensor
  motor.linkSensor(&sensor);
  // choose FOC modulation
  // FOCModulationType::SinePWM;
  motor.foc_modulation = FOCModulationType::SinePWM; //  SinePWM SpaceVectorPWM

  // link the motor and the driver
  motor.linkDriver(&driver);

  // set torque mode to be used
  // TorqueControlType::voltage    ( default )
  // TorqueControlType::dc_current
  // TorqueControlType::foc_current
  motor.torque_controller = TorqueControlType::voltage;

  // Closed-Loop control
  //SimpleFOClibrary gives you the choice of using 3 different Closed-Loop control strategies:
  // set motion control loop to be used
  // MotionControlType::torque
  // MotionControlType::velocity
  // MotionControlType::angle
  motor.controller = MotionControlType::angle;

  // contoller configuration
  // default parameters in defaults.h

  // velocity PI controller parameters
  motor.PID_velocity.P = 0.2f; // 0.2f 0.8f
  motor.PID_velocity.I = 20.0f; // 20
  motor.PID_velocity.D = 0.001; // 0.001 / 0

  // jerk control using voltage voltage ramp
  // default value is 300 volts per sec  ~ 0.3V per millisecond
  motor.PID_velocity.output_ramp = 1000; // 1000

  // setting the limits
  //  maximal velocity of the position control
  motor.velocity_limit = 100; // rad/s - default 20 (limite vitesse & 6 vitese est lent mais ok)

  // velocity low pass filtering time constant
  // the lower the less filtered
  motor.LPF_velocity.Tf = 0.04f; // 0.01f ==> max 0.06 après vibre en mode velocity !

  // angle PID controller
  // default P=20
  motor.P_angle.P = 20.0f; // 6 20  80 (faible amortis l'arrêt)
  motor.P_angle.I = 0;  // 0 usually only P controller is enough
  motor.P_angle.D = 0;  // 0 usually only P controller is enough
  // acceleration control using output ramp
  // this variable is in rad/s^2 and sets the limit of acceleration
  motor.P_angle.output_ramp = 10000; // 10000 // default 1e6 rad/s^2

  // angle low pass filtering
  // default 0 - disabled
  // use only for very noisy position sensors - try to avoid and keep the values very small
  motor.LPF_angle.Tf = 0; // default 0

  // sensor offset [rad]
  motor.sensor_offset = SensorOffset; // default 0 rad (dcaler offset 0 sur capteur/encodeur=

  // limiting voltage
  motor.voltage_limit = 3; // PowerInVolts  // limiting Voltage Volts

  // Global current limit. Limits Q-axis current.
  motor.current_limit = MotorInAmps; // 180 M-Amps

  // motor phase resistance [Ohms]
  motor.phase_resistance = MotorResInOhms; //

  // motor KV rating [rpm/V]
  //KV = velocity_at_one_volt * 30/pi
  //motor.KV_rating = MOTOR_KV_RATING; // rpm/volt - default not set

  //▬▬▬▬▬▬▬▬Velocity PID controller output limit. Set to limit velocity to this maximum.
  // ATTENTION volts ou amps ???
  // https://community.simplefoc.com/t/setting-current-limits-in-main-loop/1972/2
  motor.PID_velocity.limit = 12;

  // aligning voltage [V]
  motor.voltage_sensor_align = 3; // default 3V
  // incremental encoder index search velocity [rad/s]
  motor.velocity_index_search = 3; // default 1 rad/s

  motor.sensor_direction = Direction::CW; // CW or CCW
  motor.zero_electric_angle = 6.2280;

  // Set to values > 1 to reduce how often move() is executed compared to loopFOC().
  // On fast MCUs it makes sense to reduce how often move() gets called.
  motor.motion_downsample = 0;

  // initialize motor
  motor.init();

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

  // https://github.com/simplefoc/Arduino-FOC/blob/dev/src/common/defaults.h
  // https://docs.simplefoc.com/cheetsheet/options_reference
  // https://docs.simplefoc.com/commander_interface
  // https://docs.simplefoc.com/commander_motor
  // https://docs.simplefoc.com/commander_target

  // https://docs.simplefoc.com/studio
  // add the motor to the commander interface
  // The letter (here 'M') you will provide to the SimpleFOCStudio
  //command.add('M', doMotor, "My motor motion");
  command.add('M', doMotor, "motor");
  command.decimal_places = 4; // default 3 (moi 4)
  // tell the motor to use the monitoring
  motor.useMonitoring(Serial);
  motor.monitor_downsample = 0; // 0 = disable monitor at first - optional

  // Led
  p.neoPixelFill(Intensity, 0, 0, true);
  p.neoPixelClear(true);

  _delay(1000);
} // End_setup
//▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬End_setup▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬


//▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬loop▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬
void loop() {
  // main FOC algorithm function
  motor.loopFOC();

  // Motion control function
  // velocity, position or voltage (defined in motor.controller)
  // this function can be run at much lower frequency than loopFOC() function
  // You can also use motor.move() and set the motor.target in the code

  // Motion control function
  motor.move();

  //Serial.print(String(sensor.getAngle()) + "\t" + String(sensor.getVelocity()) + "\t" + String(((sensor.getAngle()-motor.sensor_offset)*180/_PI)) + "\n");

  // calculate the KV
  //Serial.println(motor.shaft_velocity / motor.target * 30.0f / _PI);

  // function intended to be used with serial plotter to monitor motor variables
  // significantly slowing the execution down!!!!
  motor.monitor();

  // user communication
  command.run();
} // End_loop
//▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬End_loop▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬▬

A short video (Sorry I’m not good at amateur video :-p )
https://youtu.be/CqxPtJRbVbk

1 Like