PID parameters adapted - but not fine tunned.

This commit is contained in:
jenoack 2023-03-16 09:06:27 +01:00
parent 3a69935127
commit 457b13c46b
3 changed files with 56 additions and 55 deletions

View file

@ -13,7 +13,8 @@ typedef struct
const char * unit; const char * unit;
double value; double value;
float unit_factor; float unit_factor;
unsigned long last_update_ms; unsigned long prev_update_ms;
unsigned long act_update_ms;
unsigned long timestamp; unsigned long timestamp;
} DataStruct; } DataStruct;

View file

@ -55,6 +55,7 @@ Servo ESC; // Der ESC-Controller (Electronic Speed Controller bzw. elektroni
Oled display; Oled display;
const unsigned long UPDATE_TURN_VALUES_EVERY_MS = 1000; const unsigned long UPDATE_TURN_VALUES_EVERY_MS = 1000;
const unsigned long UPDATE_ESC_EVERY_MS = 0;
const uint8_t HALL_SENSORS_COUNT = 8; // input, sec, min, hour, day, week, month, year const uint8_t HALL_SENSORS_COUNT = 8; // input, sec, min, hour, day, week, month, year
const uint8_t ALL_DATA_COUNT = HALL_SENSORS_COUNT; const uint8_t ALL_DATA_COUNT = HALL_SENSORS_COUNT;
@ -102,7 +103,7 @@ const uint8_t HALL8_PIN = 14;
const uint16_t MIN_SPEED = 600; const uint16_t MIN_SPEED = 600;
const uint16_t MAX_SPEED = 1200; const uint16_t MAX_SPEED = 1200;
const uint8_t MAX_ESC_SPEED = 60; const uint8_t MAX_ESC_SPEED = 60;
const uint8_t MIN_ESC_SPEED = 35; const uint8_t MIN_ESC_SPEED = 37;
const uint16_t MAX_POTI_VALUE = 4095; const uint16_t MAX_POTI_VALUE = 4095;
const uint16_t JITTER_POTI_PERCENT = 10; const uint16_t JITTER_POTI_PERCENT = 10;

View file

