26 Commits

Author SHA1 Message Date
d362fdd639 TEDü Getac Changes 2024-10-05 19:01:02 +02:00
661e1a2274 Add brake balance display 2022-03-24 17:48:03 +01:00
58b0b72c6d Disable P_OIL alarm 2022-03-23 15:09:40 +01:00
b5ece154c5 Lower tire temp green threshold 2022-03-21 17:19:38 +01:00
8a05663fbc Fix CAN filter bitmask 2022-03-18 17:21:25 +01:00
28b4e15ed2 added DRS control 2022-03-17 00:51:16 +01:00
1a72d6aa0f Attempt to resurrect the display after disconnect 2022-03-17 00:11:01 +01:00
1fdadd8b85 Reduce flicker 2022-03-17 00:10:41 +01:00
130a0dde2f Lower UBAT LED threshold 2022-03-17 00:09:54 +01:00
6609947618 Fix RPM CAN bytes 2022-03-17 00:09:36 +01:00
c8e94175d1 Read tire temps from CAN 2022-03-17 00:09:13 +01:00
197b805f35 Display fuel pressure 2022-03-16 16:13:50 +01:00
c5df4d7b79 Use one fewer CAN mailbox 2022-03-14 16:28:12 +01:00
37123a43e8 Alternate color of testing view rows 2022-03-14 14:30:33 +01:00
fc65d22450 Rename driver/testing pages to views 2022-03-14 14:06:52 +01:00
4de2baa867 Don't clear display periodically 2022-03-13 21:07:44 +01:00
c6c0fa987e Update CAN
There are only 7 RX mailboxes available, so one of the filters won't
work.
2022-03-13 21:06:05 +01:00
d0afcb6da4 Add .git-blame-ignore-revs
You can use this file to ignore this commit when running git blame.
Simply run

    git blame --ignore-revs-file .git-blame-ignore-revs [...]

Or configure git to persistently ignore the commit:

    git config blame.ignoreRevsFile .git-blame-ignore-revs
2022-03-13 20:33:59 +01:00
41d3bd907e Format everything
The next commit will add this to a `.git-blame-ignore-revs` file which
you can use to ignore this commit when running git blame. Simply run

    git blame --ignore-revs-file .git-blame-ignore-revs [...]

Or configure git to persistently ignore the commit:

    git config blame.ignoreRevsFile .git-blame-ignore-revs
2022-03-13 20:30:14 +01:00
14b5f6988d Use both buttons to toggle driver & testing view 2022-03-13 20:01:46 +01:00
3cf68cd3cb Add more values 2022-03-13 19:57:34 +01:00
894ced16ef Redraw screen after alarms/changing encoders 2022-03-13 19:54:54 +01:00
5eecc507a0 Use debouncer for button states 2022-03-13 19:52:11 +01:00
373266f6be [WIP] Major rewrite of display code
Currently, the displayed values are hardcoded
2022-03-13 18:18:11 +01:00
f62f264b29 Implement some EDIPTFT commands 2022-03-13 18:17:41 +01:00
0eeafa9393 Debounce the rest of the buttons 2022-03-13 18:15:41 +01:00
18 changed files with 2541 additions and 2199 deletions

8
.editorconfig Normal file
View File

@ -0,0 +1,8 @@
[*]
charset = utf-8
end_of_line = lf
insert_final_newline = true
[*.{cpp,c,h,hpp}]
indent_style = space
indent_size = 4

2
.git-blame-ignore-revs Normal file
View File

@ -0,0 +1,2 @@
# Format everything
41d3bd907e65b484876859b767328e5d81181911

View File

@ -2,7 +2,9 @@
// See http://go.microsoft.com/fwlink/?LinkId=827846 // See http://go.microsoft.com/fwlink/?LinkId=827846
// for the documentation about the extensions.json format // for the documentation about the extensions.json format
"recommendations": [ "recommendations": [
"platformio.platformio-ide", "platformio.platformio-ide"
"ms-vscode.cpptools-extension-pack"
], ],
"unwantedRecommendations": [
"ms-vscode.cpptools-extension-pack"
]
} }

View File

