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
This commit is contained in:
Jasper Blanckenburg 2022-03-13 20:30:14 +01:00
parent 14b5f6988d
commit 41d3bd907e
16 changed files with 2336 additions and 2319 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

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,412 +1,441 @@
#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); EDIPTFT tft(true, false);
String bezeichnungen[]={"T_mot","T_oil","P_oil","% fa","U_batt","P_wat","T_air", String bezeichnungen[] = {"T_mot", "T_oil", "P_oil", "% fa",
"P_b_front","P_b_rear","Error Type","Speed_fl","Speed_fr","Speed"}; "U_batt", "P_wat", "T_air", "P_b_front",
//"Drehzahl","P_fuel","Index" "P_b_rear", "Error Type", "Speed_fl", "Speed_fr",
int led_s[] = {led1,led2,led3,led4,led5,led6,led7,led8,led9,led10,led11,led12,led13,led14,led15,led16}; "Speed"};
//"Drehzahl","P_fuel","Index"
DataBox gear_box(121, 0, 199, 94, 160, 0, EA_SWISS30B, 4, 4, 'C'); int led_s[] = {led1, led2, led3, led4, led5, led6, led7, led8,
DataBox left_box(0, 0, 119, 94, 110, 12, EA_FONT7X12, 3, 8, 'R'); led9, led10, led11, led12, led13, led14, led15, led16};
DataBox right_box(201, 0, 320, 94, 310, 12, EA_FONT7X12, 3, 8, 'R');
TireTempBox fl_box(80, 130, 156, 176, 118, 124, EA_FONT7X12, 3, 5, 'C'); DataBox gear_box(121, 0, 199, 94, 160, 0, EA_SWISS30B, 4, 4, 'C');
TireTempBox fr_box(164, 130, 240, 176, 202, 124, EA_FONT7X12, 3, 5, 'C'); DataBox left_box(0, 0, 119, 94, 110, 12, EA_FONT7X12, 3, 8, 'R');
TireTempBox rl_box(80, 184, 156, 230, 118, 178, EA_FONT7X12, 3, 5, 'C'); DataBox right_box(201, 0, 320, 94, 310, 12, EA_FONT7X12, 3, 8, 'R');
TireTempBox rr_box(164, 184, 240, 230, 202, 178, EA_FONT7X12, 3, 5, 'C'); TireTempBox fl_box(80, 130, 156, 176, 118, 124, EA_FONT7X12, 3, 5, 'C');
TireTempBox fr_box(164, 130, 240, 176, 202, 124, EA_FONT7X12, 3, 5, 'C');
void init_display() { TireTempBox rl_box(80, 184, 156, 230, 118, 178, EA_FONT7X12, 3, 5, 'C');
pinMode(writeprotect, OUTPUT); TireTempBox rr_box(164, 184, 240, 230, 202, 178, EA_FONT7X12, 3, 5, 'C');
digitalWrite(writeprotect, HIGH);
pinMode(reset, OUTPUT); void init_display() {
pinMode(disp_cs, OUTPUT); pinMode(writeprotect, OUTPUT);
pinMode(MOSI, OUTPUT); digitalWrite(writeprotect, HIGH);
pinMode(MISO, OUTPUT); pinMode(reset, OUTPUT);
digitalWrite(disp_cs, HIGH); pinMode(disp_cs, OUTPUT);
digitalWrite(MOSI, HIGH); pinMode(MOSI, OUTPUT);
digitalWrite(MISO, HIGH); pinMode(MISO, OUTPUT);
digitalWrite(reset, LOW); digitalWrite(disp_cs, HIGH);
digitalWrite(reset,HIGH); digitalWrite(MOSI, HIGH);
tft.begin(115200); // start display communication digitalWrite(MISO, HIGH);
tft.cursorOn(false); digitalWrite(reset, LOW);
tft.terminalOn(false); digitalWrite(reset, HIGH);
tft.setDisplayColor(EA_WHITE,EA_BLACK); tft.begin(115200); // start display communication
tft.setTextColor(EA_WHITE,EA_TRANSPARENT); tft.cursorOn(false);
tft.setTextSize(5,8); tft.terminalOn(false);
tft.clear(); tft.setDisplayColor(EA_WHITE, EA_BLACK);
tft.setTextColor(EA_WHITE, EA_TRANSPARENT);
gear_box.update_label(get_label(VAL_GEAR)); tft.setTextSize(5, 8);
left_box.update_label(get_label(VAL_FIRST_LEFT_BOX)); tft.clear();
right_box.update_label(get_label(VAL_RPM));
} gear_box.update_label(get_label(VAL_GEAR));
left_box.update_label(get_label(VAL_FIRST_LEFT_BOX));
String get_value(Value val) { right_box.update_label(get_label(VAL_RPM));
switch (val) { }
case VAL_GEAR:
if (Vehicle_data.gear == 0) { String get_value(Value val) {
return "N"; switch (val) {
} case VAL_GEAR:
return String(Vehicle_data.gear); if (Vehicle_data.gear == 0) {
case VAL_RPM: return "N";
return String(Vehicle_data.revol); }
case VAL_TT_FL: return String(Vehicle_data.gear);
return "00"; case VAL_RPM:
case VAL_TT_FR: return String(Vehicle_data.revol);
return "01"; case VAL_TT_FL:
case VAL_TT_RL: return "00";
return "10"; case VAL_TT_FR:
case VAL_TT_RR: return "01";
return "11"; case VAL_TT_RL:
case VAL_LAPTIME: return "10";
return "93.13"; case VAL_TT_RR:
case VAL_UBATT: return "11";
return String(0.0706949 * Vehicle_data.u_batt, 2); case VAL_LAPTIME:
case VAL_TMOT: return "93.13";
return String(Vehicle_data.t_mot - 40); case VAL_UBATT:
case VAL_TAIR: return String(0.0706949 * Vehicle_data.u_batt, 2);
return String(Vehicle_data.t_air - 40); case VAL_TMOT:
case VAL_TOIL: return String(Vehicle_data.t_mot - 40);
return String(Vehicle_data.t_oil - 40); case VAL_TAIR:
case VAL_ERR_TYPE: return String(Vehicle_data.t_air - 40);
return String(Stw_data.error_type); case VAL_TOIL:
case VAL_PWAT: return String(Vehicle_data.t_oil - 40);
return String(0.0514*Vehicle_data.p_wat, 2); case VAL_ERR_TYPE:
case VAL_POIL: return String(Stw_data.error_type);
return String(0.0514*Vehicle_data.p_oil, 2); case VAL_PWAT:
case VAL_PBF: return String(0.0514 * Vehicle_data.p_wat, 2);
return String(Vehicle_data.p_brake_front); case VAL_POIL:
case VAL_PBR: return String(0.0514 * Vehicle_data.p_oil, 2);
return String(Vehicle_data.p_brake_rear); case VAL_PBF:
case VAL_SPEED_FL: return String(Vehicle_data.p_brake_front);
return String(Vehicle_data.speed_fl); case VAL_PBR:
case VAL_SPEED_FR: return String(Vehicle_data.p_brake_rear);
return String(Vehicle_data.speed_fr); case VAL_SPEED_FL:
case VAL_SPEED: return String(Vehicle_data.speed_fl);
return String(Vehicle_data.speed); case VAL_SPEED_FR:
default: return String(Vehicle_data.speed_fr);
return "???"; case VAL_SPEED:
} return String(Vehicle_data.speed);
} default:
return "???";
String get_label(Value val) { }
switch (val) { }
case VAL_GEAR:
return "GEAR"; String get_label(Value val) {
case VAL_RPM: switch (val) {
return "RPM"; case VAL_GEAR:
case VAL_TT_FL: return "GEAR";
return "TEMP FL"; case VAL_RPM:
case VAL_TT_FR: return "RPM";
return "TEMP FR"; case VAL_TT_FL:
case VAL_TT_RL: return "TEMP FL";
return "TEMP RL"; case VAL_TT_FR:
case VAL_TT_RR: return "TEMP FR";
return "TEMP RR"; case VAL_TT_RL:
case VAL_LAPTIME: return "TEMP RL";
return "LAPTIME"; case VAL_TT_RR:
case VAL_UBATT: return "TEMP RR";
return "BATT VOLTAGE"; case VAL_LAPTIME:
case VAL_TMOT: return "LAPTIME";
return "TEMP ENG"; case VAL_UBATT:
case VAL_TAIR: return "BATT VOLTAGE";
return "TEMP AIR"; case VAL_TMOT:
case VAL_TOIL: return "TEMP ENG";
return "TEMP OIL"; case VAL_TAIR:
case VAL_ERR_TYPE: return "TEMP AIR";
return "ERROR TYPE"; case VAL_TOIL:
case VAL_PWAT: return "TEMP OIL";
return "PRESS WAT"; case VAL_ERR_TYPE:
case VAL_POIL: return "ERROR TYPE";
return "PRESS OIL"; case VAL_PWAT:
case VAL_PBF: return "PRESS WAT";
return "PRESS BRAKE F"; case VAL_POIL:
case VAL_PBR: return "PRESS OIL";
return "PRESS BRAKE R"; case VAL_PBF:
case VAL_SPEED_FL: return "PRESS BRAKE F";
return "SPEED FL"; case VAL_PBR:
case VAL_SPEED_FR: return "PRESS BRAKE R";
return "SPEED FR"; case VAL_SPEED_FL:
case VAL_SPEED: return "SPEED FL";
return "SPEED"; case VAL_SPEED_FR:
default: return "SPEED FR";
return "???"; case VAL_SPEED:
} return "SPEED";
} default:
return "???";
bool check_alarms() { }
static uint32_t poil_last_valid, tmot_last_valid, toil_last_valid; }
uint32_t now = millis();
if (Vehicle_data.p_oil >= POIL_ALARM_THRESH || Vehicle_data.speed == 0) { bool check_alarms() {
poil_last_valid = now; static uint32_t poil_last_valid, tmot_last_valid, toil_last_valid;
} uint32_t now = millis();
if (Vehicle_data.t_mot <= TMOT_ALARM_THRESH || Vehicle_data.t_mot == TMOT_SAFE_VALUE) { if (Vehicle_data.p_oil >= POIL_ALARM_THRESH || Vehicle_data.speed == 0) {
tmot_last_valid = now; poil_last_valid = now;
} }
if (Vehicle_data.t_oil <= TOIL_ALARM_THRESH) { if (Vehicle_data.t_mot <= TMOT_ALARM_THRESH ||
toil_last_valid = now; Vehicle_data.t_mot == TMOT_SAFE_VALUE) {
} tmot_last_valid = now;
bool poil_alarm = now - poil_last_valid >= POIL_ALARM_TIME; }
bool tmot_alarm = now - tmot_last_valid >= TMOT_ALARM_TIME; if (Vehicle_data.t_oil <= TOIL_ALARM_THRESH) {
bool toil_alarm = now - toil_last_valid >= TOIL_ALARM_TIME; toil_last_valid = now;
bool alarm_active = poil_alarm || tmot_alarm || toil_alarm; }
bool poil_alarm = now - poil_last_valid >= POIL_ALARM_TIME;
if (alarm_active) { bool tmot_alarm = now - tmot_last_valid >= TMOT_ALARM_TIME;
String alarm_text = ""; bool toil_alarm = now - toil_last_valid >= TOIL_ALARM_TIME;
if (poil_alarm) alarm_text += "PO"; bool alarm_active = poil_alarm || tmot_alarm || toil_alarm;
if (tmot_alarm) alarm_text += "TM";
if (toil_alarm) alarm_text += "TO"; if (alarm_active) {
alarm(alarm_text); String alarm_text = "";
} if (poil_alarm)
alarm_text += "PO";
return alarm_active; if (tmot_alarm)
} alarm_text += "TM";
if (toil_alarm)
bool check_enc_displays() { alarm_text += "TO";
static uint8_t trc_old, mode_old; alarm(alarm_text);
static bool display_trc, display_mode; }
static uint32_t display_trc_begin, display_mode_begin;
return alarm_active;
return check_display(trc_old, Stw_data.trc, display_trc, display_trc_begin, "ARB") || }
check_display(mode_old, Stw_data.mode, display_mode, display_mode_begin, "MODE");
} bool check_enc_displays() {
static uint8_t trc_old, mode_old;
bool check_display(uint8_t& val_old, uint8_t val_new, bool& active, uint32_t& begin, const String& title) { static bool display_trc, display_mode;
if (val_old != val_new) { static uint32_t display_trc_begin, display_mode_begin;
active = true;
begin = millis(); return check_display(trc_old, Stw_data.trc, display_trc, display_trc_begin,
val_old = val_new; "ARB") ||
tft.clear(); check_display(mode_old, Stw_data.mode, display_mode,
tft.fillDisplayColor(EA_RED); display_mode_begin, "MODE");
tft.setTextColor(EA_WHITE, EA_RED); }
tft.setTextSize(7,8);
String text = title + ":" + val_new; bool check_display(uint8_t& val_old, uint8_t val_new, bool& active,
char text_arr[16]; uint32_t& begin, const String& title) {
text.toCharArray(text_arr, 16); if (val_old != val_new) {
tft.drawText(15, 68, 'C', text_arr); active = true;
} else if (active && millis() - begin > ENC_DISPLAY_TIME) { begin = millis();
tft.setTextColor(EA_WHITE, EA_TRANSPARENT); val_old = val_new;
tft.clear(); tft.clear();
active = false; tft.fillDisplayColor(EA_RED);
} tft.setTextColor(EA_WHITE, EA_RED);
tft.setTextSize(7, 8);
return active; String text = title + ":" + val_new;
} char text_arr[16];
text.toCharArray(text_arr, 16);
void update_display(){ tft.drawText(15, 68, 'C', text_arr);
static DisplayPage page = PAGE_DRIVER; } else if (active && millis() - begin > ENC_DISPLAY_TIME) {
static uint32_t last_cleared; tft.setTextColor(EA_WHITE, EA_TRANSPARENT);
static bool cleared = true; tft.clear();
active = false;
if (check_alarms()) { }
cleared = true;
return; return active;
} }
if (tft.disconnected) {
return; void update_display() {
} static DisplayPage page = PAGE_DRIVER;
static uint32_t last_cleared;
if (check_enc_displays()) { static bool cleared = true;
cleared = true;
return; if (check_alarms()) {
} cleared = true;
return;
uint32_t now = millis(); }
// Both buttons have to be pressed at the same time, but we also use the if (tft.disconnected) {
// debounced rises to ensure we don't keep toggling between the pages return;
if (Stw_data.buttonState1 && Stw_data.buttonState4 && }
(Stw_data.button1_rises > 0|| Stw_data.button4_rises > 0)){
Stw_data.button1_rises = 0; if (check_enc_displays()) {
Stw_data.button4_rises = 0; cleared = true;
page = (DisplayPage) ((page + 1) % DISPLAY_PAGES); return;
tft.clear(); }
last_cleared = now;
cleared = true; uint32_t now = millis();
} // 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 pages
if (now - last_cleared >= DISP_CLEAR_INTERVAL) { if (Stw_data.buttonState1 && Stw_data.buttonState4 &&
tft.clear(); (Stw_data.button1_rises > 0 || Stw_data.button4_rises > 0)) {
last_cleared = now; Stw_data.button1_rises = 0;
cleared = true; Stw_data.button4_rises = 0;
} page = (DisplayPage)((page + 1) % DISPLAY_PAGES);
tft.clear();
if (page == PAGE_DRIVER) { last_cleared = now;
if (cleared) { cleared = true;
redraw_page_driver(); }
cleared = false;
} else { if (now - last_cleared >= DISP_CLEAR_INTERVAL) {
update_page_driver(); tft.clear();
} last_cleared = now;
} else { cleared = true;
if (cleared) { }
redraw_page_testing();
cleared = false; if (page == PAGE_DRIVER) {
} else { if (cleared) {
update_page_testing(); redraw_page_driver();
} cleared = false;
} } else {
} update_page_driver();
}
void alarm(String textstr){ } else {
uint8_t x = 1;; if (cleared) {
char text[7]; redraw_page_testing();
textstr.toCharArray(text,7); cleared = false;
tft.setTextSize(8,8); } else {
while(x==1){ update_page_testing();
if(!tft.disconnected){ }
tft.setTextColor(EA_BLACK,EA_RED); }
tft.fillDisplayColor(EA_RED); }
tft.drawText(5,68,'L',text);
} void alarm(String textstr) {
for (int j = 0; j < 16; j++){ uint8_t x = 1;
digitalWrite(led_s[j], HIGH); ;
} char text[7];
delay(100); textstr.toCharArray(text, 7);
if(!tft.disconnected){ tft.setTextSize(8, 8);
tft.setTextColor(EA_BLACK,EA_WHITE); while (x == 1) {
tft.fillDisplayColor(EA_WHITE); if (!tft.disconnected) {
tft.drawText(5,68,'L',text); tft.setTextColor(EA_BLACK, EA_RED);
} tft.fillDisplayColor(EA_RED);
for (int j = 0; j < 16; j++){ tft.drawText(5, 68, 'L', text);
digitalWrite(led_s[j], LOW); }
} for (int j = 0; j < 16; j++) {
delay(100); digitalWrite(led_s[j], HIGH);
if(Stw_data.buttonState1 & Stw_data.buttonState4){ }
x=0; delay(100);
tft.setTextColor(EA_WHITE,EA_TRANSPARENT); if (!tft.disconnected) {
} tft.setTextColor(EA_BLACK, EA_WHITE);
} tft.fillDisplayColor(EA_WHITE);
} tft.drawText(5, 68, 'L', text);
}
void redraw_page_driver() { for (int j = 0; j < 16; j++) {
// Boxes digitalWrite(led_s[j], LOW);
tft.drawLine(0, 110, 320, 110); }
tft.drawLine(120, 0, 120, 110); delay(100);
tft.drawLine(200, 0, 200, 110); if (Stw_data.buttonState1 & Stw_data.buttonState4) {
x = 0;
// Tire temperature cross tft.setTextColor(EA_WHITE, EA_TRANSPARENT);
tft.drawLine(80, 180, 240, 180); }
tft.drawLine(160, 130, 160, 230); }
}
// Boxes
gear_box.redraw(); void redraw_page_driver() {
left_box.redraw(); // Boxes
right_box.redraw(); tft.drawLine(0, 110, 320, 110);
fl_box.redraw(); tft.drawLine(120, 0, 120, 110);
fr_box.redraw(); tft.drawLine(200, 0, 200, 110);
rl_box.redraw();
rr_box.redraw(); // Tire temperature cross
} tft.drawLine(80, 180, 240, 180);
tft.drawLine(160, 130, 160, 230);
void update_page_driver() {
static Value left_box_value = VAL_FIRST_LEFT_BOX; // Boxes
if (Stw_data.button4_rises > 0) { gear_box.redraw();
Stw_data.button4_rises--; left_box.redraw();
if (left_box_value == VAL_LAST) { right_box.redraw();
left_box_value = VAL_FIRST_LEFT_BOX; fl_box.redraw();
} else { fr_box.redraw();
left_box_value = (Value) (left_box_value + 1); rl_box.redraw();
} rr_box.redraw();
left_box.update_label(get_label(left_box_value)); }
if (Stw_data.button1_rises > 0) {
Stw_data.button1_rises--; void update_page_driver() {
if (left_box_value == VAL_FIRST_LEFT_BOX) { static Value left_box_value = VAL_FIRST_LEFT_BOX;
left_box_value = VAL_LAST; if (Stw_data.button4_rises > 0) {
} else { Stw_data.button4_rises--;
left_box_value = (Value) (left_box_value - 1); if (left_box_value == VAL_LAST) {
} left_box_value = VAL_FIRST_LEFT_BOX;
left_box.update_label(get_label(left_box_value)); } else {
} left_box_value = (Value)(left_box_value + 1);
}
gear_box.update_value(get_value(VAL_GEAR)); left_box.update_label(get_label(left_box_value));
left_box.update_value(get_value(left_box_value)); }
right_box.update_value(get_value(VAL_RPM)); if (Stw_data.button1_rises > 0) {
fl_box.update_value(2); Stw_data.button1_rises--;
fr_box.update_value(55); if (left_box_value == VAL_FIRST_LEFT_BOX) {
rl_box.update_value(65); left_box_value = VAL_LAST;
rr_box.update_value(90); } else {
} left_box_value = (Value)(left_box_value - 1);
}
void redraw_page_testing() { left_box.update_label(get_label(left_box_value));
}
gear_box.update_value(get_value(VAL_GEAR));
left_box.update_value(get_value(left_box_value));
right_box.update_value(get_value(VAL_RPM));
fl_box.update_value(2);
fr_box.update_value(55);
rl_box.update_value(65);
rr_box.update_value(90);
}
void redraw_page_testing() {
tft.setTextFont(EA_FONT7X12);
tft.setTextSize(2, 2);
for (int i = 0; i <= min(VAL_LAST, 9); i++) {
String text = get_label((Value)i) + ":";
int x = (i < 10) ? 10 : 170;
tft.drawText(x, (i % 10) * 24, 'L', text.c_str());
}
}
void update_page_testing() {
// tft.setTextFont(EA_FONT7X12);
// tft.setTextSize(2, 2);
// for (int i = 0; i < min(VALUES, 20); i++) {
// String text = get_value((Value) i);
// int x = (i < 10) ? 10 : 170;
// tft.drawText(10, (i % 10) * 24, 'L', 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)
: 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}, 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:");
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},
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 = String(val_new);
if (val_str.length() == 1) {
val_str = " " + val_str;
} else if (val_str.length() == 2) {
val_str = " " + val_str;
}
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 update_page_testing() {}
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)
: 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}, 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:");
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}, 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 = String(val_new);
if (val_str.length() == 1) {
val_str = " " + val_str;
} else if (val_str.length() == 2) {
val_str = " " + val_str;
}
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() {} void TireTempBox::redraw_label() {}

