oled methods with some errors, speed calculation
This commit is contained in:
parent
cdafb2a107
commit
ce45893fe9
5 changed files with 100 additions and 33 deletions
|
@ -13,7 +13,6 @@ typedef struct
|
||||||
const char * unit;
|
const char * unit;
|
||||||
double value;
|
double value;
|
||||||
float unit_factor;
|
float unit_factor;
|
||||||
unsigned long prev_update_ms;
|
|
||||||
unsigned long act_update_ms;
|
unsigned long act_update_ms;
|
||||||
unsigned long timestamp;
|
unsigned long timestamp;
|
||||||
} DataStruct;
|
} DataStruct;
|
||||||
|
|
|
@ -60,8 +60,8 @@ const unsigned long UPDATE_ESC_EVERY_MS = 500;
|
||||||
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;
|
||||||
|
|
||||||
const uint8_t HALL_NR_TURNS = 2; ///number of turns we wait before measuring each time
|
|
||||||
const uint8_t HALL_TICKS_PER_TURN = 4;
|
const uint8_t HALL_TICKS_PER_TURN = 4;
|
||||||
|
const uint8_t HALL_NR_TURN = 4;
|
||||||
const uint8_t HALL_MIN_PULSE_MS = 50;
|
const uint8_t HALL_MIN_PULSE_MS = 50;
|
||||||
|
|
||||||
volatile DataStruct AllData[ALL_DATA_COUNT];
|
volatile DataStruct AllData[ALL_DATA_COUNT];
|
||||||
|
@ -101,6 +101,8 @@ const uint8_t HALL6_PIN = 26;
|
||||||
const uint8_t HALL7_PIN = 27;
|
const uint8_t HALL7_PIN = 27;
|
||||||
const uint8_t HALL8_PIN = 14;
|
const uint8_t HALL8_PIN = 14;
|
||||||
|
|
||||||
|
const uint8_t TIME_PER_ROUND_VALS = 10;
|
||||||
|
|
||||||
const uint16_t MIN_SPEED = 800;
|
const uint16_t MIN_SPEED = 800;
|
||||||
const uint16_t MAX_SPEED = 5000;
|
const uint16_t MAX_SPEED = 5000;
|
||||||
const uint8_t MAX_ESC_SPEED = 100;
|
const uint8_t MAX_ESC_SPEED = 100;
|
||||||
|
|
|
@ -34,7 +34,9 @@ class Oled
|
||||||
|
|
||||||
public:
|
public:
|
||||||
void begin();
|
void begin();
|
||||||
void progressBar(uint8_t i);
|
void progressBar(uint8_t i, String big_text, String small_text1, String small_text2);
|
||||||
|
void progressBar(uint8_t i, String big_text = "", String small_text1 = "", String small_text2 = "");
|
||||||
|
void progressBar(uint8_t i, String big_text , String small_text1 = "", String small_text2 = "");
|
||||||
void show_values(int speed, int min_speed, int max_speed, volatile DataStruct *HallData, uint8_t hall_sensors_count, unsigned long runtime, String ipaddr);
|
void show_values(int speed, int min_speed, int max_speed, volatile DataStruct *HallData, uint8_t hall_sensors_count, unsigned long runtime, String ipaddr);
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
|
@ -3,6 +3,8 @@
|
||||||
int Drehregler; // Ausgabewert des Drehreglers
|
int Drehregler; // Ausgabewert des Drehreglers
|
||||||
int speed; // Das Wort "Geschwindigkeit" steht als Variable für den Ansteuerungswert am ESC.
|
int speed; // Das Wort "Geschwindigkeit" steht als Variable für den Ansteuerungswert am ESC.
|
||||||
int last_speed;
|
int last_speed;
|
||||||
|
volatile uint8_t time_per_round_pointer = 0;
|
||||||
|
volatile double time_per_round_ms[TIME_PER_ROUND_VALS];
|
||||||
|
|
||||||
time_t run_time = 0;
|
time_t run_time = 0;
|
||||||
time_t start_time = 0;
|
time_t start_time = 0;
|
||||||
|
@ -42,6 +44,7 @@ void data_init();
|
||||||
void speed_get();
|
void speed_get();
|
||||||
void speed_set();
|
void speed_set();
|
||||||
void PID();
|
void PID();
|
||||||
|
double time_per_round_calc();
|
||||||
void count_secs(time_t* run_time);
|
void count_secs(time_t* run_time);
|
||||||
|
|
||||||
void get_serial_cmd();
|
void get_serial_cmd();
|
||||||
|
@ -59,6 +62,17 @@ void setup()
|
||||||
randomSeed(micros());
|
randomSeed(micros());
|
||||||
|
|
||||||
display.begin();
|
display.begin();
|
||||||
|
|
||||||
|
/*
|
||||||
|
display->setTextAlignment(TEXT_ALIGN_CENTER);
|
||||||
|
display->setFont(ArialMT_Plain_16);
|
||||||
|
display->drawString(64, 2, "Init controller");
|
||||||
|
display->setFont(ArialMT_Plain_10);
|
||||||
|
display->drawString(64, 40, "You may hear some beeps.");
|
||||||
|
display->drawString(64, 52, "That's OK! ;-)");
|
||||||
|
display->display();
|
||||||
|
*/
|
||||||
|
|
||||||
capportal.begin();
|
capportal.begin();
|
||||||
html_content = "<!DOCTYPE html><html><head><meta http-equiv=\"refresh\" content=\"0; url='/_ac'\" /></head><body></body></html>";
|
html_content = "<!DOCTYPE html><html><head><meta http-equiv=\"refresh\" content=\"0; url='/_ac'\" /></head><body></body></html>";
|
||||||
|
|
||||||
|
@ -70,16 +84,21 @@ void setup()
|
||||||
|
|
||||||
Serial.println("Init ETC ...");
|
Serial.println("Init ETC ...");
|
||||||
ESC.attach(ESC_PIN,1000,2000);
|
ESC.attach(ESC_PIN,1000,2000);
|
||||||
display.progressBar(0);
|
display.progressBar(0,"Init controller");
|
||||||
ESC.write(180);
|
ESC.write(180);
|
||||||
|
delay(1000);
|
||||||
|
display.progressBar(1,"Connect ETC now!");
|
||||||
delay(5000);
|
delay(5000);
|
||||||
|
display.progressBar(2,"Calibrating ETC", "You may hear some beeps.", "That's OK! ;-)");
|
||||||
ESC.write(0);
|
ESC.write(0);
|
||||||
for(uint8_t i=0;i<=100;i=i+10)
|
for(uint8_t i=3;i<=100;i=i+10)
|
||||||
{
|
{
|
||||||
display.progressBar(i);
|
display.progressBar(i);
|
||||||
delay(1000);
|
delay(1000);
|
||||||
}
|
}
|
||||||
ESC.write(0);
|
ESC.write(0);
|
||||||
|
display.progressBar(100,"ETC init done!");
|
||||||
|
delay(1000);
|
||||||
data_init();
|
data_init();
|
||||||
|
|
||||||
// Initialise timer
|
// Initialise timer
|
||||||
|
@ -100,9 +119,6 @@ void setup()
|
||||||
pinMode(HALL7_PIN, INPUT);
|
pinMode(HALL7_PIN, INPUT);
|
||||||
pinMode(HALL8_PIN, INPUT);
|
pinMode(HALL8_PIN, INPUT);
|
||||||
|
|
||||||
//Serial.println("Init light sensor interrupt ...");
|
|
||||||
//attachInterrupt(LS1_PIN, ISR_LS1, RISING);
|
|
||||||
|
|
||||||
Serial.println("Init hall sensor interrupts ...");
|
Serial.println("Init hall sensor interrupts ...");
|
||||||
attachInterrupt(digitalPinToInterrupt(HALL1_PIN), ISR_HALL1, FALLING);
|
attachInterrupt(digitalPinToInterrupt(HALL1_PIN), ISR_HALL1, FALLING);
|
||||||
attachInterrupt(digitalPinToInterrupt(HALL2_PIN), ISR_HALL2, FALLING);
|
attachInterrupt(digitalPinToInterrupt(HALL2_PIN), ISR_HALL2, FALLING);
|
||||||
|
@ -169,35 +185,58 @@ void PID()
|
||||||
//current_speed = map(HallData[0].value, MIN_SPEED, MAX_SPEED, MIN_ESC_SPEED, MAX_ESC_SPEED);
|
//current_speed = map(HallData[0].value, MIN_SPEED, MAX_SPEED, MIN_ESC_SPEED, MAX_ESC_SPEED);
|
||||||
|
|
||||||
double int_err = goal_speed - current_speed;
|
double int_err = goal_speed - current_speed;
|
||||||
double int_integ = integ + int_err;
|
double int_integ = ki>0?integ + int_err:0;
|
||||||
double int_derivative = (int_err - last_error);
|
double int_derivative = kd>0?(int_err - last_error):0;
|
||||||
double int_output = kp * int_err + ki * int_integ + kd * int_derivative;
|
double int_output = kp * int_err + ki * int_integ + kd * int_derivative;
|
||||||
if( int_output <= MIN_SPEED)
|
if( int_output <= MIN_ESC_SPEED)
|
||||||
{
|
{
|
||||||
output = MIN_SPEED;
|
output = MIN_ESC_SPEED;
|
||||||
}
|
}
|
||||||
else if( int_output > MAX_SPEED)
|
else if( int_output > MAX_ESC_SPEED)
|
||||||
{
|
{
|
||||||
output = MAX_SPEED;
|
output = MAX_ESC_SPEED;
|
||||||
}
|
}
|
||||||
else if((int_output >= MIN_SPEED) && (int_output <= MAX_SPEED))
|
else if((int_output >= MIN_ESC_SPEED) && (int_output <= MAX_ESC_SPEED))
|
||||||
{
|
{
|
||||||
err = int_err;
|
err = int_err;
|
||||||
integ = int_integ;
|
integ = int_integ;
|
||||||
derivative = int_derivative;
|
derivative = int_derivative;
|
||||||
output = int_output;
|
output = int_output;
|
||||||
}
|
}
|
||||||
|
esc_output = constrain(output, MIN_ESC_SPEED, MAX_ESC_SPEED);
|
||||||
//Beschränkung der Ausgabe
|
|
||||||
esc_output = speed_map(output, MIN_SPEED, MAX_SPEED, MIN_ESC_SPEED, MAX_ESC_SPEED);
|
|
||||||
|
|
||||||
//Serial.printf("PID ... (goal: %f, current: %06.3f, err: %06.3f, integ: %06.3f, derive: %06.3f) output=%06.3f \n", goal_speed, current_speed, err, integ, derivative, output);
|
//Serial.printf("PID ... (goal: %f, current: %06.3f, err: %06.3f, integ: %06.3f, derive: %06.3f) output=%06.3f \n", goal_speed, current_speed, err, integ, derivative, output);
|
||||||
|
|
||||||
//Aktualisierung der letzten Fehler- und Zeitwerte
|
//Aktualisierung der letzten Fehler- und Zeitwerte
|
||||||
last_error = err;
|
last_error = err;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
double time_per_round_calc()
|
||||||
|
{
|
||||||
|
double mid_time = 0;
|
||||||
|
double min_time = -1;
|
||||||
|
double max_time = 0;
|
||||||
|
uint8_t nr_times = 0;
|
||||||
|
for(uint8_t i = 0; i < TIME_PER_ROUND_VALS; i++)
|
||||||
|
{
|
||||||
|
if(time_per_round_ms[i] >= 0)
|
||||||
|
{
|
||||||
|
if(time_per_round_ms[i] < min_time || min_time == -1)
|
||||||
|
{
|
||||||
|
min_time = time_per_round_ms[i];
|
||||||
|
}
|
||||||
|
else if(time_per_round_ms[i] > max_time)
|
||||||
|
{
|
||||||
|
max_time = time_per_round_ms[i];
|
||||||
|
}
|
||||||
|
nr_times++;
|
||||||
|
mid_time = mid_time + time_per_round_ms[i];
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if(nr_times >= 3)
|
||||||
|
{
|
||||||
|
mid_time = (mid_time - max_time - min_time)/(nr_times - 2);
|
||||||
|
}
|
||||||
|
return(mid_time);
|
||||||
|
}
|
||||||
|
|
||||||
void speed_set()
|
void speed_set()
|
||||||
{
|
{
|
||||||
|
@ -284,6 +323,10 @@ void data_init()
|
||||||
#endif
|
#endif
|
||||||
last_speed = 0;
|
last_speed = 0;
|
||||||
speed = 0;
|
speed = 0;
|
||||||
|
for (uint8_t i= 0; i < TIME_PER_ROUND_VALS; i++)
|
||||||
|
{
|
||||||
|
time_per_round_ms[i] = -1;
|
||||||
|
}
|
||||||
unsigned long current_millis = millis();
|
unsigned long current_millis = millis();
|
||||||
for (uint8_t i = 0; i < ALL_DATA_COUNT; i ++)
|
for (uint8_t i = 0; i < ALL_DATA_COUNT; i ++)
|
||||||
{
|
{
|
||||||
|
@ -304,7 +347,7 @@ void data_init()
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
AllData[i].act_update_ms = 0;
|
AllData[i].act_update_ms = 0;
|
||||||
AllData[i].prev_update_ms = 0;
|
//AllData[i].prev_update_ms = 0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -329,12 +372,10 @@ void data_check()
|
||||||
{
|
{
|
||||||
if( 0 == nr)
|
if( 0 == nr)
|
||||||
{
|
{
|
||||||
if( (HallData[nr].act_update_ms != 0)
|
double mid_time = time_per_round_calc();
|
||||||
&& (HallData[nr].prev_update_ms != 0)
|
if( mid_time != 0)
|
||||||
&& (HallData[nr].prev_update_ms != HallData[nr].act_update_ms)
|
|
||||||
)
|
|
||||||
{
|
{
|
||||||
HallData[nr].value = HallData[nr].unit_factor / ((HallData[nr].act_update_ms - HallData[nr].prev_update_ms)/ HALL_NR_TURNS) ;
|
HallData[nr].value = HallData[nr].unit_factor / (mid_time/HALL_NR_TURN);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
else{
|
else{
|
||||||
|
@ -436,10 +477,16 @@ 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_NR_TURNS*HALL_TICKS_PER_TURN){
|
if(HallData[hallnr].period_ticks >= (HALL_NR_TURN * HALL_TICKS_PER_TURN)){
|
||||||
|
unsigned long time_ms = millis();
|
||||||
HallData[hallnr].period_ticks = 0;
|
HallData[hallnr].period_ticks = 0;
|
||||||
HallData[hallnr].prev_update_ms = HallData[hallnr].act_update_ms;
|
time_per_round_ms[time_per_round_pointer] = time_ms - HallData[hallnr].act_update_ms;
|
||||||
HallData[hallnr].act_update_ms = millis();
|
HallData[hallnr].act_update_ms = time_ms;
|
||||||
|
time_per_round_pointer++;
|
||||||
|
if(time_per_round_pointer > TIME_PER_ROUND_VALS)
|
||||||
|
{
|
||||||
|
time_per_round_pointer = 0;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -9,21 +9,38 @@ void Oled::begin()
|
||||||
display->clear();
|
display->clear();
|
||||||
display->flipScreenVertically();
|
display->flipScreenVertically();
|
||||||
//display->setFont(ArialMT_Plain_10);
|
//display->setFont(ArialMT_Plain_10);
|
||||||
|
/*
|
||||||
display->setTextAlignment(TEXT_ALIGN_CENTER);
|
display->setTextAlignment(TEXT_ALIGN_CENTER);
|
||||||
display->setFont(ArialMT_Plain_24);
|
display->setFont(ArialMT_Plain_16);
|
||||||
display->setFont(ArialMT_Plain_16);
|
|
||||||
display->drawString(64, 2, "Init controller");
|
display->drawString(64, 2, "Init controller");
|
||||||
display->setFont(ArialMT_Plain_10);
|
display->setFont(ArialMT_Plain_10);
|
||||||
display->drawString(64, 40, "You may hear some beeps.");
|
display->drawString(64, 40, "You may hear some beeps.");
|
||||||
display->drawString(64, 52, "That's OK! ;-)");
|
display->drawString(64, 52, "That's OK! ;-)");
|
||||||
display->display();
|
display->display();
|
||||||
|
*/
|
||||||
display->setTextAlignment(TEXT_ALIGN_LEFT);
|
display->setTextAlignment(TEXT_ALIGN_LEFT);
|
||||||
display->setFont(ArialMT_Plain_16);
|
display->setFont(ArialMT_Plain_16);
|
||||||
}
|
}
|
||||||
|
|
||||||
void Oled::progressBar(uint8_t i)
|
void Oled::progressBar(uint8_t i, String big_text, String small_text1, String small_text2)
|
||||||
{
|
{
|
||||||
display->drawProgressBar(6, 28, 116, 6, i);
|
display->drawProgressBar(6, 28, 116, 6, i);
|
||||||
|
display->setTextAlignment(TEXT_ALIGN_CENTER);
|
||||||
|
if(big_text != "")
|
||||||
|
{
|
||||||
|
display->setFont(ArialMT_Plain_16);
|
||||||
|
display->drawString(64, 2, big_text);
|
||||||
|
}
|
||||||
|
if(small_text1 != "")
|
||||||
|
{
|
||||||
|
display->setFont(ArialMT_Plain_10);
|
||||||
|
display->drawString(64, 40, small_text1);
|
||||||
|
}
|
||||||
|
if(small_text2 != "")
|
||||||
|
{
|
||||||
|
display->setFont(ArialMT_Plain_10);
|
||||||
|
display->drawString(64, 52, small_text2);
|
||||||
|
}
|
||||||
display->display();
|
display->display();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Add table
Reference in a new issue