@ -13,9 +13,7 @@ struct FaultStatusRegisters {
uint32_t SHCSR; uint32_t SHCSR;
}; };
enum class FaultType { enum class FaultType { HardFault, MemManage, BusFault, UsageFault };
HardFault, MemManage, BusFault, UsageFault
};
struct FlashDump { struct FlashDump {
FaultType type; FaultType type;
@ -43,22 +41,23 @@ const FlashDump *flash_dump_get_fault(uint32_t n);
void uart_wait_for_txrdy(); void uart_wait_for_txrdy();
size_t uart_write(uint8_t c); size_t uart_write(uint8_t c);
size_t uart_print(const char* str); size_t uart_print(const char *str);
size_t uart_print_hex(uint32_t x); size_t uart_print_hex(uint32_t x);
void print_dumped_faults(bool in_irq=false); void print_dumped_faults(bool in_irq = false);
void print_stacked_registers(const uint32_t *stack, bool in_irq=false); void print_stacked_registers(const uint32_t *stack, bool in_irq = false);
void print_fault_registers(const FaultStatusRegisters *fsr, bool in_irq=false); void print_fault_registers(const FaultStatusRegisters *fsr,
bool in_irq = false);
FaultStatusRegisters get_current_fsr(); FaultStatusRegisters get_current_fsr();
const char* get_fault_type_name(FaultType type); const char *get_fault_type_name(FaultType type);
void fault_handler(uint32_t *stack_addr, FaultType fault_type, void fault_handler(uint32_t *stack_addr, FaultType fault_type, const int *leds,
const int *leds, unsigned n_leds); unsigned n_leds);
void inline busy_wait(size_t iterations) { void inline busy_wait(size_t iterations) {
for (size_t i = 0; i < iterations; i++) { for (size_t i = 0; i < iterations; i++) {
// Does nothing, but ensures the compiler doesn't optimize the loop away. // Does nothing, but ensures the compiler doesn't optimize the loop away.
__ASM ("" ::: "memory"); __ASM("" ::: "memory");
} }
} }

View File

@ -1,406 +1,584 @@
#include "Arduino.h" #include "FT18_STW_DISPLAY.h"
#include "EDIPTFT.h" #include "Arduino.h"
#include "FT_2018_STW_CAN.h" #include "EDIPTFT.h"
#include "FT18_STW_INIT.h" #include "FT18_STW_INIT.h"
#include "FT18_STW_DISPLAY.h" #include "FT_2018_STW_CAN.h"
EDIPTFT tft(true,false); String pad_left(String orig, int len, char pad_char) {
String bezeichnungen[]={"T_mot","T_oil","P_oil","% fa","U_batt","P_wat","T_air", String result = {orig};
"P_b_front","P_b_rear","Error Type","Speed_fl","Speed_fr","Speed"}; for (int i = orig.length(); i < len; i++) {
//"Drehzahl","P_fuel","Index" result = pad_char + result;
int vergleichsindex; }
int sizeaalt;
int sizeaneu; return result;
int sizebalt; }
int sizebneu;
int sizecalt; EDIPTFT tft(true, false);
int sizecneu; String bezeichnungen[] = {"T_mot", "T_oil", "P_oil", "% fa",
int sizedalt; "U_batt", "P_wat", "T_air", "P_b_front",
int sizedneu; "P_b_rear", "Error Type", "Speed_fl", "Speed_fr",
int sizeealt; "Speed"};
int sizeeneu; //"Drehzahl","P_fuel","Index"
uint8_t clearcounter = 56; int led_s[] = {led1, led2, led3, led4, led5, led6, led7, led8,
uint8_t trcalt = Stw_data.trc; led9, led10, led11, led12, led13, led14, led15, led16};
uint8_t modealt = Stw_data.mode;
uint8_t trccounter;// = Stw_data.trc; DataBox gear_box(121, 0, 199, 94, 160, 0, EA_SWISS30B, 4, 4, 'C', true);
uint8_t modecounter;// = Stw_data.mode; DataBox left_box(0, 25, 119, 94, 110, 25, EA_FONT6X8, 3, 8, 'R', false);
bool trctimer; DataBox right_box(201, 25, 320, 94, 310, 25, EA_FONT6X8, 3, 8, 'R', false);
bool modetimer; DataBox autoshift_box(164+50, 184, 240+50, 230, 202+50, 178, EA_FONT7X12, 3, 5, 'C', false);
int led_s[] = {led1,led2,led3,led4,led5,led6,led7,led8,led9,led10,led11,led12,led13,led14,led15,led16};
unsigned long poiltimer; TireTempBox fl_box(80, 130, 156, 176, 118, 124, EA_FONT7X12, 3, 5, 'C');
unsigned long tmottimer; TireTempBox fr_box(164, 130, 240, 176, 202, 124, EA_FONT7X12, 3, 5, 'C');
unsigned long toiltimer; TireTempBox rl_box(80, 184, 156, 230, 118, 178, EA_FONT7X12, 3, 5, 'C');
bool poilbool = true; TireTempBox rr_box(164, 184, 240, 230, 202, 178, EA_FONT7X12, 3, 5, 'C');
bool tmotbool = true;
bool toilbool = true; int testing_page = 0;
uint16_t clearcounter = 1;
void init_display() { void init_display() {
pinMode(writeprotect, OUTPUT); pinMode(writeprotect, OUTPUT);
digitalWrite(writeprotect, HIGH); digitalWrite(writeprotect, HIGH);
pinMode(reset, OUTPUT); pinMode(reset, OUTPUT);
pinMode(disp_cs, OUTPUT); pinMode(disp_cs, OUTPUT);
pinMode(MOSI, OUTPUT); pinMode(MOSI, OUTPUT);
pinMode(MISO, OUTPUT); pinMode(MISO, OUTPUT);
//pinMode(CLK, INPUT); digitalWrite(disp_cs, HIGH);
digitalWrite(disp_cs, HIGH); digitalWrite(MOSI, HIGH);
digitalWrite(MOSI, HIGH); digitalWrite(MISO, HIGH);
digitalWrite(MISO, HIGH); digitalWrite(reset, LOW);
digitalWrite(reset, LOW); digitalWrite(reset, HIGH);
//edip.smallProtoSelect(7); tft.begin(115200); // start display communication
//edip.setNewColor(EA_GREY, 0xe3, 0xe3,0xe3); // redefine r-g-b-values of EA_GREY tft.cursorOn(false);
//edip.drawImage(0,50,FASTTUBE_LOGO_PNG); tft.terminalOn(false);
digitalWrite(reset,HIGH); tft.setDisplayColor(EA_WHITE, EA_BLACK);
tft.begin(115200); // start display communication tft.setTextColor(EA_WHITE, EA_TRANSPARENT);
/*int h = 20; tft.setTextSize(5, 8);
char charh[2]; tft.clear();
String strh = String(h);
strh.toCharArray(charh,2); gear_box.update_label(get_label(VAL_GEAR));
tft.DisplayLight(charh);*/ left_box.update_label(get_label(VAL_FIRST_LEFT_BOX));
tft.cursorOn(false); right_box.update_label(get_label(VAL_RPM));
tft.terminalOn(false); autoshift_box.update_label("");
tft.setDisplayColor(EA_WHITE,EA_BLACK); }
tft.setTextColor(EA_WHITE,EA_BLACK);
//tft.setTextFont('4'); String get_value(Value val) {
tft.setTextSize(5,8); switch (val) {
tft.clear(); case VAL_GEAR:
//tft.displayLight('30'); if (Vehicle_data.gear == 0) {
tft.drawText(0, 14, 'C', "FaSTTUBe"); //draw some text return "N";
//tft.loadImage(0,0,1); }
//delay(2000); return String(Vehicle_data.gear);
} case VAL_RPM:
return String(Vehicle_data.revol / 2);
double get_value(int a){ case VAL_TT_FL:
double value; return String(Vehicle_data.t_tfl * 0.423529 + 8, 0);
if (a == 0){ case VAL_TT_FR:
value = Vehicle_data.gear; return String(Vehicle_data.t_tfr * 0.423529 + 0, 0);
//}else if (a == 11){ case VAL_TT_RL:
// value = Stw_data.i; return String(Vehicle_data.t_trl * 0.423529 + 11, 0);
//}else if (a == 1){ case VAL_TT_RR:
// value = Vehicle_data.revol/2; return String(Vehicle_data.t_trr * 0.423529 + 4, 0);
}else if (a == 1){ case VAL_LAPTIME: {
value = Vehicle_data.t_mot-40; double time =
}else if (a == 5){ Vehicle_data.lap_time_sec + Vehicle_data.lap_time_msec / 1000.0;
value = 0.0706949*Vehicle_data.u_batt; if (time < 100) {
}else if (a == 7){ return String(time, 2);
value = Vehicle_data.t_air-40; } else if (time < 1000) {
}else if(a == 10){ return String(time, 1);
value = Stw_data.error_type; } else if (time < 10000) {
}else if (a == 2){ return String(time, 0);
value = Vehicle_data.t_oil-40; } else {
}else if (a == 6){ return "2SLOW";
value = 0.0514*Vehicle_data.p_wat; }
//}else if (a == 7){ }
// value = 0.0514*Vehicle_data.p_fuel; case VAL_UBATT:
}else if (a == 3){ return String(0.0706949 * Vehicle_data.u_batt, 2);
value = 0.0514*Vehicle_data.p_oil; case VAL_TMOT:
}else if (a == 8){ return String(Vehicle_data.t_mot - 40);
value = Vehicle_data.p_brake_front; case VAL_TAIR:
}else if (a == 9){ return String(Vehicle_data.t_air - 40);
value = Vehicle_data.p_brake_rear; case VAL_TOIL:
}else if(a == 4){ return String(Vehicle_data.t_oil - 40);
value = 200*Vehicle_data.p_brake_front/(Vehicle_data.p_brake_rear+(2*Vehicle_data.p_brake_front)); case VAL_ERR_TYPE:
}else if (a == 11){ return String(Stw_data.error_type);
value = Vehicle_data.speed_fl; case VAL_PFUEL:
}else if (a == 12){ return String(0.0514 * Vehicle_data.p_fuel, 2);
value = Vehicle_data.speed_fr; case VAL_PWAT:
}else if(a == 13){ return String(0.0514 * Vehicle_data.p_wat, 2);
value = Vehicle_data.speed; case VAL_POIL:
} return String(0.0514 * Vehicle_data.p_oil, 2);
return value; case VAL_PBF:
} return String(Vehicle_data.p_brake_front);
case VAL_PBR:
void update_display(){ return String(Vehicle_data.p_brake_rear);
if(((millis()-poiltimer)>=20000) and poilbool){ case VAL_SPEED_FL:
poilbool = false; return String(Vehicle_data.speed_fl);
alarm("P_oil"); case VAL_SPEED_FR:
} return String(Vehicle_data.speed_fr);
if(((millis()-tmottimer)>=20000) and tmotbool){ case VAL_SPEED:
tmotbool = false; return String(Vehicle_data.speed);
alarm("T_mot"); case VAL_BBAL: {
} double p_total =
if(((millis()-toiltimer)>=10000) and toilbool){ Vehicle_data.p_brake_front + Vehicle_data.p_brake_rear / 2.398;
toilbool = false; double bbal = p_total == 0 ? 0 : 100 * Vehicle_data.p_brake_front / p_total;
alarm("T_oil"); if (bbal >= 100) {
} return "100";
if((0.0514*Vehicle_data.p_oil)>=0,1 or Vehicle_data.speed == 0){ }
poiltimer = millis(); return String(bbal, 2);
} }
if(((Vehicle_data.t_mot - 40) <= 0x69) or ((Vehicle_data.t_mot - 40)==0xC8)){ default:
tmottimer = millis(); return "???";
} }
if((Vehicle_data.t_oil - 40) <= 0x96){ }
toiltimer = millis();
} String get_label(Value val) {
if(Stw_data.buttonState1 & Stw_data.buttonState4){ switch (val) {
alarm(""); case VAL_GEAR:
} return "GEAR";
if(!tft.disconnected){ case VAL_RPM:
tft.cursorOn(false); return "RPM";
if(trcalt!=Stw_data.trc or trctimer == true or Stw_data.buttonStateEnc1 == HIGH){ case VAL_TT_FL:
display_trc(); return "TEMP FL";
}else if(modealt!=Stw_data.mode or modetimer == true or Stw_data.buttonStateEnc2 == HIGH){ case VAL_TT_FR:
display_mode(); return "TEMP FR";
}else{ case VAL_TT_RL:
if(clearcounter>=56){ return "TEMP RL";
tft.clear(); case VAL_TT_RR:
clearcounter = 0; return "TEMP RR";
} case VAL_LAPTIME:
clearcounter+=1; return "LAPTIME";
if(Stw_data.buttonState4){ case VAL_UBATT:
if(Stw_data.displayindex>=sizeof(bezeichnungen)/sizeof(String)-3){ return "BATT VOLTAGE";
Stw_data.displayindex = 0; case VAL_TMOT:
delay(250); return "TEMP ENG";
}else{ case VAL_TAIR:
Stw_data.displayindex+=1; return "TEMP AIR";
delay(250); case VAL_TOIL:
} return "TEMP OIL";
} case VAL_ERR_TYPE:
if(Stw_data.buttonState1){ return "ERROR TYPE";
if(Stw_data.displayindex<=0){ case VAL_PFUEL:
Stw_data.displayindex = sizeof(bezeichnungen)/sizeof(String)-3; return "PRESS FUEL";
delay(250); case VAL_PWAT:
}else{ return "PRESS WAT";
Stw_data.displayindex-=1; case VAL_POIL:
delay(250); return "PRESS OIL";
} case VAL_PBF:
} return "PRESS BRAKE F";
if(vergleichsindex!=Stw_data.displayindex){ case VAL_PBR:
tft.clear(); return "PRESS BRAKE R";
vergleichsindex=Stw_data.displayindex; case VAL_SPEED_FL:
} return "SPEED FL";
int a = sizeof(bezeichnungen[Stw_data.displayindex]); case VAL_SPEED_FR:
int g = sizeof(bezeichnungen[Stw_data.displayindex+1]); return "SPEED FR";
int h = sizeof(bezeichnungen[Stw_data.displayindex+2]); case VAL_SPEED:
char d[a]; return "SPEED";
char e[g]; case VAL_BBAL:
char f[h]; return "BBAL";
bezeichnungen[Stw_data.displayindex].toCharArray(d,a); default:
bezeichnungen[Stw_data.displayindex+1].toCharArray(e,g); return "???";
bezeichnungen[Stw_data.displayindex+2].toCharArray(f,h); }
char b[2]; }
char c[5];
char i[5]; bool check_alarms() {
char j[5]; static uint32_t poil_last_valid, tmot_last_valid, toil_last_valid;
char k[5]; uint32_t now = millis();
char m[5]; if (Vehicle_data.p_oil >= POIL_ALARM_THRESH || Vehicle_data.speed == 0) {
String str=String(int(get_value(0))); poil_last_valid = now;
if(str.equals(String(0))){ }
str = "N"; if (Vehicle_data.t_mot <= TMOT_ALARM_THRESH ||
} Vehicle_data.t_mot == TMOT_SAFE_VALUE) {
String str1; tmot_last_valid = now;
String str2; }
String str3; if (Vehicle_data.t_oil <= TOIL_ALARM_THRESH) {
if(Stw_data.displayindex+1==0 or Stw_data.displayindex+1==2 or Stw_data.displayindex+1==1 or Stw_data.displayindex+1==10 or Stw_data.displayindex+1==7 or Stw_data.displayindex+1==11 or Stw_data.displayindex+1==12 or Stw_data.displayindex+1==13){ toil_last_valid = now;
str1=String(int(get_value(Stw_data.displayindex+1))); }
}else{ // bool poil_alarm = now - poil_last_valid >= POIL_ALARM_TIME;
str1=String(get_value(Stw_data.displayindex+1)); bool poil_alarm = false;
} bool tmot_alarm = now - tmot_last_valid >= TMOT_ALARM_TIME;
if(Stw_data.displayindex+1 == 10){ bool toil_alarm = now - toil_last_valid >= TOIL_ALARM_TIME;
if(str1.equals(String(1))){ bool alarm_active = poil_alarm || tmot_alarm || toil_alarm;
str1 = "PC";
}else if(str1.equals(String(2))){ if (alarm_active) {
str1 = "BSE"; String alarm_text = "";
}else if(str1.equals(String(3))){ if (poil_alarm)
str1 = "APS"; alarm_text += "PO";
}else if(str1.equals(String(4))){ if (tmot_alarm)
str1 = "ETB"; alarm_text += "TM";
}else if(str1.equals(String(0))){ if (toil_alarm)
str1 = "None"; alarm_text += "TO";
} alarm(alarm_text);
} }
if(Stw_data.displayindex+2==0 or Stw_data.displayindex+2==2 or Stw_data.displayindex+2==1 or Stw_data.displayindex+2==10 or Stw_data.displayindex+2==7 or Stw_data.displayindex+2==11 or Stw_data.displayindex+2==12 or Stw_data.displayindex+2==13){
str2=String(int(get_value(Stw_data.displayindex+2))); return alarm_active;
}else{ }
str2=String(get_value(Stw_data.displayindex+2));
} bool check_enc_displays() {
if(Stw_data.displayindex+2 == 10){ static uint8_t trc_old, mode_old;
if(str2.equals(String(1))){ static bool display_trc, display_mode;
str2 = "PC"; static uint32_t display_trc_begin, display_mode_begin;
}else if(str2.equals(String(2))){
str2 = "BSE"; return check_display(trc_old, Stw_data.trc, display_trc, display_trc_begin,
}else if(str2.equals(String(3))){ "ARB") ||
str2 = "APS"; check_display(mode_old, Stw_data.mode, display_mode,
}else if(str2.equals(String(4))){ display_mode_begin, "MODE");
str2 = "ETB"; }
}else if(str2.equals(String(0))){
str2 = "None"; bool check_display(uint8_t& val_old, uint8_t val_new, bool& active,
} uint32_t& begin, const String& title) {
} if (val_old != val_new) {
if(Stw_data.displayindex+3==0 or Stw_data.displayindex+3==2 or Stw_data.displayindex+3==1 or Stw_data.displayindex+3==10 or Stw_data.displayindex+3==7 or Stw_data.displayindex+3==11 or Stw_data.displayindex+3==12 or Stw_data.displayindex+3==13){ active = true;
str3=String(int(get_value(Stw_data.displayindex+3))); begin = millis();
}else{ val_old = val_new;
str3=String(get_value(Stw_data.displayindex+3)); tft.clear();
} tft.fillDisplayColor(EA_RED);
if(Stw_data.displayindex+3 == 10){ tft.setTextColor(EA_WHITE, EA_RED);
if(str3.equals(String(1))){ tft.setTextSize(7, 8);
str3 = "PC"; String text = title + ":" + val_new;
}else if(str3.equals(String(2))){ char text_arr[16];
str3 = "BSE"; text.toCharArray(text_arr, 16);
}else if(str3.equals(String(3))){ tft.drawText(15, 68, 'C', text_arr);
str3 = "APS"; } else if (active && millis() - begin > ENC_DISPLAY_TIME) {
}else if(str3.equals(String(4))){ tft.setTextColor(EA_WHITE, EA_TRANSPARENT);
str3 = "ETB"; tft.clear();
}else if(str3.equals(String(0))){ active = false;
str3 = "None"; }
}
} return active;
String str5=String(Vehicle_data.revol/2); }
String str4=String(0.0514*Vehicle_data.p_fuel);
str.toCharArray(b,2); void update_display() {
str1.toCharArray(c,5); static DisplayView view = VIEW_DRIVER;
str2.toCharArray(i,5); static uint32_t last_cleared;
str3.toCharArray(j,5); static bool cleared = true;
str4.toCharArray(k,5);
str5.toCharArray(m,5); if (check_alarms()) {
sizeaneu = strlen(c); cleared = true;
sizebneu = strlen(i); return;
sizecneu = strlen(j); }
sizedneu = strlen(k); if (tft.disconnected) {
sizeeneu = strlen(m); uint32_t now = millis();
if(sizeaalt!=sizeaneu){ if (now - last_cleared < 1000) {
tft.clear(); return;
sizeaalt=sizeaneu; }
} digitalWrite(reset, LOW);
if(sizebalt!=sizebneu){ delay(100);
tft.clear(); digitalWrite(reset, HIGH);
sizebalt=sizebneu; tft.disconnected = false;
} tft.clear();
if(sizecalt!=sizecneu){ cleared = true;
tft.clear(); last_cleared = now;
sizecalt=sizecneu; }
}
if(sizedalt!=sizedneu){ if (check_enc_displays()) {
tft.clear(); cleared = true;
sizedalt=sizedneu; return;
} }
if(sizeealt!=sizeeneu){
tft.clear(); uint32_t now = millis();
sizeealt=sizeeneu; // Both buttons have to be pressed at the same time, but we also use the
} // debounced rises to ensure we don't keep toggling between the views
tft.setTextSize(6,8); if (Stw_data.buttonState1 && Stw_data.buttonState4 &&
tft.drawText(132, 0, 'L', b); (Stw_data.button1_rises > 0 || Stw_data.button4_rises > 0)) {
tft.setTextSize(2,7); Stw_data.button1_rises = 0;
tft.drawText(10, 20, 'L', k); Stw_data.button4_rises = 0;
tft.drawText(240, 20, 'L', m); view = (DisplayView)((view + 1) % (VIEW_LAST + 1));
tft.drawText(10,130, 'L', c); tft.clear();
tft.drawText(120, 130, 'L', i); cleared = true;
tft.drawText(240,130, 'L', j); }
tft.setTextSize(1,1);
tft.drawText(136,116, 'L', "Gang"); if (view == VIEW_DRIVER) {
tft.drawText(10,116, 'L', "P_fuel"); if (cleared) {
tft.drawText(240,116, 'L', "Drehzahl"); redraw_view_driver();
tft.drawText(10,226, 'L', d); cleared = false;
tft.drawText(120,226, 'L', e); } else {
tft.drawText(240,226, 'L', f); update_view_driver();
/*if (cleaner){ }
tft.setTextSize(5,8); } else {
tft.drawText(0, 14, 'C', "FaSTTUBe"); // draw some text if (cleared) {
tft.setTextSize(4,4); redraw_view_testing();
tft.drawText(24, 120, 'C', "insert coin"); // draw some text cleared = false;
tft.drawText(0, 180, 'C', "to continue"); } else {
cleaner = false; update_view_testing();
}else{ }
tft.setTextSize(5,8); }
tft.drawText(0, 14, 'C', "FaSTTUBe"); // draw some text if (clearcounter>= 10000){
tft.setTextSize(4,4); pinMode(writeprotect, OUTPUT);
tft.drawText(24, 120, 'C', " "); // draw some text digitalWrite(writeprotect, HIGH);
tft.drawText(0, 180, 'C', " "); pinMode(reset, OUTPUT);
cleaner = true; pinMode(disp_cs, OUTPUT);
} pinMode(MOSI, OUTPUT);
delay(80);*/ pinMode(MISO, OUTPUT);
} digitalWrite(disp_cs, HIGH);
} digitalWrite(MOSI, HIGH);
} digitalWrite(MISO, HIGH);
digitalWrite(reset, LOW);
void display_trc(){ digitalWrite(reset, HIGH);
if(trcalt!=Stw_data.trc or Stw_data.buttonStateEnc1 == HIGH){ //tft.begin(115200); // start display communication
tft.clear(); //tft.cursorOn(false);
tft.setTextSize(7,8); //tft.terminalOn(false);
tft.setDisplayColor(EA_WHITE,EA_RED); //tft.setDisplayColor(EA_WHITE, EA_BLACK);
tft.setTextColor(EA_WHITE,EA_RED); //tft.setTextColor(EA_WHITE, EA_TRANSPARENT);
char trcanzeige[7]; //tft.setTextSize(5, 8);
String str = String("ARB:"); //tft.clear();
if(Stw_data.trc==11){
str+="ED"; // gear_box.update_label(get_label(VAL_GEAR));
}else{ // left_box.update_label(get_label(VAL_FIRST_LEFT_BOX));
str+=String(Stw_data.trc); // right_box.update_label(get_label(VAL_RPM));
}
str.toCharArray(trcanzeige,7); clearcounter = 0; //clearen des display nach definierter Zeit
tft.drawText(0,0,'L'," "); cleared =true;
tft.drawText(0,60,'L'," "); //
tft.drawText(0,120,'L'," "); }
tft.drawText(0,180,'L'," "); clearcounter+=1;
tft.drawText(15,68,'L',trcanzeige); }
trccounter = 0;
trcalt = Stw_data.trc; void alarm(String textstr) {
trctimer = true; uint8_t x = 1;
}else if(trccounter >= 255){ ;
tft.setDisplayColor(EA_WHITE,EA_BLACK); char text[7];
tft.setTextColor(EA_WHITE,EA_BLACK); textstr.toCharArray(text, 7);
tft.clear(); tft.setTextSize(8, 8);
trctimer = false; while (x == 1) {
}else{ if (!tft.disconnected) {
trccounter+=1; tft.setTextColor(EA_BLACK, EA_RED);
delay(5); tft.fillDisplayColor(EA_RED);
} tft.drawText(5, 68, 'L', text);
} }
for (int j = 0; j < 16; j++) {
void display_mode(){ digitalWrite(led_s[j], HIGH);
if(modealt!=Stw_data.mode or Stw_data.buttonStateEnc2 == HIGH){ }
tft.clear(); delay(100);
tft.setTextSize(6,8); if (!tft.disconnected) {
tft.setDisplayColor(EA_WHITE,EA_RED); tft.setTextColor(EA_BLACK, EA_WHITE);
tft.setTextColor(EA_WHITE,EA_RED); tft.fillDisplayColor(EA_WHITE);
char modeanzeige[7]; tft.drawText(5, 68, 'L', text);
String str = String("MODE:"); }
str+=String(Stw_data.mode); for (int j = 0; j < 16; j++) {
str.toCharArray(modeanzeige,7); digitalWrite(led_s[j], LOW);
tft.drawText(0,0,'L'," "); }
tft.drawText(0,60,'L'," "); delay(100);
tft.drawText(0,120,'L'," "); if (Stw_data.buttonState1 & Stw_data.buttonState4) {
tft.drawText(0,180,'L'," "); x = 0;
tft.drawText(15,68,'L',modeanzeige); tft.setTextColor(EA_WHITE, EA_TRANSPARENT);
modecounter = 0; }
modealt = Stw_data.mode; }
modetimer = true; }
}else if(modecounter >= 255){
tft.setDisplayColor(EA_WHITE,EA_BLACK); void redraw_view_driver() {
tft.setTextColor(EA_WHITE,EA_BLACK); tft.setTextColor(EA_WHITE, EA_TRANSPARENT);
tft.clear();
modetimer = false; // Boxes
}else{ tft.drawLine(0, 110, 320, 110);
modecounter+=1; tft.drawLine(120, 0, 120, 110);
delay(5); tft.drawLine(200, 0, 200, 110);
}
} // Tire temperature cross
tft.drawLine(80, 180, 240, 180);
void alarm(String textstr){ tft.drawLine(160, 130, 160, 230);
uint8_t x = 1;;
char text[7]; // Boxes
textstr.toCharArray(text,7); gear_box.redraw();
tft.setTextSize(8,8); left_box.redraw();
while(x==1){ right_box.redraw();
if(!tft.disconnected){ autoshift_box.redraw();
tft.setTextColor(EA_BLACK,EA_RED); fl_box.redraw();
tft.fillDisplayColor(EA_RED); fr_box.redraw();
tft.drawText(5,68,'L',text); rl_box.redraw();
} rr_box.redraw();
for (int j = 0; j < 16; j++){ }
digitalWrite(led_s[j], HIGH);
} void update_view_driver() {
delay(100); uint8_t prev_autoshift = Vehicle_data.autoshift;
if(!tft.disconnected){ static Value left_box_value = VAL_FIRST_LEFT_BOX;
tft.setTextColor(EA_BLACK,EA_WHITE); if (Stw_data.button4_rises > 0) {
tft.fillDisplayColor(EA_WHITE); Stw_data.button4_rises--;
tft.drawText(5,68,'L',text); if (left_box_value == VAL_LAST) {
} left_box_value = VAL_FIRST_LEFT_BOX;
for (int j = 0; j < 16; j++){ } else {
digitalWrite(led_s[j], LOW); left_box_value = (Value)(left_box_value + 1);
} }
delay(100); left_box.update_label(get_label(left_box_value));
if(Stw_data.buttonState1 & Stw_data.buttonState4){ }
x=0; if (Stw_data.button1_rises > 0) {
tft.setTextColor(EA_WHITE,EA_BLACK); Stw_data.button1_rises--;
} if (left_box_value == VAL_FIRST_LEFT_BOX) {
} left_box_value = VAL_LAST;
} } else {
left_box_value = (Value)(left_box_value - 1);
}
left_box.update_label(get_label(left_box_value));
}
// These can change rapidly, which would lead to a lot of flickering if
// rendered in the clear-redraw method. So instead, they're simply overwritten
// with a black background.
tft.setTextColor(EA_WHITE, EA_BLACK);
left_box.update_value(pad_left(get_value(left_box_value), 5));
right_box.update_value(pad_left(get_value(VAL_RPM), 5));
// Vehicle_data.autoshift = true;
if(Vehicle_data.autoshift == true){
tft.drawRectf(164+100, 184, 240+100, 230, TT_COL3);
}
else{
tft.drawRectf(164+100, 184, 240+100, 230, EA_BLACK);
}
autoshift_box.update_value(pad_left(String(Vehicle_data.autoshift), 5));
// These don't change as rapidly, and would overwrite adjacent elements
// (lines/labels) if rendered with a background because of the empty pixels
// above/below the characters. So they're rendered using the clear-redraw
// method.0
tft.setTextColor(EA_WHITE, EA_TRANSPARENT);
//gear_box.update_value(get_value(VAL_GEAR));
fl_box.update_value(get_value(VAL_TT_FL).toInt());
fr_box.update_value(get_value(VAL_TT_FR).toInt());
rl_box.update_value(get_value(VAL_TT_RL).toInt());
rr_box.update_value(get_value(VAL_TT_RR).toInt());
//Vehicle_data.autoshift = true; //For testing only!!
if(Vehicle_data.autoshift == true){
tft.setTextColor(EA_ORANGE, EA_TRANSPARENT);
}
gear_box.update_value(get_value(VAL_GEAR));
}
void redraw_view_testing() {
tft.clear();
tft.setTextFont(EA_FONT7X12);
tft.setTextSize(2, 2);
int start = 10 * testing_page;
tft.setTextColor(EA_WHITE, EA_BLACK);
for (int i = start; i <= min(VAL_LAST, start + 9); i += 2) {
redraw_label_testing(i, EA_BLACK);
}
tft.setTextColor(EA_WHITE, EA_DARKGREY);
for (int i = start + 1; i <= min(VAL_LAST, start + 9); i += 2) {
redraw_label_testing(i, EA_DARKGREY);
}
update_view_testing();
}
void update_view_testing() {
if (Stw_data.button4_rises > 0) {
Stw_data.button4_rises--;
testing_page++;
if (testing_page * 10 > VAL_LAST) {
testing_page = 0;
}
redraw_view_testing();
}
if (Stw_data.button1_rises > 0) {
Stw_data.button1_rises--;
testing_page--;
if (testing_page < 0) {
testing_page = VAL_LAST / 10;
}
redraw_view_testing();
}
tft.setTextFont(EA_FONT7X12);
tft.setTextSize(2, 2);
int start = 10 * testing_page;
tft.setTextColor(EA_WHITE, EA_BLACK);
for (int i = start; i <= min(VAL_LAST, start + 9); i += 2) {
update_value_testing(i);
}
tft.setTextColor(EA_WHITE, EA_DARKGREY);
for (int i = start + 1; i <= min(VAL_LAST, start + 9); i += 2) {
update_value_testing(i);
}
}
void redraw_label_testing(int i, uint8_t color) {
String text = get_label((Value)i) + ":";
int y = (i % 10) * 24;
tft.drawRectf(0, y, 320, y + 23, color);
tft.drawText(10, y, 'L', text.c_str());
}
void update_value_testing(int i) {
String text = pad_left(get_value((Value)i), 5);
int y = (i % 10) * 24;
tft.drawText(310, y, 'R', text.c_str());
}
DataBox::DataBox(int x1, int y1, int x2, int y2, int text_x, int text_y,
int font, int size_x, int size_y, uint8_t justification,
bool do_clear)
: x1{x1}, y1{y1}, x2{x2}, y2{y2}, text_x{text_x}, text_y{text_y},
font{font}, size_x{size_x}, size_y{size_y},
justification{justification}, do_clear{do_clear}, value{""}, label{""} {}
void DataBox::update_value(String val_new) {
if (!val_new.equals(value)) {
value = val_new;
redraw_value();
}
}
void DataBox::update_label(String label_new) {
if (!label_new.equals(label)) {
label = label_new;
redraw_label();
}
}
void DataBox::redraw() {
redraw_value();
redraw_label();
}
void DataBox::redraw_value() {
tft.setTextFont(font);
tft.setTextSize(size_x, size_y);
Serial.println("Redrawing value:");
if (do_clear) {
tft.clearRect(x1, y1, x2, y2);
}
tft.drawText(text_x, text_y, justification, value.c_str());
}
void DataBox::redraw_label() {
tft.setTextFont(EA_FONT7X12);
tft.setTextSize(1, 1);
Serial.println("Redrawing label:");
tft.clearRect(x1, y2 + 1, x2, y2 + 13);
tft.drawText((x1 + x2) / 2, y2 + 1, 'C', label.c_str());
}
TireTempBox::TireTempBox(int x1, int y1, int x2, int y2, int text_x, int text_y,
int font, int size_x, int size_y,
uint8_t justification)
: DataBox{x1, y1, x2, y2, text_x,
text_y, font, size_x, size_y, justification,
false},
num_value{-1} {}
void TireTempBox::update_value(int val_new) {
if (val_new != num_value) {
num_value = val_new;
if (val_new < TT_THRESH1) {
color = TT_COL0;
} else if (val_new < TT_THRESH2) {
color = TT_COL1;
} else if (val_new < TT_THRESH3) {
color = TT_COL2;
} else {
color = TT_COL3;
}
String val_str = pad_left(String(val_new), 3);
DataBox::update_value(val_str);
}
}
void TireTempBox::redraw_value() {
tft.setTextFont(font);
tft.setTextSize(size_x, size_y);
tft.drawRectf(x1, y1, x2, y2, color);
tft.drawText(text_x, text_y, justification, value.c_str());
}
void TireTempBox::redraw_label() {}

View File

@ -1,28 +1,117 @@
#include "Arduino.h" #include "Arduino.h"
#include "EDIPTFT.h" #include "EDIPTFT.h"
#include "FT_2018_STW_CAN.h" #include "FT18_STW_INIT.h"
#include "FT18_STW_INIT.h" #include "FT_2018_STW_CAN.h"
#ifndef FT18_STW_DISPLAY_h #ifndef FT18_STW_DISPLAY_h
#define FT18_STW_DISPLAY_h #define FT18_STW_DISPLAY_h
#define EA_BLACK 1 #define MOSI 75
#define EA_RED 3 #define MISO 74
#define EA_GREY 10 #define CLK 76
#define EA_WHITE 8 #define disp_cs 42
#define reset 43
#define MOSI 75 #define writeprotect 52
#define MISO 74
#define CLK 76 #define POIL_ALARM_THRESH ((uint32_t)(0.1 / 0.0514))
#define disp_cs 42 #define POIL_ALARM_TIME 20000 // ms
#define reset 43 #define TMOT_ALARM_THRESH (40 + 105)
#define writeprotect 52 #define TMOT_SAFE_VALUE (40 + 200)
#define TMOT_ALARM_TIME 20000 // ms
#define TOIL_ALARM_THRESH (40 + 150)
void init_display(void); #define TOIL_ALARM_TIME 10000 // ms
void update_display(void); #define ENC_DISPLAY_TIME 1000 // ms
double get_value(int a);
void display_trc(void); String pad_left(String orig, int len, char pad_char = ' ');
void display_mode(void);
void alarm(String text); enum DisplayView { VIEW_DRIVER, VIEW_TESTING, VIEW_LAST = VIEW_TESTING };
enum Value {
VAL_GEAR,
VAL_RPM,
VAL_TT_FL,
VAL_TT_FR,
VAL_TT_RL,
VAL_TT_RR,
VAL_LAPTIME,
VAL_UBATT,
VAL_TMOT,
VAL_TAIR,
VAL_TOIL,
VAL_ERR_TYPE,
VAL_PFUEL,
VAL_PWAT,
VAL_POIL,
VAL_PBF,
VAL_PBR,
VAL_SPEED_FL,
VAL_SPEED_FR,
VAL_SPEED,
VAL_BBAL,
VAL_FIRST_LEFT_BOX = VAL_LAPTIME,
VAL_LAST = VAL_BBAL
};
String get_value(Value val);
String get_label(Value val);
void init_display(void);
void update_display(void);
void display_trc(void);
void display_mode(void);
void alarm(String text);
bool check_alarms();
bool check_enc_displays();
bool check_display(uint8_t& val_old, uint8_t val_new, bool& active,
uint32_t& begin, const String& title);
void redraw_view_driver();
void update_view_driver();
void redraw_view_testing();
void update_view_testing();
void redraw_label_testing(int i, uint8_t bg_color);
void update_value_testing(int i);
class DataBox {
public:
DataBox(int x1, int y1, int x2, int y2, int text_x, int text_y, int font,
int size_x, int size_y, uint8_t justification, bool do_clear);
void update_value(String val_new);
void update_label(String label_new);
void redraw();
virtual void redraw_value();
virtual void redraw_label();
protected:
int x1, y1, x2, y2, text_x, text_y, font, size_x, size_y;
uint8_t justification;
bool do_clear;
String value;
String label;
};
#define TT_COL0 EA_LIGHTBLUE
#define TT_COL1 EA_GREEN
#define TT_COL2 EA_ORANGE
#define TT_COL3 EA_RED
#define TT_THRESH1 40
#define TT_THRESH2 60
#define TT_THRESH3 70
class TireTempBox : public DataBox {
public:
TireTempBox(int x1, int y1, int x2, int y2, int text_x, int text_y, int font,
int size_x, int size_y, uint8_t justification);
void update_value(int val_new);
void redraw_value() override;
void redraw_label() override;
private:
int color;
int num_value;
};
#endif #endif

View File

@ -1,133 +1,147 @@
#include "FT18_STW_INIT.h" #include "FT18_STW_INIT.h"
#include <Arduino.h> #include <Arduino.h>
#include <Bounce2.h> #include <Bounce2.h>
#include <RotaryEncoder.h> #include <RotaryEncoder.h>
volatile stw_data_type Stw_data = {0}; //alles mit 0 initialisieren volatile stw_data_type Stw_data = {0}; // alles mit 0 initialisieren
volatile vehicle_data_type Vehicle_data = {0}; //alles mit 0 initialisieren volatile vehicle_data_type Vehicle_data = {0}; // alles mit 0 initialisieren
bool enc1PinALast,enc1PinANow,enc2PinALast,enc2PinANow; bool enc1PinALast, enc1PinANow, enc2PinALast, enc2PinANow;
int led[] = {led1,led2,led3,led4,led5,led6,led7,led8,led9,led10,led11,led12,led13,led14,led15,led16}; int led[] = {led1, led2, led3, led4, led5, led6, led7, led8,
bool entprell; led9, led10, led11, led12, led13, led14, led15, led16};
int buttons[] = {button1,button2,button3,button4,button5,button6,enc1PinS,enc2PinS}; bool entprell;
constexpr size_t N_BUTTONS = sizeof(buttons)/sizeof(buttons[0]); int buttons[] = {button1, button2, button3, button4,
Bounce2::Button debouncer[N_BUTTONS]; button5, button6, enc1PinS, enc2PinS};
double val = 0; constexpr size_t N_BUTTONS = sizeof(buttons) / sizeof(buttons[0]);
double val2 = 0; Bounce2::Button debouncer[N_BUTTONS];
RotaryEncoder encoder(enc1PinA,enc1PinB,1,1,50); double val = 0;
RotaryEncoder encoder2(enc2PinA,enc2PinB,1,1,50); double val2 = 0;
/////////////////////////////////////////////////// RotaryEncoder encoder(enc1PinA, enc1PinB, 1, 1, 50);
// functions RotaryEncoder encoder2(enc2PinA, enc2PinB, 1, 1, 50);
/////////////////////////////////////////////////// ///////////////////////////////////////////////////
// functions
void set_pins(){ ///////////////////////////////////////////////////
pinMode (l,OUTPUT);
for (int thisLed = 0; thisLed < sizeof(led)/sizeof(int); thisLed++) { void set_pins() {
pinMode(led[thisLed], OUTPUT); pinMode(l, OUTPUT);
} for (int thisLed = 0; thisLed < sizeof(led) / sizeof(int); thisLed++) {
pinMode(enc1PinA, INPUT); pinMode(led[thisLed], OUTPUT);
pinMode(enc1PinB, INPUT); }
pinMode(enc2PinA, INPUT); pinMode(enc1PinA, INPUT);
pinMode(enc2PinB, INPUT); pinMode(enc1PinB, INPUT);
enc1PinALast=LOW; pinMode(enc2PinA, INPUT);
enc1PinANow=LOW; pinMode(enc2PinB, INPUT);
enc2PinALast=LOW; enc1PinALast = LOW;
enc2PinANow=LOW; enc1PinANow = LOW;
for(int i = 0; i < N_BUTTONS; i++){ enc2PinALast = LOW;
debouncer[i].attach(buttons[i], INPUT); enc2PinANow = LOW;
debouncer[i].interval(10); for (int i = 0; i < N_BUTTONS; i++) {
} debouncer[i].attach(buttons[i], INPUT);
} debouncer[i].interval(10);
}
void read_buttons(){ }
for (int i = 0; i < N_BUTTONS; i++) {
debouncer[i].update(); void read_buttons() {
} for (int i = 0; i < N_BUTTONS; i++) {
debouncer[i].update();
// These are only used to send them out via CAN, so they only need to be }
// high once.
Stw_data.Stw_neutral = debouncer[1].rose(); // These are only used to send them out via CAN, so they only need to be
Stw_data.Stw_auto_shift = debouncer[2].rose(); // high once.
Stw_data.Stw_shift_down = debouncer[4].rose(); //Stw_data.Stw_neutral = debouncer[1].rose();
Stw_data.Stw_shift_up = debouncer[5].rose(); //Stw_data.Stw_auto_shift = debouncer[2].isPressed(); //Hold to open DRS
// 05.09.: swapped neutral and auto_shift (DRS)
// These are also used for GUI, so if we set them only at rising edge, they Stw_data.Stw_neutral = debouncer[2].rose();
// might never be high when checked in the GUI. Stw_data.Stw_auto_shift = debouncer[1].isPressed(); //Hold to open DRS
// TODO: Rewrite so we can use debounced values here as well Stw_data.Stw_shift_down = debouncer[4].rose();
Stw_data.buttonState1 = digitalRead(button1); Stw_data.Stw_shift_up = debouncer[5].rose();
Stw_data.buttonState4 = digitalRead(button4);
Stw_data.buttonStateEnc1 = digitalRead(enc1PinS); Stw_data.buttonState1 = debouncer[0].isPressed();
Stw_data.buttonStateEnc2 = digitalRead(enc2PinS); Stw_data.buttonState4 = debouncer[3].isPressed();
} Stw_data.buttonStateEnc1 = debouncer[6].isPressed();
Stw_data.buttonStateEnc2 = debouncer[7].isPressed();
void read_rotary(){ if (debouncer[0].rose()) {
int enc = encoder.readEncoder(); Stw_data.button1_rises++;
int enc2 = encoder2.readEncoder(); }
if(enc != 0){ if (debouncer[3].rose()) {
val = val +0.5*enc; Stw_data.button4_rises++;
if (val==1 or val ==-1){ }
if(Stw_data.trc==0 and enc<0){ if (debouncer[6].rose()) {
Stw_data.trc = 11; Stw_data.enc1_rises++;
}else if(Stw_data.trc==11 and enc>0){ }
Stw_data.trc=0; if (debouncer[7].rose()) {
}else{ Stw_data.enc2_rises++;
Stw_data.trc = Stw_data.trc + enc; }
} }
val = 0;
} void read_rotary() {
} int enc = encoder.readEncoder();
/*enc1PinANow = digitalRead(enc1PinA); int enc2 = encoder2.readEncoder();
enc2PinANow = digitalRead(enc2PinA); if (enc != 0) {
if ((enc1PinALast == LOW) && (enc1PinANow == HIGH)) { val = val + 0.5 * enc;
if (digitalRead(enc1PinB) == HIGH) { if (val == 1 or val == -1) {
if(Stw_data.trc==0){ if (Stw_data.trc == 0 and enc < 0) {
Stw_data.trc = 5; Stw_data.trc = 11;
}else{ } else if (Stw_data.trc == 11 and enc > 0) {
Stw_data.trc--; Stw_data.trc = 0;
} } else {
}else { Stw_data.trc = Stw_data.trc + enc;
if(Stw_data.trc==5){ }
Stw_data.trc=0; val = 0;
}else{ }
Stw_data.trc++; }
} /*enc1PinANow = digitalRead(enc1PinA);
} enc2PinANow = digitalRead(enc2PinA);
} if ((enc1PinALast == LOW) && (enc1PinANow == HIGH)) {
enc1PinALast = enc1PinANow; if (digitalRead(enc1PinB) == HIGH) {
/*if (Stw_data.buttonStateEnc1 == HIGH){ if(Stw_data.trc==0){
digitalWrite(led[Stw_data.i], HIGH); Stw_data.trc = 5;
}*/ }else{
if(enc2 != 0){ Stw_data.trc--;
val2 = val2 +0.5*enc2; }
if(val2==1 or val2==-1){ }else {
if((Stw_data.mode==1 or Stw_data.mode==0) and enc2<0){ if(Stw_data.trc==5){
Stw_data.mode = 5; Stw_data.trc=0;
}else if(Stw_data.mode==5 and enc2>0){ }else{
Stw_data.mode=1; Stw_data.trc++;
}else{ }
Stw_data.mode = Stw_data.mode + enc2; }
} }
val2=0; enc1PinALast = enc1PinANow;
} /*if (Stw_data.buttonStateEnc1 == HIGH){
} digitalWrite(led[Stw_data.i], HIGH);
/*if ((enc2PinALast == LOW) && (enc2PinANow == HIGH)) { }*/
//if(enc2PinALast != enc2PinANow){ if (enc2 != 0) {
if (digitalRead(enc2PinB) == HIGH) { val2 = val2 + 0.5 * enc2;
if(Stw_data.i==0){ if (val2 == 1 or val2 == -1) {
Stw_data.i = sizeof(led)/sizeof(int)-1; if ((Stw_data.mode == 1 or Stw_data.mode == 0) and enc2 < 0) {
}else{ Stw_data.mode = 5;
Stw_data.i--; } else if (Stw_data.mode == 5 and enc2 > 0) {
} Stw_data.mode = 1;
}else { } else {
if(Stw_data.i==sizeof(led)/sizeof(int)-1){ Stw_data.mode = Stw_data.mode + enc2;
Stw_data.i=0; }
}else{ val2 = 0;
Stw_data.i++; }
} }
} /*if ((enc2PinALast == LOW) && (enc2PinANow == HIGH)) {
} //if(enc2PinALast != enc2PinANow){
enc2PinALast = enc2PinANow;*/ if (digitalRead(enc2PinB) == HIGH) {
/*if (Stw_data.buttonStateEnc2 == HIGH){ if(Stw_data.i==0){
digitalWrite(led[Stw_data.i], HIGH); Stw_data.i = sizeof(led)/sizeof(int)-1;
}*/ }else{
} Stw_data.i--;
}
}else {
if(Stw_data.i==sizeof(led)/sizeof(int)-1){
Stw_data.i=0;
}else{
Stw_data.i++;
}
}
}
enc2PinALast = enc2PinANow;*/
/*if (Stw_data.buttonStateEnc2 == HIGH){
digitalWrite(led[Stw_data.i], HIGH);
}*/
}

