add menu for display
This commit is contained in:
parent
3c01e9f9b3
commit
932f4ed95a
|
@ -27,3 +27,4 @@ lib_deps =
|
|||
adafruit/Adafruit BusIO@^1.11.3
|
||||
https://github.com/adafruit/Adafruit-GFX-Library
|
||||
arduino-libraries/SD@^1.2.4
|
||||
mathertel/OneButton@^2.0.3
|
|
@ -1,6 +1,8 @@
|
|||
#include <Arduino.h>
|
||||
#define SERIAL_BAUD 115200 // [-] Baud rate for built-in Serial (used for the Serial Monitor)
|
||||
|
||||
#include <OneButton.h>
|
||||
|
||||
#include <SPI.h>
|
||||
#include <Wire.h>
|
||||
#include <Adafruit_GFX.h>
|
||||
|
@ -12,6 +14,15 @@
|
|||
#define OLED_RESET -1 // Reset pin # (or -1 if sharing Arduino reset pin)
|
||||
Adafruit_SSD1306 display(SCREEN_WIDTH, SCREEN_HEIGHT, &Wire, OLED_RESET);
|
||||
#define DISPLAYUPDATE_INTERVAL 200
|
||||
bool flag_updatedisplay=false;
|
||||
|
||||
uint8_t displaymode=0;
|
||||
#define DISPLAY_STATS 0
|
||||
#define DISPLAY_STATS2 1
|
||||
#define DISPLAY_STATS3 2
|
||||
#define DISPLAY_MENU 3
|
||||
uint8_t menu_entrypos=0;
|
||||
#define MENU_ENTRIES 3 // max id is MENU_ENTRIES-1
|
||||
|
||||
uint8_t error = 0;
|
||||
#define IMU_NO_CHANGE 2 //IMU values did not change for too long
|
||||
|
@ -23,6 +34,21 @@ ESCSerialComm esc(Serial2);
|
|||
//Serial2 = TX2=10, RX2=9
|
||||
//Serial3 = TX3=8, RX3=7
|
||||
|
||||
#define PIN_BUTTON_UP 3
|
||||
#define PIN_BUTTON_INC 4
|
||||
#define PIN_BUTTON_DEC 5
|
||||
#define PIN_BUTTON_DOWN 6
|
||||
|
||||
OneButton btn_up = OneButton(PIN_BUTTON_UP, true, true); // Input pin for the button, Button is active LOW, Enable internal pull-up resistor
|
||||
OneButton btn_inc = OneButton(PIN_BUTTON_INC, true, true);
|
||||
OneButton btn_dec = OneButton(PIN_BUTTON_DEC, true, true);
|
||||
OneButton btn_down = OneButton(PIN_BUTTON_DOWN, true, true);
|
||||
|
||||
//flags
|
||||
bool button_up_click=false;
|
||||
bool button_inc_click=false;
|
||||
bool button_dec_click=false;
|
||||
bool button_down_click=false;
|
||||
|
||||
#define PIN_GAMETRAK_LENGTH_A A6 //A6=20
|
||||
#define PIN_GAMETRAK_LENGTH_B A7 //A7=21
|
||||
|
@ -30,13 +56,15 @@ ESCSerialComm esc(Serial2);
|
|||
#define PIN_GAMETRAK_HORIZONTAL A9 //A9=23
|
||||
|
||||
|
||||
|
||||
|
||||
long last_adcupdated=0;
|
||||
#define ADC_UPDATEPERIOD 10 //in ms
|
||||
|
||||
#define CONTROLUPDATEPERIOD 10
|
||||
long last_controlupdate = 0;
|
||||
#define FILTER_NRF_SET_SPEED 0.1 //higher value, faster response. depends on CONTROLUPDATEPERIOD
|
||||
#define FILTER_NRF_SET_STEER 0.1
|
||||
float filter_nrf_set_speed=0.1; //higher value, faster response. depends on CONTROLUPDATEPERIOD
|
||||
float filter_nrf_set_steer=0.1;
|
||||
|
||||
#define GT_LENGTH_MIN 200 //minimum length for stuff to start happen
|
||||
|
||||
|
@ -152,8 +180,12 @@ uint8_t controlmode=0;
|
|||
#define MODE_GAMETRAK 2
|
||||
|
||||
|
||||
void updateInputs(unsigned long loopmillis);
|
||||
void updateDisplay(unsigned long loopmillis);
|
||||
|
||||
void display_show_stats();
|
||||
void display_show_stats2();
|
||||
void display_show_stats3();
|
||||
void display_show_menu();
|
||||
|
||||
void setup() {
|
||||
Serial.begin(SERIAL_BAUD); //Debug and Program
|
||||
|
@ -166,6 +198,20 @@ void setup() {
|
|||
pinMode(PIN_GAMETRAK_VERTICAL, INPUT_PULLUP);
|
||||
pinMode(PIN_GAMETRAK_HORIZONTAL, INPUT_PULLUP);
|
||||
|
||||
btn_up.attachClick([]() {
|
||||
button_up_click=true;
|
||||
});
|
||||
btn_down.attachClick([]() {
|
||||
button_down_click=true;
|
||||
});
|
||||
btn_inc.attachClick([]() {
|
||||
button_inc_click=true;
|
||||
});
|
||||
btn_dec.attachClick([]() {
|
||||
button_dec_click=true;
|
||||
});
|
||||
|
||||
|
||||
Wire.begin();
|
||||
// SSD1306_SWITCHCAPVCC = generate display voltage from 3.3V internally
|
||||
if(!display.begin(SSD1306_SWITCHCAPVCC, SCREEN_ADDRESS)) {
|
||||
|
@ -219,7 +265,10 @@ void setup() {
|
|||
void loop() {
|
||||
unsigned long loopmillis=millis();
|
||||
|
||||
|
||||
btn_up.tick();
|
||||
btn_inc.tick();
|
||||
btn_dec.tick();
|
||||
btn_down.tick();
|
||||
|
||||
|
||||
if (loopmillis - last_adcupdated > ADC_UPDATEPERIOD) { //update analog readings
|
||||
|
@ -343,8 +392,8 @@ void loop() {
|
|||
int16_t new_set_steer = (int16_t)( ((int16_t)(lastnrfdata.steer) - NRFDATA_CENTER) * 1000 / 127 );
|
||||
|
||||
|
||||
set_speed = set_speed*(1.0-FILTER_NRF_SET_SPEED) + new_set_speed*FILTER_NRF_SET_SPEED; //simple Filter
|
||||
set_steer = set_steer*(1.0-FILTER_NRF_SET_STEER) + new_set_steer*FILTER_NRF_SET_STEER;
|
||||
set_speed = set_speed*(1.0-filter_nrf_set_speed) + new_set_speed*filter_nrf_set_speed; //simple Filter
|
||||
set_steer = set_steer*(1.0-filter_nrf_set_steer) + new_set_steer*filter_nrf_set_steer;
|
||||
|
||||
//calculate speed l and r from speed and steer
|
||||
#define SPEED_COEFFICIENT_NRF 1 // higher value == stronger
|
||||
|
@ -474,61 +523,196 @@ void loop() {
|
|||
|
||||
|
||||
esc.update(loopmillis);
|
||||
updateInputs(loopmillis);
|
||||
updateDisplay(loopmillis);
|
||||
}
|
||||
|
||||
void updateInputs(unsigned long loopmillis) {
|
||||
switch (displaymode) {
|
||||
case DISPLAY_STATS: case DISPLAY_STATS2: case DISPLAY_STATS3:
|
||||
if (button_up_click) { //first button opens menu
|
||||
displaymode=DISPLAY_MENU; // go to menu
|
||||
}
|
||||
if (button_inc_click) {
|
||||
displaymode=DISPLAY_STATS;
|
||||
}
|
||||
if (button_dec_click) {
|
||||
displaymode=DISPLAY_STATS2;
|
||||
}
|
||||
if (button_down_click) {
|
||||
displaymode=DISPLAY_STATS3;
|
||||
}
|
||||
break;
|
||||
case DISPLAY_MENU:
|
||||
if (button_up_click) {
|
||||
if (menu_entrypos>0) {
|
||||
menu_entrypos--;
|
||||
}
|
||||
}
|
||||
if (button_down_click) {
|
||||
if (menu_entrypos< (MENU_ENTRIES-1)) {
|
||||
menu_entrypos++;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
switch(menu_entrypos) {
|
||||
case 0: //Exit
|
||||
if (button_inc_click || button_dec_click) {
|
||||
displaymode=DISPLAY_STATS;
|
||||
}
|
||||
break;
|
||||
case 1: //Filter NRF Speed
|
||||
if (button_inc_click) {
|
||||
filter_nrf_set_speed+=0.01;
|
||||
filter_nrf_set_speed = constrain(filter_nrf_set_speed, 0.01, 1.0);
|
||||
}
|
||||
if (button_dec_click) {
|
||||
filter_nrf_set_speed-=0.01;
|
||||
filter_nrf_set_speed = constrain(filter_nrf_set_speed, 0.01, 1.0);
|
||||
}
|
||||
break;
|
||||
case 2: //Filter NRF Steer
|
||||
if (button_inc_click) {
|
||||
filter_nrf_set_steer+=0.01;
|
||||
filter_nrf_set_steer = constrain(filter_nrf_set_steer, 0.01, 1.0);
|
||||
}
|
||||
if (button_dec_click) {
|
||||
filter_nrf_set_steer-=0.01;
|
||||
filter_nrf_set_steer = constrain(filter_nrf_set_steer, 0.01, 1.0);
|
||||
}
|
||||
break;
|
||||
}
|
||||
break;
|
||||
|
||||
}
|
||||
|
||||
if (button_up_click || button_down_click || button_inc_click || button_dec_click) { //any button was pressed
|
||||
flag_updatedisplay=true;
|
||||
button_up_click=false;
|
||||
button_down_click=false;
|
||||
button_inc_click=false;
|
||||
button_dec_click=false;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void updateDisplay(unsigned long loopmillis)
|
||||
{
|
||||
static unsigned long last_updatedisplay=0;
|
||||
if (loopmillis-last_updatedisplay>DISPLAYUPDATE_INTERVAL) {
|
||||
display.clearDisplay();
|
||||
display.setTextSize(1);
|
||||
display.setTextColor(SSD1306_WHITE);
|
||||
display.setCursor(1, 0);
|
||||
display.print(F("MODE="));
|
||||
if (loopmillis-last_updatedisplay>DISPLAYUPDATE_INTERVAL || flag_updatedisplay) {
|
||||
flag_updatedisplay=false;
|
||||
|
||||
switch(controlmode) {
|
||||
case MODE_DISARMED:
|
||||
display.println(F("DISARMED"));
|
||||
break;
|
||||
case MODE_RADIONRF:
|
||||
display.println(F("RADIONRF"));
|
||||
break;
|
||||
case MODE_GAMETRAK:
|
||||
display.println(F("GAMETRAK"));
|
||||
break;
|
||||
default:
|
||||
display.println(F("UNDEF"));
|
||||
break;
|
||||
|
||||
if (displaymode==DISPLAY_STATS) {
|
||||
display_show_stats();
|
||||
}else if(displaymode==DISPLAY_STATS2) {
|
||||
display_show_stats2();
|
||||
}else if(displaymode==DISPLAY_STATS3) {
|
||||
display_show_stats3();
|
||||
}else if(displaymode==DISPLAY_MENU) {
|
||||
display_show_menu();
|
||||
}
|
||||
|
||||
static float maxcurL=0;
|
||||
static float maxcurR=0;
|
||||
maxcurL=max(maxcurL,esc.getFiltered_curL());
|
||||
maxcurR=max(maxcurR,esc.getFiltered_curR());
|
||||
|
||||
static float mincurL=0;
|
||||
static float mincurR=0;
|
||||
mincurL=min(mincurL,esc.getFiltered_curL());
|
||||
mincurR=min(mincurR,esc.getFiltered_curR());
|
||||
|
||||
static float maxspdL=0;
|
||||
|
||||
display.print(F("Bat=")); display.print(esc.getFeedback_batVoltage()); display.print(F(" Temp=")); display.println(esc.getFeedback_boardTemp());
|
||||
display.print(F("nrf_delay=")); display.print(last_nrfreceive_delay); display.print(F(" L=")); display.println(gt_length);
|
||||
display.print(F("maxdiff=")); display.println(raw_length_maxdiff);
|
||||
display.print(F("CMD=")); display.print(esc.getCmdL()); display.print(F(", ")); display.print(esc.getCmdR());
|
||||
//display.print(F("FBC=")); display.print(esc.getFeedback_cmd1()); display.print(F(", ")); display.print(esc.getFeedback_cmd2());
|
||||
display.print(F(" spd=")); display.print(esc.getFeedback_speedL_meas()); display.print(F(", ")); display.println(esc.getFeedback_speedR_meas());
|
||||
display.print(F("DC max=")); display.print(maxcurL,1); display.print(F("/")); display.println(maxcurR,1); // display.print(F(" min=")); display.print(mincurL,1); display.print(F("/")); display.println(mincurR,1);
|
||||
display.print(F("trip=")); display.print(esc.getTrip(),0); display.print(F(",")); display.print(esc.getCurrentConsumed(),3); display.println(F("Ah"));
|
||||
|
||||
/*
|
||||
display.print(F("H=")); display.print(gt_horizontal); display.print(F(" V=")); display.println(gt_vertical);
|
||||
display.print(F("CMD=")); display.print(esc.getCmdL()); display.print(F(", ")); display.println(esc.getCmdR());*/
|
||||
|
||||
display.display(); // Show initial text
|
||||
last_updatedisplay=loopmillis;
|
||||
}
|
||||
}
|
||||
|
||||
void display_show_stats() {
|
||||
display.clearDisplay();
|
||||
display.setTextSize(1);
|
||||
display.setTextColor(SSD1306_WHITE);
|
||||
display.setCursor(0, 0);
|
||||
display.print(F("MODE="));
|
||||
|
||||
switch(controlmode) {
|
||||
case MODE_DISARMED:
|
||||
display.println(F("DISARMED"));
|
||||
break;
|
||||
case MODE_RADIONRF:
|
||||
display.println(F("RADIONRF"));
|
||||
break;
|
||||
case MODE_GAMETRAK:
|
||||
display.println(F("GAMETRAK"));
|
||||
break;
|
||||
default:
|
||||
display.println(F("UNDEF"));
|
||||
break;
|
||||
}
|
||||
|
||||
|
||||
//updates only when display active
|
||||
static float maxcurL=0;
|
||||
static float maxcurR=0;
|
||||
maxcurL=max(maxcurL,esc.getFiltered_curL());
|
||||
maxcurR=max(maxcurR,esc.getFiltered_curR());
|
||||
|
||||
static float mincurL=0;
|
||||
static float mincurR=0;
|
||||
mincurL=min(mincurL,esc.getFiltered_curL());
|
||||
mincurR=min(mincurR,esc.getFiltered_curR());
|
||||
|
||||
|
||||
display.print(F("Bat=")); display.print(esc.getFeedback_batVoltage()); display.print(F(" Temp=")); display.println(esc.getFeedback_boardTemp());
|
||||
display.print(F("nrf_delay=")); display.print(last_nrfreceive_delay);
|
||||
display.print(F("maxdiff=")); display.println(raw_length_maxdiff);
|
||||
display.print(F("DC max=")); display.print(maxcurL,1); display.print(F("/")); display.println(maxcurR,1); // display.print(F(" min=")); display.print(mincurL,1); display.print(F("/")); display.println(mincurR,1);
|
||||
display.print(F("trip=")); display.print(esc.getTrip(),0); display.print(F(",")); display.print(esc.getCurrentConsumed(),3); display.println(F("Ah"));
|
||||
|
||||
display.display(); // Show initial text
|
||||
}
|
||||
|
||||
void display_show_stats2() {
|
||||
display.clearDisplay();
|
||||
display.setTextSize(1);
|
||||
display.setTextColor(SSD1306_WHITE);
|
||||
display.setCursor(0, 0);
|
||||
|
||||
display.print(F("CMD=")); display.print(esc.getCmdL()); display.print(F(", ")); display.println(esc.getCmdR());
|
||||
display.print(F("FBC=")); display.print(esc.getFeedback_cmd1()); display.print(F(", ")); display.println(esc.getFeedback_cmd2());
|
||||
display.print(F("Speed=")); display.print(esc.getFeedback_speedL_meas()); display.print(F(", ")); display.println(esc.getFeedback_speedR_meas());
|
||||
display.print(F("Length=")); display.println(gt_length);
|
||||
display.print(F("H=")); display.print(gt_horizontal); display.print(F(" V=")); display.println(gt_vertical);
|
||||
display.print(F("CMD=")); display.print(esc.getCmdL()); display.print(F(", ")); display.println(esc.getCmdR());
|
||||
|
||||
display.display(); // Show initial text
|
||||
}
|
||||
|
||||
|
||||
void display_show_stats3() {
|
||||
display.clearDisplay();
|
||||
display.setTextSize(1);
|
||||
display.setTextColor(SSD1306_WHITE);
|
||||
display.setCursor(0, 0);
|
||||
|
||||
|
||||
display.display(); // Show initial text
|
||||
}
|
||||
|
||||
|
||||
void display_show_menu() {
|
||||
display.clearDisplay();
|
||||
display.setTextSize(1);
|
||||
display.setTextColor(SSD1306_WHITE);
|
||||
display.setCursor(0, 0);
|
||||
for (uint8_t i=0;i<MENU_ENTRIES;i++) {
|
||||
if (i==menu_entrypos) {
|
||||
display.print(F(">"));
|
||||
}else{
|
||||
display.print(F(" "));
|
||||
}
|
||||
switch(i) {
|
||||
case 0:
|
||||
display.print(F("EXIT")); display.println();
|
||||
break;
|
||||
case 1:
|
||||
display.print(F("Fltr spd=")); display.println(filter_nrf_set_speed);
|
||||
break;
|
||||
case 2:
|
||||
display.print(F("Fltr str=")); display.println(filter_nrf_set_steer);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
display.display(); // Show initial text
|
||||
}
|
Loading…
Reference in New Issue