View File

@ -1,96 +1,113 @@
#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 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
#define POIL_ALARM_THRESH ((uint32_t)(0.1 / 0.0514))
#define POIL_ALARM_THRESH ((uint32_t) (0.1 / 0.0514)) #define POIL_ALARM_TIME 20000 // ms
#define POIL_ALARM_TIME 20000 // ms #define TMOT_ALARM_THRESH (40 + 105)
#define TMOT_ALARM_THRESH (40 + 105) #define TMOT_SAFE_VALUE (40 + 200)
#define TMOT_SAFE_VALUE (40 + 200) #define TMOT_ALARM_TIME 20000 // ms
#define TMOT_ALARM_TIME 20000 // ms #define TOIL_ALARM_THRESH (40 + 150)
#define TOIL_ALARM_THRESH (40 + 150) #define TOIL_ALARM_TIME 10000 // ms
#define TOIL_ALARM_TIME 10000 // ms #define ENC_DISPLAY_TIME 1000 // ms
#define ENC_DISPLAY_TIME 1000 // ms
enum DisplayPage { PAGE_DRIVER, PAGE_TESTING };
enum DisplayPage {PAGE_DRIVER, PAGE_TESTING}; #define DISPLAY_PAGES 2
#define DISPLAY_PAGES 2
enum Value {
enum Value { VAL_GEAR,
VAL_GEAR, VAL_RPM, VAL_TT_FL, VAL_TT_FR, VAL_TT_RL, VAL_TT_RR, VAL_LAPTIME, VAL_RPM,
VAL_UBATT, VAL_TMOT, VAL_TAIR, VAL_TOIL, VAL_ERR_TYPE, VAL_PWAT, VAL_POIL, VAL_TT_FL,
VAL_PBF, VAL_PBR, VAL_SPEED_FL, VAL_SPEED_FR, VAL_SPEED, VAL_TT_FR,
VAL_FIRST_LEFT_BOX = VAL_LAPTIME, VAL_LAST = VAL_SPEED VAL_TT_RL,
}; VAL_TT_RR,
String get_value(Value val); VAL_LAPTIME,
String get_label(Value val); VAL_UBATT,
VAL_TMOT,
#define DISP_CLEAR_INTERVAL 5000 // ms VAL_TAIR,
VAL_TOIL,
void init_display(void); VAL_ERR_TYPE,
void update_display(void); VAL_PWAT,
void display_trc(void); VAL_POIL,
void display_mode(void); VAL_PBF,
void alarm(String text); VAL_PBR,
VAL_SPEED_FL,
bool check_alarms(); VAL_SPEED_FR,
bool check_enc_displays(); VAL_SPEED,
bool check_display(uint8_t& val_old, uint8_t val_new, bool& active, uint32_t& begin, const String& title); VAL_FIRST_LEFT_BOX = VAL_LAPTIME,
VAL_LAST = VAL_SPEED
void redraw_page_driver(); };
void update_page_driver(); String get_value(Value val);
void redraw_page_testing(); String get_label(Value val);
void update_page_testing();
#define DISP_CLEAR_INTERVAL 5000 // ms
class DataBox {
public: void init_display(void);
DataBox(int x1, int y1, int x2, int y2, int text_x, int text_y, int font, void update_display(void);
int size_x, int size_y, uint8_t justification); void display_trc(void);
void display_mode(void);
void update_value(String val_new); void alarm(String text);
void update_label(String label_new);
bool check_alarms();
void redraw(); bool check_enc_displays();
virtual void redraw_value(); bool check_display(uint8_t& val_old, uint8_t val_new, bool& active,
virtual void redraw_label(); uint32_t& begin, const String& title);
protected: void redraw_page_driver();
int x1, y1, x2, y2, text_x, text_y, font, size_x, size_y; void update_page_driver();
uint8_t justification; void redraw_page_testing();
String value; void update_page_testing();
String label;
}; class DataBox {
public:
#define TT_COL0 EA_LIGHTBLUE DataBox(int x1, int y1, int x2, int y2, int text_x, int text_y, int font,
#define TT_COL1 EA_GREEN int size_x, int size_y, uint8_t justification);
#define TT_COL2 EA_ORANGE
#define TT_COL3 EA_RED void update_value(String val_new);
#define TT_THRESH1 50 void update_label(String label_new);
#define TT_THRESH2 60
#define TT_THRESH3 70 void redraw();
virtual void redraw_value();
class TireTempBox : public DataBox { virtual void redraw_label();
public:
TireTempBox(int x1, int y1, int x2, int y2, int text_x, int text_y, protected:
int font, int size_x, int size_y, uint8_t justification); int x1, y1, x2, y2, text_x, text_y, font, size_x, size_y;
uint8_t justification;
void update_value(int val_new); String value;
String label;
void redraw_value() override; };
void redraw_label() override;
#define TT_COL0 EA_LIGHTBLUE
private: #define TT_COL1 EA_GREEN
int color; #define TT_COL2 EA_ORANGE
int num_value; #define TT_COL3 EA_RED
}; #define TT_THRESH1 50
#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,142 +1,144 @@
#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].rose();
Stw_data.Stw_shift_down = debouncer[4].rose();
Stw_data.buttonState1 = debouncer[0].isPressed(); Stw_data.Stw_shift_up = debouncer[5].rose();
Stw_data.buttonState4 = debouncer[3].isPressed();
Stw_data.buttonStateEnc1 = debouncer[6].isPressed(); Stw_data.buttonState1 = debouncer[0].isPressed();
Stw_data.buttonStateEnc2 = debouncer[7].isPressed(); Stw_data.buttonState4 = debouncer[3].isPressed();
if (debouncer[0].rose()) { Stw_data.buttonStateEnc1 = debouncer[6].isPressed();
Stw_data.button1_rises++; Stw_data.buttonStateEnc2 = debouncer[7].isPressed();
} if (debouncer[0].rose()) {
if (debouncer[3].rose()) { Stw_data.button1_rises++;
Stw_data.button4_rises++; }
} if (debouncer[3].rose()) {
if (debouncer[6].rose()) { Stw_data.button4_rises++;
Stw_data.enc1_rises++; }
} if (debouncer[6].rose()) {
if (debouncer[7].rose()) { Stw_data.enc1_rises++;
Stw_data.enc2_rises++; }
} if (debouncer[7].rose()) {
} Stw_data.enc2_rises++;
}
void read_rotary(){ }
int enc = encoder.readEncoder();
int enc2 = encoder2.readEncoder(); void read_rotary() {
if(enc != 0){ int enc = encoder.readEncoder();
val = val +0.5*enc; int enc2 = encoder2.readEncoder();
if (val==1 or val ==-1){ if (enc != 0) {
if(Stw_data.trc==0 and enc<0){ val = val + 0.5 * enc;
Stw_data.trc = 11; if (val == 1 or val == -1) {
}else if(Stw_data.trc==11 and enc>0){ if (Stw_data.trc == 0 and enc < 0) {
Stw_data.trc=0; Stw_data.trc = 11;
}else{ } else if (Stw_data.trc == 11 and enc > 0) {
Stw_data.trc = Stw_data.trc + enc; Stw_data.trc = 0;
} } else {
val = 0; Stw_data.trc = Stw_data.trc + enc;
} }
} val = 0;
/*enc1PinANow = digitalRead(enc1PinA); }
enc2PinANow = digitalRead(enc2PinA); }
if ((enc1PinALast == LOW) && (enc1PinANow == HIGH)) { /*enc1PinANow = digitalRead(enc1PinA);
if (digitalRead(enc1PinB) == HIGH) { enc2PinANow = digitalRead(enc2PinA);
if(Stw_data.trc==0){ if ((enc1PinALast == LOW) && (enc1PinANow == HIGH)) {
Stw_data.trc = 5; if (digitalRead(enc1PinB) == HIGH) {
}else{ if(Stw_data.trc==0){
Stw_data.trc--; Stw_data.trc = 5;
} }else{
}else { Stw_data.trc--;
if(Stw_data.trc==5){ }
Stw_data.trc=0; }else {
}else{ if(Stw_data.trc==5){
Stw_data.trc++; Stw_data.trc=0;
} }else{
} Stw_data.trc++;
} }
enc1PinALast = enc1PinANow; }
/*if (Stw_data.buttonStateEnc1 == HIGH){ }
digitalWrite(led[Stw_data.i], HIGH); enc1PinALast = enc1PinANow;
}*/ /*if (Stw_data.buttonStateEnc1 == HIGH){
if(enc2 != 0){ digitalWrite(led[Stw_data.i], HIGH);
val2 = val2 +0.5*enc2; }*/
if(val2==1 or val2==-1){ if (enc2 != 0) {
if((Stw_data.mode==1 or Stw_data.mode==0) and enc2<0){ val2 = val2 + 0.5 * enc2;
Stw_data.mode = 5; if (val2 == 1 or val2 == -1) {
}else if(Stw_data.mode==5 and enc2>0){ if ((Stw_data.mode == 1 or Stw_data.mode == 0) and enc2 < 0) {
Stw_data.mode=1; Stw_data.mode = 5;
}else{ } else if (Stw_data.mode == 5 and enc2 > 0) {
Stw_data.mode = Stw_data.mode + enc2; Stw_data.mode = 1;
} } else {
val2=0; Stw_data.mode = Stw_data.mode + enc2;
} }
} val2 = 0;
/*if ((enc2PinALast == LOW) && (enc2PinANow == HIGH)) { }
//if(enc2PinALast != enc2PinANow){ }
if (digitalRead(enc2PinB) == HIGH) { /*if ((enc2PinALast == LOW) && (enc2PinANow == HIGH)) {
if(Stw_data.i==0){ //if(enc2PinALast != enc2PinANow){
Stw_data.i = sizeof(led)/sizeof(int)-1; if (digitalRead(enc2PinB) == HIGH) {
}else{ if(Stw_data.i==0){
Stw_data.i--; Stw_data.i = sizeof(led)/sizeof(int)-1;
} }else{
}else { Stw_data.i--;
if(Stw_data.i==sizeof(led)/sizeof(int)-1){ }
Stw_data.i=0; }else {
}else{ if(Stw_data.i==sizeof(led)/sizeof(int)-1){
Stw_data.i++; Stw_data.i=0;
} }else{
} Stw_data.i++;
} }
enc2PinALast = enc2PinANow;*/ }
/*if (Stw_data.buttonStateEnc2 == HIGH){ }
digitalWrite(led[Stw_data.i], HIGH); enc2PinALast = enc2PinANow;*/
}*/ /*if (Stw_data.buttonStateEnc2 == HIGH){
} digitalWrite(led[Stw_data.i], HIGH);
}*/
}

View File

@ -1,105 +1,101 @@
#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 1000
#define RPM_THRES_1 1000 #define RPM_THRES_2 6000
#define RPM_THRES_2 6000 #define RPM_THRES_3 7000
#define RPM_THRES_3 7000 #define RPM_THRES_4 8000
#define RPM_THRES_4 8000 #define RPM_THRES_5 10000
#define RPM_THRES_5 10000 #define RPM_THRES_6 14000
#define RPM_THRES_6 14000 #define RPM_THRES_7 17000
#define RPM_THRES_7 17000 #define RPM_THRES_8 18000
#define RPM_THRES_8 18000 #define RPM_THRES_9 20000
#define RPM_THRES_9 20000 #define RPM_THRES_10 20000
#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 mode : mittlere
uint8_t buttonStateEnc1; // button // 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;
uint8_t button1_rises; uint8_t button4_rises;
uint8_t button4_rises; uint8_t enc1_rises;
uint8_t enc1_rises; uint8_t enc2_rises;
uint8_t enc2_rises; } stw_data_type;
} stw_data_type;
typedef struct {
typedef struct uint8_t e_thro; // E-Drossel
{ uint8_t g_auto; // Auto-Shift
uint8_t e_thro; // E-Drossel uint8_t gear; // Gang
uint8_t g_auto; // Auto-Shift uint16_t revol; // Drehzahl
uint8_t gear; // Gang uint8_t t_oil; // Öl-Motor-Temperatur
uint16_t revol; // Drehzahl uint8_t t_mot; // Wasser-Motor-Temperatur
uint8_t t_oil; // Öl-Motor-Temperatur uint8_t t_air; // LLK-Temperatur
uint8_t t_mot; // Wasser-Motor-Temperatur uint8_t u_batt; // Batteriespannung
uint8_t t_air; // LLK-Temperatur uint8_t rev_lim; // Drehzahllimit Bit
uint8_t u_batt; // Batteriespannung uint8_t p_wat;
uint8_t rev_lim; // Drehzahllimit Bit uint8_t p_fuel;
uint8_t p_wat; uint8_t p_oil;
uint8_t p_fuel; uint8_t p_brake_front;
uint8_t p_oil; uint8_t p_brake_rear;
uint8_t p_brake_front; uint8_t speed_fl;
uint8_t p_brake_rear; uint8_t speed_fr;
uint8_t speed_fl; uint8_t speed;
uint8_t speed_fr;
uint8_t speed; } vehicle_data_type;
} vehicle_data_type; extern volatile stw_data_type Stw_data;
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,171 +1,149 @@
#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 }
{ }
if (clearcounter >= 56)
{ void display_mode() {
tft.clear(); if (modealt != Stw_data.mode) {
clearcounter = 0; tft.clear();
} tft.setTextSize(6, 8);
clearcounter += 1; tft.setDisplayColor(EA_WHITE, EA_RED);
} tft.setTextColor(EA_WHITE, EA_RED);
} char modeanzeige[7];
} String str = String("MODE:");
str += String(Stw_data.mode);
void display_mode() str.toCharArray(modeanzeige, 7);
{ tft.drawText(0, 0, 'L', " ");
if (modealt != Stw_data.mode) tft.drawText(0, 60, 'L', " ");
{ tft.drawText(0, 120, 'L', " ");
tft.clear(); tft.drawText(0, 180, 'L', " ");
tft.setTextSize(6, 8); tft.drawText(15, 68, 'L', modeanzeige);
tft.setDisplayColor(EA_WHITE, EA_RED); modecounter = 0;
tft.setTextColor(EA_WHITE, EA_RED); modealt = Stw_data.mode;
char modeanzeige[7]; modetimer = true;
String str = String("MODE:"); } else if (modecounter >= 255) {
str += String(Stw_data.mode); tft.setDisplayColor(EA_WHITE, EA_BLACK);
str.toCharArray(modeanzeige, 7); tft.setTextColor(EA_WHITE, EA_BLACK);
tft.drawText(0, 0, 'L', " "); tft.clear();
tft.drawText(0, 60, 'L', " "); modetimer = false;
tft.drawText(0, 120, 'L', " "); } else {
tft.drawText(0, 180, 'L', " "); modecounter += 1;
tft.drawText(15, 68, 'L', modeanzeige); delay(5);
modecounter = 0; }
modealt = Stw_data.mode; }
modetimer = true;
} void alarm(String textstr) {
else if (modecounter >= 255) uint8_t x = 1;
{ ;
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);
modetimer = false; while (x == 1) {
} if (!tft.disconnected) {
else tft.setTextColor(EA_BLACK, EA_RED);
{ tft.fillDisplayColor(EA_RED);
modecounter += 1; tft.drawText(5, 68, 'L', text);
delay(5); }
} for (int j = 0; j < 16; j++) {
} digitalWrite(led_s[j], HIGH);
}
void alarm(String textstr) delay(100);
{ if (!tft.disconnected) {
uint8_t x = 1; tft.setTextColor(EA_BLACK, EA_WHITE);
; tft.fillDisplayColor(EA_WHITE);
char text[7]; tft.drawText(5, 68, 'L', text);
textstr.toCharArray(text, 7); }
tft.setTextSize(8, 8); for (int j = 0; j < 16; j++) {
while (x == 1) digitalWrite(led_s[j], LOW);
{ }
if (!tft.disconnected) delay(100);
{ if (Stw_data.button_ll & Stw_data.button_rr) {
tft.setTextColor(EA_BLACK, EA_RED); x = 0;
tft.fillDisplayColor(EA_RED); tft.setTextColor(EA_WHITE, EA_BLACK);
tft.drawText(5, 68, 'L', text); }
} }
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,281 @@
/* /*
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(){ void Init_Can_0() {
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(0x502); // set CAN RX filter for ID 0x502 and reserves mailbox 1 for rx // available (the other 7 mailboxes are for rx)
Can0.watchFor(0x504); Can0.watchFor(
Can0.watchFor(0x500); 0x502); // set CAN RX filter for ID 0x502 and reserves mailbox 1 for rx
Can0.watchFor(0x773); // set CAN RX filter for ID 0x773 and reserves mailbox 3 for rx Can0.watchFor(0x504);
Can0.watchFor(0x775); Can0.watchFor(0x500);
// Can0.watchFor(0x777); // set CAN RX filter for ID 0x777 and reserves mailbox 5 for rx Can0.watchFor(
Can0.watchFor(0x779); // set CAN RX filter for ID 0x779 and reserves mailbox 6 for rx 0x773); // set CAN RX filter for ID 0x773 and reserves mailbox 3 for rx
Can0.watchFor(0x77A); Can0.watchFor(0x775);
Can0.setGeneralCallback(Receive_Can_0); // Can0.watchFor(0x777); // set CAN RX filter
Timer3.attachInterrupt(Send_0x110); // set send interrupt //for ID 0x777 and reserves mailbox 5 for rx
Timer3.start(10000); // Calls every 10ms Can0.watchFor(
} 0x779); // set CAN RX filter for ID 0x779 and reserves mailbox 6 for rx
Can0.watchFor(0x77A);
void Send_0x110(){ Can0.setGeneralCallback(Receive_Can_0);
read_buttons(); Timer3.attachInterrupt(Send_0x110); // set send interrupt
read_rotary(); Timer3.start(10000); // Calls every 10ms
can_0_msg.id = 0x110; }
can_0_msg.fid = 0;
can_0_msg.rtr = 0; void Send_0x110() {
can_0_msg.priority = 0; read_buttons();
can_0_msg.length = 2; read_rotary();
can_0_msg.extended = 0; can_0_msg.id = 0x110;
can_0_temp_data = 0; can_0_msg.fid = 0;
can_0_temp_data |= Stw_data.Stw_shift_up & 0b00000001; can_0_msg.rtr = 0;
can_0_temp_data |= Stw_data.Stw_shift_down << 1 & 0b00000010; can_0_msg.priority = 0;
can_0_temp_data |= Stw_data.Stw_neutral << 2 & 0b00000100; can_0_msg.length = 2;
can_0_temp_data |= Stw_data.Stw_auto_shift << 3 & 0b00001000; can_0_msg.extended = 0;
can_0_temp_data |= Stw_data.buttonStateEnc1 << 5 & 0b00100000; //pitlane can_0_temp_data = 0;
can_0_msg.data.byte[0] = can_0_temp_data; can_0_temp_data |= Stw_data.Stw_shift_up & 0b00000001;
can_0_msg.data.byte[1] = Stw_data.trc & 0b00001111; can_0_temp_data |= Stw_data.Stw_shift_down << 1 & 0b00000010;
can_0_msg.data.byte[2] = Stw_data.mode & 0b00000111; can_0_temp_data |= Stw_data.Stw_neutral << 2 & 0b00000100;
if ((Stw_data.Stw_auto_shift << 3 & 0b00001000)){ can_0_temp_data |= Stw_data.Stw_auto_shift << 3 & 0b00001000;
if(Vehicle_data.g_auto){ can_0_temp_data |= Stw_data.buttonStateEnc1 << 5 & 0b00100000; // pitlane
Vehicle_data.g_auto = false; can_0_msg.data.byte[0] = can_0_temp_data;
}else{ can_0_msg.data.byte[1] = Stw_data.trc & 0b00001111;
Vehicle_data.g_auto = true; can_0_msg.data.byte[2] = Stw_data.mode & 0b00000111;
} if ((Stw_data.Stw_auto_shift << 3 & 0b00001000)) {
} if (Vehicle_data.g_auto) {
Can0.sendFrame(can_0_msg); Vehicle_data.g_auto = false;
} } else {
Vehicle_data.g_auto = true;
void Receive_Can_0(CAN_FRAME *temp_message){ }
switch (temp_message->id) { }
//g_auto Can0.sendFrame(can_0_msg);
case 0x502:{ // eDrossel error bit }
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
void Receive_Can_0(CAN_FRAME *temp_message) {
if(temp_message->data.byte[0] & 0x80){ switch (temp_message->id) {
Stw_data.error_type = 1;//"pc_error"; // g_auto
} case 0x502: { // eDrossel error bit
if(temp_message->data.byte[0] & 0x40){ Vehicle_data.e_thro = (temp_message->data.byte[0] & 0x80) |
Stw_data.error_type = 2;//"bse_error"; (temp_message->data.byte[0] & 0x40) |
} (temp_message->data.byte[0] & 0x20) |
if(temp_message->data.byte[0] & 0x20){ (temp_message->data.byte[0] & 0x10); // bit 4-7
Stw_data.error_type = 3;//"aps_error";
} if (temp_message->data.byte[0] & 0x80) {
if(temp_message->data.byte[0] & 0x10){ Stw_data.error_type = 1; //"pc_error";
Stw_data.error_type = 4;//"etb_error"; }
} if (temp_message->data.byte[0] & 0x40) {
//can_1_temp_data |= g_etb_e << 4; Stw_data.error_type = 2; //"bse_error";
//can_1_temp_data |= g_aps_e << 5; }
//can_1_temp_data |= g_bse_e << 6; if (temp_message->data.byte[0] & 0x20) {
//can_1_temp_data |= g_pc_e << 7; Stw_data.error_type = 3; //"aps_error";
break; }
} if (temp_message->data.byte[0] & 0x10) {
case 0x504:{ //autoshift+gear Stw_data.error_type = 4; //"etb_error";
//Vehicle_data.g_auto = (temp_message->data.byte[1]) >> 4; }
Vehicle_data.gear = (temp_message->data.byte[1]) >> 5; // can_1_temp_data |= g_etb_e << 4;
break; // can_1_temp_data |= g_aps_e << 5;
} // can_1_temp_data |= g_bse_e << 6;
case 0x773:{ // rpm // can_1_temp_data |= g_pc_e << 7;
Vehicle_data.revol = (temp_message->data.byte[4] | temp_message->data.byte[3] << 8); break;
break; }
} case 0x504: { // autoshift+gear
case 0x779:{ // battery voltage // Vehicle_data.g_auto =
Vehicle_data.u_batt = temp_message->data.byte[6]; // (temp_message->data.byte[1])
break; // >> 4;
} Vehicle_data.gear = (temp_message->data.byte[1]) >> 5;
/*case 0x77A: // revolution limit bit break;
Vehicle_data.rev_lim = (temp_message->data.byte[3] & 0x20) >> 4; }
switch(temp_message->data.byte[0]) { case 0x773: { // rpm
case 0x02: // temp. intercooler Vehicle_data.revol =
Vehicle_data.t_air = temp_message->data.byte[7]; (temp_message->data.byte[4] | temp_message->data.byte[3] << 8);
break; break;
case 0x05: // temp. water }
Vehicle_data.t_mot = temp_message->data.byte[4]; case 0x779: { // battery voltage
break; Vehicle_data.u_batt = temp_message->data.byte[6];
case 0x04: // temp. oil break;
Vehicle_data.t_oil = temp_message->data.byte[5]; }
case 0x01: { /*case 0x77A: // revolution limit bit
Vehicle_data.p_wat = temp_message->data.byte[6]; Vehicle_data.rev_lim =
Vehicle_data.p_fuel = temp_message->data.byte[7]; (temp_message->data.byte[3] & 0x20) >> 4;
Vehicle_data.p_oil = temp_message->data.byte[5]; switch(temp_message->data.byte[0]) {
break; case 0x02: // temp. intercooler
} Vehicle_data.t_air =
} temp_message->data.byte[7]; break; case 0x05: // temp. water
break;*/ Vehicle_data.t_mot =
case 0x77A:{//temp und p temp_message->data.byte[4]; break; case 0x04: // temp. oil
//g_ms4_idle_b = (temp_message->data.byte[2] & 0b10000000) >> 7; Vehicle_data.t_oil =
//g_ms4_engine_status = (temp_message->data.byte[3] & 0b01000000) >> 6; temp_message->data.byte[5]; case 0x01: {
//g_ms4_ignoff_b = (temp_message->data.byte[3] & 0b10000000) >> 7; Vehicle_data.p_wat =
// Serial.println("CAN 77A"); temp_message->data.byte[6]; Vehicle_data.p_fuel =
// for (int i = 0; i < 8; i++) { temp_message->data.byte[7]; Vehicle_data.p_oil =
// Serial.print('['); temp_message->data.byte[5]; break;
// Serial.print(i); }
// Serial.print("] "); }
// Serial.println(temp_message->data.byte[i], HEX); break;*/
// } case 0x77A: { // temp und p
// g_ms4_idle_b = (temp_message->data.byte[2] &
if ( temp_message->data.byte[0] == 1){ // 0b10000000)
Vehicle_data.p_oil = temp_message->data.byte[5]; // >> 7; g_ms4_engine_status = (temp_message->data.byte[3] &
Vehicle_data.p_fuel = temp_message->data.byte[7]; // 0b01000000) >> 6; g_ms4_ignoff_b =
} // (temp_message->data.byte[3] & 0b10000000) >> 7;
else if ( temp_message->data.byte[0] == 2){ // Serial.println("CAN 77A");
Vehicle_data.t_air = temp_message->data.byte[7]; // for (int i = 0; i < 8; i++) {
} // Serial.print('[');
else if ( temp_message->data.byte[0] == 4){ // Serial.print(i);
Vehicle_data.t_oil = temp_message->data.byte[5]; // Serial.print("] ");
} // Serial.println(temp_message->data.byte[i], HEX);
else if ( temp_message->data.byte[0] == 5){ // }
Vehicle_data.t_mot = temp_message->data.byte[4];
} 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 0x775:{//speed } else if (temp_message->data.byte[0] == 2) {
Vehicle_data.speed_fl = 2*(temp_message->data.byte[2]); Vehicle_data.t_air = temp_message->data.byte[7];
Vehicle_data.speed_fr = 2*(temp_message->data.byte[3]); } else if (temp_message->data.byte[0] == 4) {
Vehicle_data.speed = (Vehicle_data.speed_fl+Vehicle_data.speed_fr)/2; Vehicle_data.t_oil = temp_message->data.byte[5];
break; } else if (temp_message->data.byte[0] == 5) {
} Vehicle_data.t_mot = temp_message->data.byte[4];
/*case 0x777:{//m4_gear }
Vehicle_data.gear = temp_message->data.byte[0]; break;
break; }
}*/ case 0x775: { // speed
case 0x500:{ Vehicle_data.speed_fl = 2 * (temp_message->data.byte[2]);
Vehicle_data.p_brake_front = temp_message->data.byte[1]; Vehicle_data.speed_fr = 2 * (temp_message->data.byte[3]);
Vehicle_data.p_brake_rear = temp_message->data.byte[2]; Vehicle_data.speed = (Vehicle_data.speed_fl + Vehicle_data.speed_fr) / 2;
break; break;
} }
} /*case 0x777:{//m4_gear
} Vehicle_data.gear =
temp_message->data.byte[0]; break;
void update_LED(){ }*/
//Copyright Michael Dietzel case 0x500: {
//m.dietzel@fasttube.de Vehicle_data.p_brake_front = temp_message->data.byte[1];
//Edit Michael Witt 05-2015 Vehicle_data.p_brake_rear = temp_message->data.byte[2];
//m.witt@fasttube.de break;
}
//EDIT BAHA ZARROUKI 05-2107 }
//z.baha@fasttube.de }
// alle Werte als Hex-Werte angegeben void update_LED() {
bool t_oil = (Vehicle_data.t_oil - 40) >= 0x96; // 150°C temp.oil // Copyright Michael Dietzel
bool t_air = (Vehicle_data.t_air - 40) >= 0x3C; // 60°C temp.llk // m.dietzel@fasttube.de
bool t_mot = ((Vehicle_data.t_mot - 40) >= 0x69) and ((Vehicle_data.t_mot - 40)!=0xC8); // 105°C temp.water und !=200 // Edit Michael Witt 05-2015
// m.witt@fasttube.de
bool g_auto = Vehicle_data.g_auto;
bool u_batt = Vehicle_data.u_batt <= 0xB1; // 12.5V batt.spann. // EDIT BAHA ZARROUKI 05-2107
bool e_dros = Vehicle_data.e_thro; // error-bit // z.baha@fasttube.de
bool rev_lim = Vehicle_data.rev_lim; // alle Werte als Hex-Werte angegeben
bool t_oil = (Vehicle_data.t_oil - 40) >= 0x96; // 150°C temp.oil
uint16_t rev = Vehicle_data.revol; bool t_air = (Vehicle_data.t_air - 40) >= 0x3C; // 60°C temp.llk
bool t_mot =
/*if(Vehicle_data.rev_lim){ ((Vehicle_data.t_mot - 40) >= 0x69) and
for (int j = 0; j < 10; j++){ ((Vehicle_data.t_mot - 40) != 0xC8); // 105°C temp.water und !=200
digitalWrite(leds[j], HIGH);
//analogWrite(leds[j], STW_data.br); //nur eine der zwei zeilen bool g_auto = Vehicle_data.g_auto;
} bool u_batt = Vehicle_data.u_batt <= 0xB1; // 12.5V batt.spann.
delay(100); bool e_dros = Vehicle_data.e_thro; // error-bit
for (int j = 0; j < 10; j++){
digitalWrite(leds[j], LOW); bool rev_lim = Vehicle_data.rev_lim;
}
delay(100); uint16_t rev = Vehicle_data.revol;
}else{*/
/*uint8_t helligkeit = 20; /*if(Vehicle_data.rev_lim){
if(RPM_THRES_1 <= rev){ for (int j = 0; j < 10; j++){
analogWrite(led1, helligkeit); digitalWrite(leds[j], HIGH);
}else{ //analogWrite(leds[j], STW_data.br); //nur eine der zwei
analogWrite(led1, 0); zeilen
} }
if(RPM_THRES_2 <= rev){ delay(100);
analogWrite(led2, helligkeit); for (int j = 0; j < 10; j++){
}else{ digitalWrite(leds[j], LOW);
analogWrite(led2, 0); }
} delay(100);
if(RPM_THRES_3 <= rev){ }else{*/
analogWrite(led3, helligkeit); /*uint8_t helligkeit = 20;
}else{ if(RPM_THRES_1 <= rev){
analogWrite(led3, 0); analogWrite(led1, helligkeit);
} }else{
if(RPM_THRES_4 <= rev){ analogWrite(led1, 0);
analogWrite(led4, helligkeit); }
}else{ if(RPM_THRES_2 <= rev){
analogWrite(led4, 0); analogWrite(led2, helligkeit);
} }else{
if(RPM_THRES_5 <= rev){ analogWrite(led2, 0);
analogWrite(led5, helligkeit); }
}else{ if(RPM_THRES_3 <= rev){
analogWrite(led5, 0); analogWrite(led3, helligkeit);
} }else{
if(RPM_THRES_6 <= rev){ analogWrite(led3, 0);
analogWrite(led6, helligkeit); }
}else{ if(RPM_THRES_4 <= rev){
analogWrite(led6, 0); analogWrite(led4, helligkeit);
} }else{
if(RPM_THRES_7 <= rev){ analogWrite(led4, 0);
analogWrite(led7, helligkeit); }
}else{ if(RPM_THRES_5 <= rev){
analogWrite(led7, 0); analogWrite(led5, helligkeit);
} }else{
if(RPM_THRES_8 <= rev){ analogWrite(led5, 0);
analogWrite(led8, helligkeit); }
}else{ if(RPM_THRES_6 <= rev){
analogWrite(led8, 0); analogWrite(led6, helligkeit);
} }else{
if(RPM_THRES_9 <= rev){ analogWrite(led6, 0);
analogWrite(led9, helligkeit); }
}else{ if(RPM_THRES_7 <= rev){
analogWrite(led9, 0); analogWrite(led7, helligkeit);
} }else{
if(RPM_THRES_10 <= rev){ analogWrite(led7, 0);
analogWrite(led10, helligkeit); }
}else{ if(RPM_THRES_8 <= rev){
analogWrite(led10, 0); analogWrite(led8, helligkeit);
}*/ }else{
digitalWrite(led1, RPM_THRES_1 <= rev); analogWrite(led8, 0);
digitalWrite(led2, RPM_THRES_2 <= rev); }
digitalWrite(led3, RPM_THRES_3 <= rev); if(RPM_THRES_9 <= rev){
digitalWrite(led4, RPM_THRES_4 <= rev); analogWrite(led9, helligkeit);
digitalWrite(led5, RPM_THRES_5 <= rev); }else{
digitalWrite(led6, RPM_THRES_6 <= rev); analogWrite(led9, 0);
digitalWrite(led7, RPM_THRES_7 <= rev); }
digitalWrite(led8, RPM_THRES_8 <= rev); if(RPM_THRES_10 <= rev){
digitalWrite(led9, RPM_THRES_9 <= rev); analogWrite(led10, helligkeit);
digitalWrite(led10, RPM_THRES_10 <= rev); }else{
analogWrite(led10, 0);
digitalWrite(led11, t_mot); // rot, links, oben }*/
digitalWrite(led12, t_air); // rot, links, mitte digitalWrite(led1, RPM_THRES_1 <= rev);
digitalWrite(led13, t_oil); // rot, links, unten digitalWrite(led2, RPM_THRES_2 <= rev);
digitalWrite(led3, RPM_THRES_3 <= rev);
digitalWrite(led14, e_dros); // rot, rechts, oben digitalWrite(led4, RPM_THRES_4 <= rev);
digitalWrite(led15, u_batt); // rot rechts, mitte digitalWrite(led5, RPM_THRES_5 <= rev);
digitalWrite(led16, g_auto); // blau rechts, unten digitalWrite(led6, RPM_THRES_6 <= rev);
/*if(Vehicle_data.g_auto){ digitalWrite(led7, RPM_THRES_7 <= rev);
digitalWrite(led16, HIGH); digitalWrite(led8, RPM_THRES_8 <= rev);
}else{ digitalWrite(led9, RPM_THRES_9 <= rev);
digitalWrite(led16, LOW); 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,12 @@
/* /*
FT_2018_STW_CAN.h FT_2018_STW_CAN.h
*/ */
#include "Arduino.h" #include "Arduino.h"
#include "DueTimer.h" #include "DueTimer.h"
#include "due_can.h" #include "due_can.h"
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 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,15 +26,15 @@
#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_TRANSPARENT 0
@ -72,382 +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);
/*! \brief Draw text on display in an area /*! \brief Draw text on display
* *
* Draw a *text* on screen. Several lines are separated by the character `|` * Draw a *text* on screen. Several lines are separated by the character `|`
* ($7C). * ($7C).
* * place text between `~`: characters flash on/off * * place text between `~`: characters flash on/off
* * place text between `@`: characters flash inversely * * place text between `@`: characters flash inversely
* * use `\\` as to escape special characters * * use `\\` as to escape special characters
* *
* \param align set alignment in the rectangle. 1 = top left, 2 = top * \param x1: x coordinate
* center, 3 = top right, 4 = center left, 5 = center, 6 = center right, 7 = * \param y1: y coordinate
* bottom left, 8 = bottom center, 9 = bottom right. * \param justification set text justification to `L`(eft), `R`(ight),
* \param text text to draw on display * `C`(enter)
*/ * \param text text to draw on display
void drawTextInRect(int x1, int y1, int x2, int y2, uint8_t align, const char* text); */
void drawText(uint16_t x1, uint16_t y1, char justification, const char* text);
// Rectangle and Line /*! \brief Draw text on display in an area
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 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 Point size/line thickness // Rectangle and Line
* void setLineColor(char fg, char bg);
* \param x x-point size (1..15)
* \param y y-point size (1..15)
*/
void setLineThick(char x, char y);
/*! \brief Draw straight line /*! \brief Point size/line thickness
* *
* Draw straight line from point *x1*, *y1* to point *x2*, *y2* * \param x x-point size (1..15)
*/ * \param y y-point size (1..15)
void drawLine(int x1, int y1, int x2, int y2); */
void setLineThick(char x, char y);
/*! \brief Draw rectangle /*! \brief Draw straight line
* *
* Draw four straight lines as a rectangle from *x1*, *y1* to *x2*, *y2* * Draw straight line from point *x1*, *y1* to point *x2*, *y2*
*/ */
void drawRect(int x1, int y1, int x2, int y2); void drawLine(int x1, int y1, int x2, int y2);
void drawRectf(int x1, int y1, int x2, int y2, char color); /*! \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 Clear rectangular area */ void drawRectf(int x1, int y1, int x2, int y2, char color);
void clearRect(int x1, int y1, int x2, int y2);
// Touch keys /*! \brief Clear rectangular area */
void clearRect(int x1, int y1, int x2, int y2);
/*! \brief Define touch key // Touch keys
*
* 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 Define touch key
* *
* Status of the switch toggles after each contact. The area from *x1*, *y1* * 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. * 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 * The label is drawn with the current touch font. The first character
* determines the alignment of the text (`L`(eft), `R`(ight), `C`(enter)). * determines the alignment of the text (`L`(eft), `R`(ight), `C`(enter)).
* Multiline texts are separated by the character `|`. * Multiline texts are separated by the character `|`.
* *
* \param down return/touchmacro (1-255) if pressed * \param down return/touchmacro (1-255) if pressed
* \param up return/touchmacro (1-255) if released * \param up return/touchmacro (1-255) if released
* \param text label of the touch key * \param text label of the touch key
*/ */
void defineTouchSwitch(int x1, int y1, int x2, int y2, void defineTouchKey(int x1, int y1, int x2, int y2, char down, char up,
char down, char up, const char* text); const char* text);
/*! \brief Define touch switch with image /*! \brief Define touch switch
* *
* Status of the switch toggles after each contact. Image number *img* is * Status of the switch toggles after each contact. The area from *x1*, *y1*
* loaded to *x*, *y* and defined as a switch. * 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 * The label is drawn with the current touch font. The first character
* determines the alignment of the text (`L`(eft), `R`(ight), `C`(enter)). * determines the alignment of the text (`L`(eft), `R`(ight), `C`(enter)).
* Multiline texts are separated by the character `|`. * Multiline texts are separated by the character `|`.
* *
* \param down return/touchmacro (1-255) if pressed * \param down return/touchmacro (1-255) if pressed
* \param up return/touchmacro (1-255) if released * \param up return/touchmacro (1-255) if released
* \param text label of the touch switch * \param text label of the touch key
*/ */
void defineTouchSwitch(int x, int y, int img, char downcode, void defineTouchSwitch(int x1, int y1, int x2, int y2, char down, char up,
char upcode, const char* text); const char* text);
/*! \brief Set touch switch /*! \brief Define touch switch with image
* *
* Set the status of the touch switch with the return code *code* * Status of the switch toggles after each contact. Image number *img* is
* to *value*. * loaded to *x*, *y* and defined as a switch.
* * 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 switch
*/
void defineTouchSwitch(int x, int y, int img, char downcode, char upcode,
const char* text);
void setTouchkeyColors(char n1, char n2, char n3, /*! \brief Set touch switch
char s1, char s2, char s3); *
* 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 Label font void setTouchkeyColors(char n1, char n2, char n3, char s1, char s2, char s3);
*
* Apply font with number *font* for touch key labels
*/
void setTouchkeyFont(char font);
void setTouchkeyLabelColors(char nf,char sf); /*! \brief Label font
*
* Apply font with number *font* for touch key labels
*/
void setTouchkeyFont(char font);
/*! \brief Radio group for switches void setTouchkeyLabelColors(char nf, char sf);
*
* `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 Radio group for switches
* *
* The touch area with the return code is removed from the touch query * `group=0`: newly defined switches don't belong to a group
* * `group=1..255`: newly defined switches are assigned to the group with
* \param code the code of the touch area (code=0: all touch areas) * the given number
* \param n1 n1==0: the area remains visible on the display, * Only one switch in a group is active at once. All others are deactivated.
* n1==1: the area is deleted * For switches only the *down code* is applicable. The *up code* will be
*/ * ignored.
void removeTouchArea(char code,char n1); */
void setTouchGroup(char group);
// Macro Calls /*! \brief Delete toch area by up- or downcode
/*! \brief Run macro *
* * The touch area with the return code is removed from the touch query
* Call the (normal) macro with number *nr* (max. 7 levels). *
*/ * \param code the code of the touch area (code=0: all touch areas)
void callMacro(uint nr); * \param n1 n1==0: the area remains visible on the display,
* n1==1: the area is deleted
*/
void removeTouchArea(char code, char n1);
/*! \brief Run touch macro // Macro Calls
* /*! \brief Run macro
* Call touch macro with number *nr* (max. 7 levels) *
*/ * Call the (normal) macro with number *nr* (max. 7 levels).
void callTouchMacro(uint nr); */
void callMacro(uint nr);
/*! \brief Run menu macro /*! \brief Run touch macro
* *
* Call menu macro with number *nr* (max. 7 levels) * Call touch macro with number *nr* (max. 7 levels)
*/ */
void callMenuMacro(uint nr); void callTouchMacro(uint nr);
/*! \brief Define touch key with menu function /*! \brief Run menu macro
* *
* Define the area from *x1*, *y1* to *x2*, *y2* as a menu key. * Call menu macro with number *nr* (max. 7 levels)
* The first character determines the direction in which the menu opens (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) void callMenuMacro(uint nr);
* The menu items are 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);
/*! \brief Send *open* signal after a Menu open request has been sent from TFT. /*! \brief Define touch key with menu function
* *
* If a touch menu is not set to open automatically the TFT sends a * Define the area from *x1*, *y1* to *x2*, *y2* as a menu key.
* request 'ESC T 0'. This function sends 'ESC N T 2' to open the menu. * The first character determines the direction in which the menu opens
*/ * (R=right,L=left,O=up,U=down) The second character determines the alignment
void openTouchMenu(); * 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". 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 Set menu font /*! \brief Send *open* signal after a Menu open request has been sent from
* * TFT.
* Set font with number *font* (`0..15`) for menu display *
*/ * If a touch menu is not set to open automatically the TFT sends a
void setMenuFont(char font); * request 'ESC T 0'. This function sends 'ESC N T 2' to open the menu.
*/
void openTouchMenu();
/*! \brief enable/disable touchmenu automation /*! \brief Set menu font
* *
* if val==true touch menu opens automatically, if val==false touchmenu * Set font with number *font* (`0..15`) for menu display
* doesn' t open automatically, instead a request is sent to the */
* host computer, which can then open the menu with openTouchMenu() void setMenuFont(char font);
*/
void setTouchMenuAutomation(bool val);
private: /*! \brief enable/disable touchmenu automation
boolean _smallprotocol; *
int _counter; * if val==true touch menu opens automatically, if val==false touchmenu
unsigned char bytesAvailable(); * doesn' t open automatically, instead a request is sent to the
void waitBytesAvailable(); * host computer, which can then open the menu with openTouchMenu()
void sendByte(char data); */
void sendSmall(char* data, char len); void setTouchMenuAutomation(bool val);
void sendSmallDC2(char* data, char len);
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