View File

@ -1,101 +1,108 @@
#include "Arduino.h" #include "Arduino.h"
#ifndef FT18_STW_Init #ifndef FT18_STW_Init
#define FT18_STW_Init #define FT18_STW_Init
#define l 78 //test_led #define l 78 // test_led
#define led1 12//PD8 #define led1 12 // PD8
#define led2 11//PD7 #define led2 11 // PD7
#define led3 9//PC21 #define led3 9 // PC21
#define led4 8//PC22 #define led4 8 // PC22
#define led5 7//PC23 #define led5 7 // PC23
#define led6 6//PC24 #define led6 6 // PC24
#define led7 5//PC25 #define led7 5 // PC25
#define led8 4//PC26 und PA29 #define led8 4 // PC26 und PA29
#define led9 3//PC28 #define led9 3 // PC28
#define led10 2//PB25 #define led10 2 // PB25
#define led11 10//PC29 und PA28 #define led11 10 // PC29 und PA28
#define led12 22//PB26 #define led12 22 // PB26
#define led13 19//PA10 #define led13 19 // PA10
#define led14 13//PB27 #define led14 13 // PB27
#define led15 17//PA12 #define led15 17 // PA12
#define led16 18//PA11 #define led16 18 // PA11
#define button1 48//bl #define button1 48 // bl
#define button2 47//gl #define button2 47 // gl
#define button3 44//gr #define button3 44 // gr
#define button4 46//br #define button4 46 // br
#define button5 45//sl #define button5 45 // sl
#define button6 49//sr #define button6 49 // sr
#define enc1PinA 37 #define enc1PinA 37
#define enc1PinB 38 #define enc1PinB 38
#define enc1PinS 35 #define enc1PinS 35
#define enc2PinA 40 #define enc2PinA 40
#define enc2PinB 41 #define enc2PinB 41
#define enc2PinS 39 #define enc2PinS 39
// define Drehzahlgrenzen TODOOOO
// define Drehzahlgrenzen TODOOOO #define RPM_THRES_1 6000
#define RPM_THRES_1 1000 #define RPM_THRES_2 12000
#define RPM_THRES_2 6000 #define RPM_THRES_3 12800
#define RPM_THRES_3 7000 #define RPM_THRES_4 13600
#define RPM_THRES_4 8000 #define RPM_THRES_5 14400
#define RPM_THRES_5 10000 #define RPM_THRES_6 15200
#define RPM_THRES_6 14000 #define RPM_THRES_7 16000
#define RPM_THRES_7 17000 #define RPM_THRES_8 16800
#define RPM_THRES_8 18000 #define RPM_THRES_9 18000
#define RPM_THRES_9 20000 #define RPM_THRES_10 18000
#define RPM_THRES_10 20000
void set_pins(void);
void read_buttons(void);
void set_pins(void); void read_rotary(void); // read rotary switches
void read_buttons(void);
void read_rotary(void); // read rotary switches typedef struct {
uint8_t Stw_shift_up; // 1 Bit 0
typedef struct uint8_t Stw_shift_down; // 1 Bit 1
{ uint8_t Stw_neutral; // 1 Bit 2
uint8_t Stw_shift_up; // 1 Bit 0 uint8_t Stw_auto_shift; // 1 Bit 3
uint8_t Stw_shift_down; // 1 Bit 1 uint8_t buttonState1; // 1 Bit 4
uint8_t Stw_neutral; // 1 Bit 2 uint8_t buttonState4; // 1 Bit 5
uint8_t Stw_auto_shift; // 1 Bit 3 // bool CAN_toggle;
uint8_t buttonState1; // 1 Bit 4 // bool CAN_check;
uint8_t buttonState4; // 1 Bit 5 // uint8_t i; //Index
//bool CAN_toggle; // linker Drehschalter
//bool CAN_check; uint8_t buttonStateEnc1; // button
//uint8_t i; //Index linker Drehschalter // uint8_t br; //test
uint8_t buttonStateEnc1; // button // mode : mittlere Drehschalter position
//uint8_t br; //test mode : mittlere Drehschalter position uint8_t buttonStateEnc2; // button
uint8_t buttonStateEnc2; //button uint8_t displayindex; // index für Displayanzeige
uint8_t displayindex; //index für Displayanzeige uint8_t error_type; // Extrainfos über Error-LED
uint8_t error_type; //Extrainfos über Error-LED uint8_t trc;
uint8_t trc; uint8_t mode;
uint8_t mode;
uint8_t button1_rises;
} stw_data_type; uint8_t button4_rises;
uint8_t enc1_rises;
typedef struct uint8_t enc2_rises;
{ } stw_data_type;
uint8_t e_thro; // E-Drossel
uint8_t g_auto; // Auto-Shift typedef struct {
uint8_t gear; // Gang uint8_t e_thro; // E-Drossel
uint16_t revol; // Drehzahl uint8_t g_auto; // Auto-Shift
uint8_t t_oil; // Öl-Motor-Temperatur uint8_t gear; // Gang
uint8_t t_mot; // Wasser-Motor-Temperatur uint16_t revol; // Drehzahl
uint8_t t_air; // LLK-Temperatur uint8_t t_oil; // Öl-Motor-Temperatur
uint8_t u_batt; // Batteriespannung uint8_t t_mot; // Wasser-Motor-Temperatur
uint8_t rev_lim; // Drehzahllimit Bit uint8_t t_air; // LLK-Temperatur
uint8_t p_wat; uint8_t t_tfl; // Tire temp front left
uint8_t p_fuel; uint8_t t_tfr; // Tire temp front right
uint8_t p_oil; uint8_t t_trl; // Tire temp rear left
uint8_t p_brake_front; uint8_t t_trr; // Tire temp rear right
uint8_t p_brake_rear; uint8_t u_batt; // Batteriespannung
uint8_t speed_fl; uint8_t rev_lim; // Drehzahllimit Bit
uint8_t speed_fr; bool drs_active; // DRS status from BCU
uint8_t speed; bool autoshift; // Autoshift status from BCU
uint8_t p_wat;
} vehicle_data_type; uint8_t p_fuel;
uint8_t p_oil;
uint8_t p_brake_front;
extern volatile stw_data_type Stw_data; uint8_t p_brake_rear;
extern volatile vehicle_data_type Vehicle_data; uint8_t speed_fl;
uint8_t speed_fr;
uint8_t speed;
uint8_t lap_time_sec;
uint16_t lap_time_msec;
} vehicle_data_type;
extern volatile stw_data_type Stw_data;
extern volatile vehicle_data_type Vehicle_data;
#endif #endif

