Thanks Valentine for your reply. I’ve already seen this thread but couldn’t find any points to try in my setup. Let me summarise:
-
lib_archive = false build flag → check
-
no print statements in main loop → check
-
test only one motor → check
The supply/motor voltage topic didn’t seem relevant for me, because the noise is only present when I switch to the Lib V2.3.4. But I double checked it and corrected the values a little bit and it reduced the clicking noise a little bit. That means that it appears at a bigger target value.
You also mentioned a counter over-flow issue. I don’t know what to check or where to find more information on this.
Anyway, I striped down my code to a minimum. Maybe someone will find a critical part or give me some hints on what to test next. But I think there must be some lib changes from V2.3.3 to V2.3.4, the ESP32 toolchain or maybe the API…
greetings
bedyn
#include <Arduino.h>
#include <SimpleFOC.h>
#include "SimpleFOCDrivers.h"
#include "encoders/calibrated/CalibratedSensor.h"
#include "encoders/as5047/MagneticSensorAS5047.h"
// #include "myUtils.h"
BLDCMotor motor0 = BLDCMotor(7);
BLDCDriver3PWM driver0 = BLDCDriver3PWM(32,33,25,22);
#define sen0_CS 5 // MKS-ESP32 -> SCL_1
#define sen1_CS 13 // MKS-ESP32 -> I_1
#define sen_mosi 23 // MKS-ESP32 -> SDA_1
#define sen_miso 19 // MKS-ESP32 -> SDA_0
#define sen_sclk 18 // MKS-ESP32 -> SCL_0
#define EncoderSPISpeed 5000000 // SPI Speed for encoder
SPIClass * spi_bus_ptr = NULL;
SPISettings mySPISettings(EncoderSPISpeed, AS5047_BITORDER, SPI_MODE1); // siehe Definition in "simplefoc-driver"; https://community.simplefoc.com/t/challenges-going-faster-than-certain-rpm/1688/19
MagneticSensorAS5047 encoder0(sen0_CS, false, mySPISettings); // https://github.com/simplefoc/Arduino-FOC-drivers/tree/master/src/encoders/as5047
bool skip_sens_allign = false;
bool skip_curr_allign = false;
bool calibrate_motor = false;
float target_velocity = 0;
float i_alpha;
float i_beta;
const int dt_clock_us = 200;
unsigned long time_now_us = 0;
unsigned long time_now_1_us = 0;
unsigned long t_chk_phase = 0;
unsigned long t1 = 0;
unsigned long dt1 = 0;
DQCurrent_s current;
PhaseCurrent_s current_phases;
AS5047Diagnostics diagnostics;
bool diagFl1 = false;
bool diagFl2 = false;
bool drv_disable_Fl = false;
bool drv_enable_Fl = false;
bool fl_normal_loop = true;
bool fl_chck_Ph_a = false;
bool fl_chck_Ph_b = false;
bool fl_chck_Ph_c = false;
static long count_move = 0;
bool fl_bg_meas = false;
bool fl_bg_down = false;
bool fl_sens_zero = false;
bool fl_check_encoder0 = false;
const int N_meas = 2500; // Angenommene Anzahl der Messwerte fuer Array
const int mod_meas_val = 50; // jeder x Wert wird nur gemessen
String inputString = ""; // a String to hold incoming data
bool stringComplete = false; // whether the string is complete
int i;
char send_str[300];
int t_ms_start;
double current_a[N_meas];
double current_b[N_meas];
double current_c[N_meas];
bool flCheckCommand = false;
const unsigned int MAX_INPUT_ = 50; // how much serial data we expect before a newline
char ser_char_Arr[MAX_INPUT_];
char char_arr_small[15];
char *char_arr_small_ptr = char_arr_small;
// InlineCurrentSense current_sense0 = InlineCurrentSense(0.01f, 50.0f, 39, 36); // etsten beide Args muessen mit float def. werden, z.B. 0.01f, 50.0f
// include commander interface
Commander command = Commander(Serial);
// comander functions
void doTarget(char* cmd) {
command.scalar(&motor0.target, cmd);
}
void doMotor(char* cmd) {
command.motor(&motor0, cmd);
}
void setup(){
Serial.begin(115200);
while (!Serial) {;}
_delay(5000);
Serial.println("Serial ready!");
// Debug:
SimpleFOCDebug::enable();
// initialize encoder hardware
spi_bus_ptr = new SPIClass(VSPI);
spi_bus_ptr->begin(sen_sclk, sen_miso, sen_mosi, sen0_CS);
encoder0.init(spi_bus_ptr);
delay(100);
motor0.linkSensor(&encoder0);
// ------------------- driver config ----------------------
driver0.voltage_power_supply = 20;
driver0.pwm_frequency = 25000;
driver0.voltage_limit = 20;
driver0.init();
// link the driver to the current sense
// current_sense0.linkDriver(&driver0);
// link the motor and the driver
motor0.linkDriver(&driver0);
// init motor
motor0.init();
motor0.phase_resistance = 16.;
// current_sense0.init();
// current_sense0.gain_b *= 1;
// current_sense0.gain_a *= 1;
// motor0.linkCurrentSense(¤t_sense0);
motor0.voltage_sensor_align = 8;
// --------- motor0 Parameters V2 ------------
motor0.PID_velocity.P = 0.07;
motor0.PID_velocity.I = 0.05;
motor0.PID_velocity.D = 0.0;
motor0.PID_velocity.output_ramp = 0.0;
motor0.PID_velocity.limit = 2.0;
motor0.LPF_velocity.Tf = 0.01;
// angle loop PID
motor0.P_angle.P = 20.0;
motor0.P_angle.I = 0.0;
motor0.P_angle.D = 0.0;
motor0.P_angle.output_ramp = 0.0;
motor0.P_angle.limit = 20.0;
motor0.LPF_angle.Tf = 0.1;
// current q loop PID
motor0.PID_current_q.P = 3;
motor0.PID_current_q.I = 300.0;
motor0.PID_current_q.D = 0.0;
motor0.PID_current_q.output_ramp = 0;
motor0.PID_current_q.limit = 10.0;
motor0.LPF_current_q.Tf = 0.01;
// current d loop PID
motor0.PID_current_d.P = 3;
motor0.PID_current_d.I = 300.0;
motor0.PID_current_d.D = 0.0;
motor0.PID_current_d.output_ramp = 0;
motor0.PID_current_d.limit = 10.0;
motor0.LPF_current_d.Tf = 0.01;
// Limits
motor0.velocity_limit = 70.0;
motor0.voltage_limit = 10;
motor0.current_limit = 3.0;
motor0.foc_modulation = FOCModulationType::SinePWM;
motor0.modulation_centered = 1.0;
// set motion control loop to be used
motor0.torque_controller = TorqueControlType::voltage;
// motor0.torque_controller = TorqueControlType::dc_current;
//motor0.torque_controller = TorqueControlType::foc_current;
motor0.controller = MotionControlType::torque;
//motor0.controller = MotionControlType::velocity;
motor0.motion_downsample = 10.0;
// comment out if not needed
motor0.useMonitoring(Serial);
motor0.monitor_downsample = 100; // set downsampling can be even more > 100 // hier Fehler in Beispielcode
//motor0.monitor_variables = _MON_CURR_Q | _MON_CURR_D; // set monitoring of d and q currents
motor0.initFOC();
// set the initial motor target
motor0.target = 0.0; // Amps - if phase resistance defined
// add target command T
// command.add('T', doTarget, "target velocity");
command.add('T', doTarget, "target");
// add the motor to the commander interface
// The letter (here 'M') you will provide to the SimpleFOCStudio
command.add('M', doMotor, "motor");
// //motor0.monitor_variables = _MON_TARGET | _MON_VEL | _MON_ANGLE;
// motor0.monitor_variables = _MON_CURR_Q | _MON_CURR_D; // set monitoring of d and q currents
motor0.monitor_variables = 0;
}
void loop(){
// if((unsigned long)(micros() - time_now_us) > dt_clock_us)
// {
if (fl_normal_loop) {
t1 = micros();
time_now_us = micros();
motor0.loopFOC();
count_move++;
if (count_move % 20 ==0) {
//motor0.move(target_velocity); // muss regelmaessig durchlaufen werden!
motor0.move(); // muss regelmaessig durchlaufen werden!
count_move = 0;
}
// current_phases = current_sense0.getPhaseCurrents();
// current_phases.c = -(current_phases.a + current_phases.b);
// i_alpha = current_phases.a;
// i_beta = _1_SQRT3 * current_phases.a + _2_SQRT3 * current_phases.b;
command.run();
dt1 = micros()-t1;
// Serial.println(dt1);
}
if (fl_check_encoder0)
{
if (count_move % 50 ==0)
{
encoder0.update();
Serial.print(encoder0.getAngle());
Serial.print("\t");
Serial.println(encoder0.getVelocity());
}
} // End fl_check_encoder0
// }
}
platformio.ini File:
[platformio]
default_envs = project
[env]
framework = arduino
monitor_filters = send_on_enter
monitor_eol = LF
# dummy
[env:project]
[env:esp32dev]
build_src_filter =
+<main_MKS_ESP32_V1.cpp>
# +<myUtils.cpp>
monitor_speed = 115200
platform = espressif32
board = esp32dev
lib_deps =
# works with platform = espressif32:
# https://github.com/simplefoc/Arduino-FOC#v2.3.3
# https://github.com/simplefoc/Arduino-FOC-drivers#v1.0.7
# works with platform = espressif32 and platform_packages = ...:
https://github.com/simplefoc/Arduino-FOC#v2.3.4
https://github.com/simplefoc/Arduino-FOC-drivers#v1.0.8
SPI
Wire
platform_packages =
framework-arduinoespressif32 @ https://github.com/espressif/arduino-esp32.git # siehe Infos in https://community.simplefoc.com/t/having-hard-time-using-v2-3-4-in-platformio/5246/9
framework-arduinoespressif32-libs @ https://github.com/espressif/arduino-esp32/releases/download/3.0.4/esp32-arduino-libs-3.0.4.zip # siehe Infos in https://community.simplefoc.com/t/having-hard-time-using-v2-3-4-in-platformio/5246/9
lib_archive = false # um simplefoc korrekt zu kompilieren
build_flags =
-Wl,-u_printf_float # freischalten float in sprintf Fcn; https://www.e-tinkers.com/2020/01/do-you-know-arduino-sprintf-and-floating-point/
# -v # verbose Modus