@ -17,9 +17,9 @@ volatile double goal_speed = 1000; //1.0 * speed;
volatile double current_speed = 0; volatile double current_speed = 0;
volatile double err = 0; volatile double err = 0;
volatile double output = 0.0; volatile double output = 0.0;
const double kp = 0.01; const double kp = 0.005;
const double ki = 0.001; const double ki = 0.0008;
const double kd = 0.0005; const double kd = 0.0001;
void ISR_HALL1(); void ISR_HALL1();
void ISR_HALL2(); void ISR_HALL2();
@ -35,6 +35,7 @@ void data_generate();
void data_store(); void data_store();
void data_check(); void data_check();
void data_init(); void data_init();
void speed_get();
void speed_set(); void speed_set();
void count_secs(time_t* run_time); void count_secs(time_t* run_time);
@ -75,7 +76,7 @@ void setup()
// Initialise timer // Initialise timer
timer = timerBegin(0, 80, true); // Timer 0, Prescaler 80, zähle im Up-Modus timer = timerBegin(0, 80, true); // Timer 0, Prescaler 80, zähle im Up-Modus
timerAttachInterrupt(timer, &ISR_onTimer, true); // Setze den Interrupt-Handler und aktiviere den Interrupt auf steigende Flanke timerAttachInterrupt(timer, &ISR_onTimer, true); // Setze den Interrupt-Handler und aktiviere den Interrupt auf steigende Flanke
timerAlarmWrite(timer, 1000000, true); // Setze den Alarm auf 1/4 Sekunde und aktiviere ihn timerAlarmWrite(timer, 1000000/8, true); // Setze den Alarm auf 1/4 Sekunde und aktiviere ihn
timerAlarmEnable(timer); // Aktiviere den Alarm timerAlarmEnable(timer); // Aktiviere den Alarm
pinMode(39, INPUT_PULLDOWN); pinMode(39, INPUT_PULLDOWN);
@ -113,8 +114,9 @@ void loop()
data_generate(); data_generate();
count_secs(&run_time); count_secs(&run_time);
speed_get();
speed_set(); speed_set();
//data_check(); data_check();
data_store(); data_store();
#ifdef HAS_MQTT #ifdef HAS_MQTT
@ -123,8 +125,7 @@ void loop()
display.show_values(speed, MIN_SPEED, MAX_SPEED, HallData, HALL_SENSORS_COUNT, run_time, capportal.localIP()); display.show_values(speed, MIN_SPEED, MAX_SPEED, HallData, HALL_SENSORS_COUNT, run_time, capportal.localIP());
Serial.printf("PID ... (goal: %06.3f, current: %06.3f, err: %06.3f, integ: %06.3f, derive: %06.3f, output=%06.3f), esc_output=%06.3f \n", goal_speed, current_speed, err, integ, derivative, output, esc_output);
ESC.write(50);
} }
void count_secs(time_t* run_time) void count_secs(time_t* run_time)
@ -142,6 +143,24 @@ void count_secs(time_t* run_time)
} }
void speed_set() void speed_set()
{
static unsigned long last_esc_write_ms = 0;
static double last_esc_output = 0;
if(0 == last_esc_write_ms || millis() - last_esc_write_ms > UPDATE_ESC_EVERY_MS)
{
Serial.printf(">goal:%06.3f\n>current:%06.3f\n>err:%06.3f\n>integ:%06.3f\n>derive:%06.3f\n>output:%06.3f\n>esc_output:%06.3f\n", goal_speed, current_speed, err, integ, derivative, output, esc_output);
if(esc_output != last_esc_output)
{
//Serial.printf("PID ... (goal>:%06.3f, current>:%06.3f, err>:%06.3f, integ>:%06.3f, derive>:%06.3f, output>:%06.3f), esc_output>:%06.3f \n", goal_speed, current_speed, err, integ, derivative, output, esc_output);
ESC.write(esc_output);
last_esc_output = esc_output;
last_esc_write_ms = millis();
}
}
}
void speed_get()
{ {
static uint8_t _count_meas = 0; static uint8_t _count_meas = 0;
static int _Drehregler = 0; static int _Drehregler = 0;
@ -219,16 +238,14 @@ void data_init()
AllData[i].value = (AllData[i].ticks * AllData[i].unit_factor); AllData[i].value = (AllData[i].ticks * AllData[i].unit_factor);
} }
#endif #endif
AllData[i].last_update_ms = current_millis; AllData[i].act_update_ms = 0;
AllData[i].prev_update_ms = 0;
} }
} }
/*
void data_check() void data_check()
{ {
unsigned long current_millis = millis();
static unsigned long speedchanged_ms = current_millis ;
/* /*
Serial.printf("H1(pin %d): %d, H2(pin %d): %d, H3(pin %d): %d, H4(pin %d): %d, H5(pin %d) : %d, H6(pin %d) : %d, H7(pin %d) : %d, H8(pin %d) : %d.\n", Serial.printf("H1(pin %d): %d, H2(pin %d): %d, H3(pin %d): %d, H4(pin %d): %d, H5(pin %d) : %d, H6(pin %d) : %d, H7(pin %d) : %d, H8(pin %d) : %d.\n",
HALL1_PIN, digitalRead(HALL1_PIN), HALL1_PIN, digitalRead(HALL1_PIN),
@ -243,22 +260,23 @@ void data_check()
*/ */
/* for(uint8_t nr = 0; nr < HALL_SENSORS_COUNT; nr++)
if(current_millis - speedchanged_ms >= UPDATE_TURN_VALUES_EVERY_MS)
{ {
HallData[0].value = (HallData[0].period_ticks * HallData[0].unit_factor); if( 0 == nr)
HallData[0].period_ticks = 0; {
Serial.printf("current_millis: %lu goal speed: %lu calc speed: %f (%lu ticks in %lu ms) \n", current_millis, speed, HallData[0].value, current_millis - speedchanged_ms); if( (HallData[nr].act_update_ms != 0)
speedchanged_ms = current_millis; && (HallData[nr].prev_update_ms != 0)
} && (HallData[nr].prev_update_ms != HallData[nr].act_update_ms)
)
for(uint8_t nr = 1; nr < HALL_SENSORS_COUNT; nr++) {
{ HallData[nr].value = HallData[nr].unit_factor / (HallData[nr].act_update_ms - HallData[nr].prev_update_ms) ;
HallData[nr].value = (HallData[nr].ticks * HallData[nr].unit_factor); }
HallData[nr].period_ticks = 0; }
else{
HallData[nr].value = (HallData[nr].ticks * HallData[nr].unit_factor);
}
} }
} }
*/
void data_store() void data_store()
{ {
@ -287,16 +305,11 @@ void IRAM_ATTR ISR_HALL1()
HallData[hallnr].timestamp = run_time; HallData[hallnr].timestamp = run_time;
// each 4 ticks is one turn // each 4 ticks is one turn
// so we calculate speed each 4 ticks... just in case we check for bigger ... // so we calculate speed each 4 ticks... just in case we check for bigger ...
/*
if(HallData[hallnr].period_ticks >= HALL_TICKS_PER_TURN){ if(HallData[hallnr].period_ticks >= HALL_TICKS_PER_TURN){
HallData[hallnr].period_ticks = 0; HallData[hallnr].period_ticks = 0;
if(HallData[hallnr].last_update_ms != 0) HallData[hallnr].prev_update_ms = HallData[hallnr].act_update_ms;
{ HallData[hallnr].act_update_ms = millis();
HallData[hallnr].value = HallData[hallnr].unit_factor / HallData[hallnr].last_update_ms;
}
HallData[hallnr].last_update_ms = millis();
} }
*/
} }
void IRAM_ATTR ISR_HALL2() void IRAM_ATTR ISR_HALL2()
@ -304,8 +317,7 @@ void IRAM_ATTR ISR_HALL2()
const uint8_t hallnr = 1; const uint8_t hallnr = 1;
HallData[hallnr].ticks++; HallData[hallnr].ticks++;
HallData[hallnr].timestamp = run_time; HallData[hallnr].timestamp = run_time;
HallData[hallnr].last_update_ms = millis(); HallData[hallnr].act_update_ms = millis();
//HallData[hallnr].value = (HallData[hallnr].ticks * HallData[hallnr].unit_factor);
} }
void IRAM_ATTR ISR_HALL3() void IRAM_ATTR ISR_HALL3()
@ -313,8 +325,7 @@ void IRAM_ATTR ISR_HALL3()
const uint8_t hallnr = 2; const uint8_t hallnr = 2;
HallData[hallnr].ticks++; HallData[hallnr].ticks++;
HallData[hallnr].timestamp = run_time; HallData[hallnr].timestamp = run_time;
HallData[hallnr].last_update_ms = millis(); HallData[hallnr].act_update_ms = millis();
//HallData[hallnr].value = (HallData[hallnr].ticks * HallData[hallnr].unit_factor);
} }
void IRAM_ATTR ISR_HALL4() void IRAM_ATTR ISR_HALL4()
@ -322,8 +333,7 @@ void IRAM_ATTR ISR_HALL4()
const uint8_t hallnr = 3; const uint8_t hallnr = 3;
HallData[hallnr].ticks++; HallData[hallnr].ticks++;
HallData[hallnr].timestamp = run_time; HallData[hallnr].timestamp = run_time;
HallData[hallnr].last_update_ms = millis(); HallData[hallnr].act_update_ms = millis();
//HallData[hallnr].value = (HallData[hallnr].ticks * HallData[hallnr].unit_factor);
} }
void IRAM_ATTR ISR_HALL5() void IRAM_ATTR ISR_HALL5()
@ -331,8 +341,7 @@ void IRAM_ATTR ISR_HALL5()
const uint8_t hallnr = 4; const uint8_t hallnr = 4;
HallData[hallnr].ticks++; HallData[hallnr].ticks++;
HallData[hallnr].timestamp = run_time; HallData[hallnr].timestamp = run_time;
HallData[hallnr].last_update_ms = millis(); HallData[hallnr].act_update_ms = millis();
//HallData[hallnr].value = (HallData[hallnr].ticks * HallData[hallnr].unit_factor);
} }
void IRAM_ATTR ISR_HALL6() void IRAM_ATTR ISR_HALL6()
@ -340,8 +349,7 @@ void IRAM_ATTR ISR_HALL6()
const uint8_t hallnr = 5; const uint8_t hallnr = 5;
HallData[hallnr].ticks++; HallData[hallnr].ticks++;
HallData[hallnr].timestamp = run_time; HallData[hallnr].timestamp = run_time;
HallData[hallnr].last_update_ms = millis(); HallData[hallnr].act_update_ms = millis();
//HallData[hallnr].value = (HallData[hallnr].ticks * HallData[hallnr].unit_factor);
} }
void IRAM_ATTR ISR_HALL7() void IRAM_ATTR ISR_HALL7()
@ -349,8 +357,7 @@ void IRAM_ATTR ISR_HALL7()
const uint8_t hallnr = 6; const uint8_t hallnr = 6;
HallData[hallnr].ticks++; HallData[hallnr].ticks++;
HallData[hallnr].timestamp = run_time; HallData[hallnr].timestamp = run_time;
HallData[hallnr].last_update_ms = millis(); HallData[hallnr].act_update_ms = millis();
//HallData[hallnr].value = (HallData[hallnr].ticks * HallData[hallnr].unit_factor);
} }
void IRAM_ATTR ISR_HALL8() void IRAM_ATTR ISR_HALL8()
@ -358,13 +365,9 @@ void IRAM_ATTR ISR_HALL8()
const uint8_t hallnr = 7; const uint8_t hallnr = 7;
HallData[hallnr].ticks++; HallData[hallnr].ticks++;
HallData[hallnr].timestamp = run_time; HallData[hallnr].timestamp = run_time;
HallData[hallnr].last_update_ms = millis(); HallData[hallnr].act_update_ms = millis();
//HallData[hallnr].value = (HallData[hallnr].ticks * HallData[hallnr].unit_factor);
} }
void IRAM_ATTR ISR_onTimer() void IRAM_ATTR ISR_onTimer()
{ {
current_speed = HallData[0].value; current_speed = HallData[0].value;
@ -379,10 +382,6 @@ void IRAM_ATTR ISR_onTimer()
//Aktualisierung der letzten Fehler- und Zeitwerte //Aktualisierung der letzten Fehler- und Zeitwerte
last_error = err; last_error = err;
//Ansteuerung des Outputs
//ESC.write(50);
} }
//this code is just for generating dummy data - in normal use not needed //this code is just for generating dummy data - in normal use not needed