View File

@ -1,171 +1,150 @@
#include "Arduino.h" #include "FT18e_STW_DISPLAY.h"
#include "EDIPTFT.h" #include "Arduino.h"
#include "FT_2018e_STW_CAN.h" #include "EDIPTFT.h"
#include "FT18e_STW_INIT.h" #include "FT18e_STW_INIT.h"
#include "FT18e_STW_DISPLAY.h" #include "FT_2018e_STW_CAN.h"
EDIPTFT tft(true, false); EDIPTFT tft(true, false);
String bezeichnungen[] = {"Batterieleistung", "Moment", "Batterietemp"}; String bezeichnungen[] = {"Batterieleistung", "Moment", "Batterietemp"};
//"T_mot","T_oil","P_oil","% fa","U_batt","P_wat","T_air", //"T_mot","T_oil","P_oil","% fa","U_batt","P_wat","T_air",
//"P_b_front","P_b_rear","Error Type","Speed_fl","Speed_fr","Speed"}; //"P_b_front","P_b_rear","Error Type","Speed_fl","Speed_fr","Speed"};
//"Drehzahl","P_fuel","Index" //"Drehzahl","P_fuel","Index"
int vergleichsindex; int vergleichsindex;
int sizeaalt; int sizeaalt;
int sizeaneu; int sizeaneu;
int sizebalt; int sizebalt;
int sizebneu; int sizebneu;
int sizecalt; int sizecalt;
int sizecneu; int sizecneu;
int sizedalt; int sizedalt;
int sizedneu; int sizedneu;
int sizeealt; int sizeealt;
int sizeeneu; int sizeeneu;
uint8_t clearcounter = 56; uint8_t clearcounter = 56;
uint8_t modealt = Stw_data.mode; uint8_t modealt = Stw_data.mode;
uint8_t trccounter; // = Stw_data.trc; uint8_t trccounter; // = Stw_data.trc;
uint8_t modecounter; // = Stw_data.mode; uint8_t modecounter; // = Stw_data.mode;
bool trctimer; bool trctimer;
bool modetimer; bool modetimer;
int led_s[] = {led1, led2, led3, led4, led5, led6, led7, led8, led9, led10, led11, led12, led13, led14, led15, led16}; int led_s[] = {led1, led2, led3, led4, led5, led6, led7, led8,
unsigned long poiltimer; led9, led10, led11, led12, led13, led14, led15, led16};
unsigned long tmottimer; unsigned long poiltimer;
unsigned long toiltimer; unsigned long tmottimer;
bool poilbool = true; unsigned long toiltimer;
bool tmotbool = true; bool poilbool = true;
bool toilbool = true; bool tmotbool = true;
bool toilbool = true;
void init_display()
{ void init_display() {
pinMode(writeprotect, OUTPUT); pinMode(writeprotect, OUTPUT);
digitalWrite(writeprotect, HIGH); digitalWrite(writeprotect, HIGH);
pinMode(reset, OUTPUT); pinMode(reset, OUTPUT);
pinMode(disp_cs, OUTPUT); pinMode(disp_cs, OUTPUT);
pinMode(MOSI, OUTPUT); pinMode(MOSI, OUTPUT);
pinMode(MISO, OUTPUT); pinMode(MISO, OUTPUT);
//pinMode(CLK, INPUT); // pinMode(CLK, INPUT);
digitalWrite(disp_cs, HIGH); digitalWrite(disp_cs, HIGH);
digitalWrite(MOSI, HIGH); digitalWrite(MOSI, HIGH);
digitalWrite(MISO, HIGH); digitalWrite(MISO, HIGH);
digitalWrite(reset, LOW); digitalWrite(reset, LOW);
//edip.smallProtoSelect(7); // edip.smallProtoSelect(7);
//edip.setNewColor(EA_GREY, 0xe3, 0xe3,0xe3); // redefine r-g-b-values of EA_GREY // edip.setNewColor(EA_GREY, 0xe3, 0xe3,0xe3); // redefine r-g-b-values
//edip.drawImage(0,50,FASTTUBE_LOGO_PNG); // of EA_GREY edip.drawImage(0,50,FASTTUBE_LOGO_PNG);
digitalWrite(reset, HIGH); digitalWrite(reset, HIGH);
tft.begin(115200); // start display communication tft.begin(115200); // start display communication
/*int h = 20; /*int h = 20;
char charh[2]; char charh[2];
String strh = String(h); String strh = String(h);
strh.toCharArray(charh,2); strh.toCharArray(charh,2);
tft.DisplayLight(charh);*/ tft.DisplayLight(charh);*/
tft.cursorOn(false); tft.cursorOn(false);
tft.terminalOn(false); tft.terminalOn(false);
tft.setDisplayColor(EA_WHITE, EA_BLACK); tft.setDisplayColor(EA_WHITE, EA_BLACK);
tft.setTextColor(EA_WHITE, EA_BLACK); tft.setTextColor(EA_WHITE, EA_BLACK);
//tft.setTextFont('4'); // tft.setTextFont('4');
tft.setTextSize(5, 8); tft.setTextSize(5, 8);
tft.clear(); tft.clear();
//tft.displayLight('30'); // tft.displayLight('30');
tft.drawText(0, 14, 'C', "FaSTTUBe"); //draw some text tft.drawText(0, 14, 'C', "FaSTTUBe"); // draw some text
//tft.loadImage(0,0,1); // tft.loadImage(0,0,1);
//delay(2000); // delay(2000);
} }
double get_value(int a) double get_value(int a) { return 0; }
{
return 0; void update_display() {
} if (!tft.disconnected) {
tft.cursorOn(false);
void update_display() if (modealt != Stw_data.mode || modetimer == true) {
{ display_mode();
if (!tft.disconnected) } else {
{ if (clearcounter >= 56) {
tft.cursorOn(false); tft.clear();
if (modealt != Stw_data.mode || modetimer == true) clearcounter = 0;
{ }
display_mode(); clearcounter += 1;
} }
else }
{ // else für neue init?
if (clearcounter >= 56) }
{
tft.clear(); void display_mode() {
clearcounter = 0; if (modealt != Stw_data.mode) {
} tft.clear();
clearcounter += 1; tft.setTextSize(6, 8);
} tft.setDisplayColor(EA_WHITE, EA_RED);
} tft.setTextColor(EA_WHITE, EA_RED);
} char modeanzeige[7];
String str = String("MODE:");
void display_mode() str += String(Stw_data.mode);
{ str.toCharArray(modeanzeige, 7);
if (modealt != Stw_data.mode) tft.drawText(0, 0, 'L', " ");
{ tft.drawText(0, 60, 'L', " ");
tft.clear(); tft.drawText(0, 120, 'L', " ");
tft.setTextSize(6, 8); tft.drawText(0, 180, 'L', " ");
tft.setDisplayColor(EA_WHITE, EA_RED); tft.drawText(15, 68, 'L', modeanzeige);
tft.setTextColor(EA_WHITE, EA_RED); modecounter = 0;
char modeanzeige[7]; modealt = Stw_data.mode;
String str = String("MODE:"); modetimer = true;
str += String(Stw_data.mode); } else if (modecounter >= 255) {
str.toCharArray(modeanzeige, 7); tft.setDisplayColor(EA_WHITE, EA_BLACK);
tft.drawText(0, 0, 'L', " "); tft.setTextColor(EA_WHITE, EA_BLACK);
tft.drawText(0, 60, 'L', " "); tft.clear();
tft.drawText(0, 120, 'L', " "); modetimer = false;
tft.drawText(0, 180, 'L', " "); } else {
tft.drawText(15, 68, 'L', modeanzeige); modecounter += 1;
modecounter = 0; delay(5);
modealt = Stw_data.mode; }
modetimer = true; }
}
else if (modecounter >= 255) void alarm(String textstr) {
{ uint8_t x = 1;
tft.setDisplayColor(EA_WHITE, EA_BLACK); ;
tft.setTextColor(EA_WHITE, EA_BLACK); char text[7];
tft.clear(); textstr.toCharArray(text, 7);
modetimer = false; tft.setTextSize(8, 8);
} while (x == 1) {
else if (!tft.disconnected) {
{ tft.setTextColor(EA_BLACK, EA_RED);
modecounter += 1; tft.fillDisplayColor(EA_RED);
delay(5); tft.drawText(5, 68, 'L', text);
} }
} for (int j = 0; j < 16; j++) {
digitalWrite(led_s[j], HIGH);
void alarm(String textstr) }
{ delay(100);
uint8_t x = 1; if (!tft.disconnected) {
; tft.setTextColor(EA_BLACK, EA_WHITE);
char text[7]; tft.fillDisplayColor(EA_WHITE);
textstr.toCharArray(text, 7); tft.drawText(5, 68, 'L', text);
tft.setTextSize(8, 8); }
while (x == 1) for (int j = 0; j < 16; j++) {
{ digitalWrite(led_s[j], LOW);
if (!tft.disconnected) }
{ delay(100);
tft.setTextColor(EA_BLACK, EA_RED); if (Stw_data.button_ll & Stw_data.button_rr) {
tft.fillDisplayColor(EA_RED); x = 0;
tft.drawText(5, 68, 'L', text); tft.setTextColor(EA_WHITE, EA_BLACK);
} }
for (int j = 0; j < 16; j++) }
{
digitalWrite(led_s[j], HIGH);
}
delay(100);
if (!tft.disconnected)
{
tft.setTextColor(EA_BLACK, EA_WHITE);
tft.fillDisplayColor(EA_WHITE);
tft.drawText(5, 68, 'L', text);
}
for (int j = 0; j < 16; j++)
{
digitalWrite(led_s[j], LOW);
}
delay(100);
if (Stw_data.button_ll & Stw_data.button_rr)
{
x = 0;
tft.setTextColor(EA_WHITE, EA_BLACK);
}
}
} }

View File

@ -1,26 +1,26 @@
#include "Arduino.h" #include "Arduino.h"
#include "EDIPTFT.h" #include "EDIPTFT.h"
#include "FT_2018e_STW_CAN.h" #include "FT18e_STW_INIT.h"
#include "FT18e_STW_INIT.h" #include "FT_2018e_STW_CAN.h"
#ifndef FT18e_STW_DISPLAY_h #ifndef FT18e_STW_DISPLAY_h
#define FT18e_STW_DISPLAY_h #define FT18e_STW_DISPLAY_h
#define EA_BLACK 1 #define EA_BLACK 1
#define EA_RED 3 #define EA_RED 3
#define EA_GREY 10 #define EA_GREY 10
#define EA_WHITE 8 #define EA_WHITE 8
#define MOSI 75 #define MOSI 75
#define MISO 74 #define MISO 74
#define CLK 76 #define CLK 76
#define disp_cs 42 #define disp_cs 42
#define reset 43 #define reset 43
#define writeprotect 52 #define writeprotect 52
void init_display(void); void init_display(void);
void update_display(void); void update_display(void);
double get_value(int a); double get_value(int a);
void display_mode(void); void display_mode(void);
void alarm(String text); void alarm(String text);
#endif #endif

View File

