-
Notifications
You must be signed in to change notification settings - Fork 91
Description
I was trying to configure a calibrated sensor according to the readme. However, the method described at https://github.com/simplefoc/Arduino-FOC-drivers/tree/master/src/encoders/calibrated#edit-march-2025 for hard-coding a calibration map is no longer correct as commit 5dc0563 removed the function signature overload.
The calibration LUT is no longer passed into the calibrate() function, but into the constructor of the CalibratedSensor.
Things that I think are important to point out in a new README are what things need to have init called on (the sensor, not the sensor_calibrated), that one doesn't need to call the calibrate() function at all anymore once a LUT is set and well, the change that the LUT has to be passed into the constructor of CalibratedSensor.
I unfortunately don't have time to write a nicely revised README to PR at the moment, so I figured I'd at least open this issue.
@MarethyuPrefect This may be of interest to you. Also, thanks for writing this implementation in the first place!
For reference, here is a confirmed working script which uses a hard-coded LUT on an ESP32-S3-WROOM1-N18R8:
//unuseable pins:
// 35-37 PSRAM
// 34-39 input-only
// 28-42 Octal PSRAM
// 0 strapping pin with pullup
#include "Arduino.h"
#include "SPI.h"
#include "SimpleFOC.h"
#include "SimpleFOCDrivers.h"
#include "encoders/MT6701/MagneticSensorMT6701SSI.h"
#include <encoders/calibrated/CalibratedSensor.h>
static SPISettings myMT6701SPISettings(4000000, MT6701_BITORDER, SPI_MODE2);
MagneticSensorMT6701SSI sensor = MagneticSensorMT6701SSI(47, myMT6701SPISettings);
float calibrationLut[200] = {
-0.021071, -0.021071, -0.021071, -0.021576, -0.021576, -0.021576, -0.021576, -0.021576, -0.021576, -0.021926, -0.021926, -0.021926, -0.021926, -0.021926, -0.021088, -0.021088,
-0.021088, -0.021088, -0.021088, -0.021088, -0.014881, -0.014881, -0.014881, -0.014881, -0.014881, -0.014881, -0.009479, -0.009479, -0.009479, -0.009479, -0.009479, -0.009479,
-0.004768, -0.004768, -0.004768, -0.004768, -0.004768, 0.003664, 0.003664, 0.003664, 0.003664, 0.003664, 0.003664, 0.008061, 0.008061, 0.008061, 0.008061, 0.008061, 0.008061, 0.008592, 0.008592, 0.008592, 0.008592, 0.008592, 0.008710, 0.008710, 0.008710, 0.008710, 0.008710, 0.008710, 0.011006, 0.011006, 0.011006, 0.011006, 0.011006, 0.011006, 0.010311, 0.010311, 0.010311, 0.010311, 0.010311, 0.010311, 0.014294, 0.014294, 0.014294, 0.014294, 0.014294, 0.014978, 0.014978, 0.014978, 0.014978, 0.014978, 0.014978, 0.013631, 0.013631, 0.013631, 0.013631, 0.013631, 0.013631, 0.012475, 0.012475, 0.012475, 0.012475, 0.012475, 0.009401, 0.009401, 0.009401, 0.009401, 0.009401, 0.009401, 0.006366, 0.006366, 0.006366, 0.006366, 0.006366, 0.006366, 0.004673, 0.004673, 0.004673, 0.004673, 0.004673, 0.004673, 0.003325, 0.003325, 0.003325, 0.003325, 0.003325, 0.004432, 0.004432, 0.004432, 0.004432, 0.004432, 0.004432, 0.006919, 0.006919, 0.006919, 0.006919, 0.006919, 0.006919, 0.007949, 0.007949, 0.007949, 0.007949, 0.007949, 0.009516, 0.009516, 0.009516, 0.009516, 0.009516, 0.009516, 0.008283, 0.008283, 0.008283, 0.008283, 0.008283, 0.008283, 0.004711, 0.004711, 0.004711, 0.004711, 0.004711, 0.004711, 0.002826, 0.002826, 0.002826, 0.002826, 0.002826, -0.000401, -0.000401, -0.000401, -0.000401, -0.000401, -0.000401, -0.003973, -0.003973, -0.003973, -0.003973, -0.003973, -0.003973, -0.004630, -0.004630, -0.004630, -0.004630, -0.004630, -0.007512, -0.007512, -0.007512, -0.007512, -0.007512, -0.007512, -0.012426, -0.012426, -0.012426, -0.012426, -0.012426, -0.012426, -0.013506, -0.013506, -0.013506, -0.013506, -0.013506, -0.013506, -0.016886, -0.016886, -0.016886, -0.016886, -0.016886, -0.021071, -0.021071, -0.021071};
float zero_electric_angle = 4.119193;
Direction sensor_direction = Direction::CW;
CalibratedSensor sensor_calibrated = CalibratedSensor(sensor, 200, calibrationLut);
// CalibratedSensor sensor_calibrated = CalibratedSensor(sensor);
// BLDCDriver3PWM( pin_pwmA, pin_pwmB, pin_pwmC, enable (optional))
BLDCDriver3PWM driver = BLDCDriver3PWM(1, 2, 42, 41);
// BLDCMotor( pole_pairs , ( phase_resistance, KV_rating optional) )
BLDCMotor motor = BLDCMotor(7, 6.5/2, 330);
void setup()
{
delay(2000);
Serial.begin(115200);
motor.useMonitoring(Serial);
// SimpleFOCDebug::enable(&Serial);
SPI.begin(48, 45, -1);
// pwm frequency to be used [Hz]
driver.pwm_frequency = 40000;
// power supply voltage [V]
driver.voltage_power_supply = 9;
// Max DC voltage allowed - default voltage_power_supply
driver.voltage_limit = 9;
// driver init
// set control loop type to be used
// motor.controller = MotionControlType::velocity_openloop;
// motor.controller = MotionControlType::velocity;
motor.zero_electric_angle = zero_electric_angle;
motor.sensor_direction = sensor_direction;
// set control loop type to be used
motor.controller = MotionControlType::velocity;
// velocity PID controller parameters
// default P=0.5 I = 10 D =0
motor.PID_velocity.P = 0.02;
motor.PID_velocity.I = 2;
motor.PID_velocity.D = 0.00;
// jerk control using voltage voltage ramp
// default value is 300 volts per sec ~ 0.3V per millisecond
motor.PID_velocity.output_ramp = 0;
// velocity low pass filtering
// default 5ms - try different values to see what is the best. m,
// the lower the less filtered
motor.LPF_velocity.Tf = 1 / (6.28 * 200);
// setting the limits
// either voltage
// motor.voltage_limit = 10; // Volts - default driver.voltage_limit
// // of current
// motor.current_limit = 2; // Amps - default 0.2Amps
// angle PID controller
// default P=20
motor.P_angle.P = 20;
motor.P_angle.I = 0; // usually only P controller is enough
motor.P_angle.D = 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 = 0; // 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
// setting the limits
// maximal velocity of the position control
motor.velocity_limit = 10000; // rad/s - default 20
// motor.PID_velocity.limit = 1;
// motor.P_angle.limit = 200;
sensor.init();
driver.init();
motor.linkDriver(&driver);
motor.linkSensor(&sensor_calibrated);
motor.init();
// // set voltage to run calibration
// sensor_calibrated.voltage_calibration = 9;
// // Running calibration
// sensor_calibrated.calibrate(motor);
if (motor.initFOC())
Serial.println("FOC init success!");
else
{
Serial.println("FOC init failed!");
return;
}
}
void loop()
{
// motor.disable();
// sensor.update();
// float angle = sensor.getAngle();
// Serial.println(angle);
motor.loopFOC();
motor.move(1);
}