@ -1,84 +1,74 @@
#include "Arduino.h" #include "FT18e_STW_INIT.h"
#include "FT18e_STW_INIT.h" #include "Arduino.h"
#include "Bounce2.h" #include "Bounce2.h"
#include "RotaryEncoder.h" #include "RotaryEncoder.h"
volatile stw_data_type Stw_data = {0}; //alles mit 0 initialisieren volatile stw_data_type Stw_data = {0}; // alles mit 0 initialisieren
volatile vehicle_data_type Vehicle_data = {0}; //alles mit 0 initialisieren volatile vehicle_data_type Vehicle_data = {0}; // alles mit 0 initialisieren
bool enc1PinALast, enc1PinANow, enc2PinALast, enc2PinANow; bool enc1PinALast, enc1PinANow, enc2PinALast, enc2PinANow;
int led[] = {led1, led2, led3, led4, led5, led6, led7, led8, led9, led10, led11, led12, led13, led14, led15, led16}; int led[] = {led1, led2, led3, led4, led5, led6, led7, led8,
bool entprell; led9, led10, led11, led12, led13, led14, led15, led16};
int buttons[] = {PIN_BUTTON_LL, PIN_BUTTON_LR, PIN_BUTTON_RL, PIN_BUTTON_RR, enc1PinS, enc2PinS}; bool entprell;
Bounce debouncer[8]; int buttons[] = {PIN_BUTTON_LL, PIN_BUTTON_LR, PIN_BUTTON_RL,
double val = 0; PIN_BUTTON_RR, enc1PinS, enc2PinS};
double val2 = 0; Bounce debouncer[8];
RotaryEncoder encoder(enc1PinA, enc1PinB, 1, 1, 50); double val = 0;
RotaryEncoder encoder2(enc2PinA, enc2PinB, 1, 1, 50); double val2 = 0;
/////////////////////////////////////////////////// RotaryEncoder encoder(enc1PinA, enc1PinB, 1, 1, 50);
// functions RotaryEncoder encoder2(enc2PinA, enc2PinB, 1, 1, 50);
/////////////////////////////////////////////////// ///////////////////////////////////////////////////
// functions
void set_pins() ///////////////////////////////////////////////////
{
for (int thisLed = 0; thisLed < sizeof(led) / sizeof(int); thisLed++) void set_pins() {
{ for (int thisLed = 0; thisLed < sizeof(led) / sizeof(int); thisLed++) {
pinMode(led[thisLed], OUTPUT); pinMode(led[thisLed], OUTPUT);
} }
pinMode(l, OUTPUT); pinMode(l, OUTPUT);
/*pinMode(button1, INPUT); /*pinMode(button1, INPUT);
pinMode(button2, INPUT); pinMode(button2, INPUT);
pinMode(button3, INPUT); pinMode(button3, INPUT);
pinMode(button4, INPUT); pinMode(button4, INPUT);
pinMode(button5, INPUT); pinMode(button5, INPUT);
pinMode(button6, INPUT);*/ pinMode(button6, INPUT);*/
pinMode(enc1PinA, INPUT); pinMode(enc1PinA, INPUT);
pinMode(enc1PinB, INPUT); pinMode(enc1PinB, INPUT);
//pinMode(enc1PinS, INPUT); // pinMode(enc1PinS, INPUT);
pinMode(enc2PinA, INPUT); pinMode(enc2PinA, INPUT);
pinMode(enc2PinB, INPUT); pinMode(enc2PinB, INPUT);
//pinMode(enc2PinS, INPUT); // pinMode(enc2PinS, INPUT);
//Stw_data.i=0; // Stw_data.i=0;
enc1PinALast = LOW; enc1PinALast = LOW;
enc1PinANow = LOW; enc1PinANow = LOW;
enc2PinALast = LOW; enc2PinALast = LOW;
enc2PinANow = LOW; enc2PinANow = LOW;
for (int i = 0; i < sizeof(buttons) / sizeof(*buttons); i++) for (int i = 0; i < sizeof(buttons) / sizeof(*buttons); i++) {
{ pinMode(buttons[i], INPUT);
pinMode(buttons[i], INPUT); debouncer[i].attach(buttons[i]);
debouncer[i].attach(buttons[i]); debouncer[i].interval(10);
debouncer[i].interval(10); }
} }
}
void read_buttons() {
void read_buttons() Stw_data.button_ll = digitalRead(PIN_BUTTON_LL);
{ Stw_data.button_lr = digitalRead(PIN_BUTTON_LR);
Stw_data.button_ll = digitalRead(PIN_BUTTON_LL); Stw_data.button_rl = digitalRead(PIN_BUTTON_RL);
Stw_data.button_lr = digitalRead(PIN_BUTTON_LR); Stw_data.button_rr = digitalRead(PIN_BUTTON_RR);
Stw_data.button_rl = digitalRead(PIN_BUTTON_RL); }
Stw_data.button_rr = digitalRead(PIN_BUTTON_RR);
} void read_rotary() {
int enc2 = encoder2.readEncoder();
void read_rotary() if (enc2 != 0) {
{ val2 = val2 + 0.5 * enc2;
int enc2 = encoder2.readEncoder(); if (val2 == 1 or val2 == -1) {
if (enc2 != 0) if ((Stw_data.mode == 1 or Stw_data.mode == 0) and enc2 < 0) {
{ Stw_data.mode = 5;
val2 = val2 + 0.5 * enc2; } else if (Stw_data.mode == 5 and enc2 > 0) {
if (val2 == 1 or val2 == -1) Stw_data.mode = 1;
{ } else {
if ((Stw_data.mode == 1 or Stw_data.mode == 0) and enc2 < 0) Stw_data.mode = Stw_data.mode + enc2;
{ }
Stw_data.mode = 5; val2 = 0;
} }
else if (Stw_data.mode == 5 and enc2 > 0) }
{
Stw_data.mode = 1;
}
else
{
Stw_data.mode = Stw_data.mode + enc2;
}
val2 = 0;
}
}
} }

View File

@ -1,98 +1,95 @@
#include "Arduino.h" #include "Arduino.h"
#ifndef FT18e_STW_Init #ifndef FT18e_STW_Init
#define FT18e_STW_Init #define FT18e_STW_Init
#define l 78 //test_led #define l 78 // test_led
#define led1 12 //PD8 #define led1 12 // PD8
#define led2 11 //PD7 #define led2 11 // PD7
#define led3 9 //PC21 #define led3 9 // PC21
#define led4 8 //PC22 #define led4 8 // PC22
#define led5 7 //PC23 #define led5 7 // PC23
#define led6 6 //PC24 #define led6 6 // PC24
#define led7 5 //PC25 #define led7 5 // PC25
#define led8 4 //PC26 und PA29 #define led8 4 // PC26 und PA29
#define led9 3 //PC28 #define led9 3 // PC28
#define led10 2 //PB25 #define led10 2 // PB25
#define led11 10 //PC29 und PA28 #define led11 10 // PC29 und PA28
#define led12 22 //PB26 #define led12 22 // PB26
#define led13 19 //PA10 #define led13 19 // PA10
#define led14 13 //PB27 #define led14 13 // PB27
#define led15 17 //PA12 #define led15 17 // PA12
#define led16 18 //PA11 #define led16 18 // PA11
#define enc1PinA 37 #define enc1PinA 37
#define enc1PinB 38 #define enc1PinB 38
#define enc1PinS 35 #define enc1PinS 35
#define enc2PinA 40 #define enc2PinA 40
#define enc2PinB 41 #define enc2PinB 41
#define enc2PinS 39 #define enc2PinS 39
constexpr int PIN_BUTTON_LL = 47; constexpr int PIN_BUTTON_LL = 47;
constexpr int PIN_BUTTON_LR = 48; constexpr int PIN_BUTTON_LR = 48;
constexpr int PIN_BUTTON_RL = 46; constexpr int PIN_BUTTON_RL = 46;
constexpr int PIN_BUTTON_RR = 44; constexpr int PIN_BUTTON_RR = 44;
constexpr int16_t RPM_THRESH_1 = 1000; constexpr int16_t RPM_THRESH_1 = 1000;
constexpr int16_t RPM_THRESH_2 = 4000; constexpr int16_t RPM_THRESH_2 = 4000;
constexpr int16_t RPM_THRESH_3 = 6000; constexpr int16_t RPM_THRESH_3 = 6000;
constexpr int16_t RPM_THRESH_4 = 8000; constexpr int16_t RPM_THRESH_4 = 8000;
constexpr int16_t RPM_THRESH_5 = 10000; constexpr int16_t RPM_THRESH_5 = 10000;
constexpr int16_t RPM_THRESH_6 = 12000; constexpr int16_t RPM_THRESH_6 = 12000;
constexpr int16_t RPM_THRESH_7 = 14000; constexpr int16_t RPM_THRESH_7 = 14000;
constexpr int16_t RPM_THRESH_8 = 16000; constexpr int16_t RPM_THRESH_8 = 16000;
constexpr int16_t RPM_THRESH_9 = 18000; constexpr int16_t RPM_THRESH_9 = 18000;
constexpr int16_t RPM_THRESH_10 = 20000; constexpr int16_t RPM_THRESH_10 = 20000;
constexpr int16_t LED_THRESH_T_MOT = 7000; // 1/100°C constexpr int16_t LED_THRESH_T_MOT = 7000; // 1/100°C
constexpr int16_t LED_THRESH_T_INV = 6000; // 1/100°C constexpr int16_t LED_THRESH_T_INV = 6000; // 1/100°C
constexpr int16_t LED_THRESH_T_BAT = 5000; // 1/100°C constexpr int16_t LED_THRESH_T_BAT = 5000; // 1/100°C
constexpr uint16_t LED_THRESH_U_BATT = 350; // 1/100V constexpr uint16_t LED_THRESH_U_BATT = 350; // 1/100V
void set_pins(void); void set_pins(void);
void read_buttons(void); void read_buttons(void);
void read_rotary(void); // read rotary switches void read_rotary(void); // read rotary switches
typedef struct typedef struct {
{ bool button_ll; // Left side, left button
bool button_ll; // Left side, left button bool button_lr; // Left side, right button
bool button_lr; // Left side, right button bool button_rl; // Right side, left button
bool button_rl; // Right side, left button bool button_rr; // Right side, right button
bool button_rr; // Right side, right button uint8_t mode;
uint8_t mode; uint8_t displayindex; // index für Displayanzeige
uint8_t displayindex; //index für Displayanzeige uint8_t error_type; // Extrainfos über Error-LED
uint8_t error_type; //Extrainfos über Error-LED
} stw_data_type;
} stw_data_type;
struct InverterData {
struct InverterData bool ready;
{ bool derating;
bool ready; bool warning;
bool derating; bool error;
bool warning; bool on;
bool error; bool precharge;
bool on; bool ams_emerg;
bool precharge; bool ts_active;
bool ams_emerg; };
bool ts_active;
}; typedef struct {
uint16_t u_cell_min; // Minimale Zellspannung
typedef struct uint16_t u_batt; // Batteriespannung (pre-AIR-voltage)
{ int16_t t_mot_l; // Motor-Wasser-Temperatur Links
uint16_t u_cell_min; // Minimale Zellspannung int16_t t_mot_r; // Motor-Wasser-Temperatur Rechts
uint16_t u_batt; // Batteriespannung (pre-AIR-voltage) int16_t t_cell_max; // Maximale Zelltemperatur
int16_t t_mot_l; // Motor-Wasser-Temperatur Links int16_t t_inv;
int16_t t_mot_r; // Motor-Wasser-Temperatur Rechts int16_t t_wat;
int16_t t_cell_max; // Maximale Zelltemperatur int16_t p_wat;
int16_t t_inv; uint8_t speed;
int16_t t_wat; InverterData inverter;
int16_t p_wat; bool rev_lim; // Drehzahllimit Bit
uint8_t speed; int16_t revol; // Drehzahl
InverterData inverter; int16_t wheel_speed;
bool rev_lim; // Drehzahllimit Bit } vehicle_data_type;
int16_t revol; // Drehzahl
int16_t wheel_speed; extern volatile stw_data_type Stw_data;
} vehicle_data_type; extern volatile vehicle_data_type Vehicle_data;
extern volatile stw_data_type Stw_data;
extern volatile vehicle_data_type Vehicle_data;
#endif #endif

View File

@ -1,269 +1,291 @@
/* /*
FT_2018_STW_CAN.cpp FT_2018_STW_CAN.cpp
*/ */
#include "Arduino.h" #include "FT_2018_STW_CAN.h"
#include "DueTimer.h" #include "Arduino.h"
#include "due_can.h" #include "DueTimer.h"
#include "FT_2018_STW_CAN.h" #include "FT18_STW_INIT.h"
#include "FT18_STW_INIT.h" #include "due_can.h"
CAN_FRAME can_0_msg; CAN_FRAME can_0_msg;
//can_1_msg.id = 0x110; // can_1_msg.id = 0x110;
int can_0_temp_data = 0; int can_0_temp_data = 0;
int leds[] = {led1,led2,led3,led4,led5,led6,led7,led8,led9,led10,led11,led12,led13,led14,led15,led16};
int leds[] = {led1, led2, led3, led4, led5, led6, led7, led8,
led9, led10, led11, led12, led13, led14, led15, led16};
void Init_Can_0(){
Can0.begin(1000000); // set CAN0 baud to 1kbit/s and don`t use enable pin! void Init_Can_0() {
Can0.setNumTXBoxes(1); // reserves mailbox 0 for tx only 8 mailboxes are available (the other 7 mailboxes are for rx)
Can0.watchFor(0x502); // set CAN RX filter for ID 0x502 and reserves mailbox 1 for rx Can0.begin(1000000); // set CAN0 baud to 1kbit/s and don`t use enable pin!
Can0.watchFor(0x504); Can0.setNumTXBoxes(1); // reserves mailbox 0 for tx only 8 mailboxes are
Can0.watchFor(0x500); // available (the other 7 mailboxes are for rx)
Can0.watchFor(0x773); // set CAN RX filter for ID 0x773 and reserves mailbox 3 for rx
Can0.watchFor(0x775); // We only have 7 mailboxes, but want to receive 9 messages. This trick should
// Can0.watchFor(0x777); // set CAN RX filter for ID 0x777 and reserves mailbox 5 for rx // allow us to receive BCU_APS_BRAKE, BCU_ETC and BCU_SHIFT_CTRL in the same
Can0.watchFor(0x779); // set CAN RX filter for ID 0x779 and reserves mailbox 6 for rx // mailbox. It will also let through 0x506, but that shouldn't be much of an
Can0.watchFor(0x77A); // issue.
Can0.setGeneralCallback(Receive_Can_0); /*
Timer3.attachInterrupt(Send_0x110); // set send interrupt Can0.watchFor(CAN_ID_BCU_APS_BRAKE & CAN_ID_BCU_ETC & CAN_ID_BCU_SHIFT_CTRL,
Timer3.start(10000); // Calls every 10ms 0x7F9);
} Can0.watchFor(CAN_ID_BCU_TIRES);
Can0.watchFor(CAN_ID_BCU_LAP_TIME);
void Send_0x110(){ Can0.watchFor(CAN_ID_MS4_IGN_REV_ATH);
read_buttons(); Can0.watchFor(CAN_ID_MS4_SPEED);
read_rotary(); Can0.watchFor(CAN_ID_MS4_ETC);
can_0_msg.id = 0x110; Can0.watchFor(CAN_ID_MS4_STATES_TEMP_PRESS);
can_0_msg.fid = 0;
can_0_msg.rtr = 0; Can0.setGeneralCallback(Receive_Can_0);
can_0_msg.priority = 0; */
can_0_msg.length = 2;
can_0_msg.extended = 0; Timer3.attachInterrupt(Send_0x110); // set send interrupt
can_0_temp_data = 0; Timer3.start(10000); // Calls every 10ms
can_0_temp_data |= Stw_data.Stw_shift_up & 0b00000001; }
can_0_temp_data |= Stw_data.Stw_shift_down << 1 & 0b00000010;
can_0_temp_data |= Stw_data.Stw_neutral << 2 & 0b00000100; void Send_0x110() {
can_0_temp_data |= Stw_data.Stw_auto_shift << 3 & 0b00001000; read_buttons();
can_0_temp_data |= Stw_data.buttonStateEnc1 << 5 & 0b00100000; //pitlane read_rotary();
can_0_msg.data.byte[0] = can_0_temp_data; can_0_msg.id = 0x110;
can_0_msg.data.byte[1] = Stw_data.trc & 0b00001111; can_0_msg.fid = 0;
can_0_msg.data.byte[2] = Stw_data.mode & 0b00000111; can_0_msg.rtr = 0;
if ((Stw_data.Stw_auto_shift << 3 & 0b00001000)){ can_0_msg.priority = 0;
if(Vehicle_data.g_auto){ can_0_msg.length = 2;
Vehicle_data.g_auto = false; can_0_msg.extended = 0;
}else{ can_0_temp_data = 0;
Vehicle_data.g_auto = true; can_0_temp_data |= Stw_data.Stw_shift_up & 0b00000001;
} can_0_temp_data |= Stw_data.Stw_shift_down << 1 & 0b00000010;
} can_0_temp_data |= Stw_data.Stw_neutral << 2 & 0b00000100;
Can0.sendFrame(can_0_msg); can_0_temp_data |= Stw_data.Stw_auto_shift << 3 & 0b00001000;
} can_0_temp_data |= Stw_data.buttonStateEnc1 << 5 & 0b00100000; // pitlane
can_0_msg.data.byte[0] = can_0_temp_data;
void Receive_Can_0(CAN_FRAME *temp_message){ can_0_msg.data.byte[1] = Stw_data.trc & 0b00001111;
switch (temp_message->id) { can_0_msg.data.byte[2] = Stw_data.mode & 0b00000111;
//g_auto if ((Stw_data.Stw_auto_shift << 3 & 0b00001000)) {
case 0x502:{ // eDrossel error bit if (Vehicle_data.g_auto) {
Vehicle_data.e_thro = (temp_message->data.byte[0] & 0x80) | (temp_message->data.byte[0] & 0x40) | (temp_message->data.byte[0] & 0x20) | (temp_message->data.byte[0] & 0x10); // bit 4-7 Vehicle_data.g_auto = false;
} else {
if(temp_message->data.byte[0] & 0x80){ Vehicle_data.g_auto = true;
Stw_data.error_type = 1;//"pc_error"; }
} }
if(temp_message->data.byte[0] & 0x40){ Can0.sendFrame(can_0_msg);
Stw_data.error_type = 2;//"bse_error"; }
}
if(temp_message->data.byte[0] & 0x20){ void Receive_Can_0(CAN_FRAME *temp_message) {
Stw_data.error_type = 3;//"aps_error"; switch (temp_message->id) {
} case CAN_ID_BCU_APS_BRAKE: {
if(temp_message->data.byte[0] & 0x10){ Vehicle_data.p_brake_front = temp_message->data.byte[1];
Stw_data.error_type = 4;//"etb_error"; Vehicle_data.p_brake_rear = temp_message->data.byte[2];
} Vehicle_data.drs_active = ((temp_message->data.byte[0] >> 7) & 0b00000001);
//can_1_temp_data |= g_etb_e << 4; Vehicle_data.autoshift = ((temp_message->data.byte[7] >> 0) & 0b00000001);
//can_1_temp_data |= g_aps_e << 5; break;
//can_1_temp_data |= g_bse_e << 6; }
//can_1_temp_data |= g_pc_e << 7; case CAN_ID_BCU_ETC: { // eDrossel error bit
break; Vehicle_data.e_thro = (temp_message->data.byte[0] & 0xF0); // bit 4-7
}
case 0x504:{ //autoshift+gear if (temp_message->data.byte[0] & 0x80) {
//Vehicle_data.g_auto = (temp_message->data.byte[1]) >> 4; Stw_data.error_type = 1; //"pc_error";
Vehicle_data.gear = (temp_message->data.byte[1]) >> 5; }
break; if (temp_message->data.byte[0] & 0x40) {
} Stw_data.error_type = 2; //"bse_error";
case 0x773:{ // rpm }
Vehicle_data.revol = (temp_message->data.byte[4] | temp_message->data.byte[3] << 8); if (temp_message->data.byte[0] & 0x20) {
break; Stw_data.error_type = 3; //"aps_error";
} }
case 0x779:{ // battery voltage if (temp_message->data.byte[0] & 0x10) {
Vehicle_data.u_batt = temp_message->data.byte[6]; Stw_data.error_type = 4; //"etb_error";
break; }
} break;
/*case 0x77A: // revolution limit bit }
Vehicle_data.rev_lim = (temp_message->data.byte[3] & 0x20) >> 4; case CAN_ID_BCU_SHIFT_CTRL: { // autoshift+gear
switch(temp_message->data.byte[0]) { Vehicle_data.gear = (temp_message->data.byte[1]) >> 5;
case 0x02: // temp. intercooler break;
Vehicle_data.t_air = temp_message->data.byte[7]; }
break; case CAN_ID_BCU_TIRES: { // Tire temps
case 0x05: // temp. water Vehicle_data.t_trl = temp_message->data.byte[1];
Vehicle_data.t_mot = temp_message->data.byte[4]; Vehicle_data.t_trr = temp_message->data.byte[4];
break; Vehicle_data.t_tfl = temp_message->data.byte[5];
case 0x04: // temp. oil Vehicle_data.t_tfr = temp_message->data.byte[6];
Vehicle_data.t_oil = temp_message->data.byte[5]; break;
case 0x01: { }
Vehicle_data.p_wat = temp_message->data.byte[6]; case CAN_ID_BCU_LAP_TIME: { // lap time
Vehicle_data.p_fuel = temp_message->data.byte[7]; Vehicle_data.lap_time_sec = temp_message->data.byte[1];
Vehicle_data.p_oil = temp_message->data.byte[5]; Vehicle_data.lap_time_msec =
break; temp_message->data.byte[2] | ((temp_message->data.byte[3] & 0b11) << 8);
} break;
} }
break;*/ case CAN_ID_MS4_IGN_REV_ATH: { // rpm
case 0x77A:{//temp und p Vehicle_data.revol =
//g_ms4_idle_b = (temp_message->data.byte[2] & 0b10000000) >> 7; (temp_message->data.byte[4] | temp_message->data.byte[3] << 8);
//g_ms4_engine_status = (temp_message->data.byte[3] & 0b01000000) >> 6; break;
//g_ms4_ignoff_b = (temp_message->data.byte[3] & 0b10000000) >> 7; }
// Serial.println("CAN 77A"); case CAN_ID_MS4_SPEED: { // speed
// for (int i = 0; i < 8; i++) { Vehicle_data.speed_fl = 2 * (temp_message->data.byte[2]);
// Serial.print('['); Vehicle_data.speed_fr = 2 * (temp_message->data.byte[3]);
// Serial.print(i); Vehicle_data.speed = (Vehicle_data.speed_fl + Vehicle_data.speed_fr) / 2;
// Serial.print("] "); break;
// Serial.println(temp_message->data.byte[i], HEX); }
// } case CAN_ID_MS4_ETC: { // battery voltage
Vehicle_data.u_batt = temp_message->data.byte[6];
if ( temp_message->data.byte[0] == 1){ break;
Vehicle_data.p_oil = temp_message->data.byte[5]; }
Vehicle_data.p_fuel = temp_message->data.byte[7]; case CAN_ID_MS4_STATES_TEMP_PRESS: { // temp und p
} if (temp_message->data.byte[0] == 1) {
else if ( temp_message->data.byte[0] == 2){ Vehicle_data.p_oil = temp_message->data.byte[5];
Vehicle_data.t_air = temp_message->data.byte[7]; Vehicle_data.p_fuel = temp_message->data.byte[7];
} } else if (temp_message->data.byte[0] == 2) {
else if ( temp_message->data.byte[0] == 4){ Vehicle_data.t_air = temp_message->data.byte[7];
Vehicle_data.t_oil = temp_message->data.byte[5]; } else if (temp_message->data.byte[0] == 4) {
} Vehicle_data.t_oil = temp_message->data.byte[5];
else if ( temp_message->data.byte[0] == 5){ } else if (temp_message->data.byte[0] == 5) {
Vehicle_data.t_mot = temp_message->data.byte[4]; Vehicle_data.t_mot = temp_message->data.byte[4];
} }
break; break;
} }
case 0x775:{//speed }
Vehicle_data.speed_fl = 2*(temp_message->data.byte[2]); }
Vehicle_data.speed_fr = 2*(temp_message->data.byte[3]);
Vehicle_data.speed = (Vehicle_data.speed_fl+Vehicle_data.speed_fr)/2;
break; void update_LED() {
} // Copyright Michael Dietzel
/*case 0x777:{//m4_gear // m.dietzel@fasttube.de
Vehicle_data.gear = temp_message->data.byte[0]; // Edit Michael Witt 05-2015
break; // m.witt@fasttube.de
}*/
case 0x500:{ // EDIT BAHA ZARROUKI 05-2107
Vehicle_data.p_brake_front = temp_message->data.byte[1]; // z.baha@fasttube.de
Vehicle_data.p_brake_rear = temp_message->data.byte[2];
break; // alle Werte als Hex-Werte angegeben
} bool t_oil = (Vehicle_data.t_oil - 40) >= 0x96; // 150°C temp.oil
} bool t_air = (Vehicle_data.t_air - 40) >= 0x3C; // 60°C temp.llk
} bool t_mot =
((Vehicle_data.t_mot - 40) >= 0x69) and
void update_LED(){ ((Vehicle_data.t_mot - 40) != 0xC8); // 105°C temp.water und !=200
//Copyright Michael Dietzel
//m.dietzel@fasttube.de bool g_auto = Vehicle_data.drs_active;
//Edit Michael Witt 05-2015 bool u_batt = Vehicle_data.u_batt <= 0xA9; // 11.95V batt.spann.
//m.witt@fasttube.de bool e_dros = Vehicle_data.e_thro; // error-bit
//EDIT BAHA ZARROUKI 05-2107 bool rev_lim = Vehicle_data.rev_lim;
//z.baha@fasttube.de
uint16_t rev = Vehicle_data.revol;
// alle Werte als Hex-Werte angegeben //uint16_t clearcounter = 1;
bool t_oil = (Vehicle_data.t_oil - 40) >= 0x96; // 150°C temp.oil
bool t_air = (Vehicle_data.t_air - 40) >= 0x3C; // 60°C temp.llk
bool t_mot = ((Vehicle_data.t_mot - 40) >= 0x69) and ((Vehicle_data.t_mot - 40)!=0xC8); // 105°C temp.water und !=200 // if (clearcounter>= 5000){
//Can0.begin(1000000); // set CAN0 baud to 1kbit/s and don`t use enable pin!
bool g_auto = Vehicle_data.g_auto; //Can0.setNumTXBoxes(1); // reserves mailbox 0 for tx only 8 mailboxes are
bool u_batt = Vehicle_data.u_batt <= 0xB1; // 12.5V batt.spann. // available (the other 7 mailboxes are for rx)
bool e_dros = Vehicle_data.e_thro; // error-bit
// We only have 7 mailboxes, but want to receive 9 messages. This trick should
bool rev_lim = Vehicle_data.rev_lim; // allow us to receive BCU_APS_BRAKE, BCU_ETC and BCU_SHIFT_CTRL in the same
// mailbox. It will also let through 0x506, but that shouldn't be much of an
uint16_t rev = Vehicle_data.revol; // issue.
/* 10.09.2024 - auskommentiert, weil wieso hier nochmal watchfor? */
/*if(Vehicle_data.rev_lim){ Can0.watchFor(CAN_ID_BCU_APS_BRAKE & CAN_ID_BCU_ETC & CAN_ID_BCU_SHIFT_CTRL, 0x7F9);
for (int j = 0; j < 10; j++){ Can0.watchFor(CAN_ID_BCU_TIRES);
digitalWrite(leds[j], HIGH); Can0.watchFor(CAN_ID_BCU_LAP_TIME);
//analogWrite(leds[j], STW_data.br); //nur eine der zwei zeilen Can0.watchFor(CAN_ID_MS4_IGN_REV_ATH);
} Can0.watchFor(CAN_ID_MS4_SPEED);
delay(100); Can0.watchFor(CAN_ID_MS4_ETC);
for (int j = 0; j < 10; j++){ Can0.watchFor(CAN_ID_MS4_STATES_TEMP_PRESS);
digitalWrite(leds[j], LOW);
} //Can0.setGeneralCallback(Receive_Can_0);
delay(100);
}else{*/ //Timer3.attachInterrupt(Send_0x110); // set send interrupt
/*uint8_t helligkeit = 20; // Timer3.start(10000); // Calls every 10ms
if(RPM_THRES_1 <= rev){
analogWrite(led1, helligkeit); // clearcounter = 0; //clearen des display nach definierter Zeit
}else{
analogWrite(led1, 0);
} // }
if(RPM_THRES_2 <= rev){
analogWrite(led2, helligkeit); // clearcounter+=1;
}else{
analogWrite(led2, 0);
} /*if(Vehicle_data.rev_lim){
if(RPM_THRES_3 <= rev){ for (int j = 0; j < 10; j++){
analogWrite(led3, helligkeit); digitalWrite(leds[j], HIGH);
}else{ //analogWrite(leds[j], STW_data.br); //nur eine der zwei
analogWrite(led3, 0); zeilen
} }
if(RPM_THRES_4 <= rev){ delay(100);
analogWrite(led4, helligkeit); for (int j = 0; j < 10; j++){
}else{ digitalWrite(leds[j], LOW);
analogWrite(led4, 0); }
} delay(100);
if(RPM_THRES_5 <= rev){ }else{*/
analogWrite(led5, helligkeit); /*uint8_t helligkeit = 20;
}else{ if(RPM_THRES_1 <= rev){
analogWrite(led5, 0); analogWrite(led1, helligkeit);
} }else{
if(RPM_THRES_6 <= rev){ analogWrite(led1, 0);
analogWrite(led6, helligkeit); }
}else{ if(RPM_THRES_2 <= rev){
analogWrite(led6, 0); analogWrite(led2, helligkeit);
} }else{
if(RPM_THRES_7 <= rev){ analogWrite(led2, 0);
analogWrite(led7, helligkeit); }
}else{ if(RPM_THRES_3 <= rev){
analogWrite(led7, 0); analogWrite(led3, helligkeit);
} }else{
if(RPM_THRES_8 <= rev){ analogWrite(led3, 0);
analogWrite(led8, helligkeit); }
}else{ if(RPM_THRES_4 <= rev){
analogWrite(led8, 0); analogWrite(led4, helligkeit);
} }else{
if(RPM_THRES_9 <= rev){ analogWrite(led4, 0);
analogWrite(led9, helligkeit); }
}else{ if(RPM_THRES_5 <= rev){
analogWrite(led9, 0); analogWrite(led5, helligkeit);
} }else{
if(RPM_THRES_10 <= rev){ analogWrite(led5, 0);
analogWrite(led10, helligkeit); }
}else{ if(RPM_THRES_6 <= rev){
analogWrite(led10, 0); analogWrite(led6, helligkeit);
}*/ }else{
digitalWrite(led1, RPM_THRES_1 <= rev); analogWrite(led6, 0);
digitalWrite(led2, RPM_THRES_2 <= rev); }
digitalWrite(led3, RPM_THRES_3 <= rev); if(RPM_THRES_7 <= rev){
digitalWrite(led4, RPM_THRES_4 <= rev); analogWrite(led7, helligkeit);
digitalWrite(led5, RPM_THRES_5 <= rev); }else{
digitalWrite(led6, RPM_THRES_6 <= rev); analogWrite(led7, 0);
digitalWrite(led7, RPM_THRES_7 <= rev); }
digitalWrite(led8, RPM_THRES_8 <= rev); if(RPM_THRES_8 <= rev){
digitalWrite(led9, RPM_THRES_9 <= rev); analogWrite(led8, helligkeit);
digitalWrite(led10, RPM_THRES_10 <= rev); }else{
analogWrite(led8, 0);
digitalWrite(led11, t_mot); // rot, links, oben }
digitalWrite(led12, t_air); // rot, links, mitte if(RPM_THRES_9 <= rev){
digitalWrite(led13, t_oil); // rot, links, unten analogWrite(led9, helligkeit);
}else{
digitalWrite(led14, e_dros); // rot, rechts, oben analogWrite(led9, 0);
digitalWrite(led15, u_batt); // rot rechts, mitte }
digitalWrite(led16, g_auto); // blau rechts, unten if(RPM_THRES_10 <= rev){
/*if(Vehicle_data.g_auto){ analogWrite(led10, helligkeit);
digitalWrite(led16, HIGH); }else{
}else{ analogWrite(led10, 0);
digitalWrite(led16, LOW); }*/
}*/ digitalWrite(led1, RPM_THRES_1 <= rev);
} digitalWrite(led2, RPM_THRES_2 <= rev);
digitalWrite(led3, RPM_THRES_3 <= rev);
digitalWrite(led4, RPM_THRES_4 <= rev);
digitalWrite(led5, RPM_THRES_5 <= rev);
digitalWrite(led6, RPM_THRES_6 <= rev);
digitalWrite(led7, RPM_THRES_7 <= rev);
digitalWrite(led8, RPM_THRES_8 <= rev);
digitalWrite(led9, RPM_THRES_9 <= rev);
digitalWrite(led10, RPM_THRES_10 <= rev);
digitalWrite(led11, t_mot); // rot, links, oben
digitalWrite(led12, t_air); // rot, links, mitte
digitalWrite(led13, t_oil); // rot, links, unten
digitalWrite(led14, e_dros); // rot, rechts, oben
digitalWrite(led15, u_batt); // rot rechts, mitte
digitalWrite(led16, g_auto); // blau rechts, unten
/*if(Vehicle_data.g_auto){
digitalWrite(led16, HIGH);
}else{
digitalWrite(led16, LOW);
}*/
}

View File

@ -1,12 +1,24 @@
/* /*
FT_2018_STW_CAN.h FT_2018_STW_CAN.h
*/ */
#include "Arduino.h" #pragma once
#include "DueTimer.h"
#include "due_can.h" #include "Arduino.h"
#include "DueTimer.h"
void Init_Can_0(); #include "due_can.h"
void Send_0x110();
void Receive_Can_0(CAN_FRAME *frame); #define CAN_ID_BCU_APS_BRAKE 0x500
#define CAN_ID_BCU_ETC 0x502
#define CAN_ID_BCU_SHIFT_CTRL 0x504
#define CAN_ID_BCU_TIRES 0x562
#define CAN_ID_BCU_LAP_TIME 0x570
#define CAN_ID_MS4_IGN_REV_ATH 0x773
#define CAN_ID_MS4_SPEED 0x775
#define CAN_ID_MS4_ETC 0x779
#define CAN_ID_MS4_STATES_TEMP_PRESS 0x77A
void Init_Can_0();
void Send_0x110();
void Receive_Can_0(CAN_FRAME *frame);
void update_LED(void); void update_LED(void);

View File

@ -1,143 +1,137 @@
/* /*
FT_2018_STW_CAN.cpp FT_2018_STW_CAN.cpp
*/ */
#include "Arduino.h" #include "FT_2018e_STW_CAN.h"
#include "DueTimer.h" #include "Arduino.h"
#include "due_can.h" #include "DueTimer.h"
#include "FT_2018e_STW_CAN.h" #include "FT18e_STW_INIT.h"
#include "FT18e_STW_INIT.h" #include "due_can.h"
CAN_FRAME can_0_msg; CAN_FRAME can_0_msg;
//can_1_msg.id = 0x110; // can_1_msg.id = 0x110;
int can_0_temp_data = 0; int can_0_temp_data = 0;
int leds[] = {led1, led2, led3, led4, led5, led6, led7, led8, led9, led10, led11, led12, led13, led14, led15, led16}; int leds[] = {led1, led2, led3, led4, led5, led6, led7, led8,
led9, led10, led11, led12, led13, led14, led15, led16};
void Init_Can_0()
{ void Init_Can_0() {
Serial.begin(9600); Serial.begin(9600);
Can0.begin(1000000); // set CAN0 baud to 1kbit/s and don`t use enable pin! Can0.begin(1000000); // set CAN0 baud to 1kbit/s and don`t use enable pin!
Can0.setNumTXBoxes(1); // reserves mailbox 0 for tx only 8 mailboxes are available (the other 7 mailboxes are for rx) Can0.setNumTXBoxes(1); // reserves mailbox 0 for tx only 8 mailboxes are
Can0.watchFor(CAN_CELL_STATS_ID); // available (the other 7 mailboxes are for rx)
Can0.watchFor(CAN_BATTERY_STATS_ID); Can0.watchFor(CAN_CELL_STATS_ID);
Can0.watchFor(CAN_COOLING_STATS_ID); Can0.watchFor(CAN_BATTERY_STATS_ID);
Can0.watchFor(CAN_INVERTER_STATS_ID); Can0.watchFor(CAN_COOLING_STATS_ID);
Can0.setGeneralCallback(Receive_Can_0); Can0.watchFor(CAN_INVERTER_STATS_ID);
Timer3.attachInterrupt(Send_0x110); // set send interrupt Can0.setGeneralCallback(Receive_Can_0);
Timer3.start(10000); // Calls every 10ms Timer3.attachInterrupt(Send_0x110); // set send interrupt
} Timer3.start(10000); // Calls every 10ms
}
void Send_0x110()
{ void Send_0x110() {
read_buttons(); read_buttons();
read_rotary(); read_rotary();
can_0_msg.id = 0x110; can_0_msg.id = 0x110;
can_0_msg.fid = 0; can_0_msg.fid = 0;
can_0_msg.rtr = 0; can_0_msg.rtr = 0;
can_0_msg.priority = 0; can_0_msg.priority = 0;
can_0_msg.length = 2; can_0_msg.length = 2;
can_0_msg.extended = 0; can_0_msg.extended = 0;
can_0_temp_data = 0; can_0_temp_data = 0;
can_0_temp_data |= Stw_data.button_ll << 0; can_0_temp_data |= Stw_data.button_ll << 0;
can_0_temp_data |= Stw_data.button_lr << 1; can_0_temp_data |= Stw_data.button_lr << 1;
can_0_temp_data |= Stw_data.button_rl << 2; can_0_temp_data |= Stw_data.button_rl << 2;
can_0_temp_data |= Stw_data.button_rr << 3; can_0_temp_data |= Stw_data.button_rr << 3;
can_0_msg.data.byte[0] = can_0_temp_data; can_0_msg.data.byte[0] = can_0_temp_data;
can_0_msg.data.byte[1] = Stw_data.mode; can_0_msg.data.byte[1] = Stw_data.mode;
Can0.sendFrame(can_0_msg); Can0.sendFrame(can_0_msg);
} }
void Receive_Can_0(CAN_FRAME *temp_message) void Receive_Can_0(CAN_FRAME *temp_message) {
{ switch (temp_message->id) {
switch (temp_message->id) case CAN_CELL_STATS_ID:
{ process_cell_stats(temp_message);
case CAN_CELL_STATS_ID: break;
process_cell_stats(temp_message); case CAN_BATTERY_STATS_ID:
break; process_battery_stats(temp_message);
case CAN_BATTERY_STATS_ID: break;
process_battery_stats(temp_message); case CAN_COOLING_STATS_ID:
break; process_cooling_stats(temp_message);
case CAN_COOLING_STATS_ID: break;
process_cooling_stats(temp_message); case CAN_INVERTER_STATS_ID:
break; process_inverter_stats(temp_message);
case CAN_INVERTER_STATS_ID: break;
process_inverter_stats(temp_message); default:
break; // TODO: How to handle this in the car?
default: Serial.print("ERROR: Unknown CAN ID: ");
// TODO: How to handle this in the car? Serial.println(temp_message->id);
Serial.print("ERROR: Unknown CAN ID: "); }
Serial.println(temp_message->id); }
}
} void process_cell_stats(CAN_FRAME *frame) {
CellStats *data = (CellStats *)&frame->data;
void process_cell_stats(CAN_FRAME *frame) Vehicle_data.t_cell_max = data->max_cell_temp;
{ Vehicle_data.u_cell_min = data->min_cell_voltage;
CellStats *data = (CellStats *)&frame->data; }
Vehicle_data.t_cell_max = data->max_cell_temp;
Vehicle_data.u_cell_min = data->min_cell_voltage; void process_battery_stats(CAN_FRAME *frame) {
} BatteryStats *data = (BatteryStats *)&frame->data;
Vehicle_data.u_batt = data->pre_air_voltage;
void process_battery_stats(CAN_FRAME *frame) }
{
BatteryStats *data = (BatteryStats *)&frame->data; void process_cooling_stats(CAN_FRAME *frame) {
Vehicle_data.u_batt = data->pre_air_voltage; CoolingStats *data = (CoolingStats *)&frame->data;
} Vehicle_data.p_wat = data->water_pressure;
Vehicle_data.t_wat = data->water_temp;
void process_cooling_stats(CAN_FRAME *frame) Vehicle_data.t_mot_l = data->motor_l_temp;
{ Vehicle_data.t_mot_r = data->motor_r_temp;
CoolingStats *data = (CoolingStats *)&frame->data; }
Vehicle_data.p_wat = data->water_pressure;
Vehicle_data.t_wat = data->water_temp; void process_inverter_stats(CAN_FRAME *frame) {
Vehicle_data.t_mot_l = data->motor_l_temp; InverterStats *data = (InverterStats *)&frame->data;
Vehicle_data.t_mot_r = data->motor_r_temp; uint8_t status = data->status;
} Vehicle_data.inverter.ready = status & CAN_INVERTER_STATS_READY;
Vehicle_data.inverter.derating = status & CAN_INVERTER_STATS_DERATING;
void process_inverter_stats(CAN_FRAME *frame) Vehicle_data.inverter.warning = status & CAN_INVERTER_STATS_WARNING;
{ Vehicle_data.inverter.error = status & CAN_INVERTER_STATS_ERROR;
InverterStats *data = (InverterStats *)&frame->data; Vehicle_data.inverter.on = status & CAN_INVERTER_STATS_ON;
uint8_t status = data->status; Vehicle_data.inverter.precharge = status & CAN_INVERTER_STATS_PRECHARGE;
Vehicle_data.inverter.ready = status & CAN_INVERTER_STATS_READY; Vehicle_data.inverter.ams_emerg = status & CAN_INVERTER_STATS_AMS_EMERG;
Vehicle_data.inverter.derating = status & CAN_INVERTER_STATS_DERATING; Vehicle_data.inverter.ts_active = status & CAN_INVERTER_STATS_TS_ACTIVE;
Vehicle_data.inverter.warning = status & CAN_INVERTER_STATS_WARNING; Vehicle_data.t_inv = data->temp;
Vehicle_data.inverter.error = status & CAN_INVERTER_STATS_ERROR; Vehicle_data.revol = data->velocity;
Vehicle_data.inverter.on = status & CAN_INVERTER_STATS_ON; Vehicle_data.wheel_speed = data->wheel_speed;
Vehicle_data.inverter.precharge = status & CAN_INVERTER_STATS_PRECHARGE; }
Vehicle_data.inverter.ams_emerg = status & CAN_INVERTER_STATS_AMS_EMERG;
Vehicle_data.inverter.ts_active = status & CAN_INVERTER_STATS_TS_ACTIVE; void update_LED() {
Vehicle_data.t_inv = data->temp; bool t_mot = (Vehicle_data.t_mot_l > LED_THRESH_T_MOT) ||
Vehicle_data.revol = data->velocity; (Vehicle_data.t_mot_r > LED_THRESH_T_MOT);
Vehicle_data.wheel_speed = data->wheel_speed; bool t_inv = Vehicle_data.t_inv > LED_THRESH_T_INV;
} bool t_bat = Vehicle_data.t_cell_max > LED_THRESH_T_BAT;
void update_LED() bool precharge_active = !Vehicle_data.inverter.precharge;
{ bool derating = Vehicle_data.inverter.derating;
bool t_mot = (Vehicle_data.t_mot_l > LED_THRESH_T_MOT) || (Vehicle_data.t_mot_r > LED_THRESH_T_MOT); bool u_batt = Vehicle_data.u_cell_min < LED_THRESH_U_BATT;
bool t_inv = Vehicle_data.t_inv > LED_THRESH_T_INV;
bool t_bat = Vehicle_data.t_cell_max > LED_THRESH_T_BAT; digitalWrite(led11, t_mot); // rot, links, oben
digitalWrite(led12, t_inv); // rot, links, mitte
bool precharge_active = !Vehicle_data.inverter.precharge; digitalWrite(led13, t_bat); // rot, links, unten
bool derating = Vehicle_data.inverter.derating;
bool u_batt = Vehicle_data.u_cell_min < LED_THRESH_U_BATT; digitalWrite(led14, precharge_active); // rot, rechts, oben
digitalWrite(led15, derating); // rot rechts, mitte
digitalWrite(led11, t_mot); // rot, links, oben digitalWrite(led16, u_batt); // blau rechts, unten
digitalWrite(led12, t_inv); // rot, links, mitte
digitalWrite(led13, t_bat); // rot, links, unten bool rev_lim = Vehicle_data.rev_lim;
digitalWrite(led14, precharge_active); // rot, rechts, oben int16_t rev = Vehicle_data.revol;
digitalWrite(led15, derating); // rot rechts, mitte digitalWrite(led1, RPM_THRESH_1 <= rev);
digitalWrite(led16, u_batt); // blau rechts, unten digitalWrite(led2, RPM_THRESH_2 <= rev);
digitalWrite(led3, RPM_THRESH_3 <= rev);
bool rev_lim = Vehicle_data.rev_lim; digitalWrite(led4, RPM_THRESH_4 <= rev);
digitalWrite(led5, RPM_THRESH_5 <= rev);
int16_t rev = Vehicle_data.revol; digitalWrite(led6, RPM_THRESH_6 <= rev);
digitalWrite(led1, RPM_THRESH_1 <= rev); digitalWrite(led7, RPM_THRESH_7 <= rev);
digitalWrite(led2, RPM_THRESH_2 <= rev); digitalWrite(led8, RPM_THRESH_8 <= rev);
digitalWrite(led3, RPM_THRESH_3 <= rev); digitalWrite(led9, RPM_THRESH_9 <= rev);
digitalWrite(led4, RPM_THRESH_4 <= rev); digitalWrite(led10, RPM_THRESH_10 <= rev);
digitalWrite(led5, RPM_THRESH_5 <= rev); }
digitalWrite(led6, RPM_THRESH_6 <= rev);
digitalWrite(led7, RPM_THRESH_7 <= rev);
digitalWrite(led8, RPM_THRESH_8 <= rev);
digitalWrite(led9, RPM_THRESH_9 <= rev);
digitalWrite(led10, RPM_THRESH_10 <= rev);
}

View File

@ -1,65 +1,61 @@
/* /*
FT_2018e_STW_CAN.h FT_2018e_STW_CAN.h
*/ */
#pragma once #pragma once
#include "Arduino.h" #include "Arduino.h"
#include "DueTimer.h" #include "DueTimer.h"
#include "due_can.h" #include "due_can.h"
constexpr uint32_t CAN_CELL_STATS_ID = 0x101; constexpr uint32_t CAN_CELL_STATS_ID = 0x101;
constexpr uint32_t CAN_BATTERY_STATS_ID = 0x102; constexpr uint32_t CAN_BATTERY_STATS_ID = 0x102;
constexpr uint32_t CAN_COOLING_STATS_ID = 0x103; constexpr uint32_t CAN_COOLING_STATS_ID = 0x103;
constexpr uint32_t CAN_INVERTER_STATS_ID = 0x104; constexpr uint32_t CAN_INVERTER_STATS_ID = 0x104;
constexpr uint8_t CAN_INVERTER_STATS_READY = (1 << 0); constexpr uint8_t CAN_INVERTER_STATS_READY = (1 << 0);
constexpr uint8_t CAN_INVERTER_STATS_DERATING = (1 << 1); constexpr uint8_t CAN_INVERTER_STATS_DERATING = (1 << 1);
constexpr uint8_t CAN_INVERTER_STATS_WARNING = (1 << 2); constexpr uint8_t CAN_INVERTER_STATS_WARNING = (1 << 2);
constexpr uint8_t CAN_INVERTER_STATS_ERROR = (1 << 3); constexpr uint8_t CAN_INVERTER_STATS_ERROR = (1 << 3);
constexpr uint8_t CAN_INVERTER_STATS_ON = (1 << 4); constexpr uint8_t CAN_INVERTER_STATS_ON = (1 << 4);
constexpr uint8_t CAN_INVERTER_STATS_PRECHARGE = (1 << 5); constexpr uint8_t CAN_INVERTER_STATS_PRECHARGE = (1 << 5);
constexpr uint8_t CAN_INVERTER_STATS_AMS_EMERG = (1 << 6); constexpr uint8_t CAN_INVERTER_STATS_AMS_EMERG = (1 << 6);
constexpr uint8_t CAN_INVERTER_STATS_TS_ACTIVE = (1 << 7); constexpr uint8_t CAN_INVERTER_STATS_TS_ACTIVE = (1 << 7);
void Init_Can_0(); void Init_Can_0();
void Send_0x110(); void Send_0x110();
void Receive_Can_0(CAN_FRAME *frame); void Receive_Can_0(CAN_FRAME *frame);
void process_cell_stats(CAN_FRAME *frame); void process_cell_stats(CAN_FRAME *frame);
void process_battery_stats(CAN_FRAME *frame); void process_battery_stats(CAN_FRAME *frame);
void process_cooling_stats(CAN_FRAME *frame); void process_cooling_stats(CAN_FRAME *frame);
void process_inverter_stats(CAN_FRAME *frame); void process_inverter_stats(CAN_FRAME *frame);
void update_LED(void); void update_LED(void);
struct CellStats struct CellStats {
{ uint16_t sum_cell_voltage;
uint16_t sum_cell_voltage; int16_t max_cell_temp;
int16_t max_cell_temp; uint16_t max_cell_voltage;
uint16_t max_cell_voltage; uint16_t min_cell_voltage;
uint16_t min_cell_voltage; };
};
struct BatteryStats {
struct BatteryStats uint16_t battery_current;
{ uint16_t pre_air_voltage;
uint16_t battery_current; uint16_t post_air_voltage;
uint16_t pre_air_voltage; uint16_t battery_power;
uint16_t post_air_voltage; };
uint16_t battery_power;
}; struct CoolingStats {
int16_t water_pressure;
struct CoolingStats int16_t water_temp;
{ int16_t motor_l_temp;
int16_t water_pressure; int16_t motor_r_temp;
int16_t water_temp; };
int16_t motor_l_temp;
int16_t motor_r_temp; struct InverterStats {
}; uint8_t status;
uint8_t _reserved;
struct InverterStats uint16_t temp;
{ int16_t velocity;
uint8_t status; int16_t wheel_speed;
uint8_t _reserved;
uint16_t temp;
int16_t velocity;
int16_t wheel_speed;
}; };

File diff suppressed because it is too large Load Diff

View File

@ -26,17 +26,18 @@
#include "Arduino.h" #include "Arduino.h"
//Devices // Devices
#define EDIP128 1 #define EDIP128 1
#define EDIP160 1 #define EDIP160 1
#define EDIP240 1 #define EDIP240 1
#define EDIP320 2 #define EDIP320 2
//Set your device // Set your device
#define DEVICE EDIP320 #define DEVICE EDIP320
#define COORD_SIZE DEVICE //Byte count for coordinates #define COORD_SIZE DEVICE // Byte count for coordinates
#define SERIAL_DEV Serial3 #define SERIAL_DEV Serial3
#define EA_TRANSPARENT 0
#define EA_BLACK 1 #define EA_BLACK 1
#define EA_BLUE 2 #define EA_BLUE 2
#define EA_RED 3 #define EA_RED 3
@ -71,364 +72,384 @@
#define uint unsigned int #define uint unsigned int
class EDIPTFT { class EDIPTFT {
public: public:
EDIPTFT(boolean smallprotocol=true, boolean disconnected=false); EDIPTFT(boolean smallprotocol = true, boolean disconnected = false);
boolean disconnected; boolean disconnected;
void begin(long baud=115200); void begin(long baud = 115200);
// helper functions // helper functions
char readByte(); char readByte();
char waitandreadByte(); char waitandreadByte();
unsigned char datainBuffer(); unsigned char datainBuffer();
int readBuffer(char* data); int readBuffer(char* data);
void smallProtoSelect(char address); void smallProtoSelect(char address);
void smallProtoDeselect(char address); void smallProtoDeselect(char address);
void sendData(char* data, char len); void sendData(char* data, char len);
// Basic display functions // Basic display functions
/*! \brief Clear display /*! \brief Clear display
* *
* Clear display contents (all pixels off) and remove touch areas * Clear display contents (all pixels off) and remove touch areas
*/ */
void clear(); void clear();
/*! \brief Delete display /*! \brief Delete display
* *
* Delete display contents (all pixels off). Touch areas are still active. * Delete display contents (all pixels off). Touch areas are still active.
*/ */
void deleteDisplay(); void deleteDisplay();
/*! \brief Invert display /*! \brief Invert display
* *
* Invert display contents (invert all pixels) * Invert display contents (invert all pixels)
*/ */
void invert(); void invert();
void setDisplayColor(char fg, char bg); void setDisplayColor(char fg, char bg);
void fillDisplayColor(char bg); void fillDisplayColor(char bg);
/*! \brief Terminal on /*! \brief Terminal on
* *
* Terminal display is switched on if \a on is true * Terminal display is switched on if \a on is true
* *
* \param on determine if terminal is switched on * \param on determine if terminal is switched on
*/ */
void terminalOn(boolean on); void terminalOn(boolean on);
/*! \brief Load internal image /*! \brief Load internal image
* *
* Load internal image with the \a nr (0..255) from the *EEPROM* memory to * Load internal image with the \a nr (0..255) from the *EEPROM* memory to
* \a x1, \a y1 * \a x1, \a y1
* *
* \param x1 x position of image on the display * \param x1 x position of image on the display
* \param y1 y position of image on the display * \param y1 y position of image on the display
* \param nr number of the image on the *EEPROM* * \param nr number of the image on the *EEPROM*
*/ */
void loadImage(int x1, int y1, int nr); void loadImage(int x1, int y1, int nr);
/*! \brief Cursor on/off /*! \brief Cursor on/off
* *
* Switch cursor on/off * Switch cursor on/off
* *
* \param on `n1=0`: cursor is invisible, `n1=1`: cursor flashes * \param on `n1=0`: cursor is invisible, `n1=1`: cursor flashes
*/ */
void cursorOn(boolean on); void cursorOn(boolean on);
/*! \brief Position cursor /*! \brief Position cursor
* *
* origin upper-left corner `(1, 1)` * origin upper-left corner `(1, 1)`
* *
* \param col new cursor column * \param col new cursor column
* \param row new cursor row * \param row new cursor row
*/ */
void setCursor(char col, char row); void setCursor(char col, char row);
void displayLight(char no); void displayLight(char no);
// Bargraph // Bargraph
/*! \brief Define bargraph /*! \brief Define bargraph
* *
* Define bargraph to form the rectangle enclosing the * Define bargraph to form the rectangle enclosing the
* bargraph. \a sv and \a ev are the values for `0%` and `100%`. * bargraph. \a sv and \a ev are the values for `0%` and `100%`.
* *
* \param dir direction ('L'eft, 'R'ight, 'O'up, 'U'down) * \param dir direction ('L'eft, 'R'ight, 'O'up, 'U'down)
* \param no bargraph number `1..32` * \param no bargraph number `1..32`
* \param x1 upper left x coordinate * \param x1 upper left x coordinate
* \param y1 upper left y coordinate * \param y1 upper left y coordinate
* \param x2 lower right x coordinate * \param x2 lower right x coordinate
* \param y2 lower right y coordinate * \param y2 lower right y coordinate
* \param sv start value (0%) * \param sv start value (0%)
* \param ev end value (100%) * \param ev end value (100%)
* \param type set the style of the bargraph:\n * \param type set the style of the bargraph:\n
* `type=0`: pattern bar, \a mst=bar pattern,\n * `type=0`: pattern bar, \a mst=bar pattern,\n
* `type=1`: pattern bar in rectangle, \a mst=bar pattern,\n * `type=1`: pattern bar in rectangle, \a mst=bar pattern,\n
* `type=2`: pattern line, \a mst=line width,\n * `type=2`: pattern line, \a mst=line width,\n
* `type=3`: pattern line in rectangle, \a mst=line width * `type=3`: pattern line in rectangle, \a mst=line width
* *
* \param mst additional parameter for type specification * \param mst additional parameter for type specification
*/ */
void defineBargraph(char dir, char no, int x1, int y1, int x2, int y2, void defineBargraph(char dir, char no, int x1, int y1, int x2, int y2,
byte sv, byte ev, char type, char mst); byte sv, byte ev, char type, char mst);
/*! \brief Update bargraph /*! \brief Update bargraph
* *
* Set and draw the bargraph *no* to the new *value* * Set and draw the bargraph *no* to the new *value*
* *
* \param no number of the bargraph `1..32` * \param no number of the bargraph `1..32`
* \param val new value of the bargraph * \param val new value of the bargraph
*/ */
void updateBargraph(char no, char val); void updateBargraph(char no, char val);
void setBargraphColor(char no, char fg, char bg, char fr); void setBargraphColor(char no, char fg, char bg, char fr);
/*! \brief Set bargraph by touch /*! \brief Set bargraph by touch
* *
* The bargraph with number *no* is defined for input by touch panel * The bargraph with number *no* is defined for input by touch panel
* *
* \param no number of the bargraph `1..32` * \param no number of the bargraph `1..32`
*/ */
void makeBargraphTouch(char no); void makeBargraphTouch(char no);
void linkBargraphLight(char no); void linkBargraphLight(char no);
/*! \brief Delete bargraph /*! \brief Delete bargraph
* *
* The definition of the bargraph with number *no* becomes invalid. If the * The definition of the bargraph with number *no* becomes invalid. If the
* bargraph was defined as input with touch, the touchfield will also be * bargraph was defined as input with touch, the touchfield will also be
* deleted. * deleted.
* *
* \param no number of the bargraph `1..32` * \param no number of the bargraph `1..32`
* \param n1 additional parameter\n * \param n1 additional parameter\n
* `n1=0`: bargraph remains visible\n * `n1=0`: bargraph remains visible\n
* `n1=1`: bargraph is deleted * `n1=1`: bargraph is deleted
*/ */
void deleteBargraph(char no, char n1); void deleteBargraph(char no, char n1);
// Instrument // Instrument
void defineInstrument(char no, int x1, int y1, char image, void defineInstrument(char no, int x1, int y1, char image, char angle,
char angle, char sv, char ev); char sv, char ev);
void updateInstrument(char no, char val); void updateInstrument(char no, char val);
void redrawInstrument(char no); void redrawInstrument(char no);
void deleteInstrument(char no, char n1, char n2); void deleteInstrument(char no, char n1, char n2);
// Text // Text
void setTextColor(char fg, char bg); void setTextColor(char fg, char bg);
/*! \brief Set font /*! \brief Set font
* *
* Set font with the number *font* * Set font with the number *font*
* *
* \param font font number `font=0..15`, use font defines here * \param font font number `font=0..15`, use font defines here
*/ */
void setTextFont(char font); void setTextFont(char font);
void setTextSize(int xsize, int ysize);
/*! \brief Set text angle void setTextSize(int xsize, int ysize);
*
* Set text output angle
*
* \param angle text output angle\n
`angle=0`: 0°
`angle=1`: 90°
*/
void setTextAngle(char angle);
/*! \brief Draw text on display /*! \brief Set text angle
* *
* Draw a *text* on screen. Several lines are separated by the character `|` * Set text output angle
* ($7C). *
* * place text between `~`: characters flash on/off * \param angle text output angle\n
* * place text between `@`: characters flash inversely `angle=0`: 0°
* * use `\\` as to escape special characters `angle=1`: 90°
* */
* \param x1: x coordinate void setTextAngle(char angle);
* \param y1: y coordinate
* \param justification set text justification to `L`(eft), `R`(ight),
* `C`(enter)
* \param text text to draw on display
*/
void drawText(uint16_t x1, uint16_t y1, char justification, const char* text);
// Rectangle and Line /*! \brief Draw text on display
void setLineColor(char fg, char bg); *
* Draw a *text* on screen. Several lines are separated by the character `|`
* ($7C).
* * place text between `~`: characters flash on/off
* * place text between `@`: characters flash inversely
* * use `\\` as to escape special characters
*
* \param x1: x coordinate
* \param y1: y coordinate
* \param justification set text justification to `L`(eft), `R`(ight),
* `C`(enter)
* \param text text to draw on display
*/
void drawText(uint16_t x1, uint16_t y1, char justification, const char* text);
/*! \brief Point size/line thickness /*! \brief Draw text on display in an area
* *
* \param x x-point size (1..15) * Draw a *text* on screen. Several lines are separated by the character `|`
* \param y y-point size (1..15) * ($7C).
*/ * * place text between `~`: characters flash on/off
void setLineThick(char x, char y); * * place text between `@`: characters flash inversely
* * use `\\` as to escape special characters
*
* \param align set alignment in the rectangle. 1 = top left, 2 = top
* center, 3 = top right, 4 = center left, 5 = center, 6 = center right, 7 =
* bottom left, 8 = bottom center, 9 = bottom right.
* \param text text to draw on display
*/
void drawTextInRect(int x1, int y1, int x2, int y2, uint8_t align,
const char* text);
/*! \brief Draw straight line // Rectangle and Line
* void setLineColor(char fg, char bg);
* Draw straight line from point *x1*, *y1* to point *x2*, *y2*
*/
void drawLine(int x1, int y1, int x2, int y2);
/*! \brief Draw rectangle /*! \brief Point size/line thickness
* *
* Draw four straight lines as a rectangle from *x1*, *y1* to *x2*, *y2* * \param x x-point size (1..15)
*/ * \param y y-point size (1..15)
void drawRect(int x1, int y1, int x2, int y2); */
void setLineThick(char x, char y);
void drawRectf(int x1, int y1, int x2, int y2, char color); /*! \brief Draw straight line
*
* Draw straight line from point *x1*, *y1* to point *x2*, *y2*
*/
void drawLine(int x1, int y1, int x2, int y2);
// Touch keys /*! \brief Draw rectangle
*
* Draw four straight lines as a rectangle from *x1*, *y1* to *x2*, *y2*
*/
void drawRect(int x1, int y1, int x2, int y2);
/*! \brief Define touch key void drawRectf(int x1, int y1, int x2, int y2, char color);
*
* Key remains pressed as long as there is contact. The area from *x1*, *y1*
* to *x2*, *y2* is drawn with actual border and defined as a key.
* The label is drawn with the current touch font. The first character
* determines the alignment of the text (`L`(eft), `R`(ight), `C`(enter)).
* Multiline texts are separated by the character `|`.
*
* \param down return/touchmacro (1-255) if pressed
* \param up return/touchmacro (1-255) if released
* \param text label of the touch key
*/
void defineTouchKey(int x1, int y1, int x2, int y2,
char down, char up, const char* text);
/*! \brief Define touch switch /*! \brief Clear rectangular area */
* void clearRect(int x1, int y1, int x2, int y2);
* Status of the switch toggles after each contact. The area from *x1*, *y1*
* to *x2*, *y2* is drawn with actual border and defined as a key.
* The label is drawn with the current touch font. The first character
* determines the alignment of the text (`L`(eft), `R`(ight), `C`(enter)).
* Multiline texts are separated by the character `|`.
*
* \param down return/touchmacro (1-255) if pressed
* \param up return/touchmacro (1-255) if released
* \param text label of the touch key
*/
void defineTouchSwitch(int x1, int y1, int x2, int y2,
char down, char up, const char* text);
/*! \brief Define touch switch with image // Touch keys
*
* Status of the switch toggles after each contact. Image number *img* is
* loaded to *x*, *y* and defined as a switch.
* The label is drawn with the current touch font. The first character
* determines the alignment of the text (`L`(eft), `R`(ight), `C`(enter)).
* Multiline texts are separated by the character `|`.
*
* \param down return/touchmacro (1-255) if pressed
* \param up return/touchmacro (1-255) if released
* \param text label of the touch switch
*/
void defineTouchSwitch(int x, int y, int img, char downcode,
char upcode, const char* text);
/*! \brief Set touch switch /*! \brief Define touch key
* *
* Set the status of the touch switch with the return code *code* * Key remains pressed as long as there is contact. The area from *x1*, *y1*
* to *value*. * to *x2*, *y2* is drawn with actual border and defined as a key.
* * The label is drawn with the current touch font. The first character
* \param code Return code of the switch * determines the alignment of the text (`L`(eft), `R`(ight), `C`(enter)).
* \param value `value=0`: OFF, `value=1`: ON * Multiline texts are separated by the character `|`.
*/ *
void setTouchSwitch(char code,char value); * \param down return/touchmacro (1-255) if pressed
* \param up return/touchmacro (1-255) if released
* \param text label of the touch key
*/
void defineTouchKey(int x1, int y1, int x2, int y2, char down, char up,
const char* text);
void setTouchkeyColors(char n1, char n2, char n3, /*! \brief Define touch switch
char s1, char s2, char s3); *
* Status of the switch toggles after each contact. The area from *x1*, *y1*
* to *x2*, *y2* is drawn with actual border and defined as a key.
* The label is drawn with the current touch font. The first character
* determines the alignment of the text (`L`(eft), `R`(ight), `C`(enter)).
* Multiline texts are separated by the character `|`.
*
* \param down return/touchmacro (1-255) if pressed
* \param up return/touchmacro (1-255) if released
* \param text label of the touch key
*/
void defineTouchSwitch(int x1, int y1, int x2, int y2, char down, char up,
const char* text);
/*! \brief Label font /*! \brief Define touch switch with image
* *
* Apply font with number *font* for touch key labels * Status of the switch toggles after each contact. Image number *img* is
*/ * loaded to *x*, *y* and defined as a switch.
void setTouchkeyFont(char font); * The label is drawn with the current touch font. The first character
* determines the alignment of the text (`L`(eft), `R`(ight), `C`(enter)).
* Multiline texts are separated by the character `|`.
*
* \param down return/touchmacro (1-255) if pressed
* \param up return/touchmacro (1-255) if released
* \param text label of the touch switch
*/
void defineTouchSwitch(int x, int y, int img, char downcode, char upcode,
const char* text);
void setTouchkeyLabelColors(char nf,char sf); /*! \brief Set touch switch
*
* Set the status of the touch switch with the return code *code*
* to *value*.
*
* \param code Return code of the switch
* \param value `value=0`: OFF, `value=1`: ON
*/
void setTouchSwitch(char code, char value);
/*! \brief Radio group for switches void setTouchkeyColors(char n1, char n2, char n3, char s1, char s2, char s3);
*
* `group=0`: newly defined switches don't belong to a group
* `group=1..255`: newly defined switches are assigned to the group with
* the given number
* Only one switch in a group is active at once. All others are deactivated.
* For switches only the *down code* is applicable. The *up code* will be
* ignored.
*/
void setTouchGroup(char group);
/*! \brief Delete toch area by up- or downcode /*! \brief Label font
* *
* The touch area with the return code is removed from the touch query * Apply font with number *font* for touch key labels
* */
* \param code the code of the touch area (code=0: all touch areas) void setTouchkeyFont(char font);
* \param n1 n1==0: the area remains visible on the display,
* n1==1: the area is deleted
*/
void removeTouchArea(char code,char n1);
// Macro Calls void setTouchkeyLabelColors(char nf, char sf);
/*! \brief Run macro
*
* Call the (normal) macro with number *nr* (max. 7 levels).
*/
void callMacro(uint nr);
/*! \brief Run touch macro /*! \brief Radio group for switches
* *
* Call touch macro with number *nr* (max. 7 levels) * `group=0`: newly defined switches don't belong to a group
*/ * `group=1..255`: newly defined switches are assigned to the group with
void callTouchMacro(uint nr); * the given number
* Only one switch in a group is active at once. All others are deactivated.
* For switches only the *down code* is applicable. The *up code* will be
* ignored.
*/
void setTouchGroup(char group);
/*! \brief Run menu macro /*! \brief Delete toch area by up- or downcode
* *
* Call menu macro with number *nr* (max. 7 levels) * The touch area with the return code is removed from the touch query
*/ *
void callMenuMacro(uint nr); * \param code the code of the touch area (code=0: all touch areas)
* \param n1 n1==0: the area remains visible on the display,
* n1==1: the area is deleted
*/
void removeTouchArea(char code, char n1);
/*! \brief Define touch key with menu function // Macro Calls
* /*! \brief Run macro
* Define the area from *x1*, *y1* to *x2*, *y2* as a menu key. *
* The first character determines the direction in which the menu opens (R=right,L=left,O=up,U=down) * Call the (normal) macro with number *nr* (max. 7 levels).
* The second character determines the alignment of the touch text (C=center,L=left-,R=right justified) */
* The menu items are separated by the character '|' ($7C,dec:124) (e.g. "UCkey|item1|item2|item3". void callMacro(uint nr);
* The key text is written with the current touch font and the menu items are written with the current menu font. The background of the menu is saved automatically.
* \param downcode `1-255` return/touchmacro if pressed
* \param upcode `1-255` return/touchmacro if released
* \param mnucode return/menumacro+(item nr - 1) after selection of a
* menu item
* \param text string with the key text and menu items
*/
void defineTouchMenu(int x1, int y1, int x2, int y2,
char downcode, char upcode, char mnucode,
const char *text);
/*! \brief Send *open* signal after a Menu open request has been sent from TFT. /*! \brief Run touch macro
* *
* If a touch menu is not set to open automatically the TFT sends a * Call touch macro with number *nr* (max. 7 levels)
* request 'ESC T 0'. This function sends 'ESC N T 2' to open the menu. */
*/ void callTouchMacro(uint nr);
void openTouchMenu();
/*! \brief Set menu font /*! \brief Run menu macro
* *
* Set font with number *font* (`0..15`) for menu display * Call menu macro with number *nr* (max. 7 levels)
*/ */
void setMenuFont(char font); void callMenuMacro(uint nr);
/*! \brief enable/disable touchmenu automation /*! \brief Define touch key with menu function
* *
* if val==true touch menu opens automatically, if val==false touchmenu * Define the area from *x1*, *y1* to *x2*, *y2* as a menu key.
* doesn' t open automatically, instead a request is sent to the * The first character determines the direction in which the menu opens
* host computer, which can then open the menu with openTouchMenu() * (R=right,L=left,O=up,U=down) The second character determines the alignment
*/ * of the touch text (C=center,L=left-,R=right justified) The menu items are
void setTouchMenuAutomation(bool val); * separated by the character '|' ($7C,dec:124) (e.g.
* "UCkey|item1|item2|item3". The key text is written with the current touch
* font and the menu items are written with the current menu font. The
* background of the menu is saved automatically. \param downcode `1-255`
* return/touchmacro if pressed \param upcode `1-255` return/touchmacro if
* released \param mnucode return/menumacro+(item nr - 1) after selection of a
* menu item
* \param text string with the key text and menu items
*/
void defineTouchMenu(int x1, int y1, int x2, int y2, char downcode,
char upcode, char mnucode, const char* text);
private: /*! \brief Send *open* signal after a Menu open request has been sent from
boolean _smallprotocol; * TFT.
int _counter; *
unsigned char bytesAvailable(); * If a touch menu is not set to open automatically the TFT sends a
void waitBytesAvailable(); * request 'ESC T 0'. This function sends 'ESC N T 2' to open the menu.
void sendByte(char data); */
void sendSmall(char* data, char len); void openTouchMenu();
void sendSmallDC2(char* data, char len);
/*! \brief Set menu font
*
* Set font with number *font* (`0..15`) for menu display
*/
void setMenuFont(char font);
/*! \brief enable/disable touchmenu automation
*
* if val==true touch menu opens automatically, if val==false touchmenu
* doesn' t open automatically, instead a request is sent to the
* host computer, which can then open the menu with openTouchMenu()
*/
void setTouchMenuAutomation(bool val);
private:
boolean _smallprotocol;
int _counter;
unsigned char bytesAvailable();
void waitBytesAvailable();
void sendByte(char data);
void sendSmall(char* data, char len);
void sendSmallDC2(char* data, char len);
}; };
#endif #endif