6 Commits

Author SHA1 Message Date
d362fdd639 TEDü Getac Changes 2024-10-05 19:01:02 +02:00
661e1a2274 Add brake balance display 2022-03-24 17:48:03 +01:00
58b0b72c6d Disable P_OIL alarm 2022-03-23 15:09:40 +01:00
b5ece154c5 Lower tire temp green threshold 2022-03-21 17:19:38 +01:00
8a05663fbc Fix CAN filter bitmask 2022-03-18 17:21:25 +01:00
28b4e15ed2 added DRS control 2022-03-17 00:51:16 +01:00
7 changed files with 130 additions and 21 deletions

View File

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

View File

@ -25,13 +25,15 @@ int led_s[] = {led1, led2, led3, led4, led5, led6, led7, led8,
DataBox gear_box(121, 0, 199, 94, 160, 0, EA_SWISS30B, 4, 4, 'C', true); DataBox gear_box(121, 0, 199, 94, 160, 0, EA_SWISS30B, 4, 4, 'C', true);
DataBox left_box(0, 25, 119, 94, 110, 25, EA_FONT6X8, 3, 8, 'R', false); DataBox left_box(0, 25, 119, 94, 110, 25, EA_FONT6X8, 3, 8, 'R', false);
DataBox right_box(201, 25, 320, 94, 310, 25, EA_FONT6X8, 3, 8, 'R', false); DataBox right_box(201, 25, 320, 94, 310, 25, EA_FONT6X8, 3, 8, 'R', false);
DataBox autoshift_box(164+50, 184, 240+50, 230, 202+50, 178, EA_FONT7X12, 3, 5, 'C', false);
TireTempBox fl_box(80, 130, 156, 176, 118, 124, 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'); TireTempBox fr_box(164, 130, 240, 176, 202, 124, EA_FONT7X12, 3, 5, 'C');
TireTempBox rl_box(80, 184, 156, 230, 118, 178, EA_FONT7X12, 3, 5, 'C'); TireTempBox rl_box(80, 184, 156, 230, 118, 178, EA_FONT7X12, 3, 5, 'C');
TireTempBox rr_box(164, 184, 240, 230, 202, 178, EA_FONT7X12, 3, 5, 'C'); TireTempBox rr_box(164, 184, 240, 230, 202, 178, EA_FONT7X12, 3, 5, 'C');
int testing_page = 0; int testing_page = 0;
uint16_t clearcounter = 1;
void init_display() { void init_display() {
pinMode(writeprotect, OUTPUT); pinMode(writeprotect, OUTPUT);
digitalWrite(writeprotect, HIGH); digitalWrite(writeprotect, HIGH);
@ -55,6 +57,7 @@ void init_display() {
gear_box.update_label(get_label(VAL_GEAR)); gear_box.update_label(get_label(VAL_GEAR));
left_box.update_label(get_label(VAL_FIRST_LEFT_BOX)); left_box.update_label(get_label(VAL_FIRST_LEFT_BOX));
right_box.update_label(get_label(VAL_RPM)); right_box.update_label(get_label(VAL_RPM));
autoshift_box.update_label("");
} }
String get_value(Value val) { String get_value(Value val) {
@ -113,6 +116,15 @@ String get_value(Value val) {
return String(Vehicle_data.speed_fr); return String(Vehicle_data.speed_fr);
case VAL_SPEED: case VAL_SPEED:
return String(Vehicle_data.speed); return String(Vehicle_data.speed);
case VAL_BBAL: {
double p_total =
Vehicle_data.p_brake_front + Vehicle_data.p_brake_rear / 2.398;
double bbal = p_total == 0 ? 0 : 100 * Vehicle_data.p_brake_front / p_total;
if (bbal >= 100) {
return "100";
}
return String(bbal, 2);
}
default: default:
return "???"; return "???";
} }
@ -160,6 +172,8 @@ String get_label(Value val) {
return "SPEED FR"; return "SPEED FR";
case VAL_SPEED: case VAL_SPEED:
return "SPEED"; return "SPEED";
case VAL_BBAL:
return "BBAL";
default: default:
return "???"; return "???";
} }
@ -178,7 +192,8 @@ bool check_alarms() {
if (Vehicle_data.t_oil <= TOIL_ALARM_THRESH) { if (Vehicle_data.t_oil <= TOIL_ALARM_THRESH) {
toil_last_valid = now; toil_last_valid = now;
} }
bool poil_alarm = now - poil_last_valid >= POIL_ALARM_TIME; // bool poil_alarm = now - poil_last_valid >= POIL_ALARM_TIME;
bool poil_alarm = false;
bool tmot_alarm = now - tmot_last_valid >= TMOT_ALARM_TIME; bool tmot_alarm = now - tmot_last_valid >= TMOT_ALARM_TIME;
bool toil_alarm = now - toil_last_valid >= TOIL_ALARM_TIME; bool toil_alarm = now - toil_last_valid >= TOIL_ALARM_TIME;
bool alarm_active = poil_alarm || tmot_alarm || toil_alarm; bool alarm_active = poil_alarm || tmot_alarm || toil_alarm;
@ -286,6 +301,35 @@ void update_display() {
update_view_testing(); update_view_testing();
} }
} }
if (clearcounter>= 10000){
pinMode(writeprotect, OUTPUT);
digitalWrite(writeprotect, HIGH);
pinMode(reset, OUTPUT);
pinMode(disp_cs, OUTPUT);
pinMode(MOSI, OUTPUT);
pinMode(MISO, OUTPUT);
digitalWrite(disp_cs, HIGH);
digitalWrite(MOSI, HIGH);
digitalWrite(MISO, HIGH);
digitalWrite(reset, LOW);
digitalWrite(reset, HIGH);
//tft.begin(115200); // start display communication
//tft.cursorOn(false);
//tft.terminalOn(false);
//tft.setDisplayColor(EA_WHITE, EA_BLACK);
//tft.setTextColor(EA_WHITE, EA_TRANSPARENT);
//tft.setTextSize(5, 8);
//tft.clear();
// gear_box.update_label(get_label(VAL_GEAR));
// left_box.update_label(get_label(VAL_FIRST_LEFT_BOX));
// right_box.update_label(get_label(VAL_RPM));
clearcounter = 0; //clearen des display nach definierter Zeit
cleared =true;
//
}
clearcounter+=1;
} }
void alarm(String textstr) { void alarm(String textstr) {
@ -336,6 +380,7 @@ void redraw_view_driver() {
gear_box.redraw(); gear_box.redraw();
left_box.redraw(); left_box.redraw();
right_box.redraw(); right_box.redraw();
autoshift_box.redraw();
fl_box.redraw(); fl_box.redraw();
fr_box.redraw(); fr_box.redraw();
rl_box.redraw(); rl_box.redraw();
@ -343,6 +388,7 @@ void redraw_view_driver() {
} }
void update_view_driver() { void update_view_driver() {
uint8_t prev_autoshift = Vehicle_data.autoshift;
static Value left_box_value = VAL_FIRST_LEFT_BOX; static Value left_box_value = VAL_FIRST_LEFT_BOX;
if (Stw_data.button4_rises > 0) { if (Stw_data.button4_rises > 0) {
Stw_data.button4_rises--; Stw_data.button4_rises--;
@ -369,16 +415,30 @@ void update_view_driver() {
tft.setTextColor(EA_WHITE, EA_BLACK); tft.setTextColor(EA_WHITE, EA_BLACK);
left_box.update_value(pad_left(get_value(left_box_value), 5)); left_box.update_value(pad_left(get_value(left_box_value), 5));
right_box.update_value(pad_left(get_value(VAL_RPM), 5)); right_box.update_value(pad_left(get_value(VAL_RPM), 5));
// Vehicle_data.autoshift = true;
if(Vehicle_data.autoshift == true){
tft.drawRectf(164+100, 184, 240+100, 230, TT_COL3);
}
else{
tft.drawRectf(164+100, 184, 240+100, 230, EA_BLACK);
}
autoshift_box.update_value(pad_left(String(Vehicle_data.autoshift), 5));
// These don't change as rapidly, and would overwrite adjacent elements // These don't change as rapidly, and would overwrite adjacent elements
// (lines/labels) if rendered with a background because of the empty pixels // (lines/labels) if rendered with a background because of the empty pixels
// above/below the characters. So they're rendered using the clear-redraw // above/below the characters. So they're rendered using the clear-redraw
// method.0 // method.0
tft.setTextColor(EA_WHITE, EA_TRANSPARENT); tft.setTextColor(EA_WHITE, EA_TRANSPARENT);
gear_box.update_value(get_value(VAL_GEAR)); //gear_box.update_value(get_value(VAL_GEAR));
fl_box.update_value(get_value(VAL_TT_FL).toInt()); fl_box.update_value(get_value(VAL_TT_FL).toInt());
fr_box.update_value(get_value(VAL_TT_FR).toInt()); fr_box.update_value(get_value(VAL_TT_FR).toInt());
rl_box.update_value(get_value(VAL_TT_RL).toInt()); rl_box.update_value(get_value(VAL_TT_RL).toInt());
rr_box.update_value(get_value(VAL_TT_RR).toInt()); rr_box.update_value(get_value(VAL_TT_RR).toInt());
//Vehicle_data.autoshift = true; //For testing only!!
if(Vehicle_data.autoshift == true){
tft.setTextColor(EA_ORANGE, EA_TRANSPARENT);
}
gear_box.update_value(get_value(VAL_GEAR));
} }
void redraw_view_testing() { void redraw_view_testing() {

View File

@ -46,8 +46,9 @@ enum Value {
VAL_SPEED_FL, VAL_SPEED_FL,
VAL_SPEED_FR, VAL_SPEED_FR,
VAL_SPEED, VAL_SPEED,
VAL_BBAL,
VAL_FIRST_LEFT_BOX = VAL_LAPTIME, VAL_FIRST_LEFT_BOX = VAL_LAPTIME,
VAL_LAST = VAL_SPEED VAL_LAST = VAL_BBAL
}; };
String get_value(Value val); String get_value(Value val);
String get_label(Value val); String get_label(Value val);
@ -94,7 +95,7 @@ protected:
#define TT_COL1 EA_GREEN #define TT_COL1 EA_GREEN
#define TT_COL2 EA_ORANGE #define TT_COL2 EA_ORANGE
#define TT_COL3 EA_RED #define TT_COL3 EA_RED
#define TT_THRESH1 50 #define TT_THRESH1 40
#define TT_THRESH2 60 #define TT_THRESH2 60
#define TT_THRESH3 70 #define TT_THRESH3 70

View File

@ -48,8 +48,11 @@ void read_buttons() {
// These are only used to send them out via CAN, so they only need to be // These are only used to send them out via CAN, so they only need to be
// high once. // high once.
Stw_data.Stw_neutral = debouncer[1].rose(); //Stw_data.Stw_neutral = debouncer[1].rose();
Stw_data.Stw_auto_shift = debouncer[2].rose(); //Stw_data.Stw_auto_shift = debouncer[2].isPressed(); //Hold to open DRS
// 05.09.: swapped neutral and auto_shift (DRS)
Stw_data.Stw_neutral = debouncer[2].rose();
Stw_data.Stw_auto_shift = debouncer[1].isPressed(); //Hold to open DRS
Stw_data.Stw_shift_down = debouncer[4].rose(); Stw_data.Stw_shift_down = debouncer[4].rose();
Stw_data.Stw_shift_up = debouncer[5].rose(); Stw_data.Stw_shift_up = debouncer[5].rose();

View File

@ -33,16 +33,16 @@
#define enc2PinS 39 #define enc2PinS 39
// define Drehzahlgrenzen TODOOOO // define Drehzahlgrenzen TODOOOO
#define RPM_THRES_1 1000 #define RPM_THRES_1 6000
#define RPM_THRES_2 6000 #define RPM_THRES_2 12000
#define RPM_THRES_3 7000 #define RPM_THRES_3 12800
#define RPM_THRES_4 8000 #define RPM_THRES_4 13600
#define RPM_THRES_5 10000 #define RPM_THRES_5 14400
#define RPM_THRES_6 14000 #define RPM_THRES_6 15200
#define RPM_THRES_7 17000 #define RPM_THRES_7 16000
#define RPM_THRES_8 18000 #define RPM_THRES_8 16800
#define RPM_THRES_9 20000 #define RPM_THRES_9 18000
#define RPM_THRES_10 20000 #define RPM_THRES_10 18000
void set_pins(void); void set_pins(void);
void read_buttons(void); void read_buttons(void);
@ -88,6 +88,8 @@ typedef struct {
uint8_t t_trr; // Tire temp rear right uint8_t t_trr; // Tire temp rear right
uint8_t u_batt; // Batteriespannung uint8_t u_batt; // Batteriespannung
uint8_t rev_lim; // Drehzahllimit Bit uint8_t rev_lim; // Drehzahllimit Bit
bool drs_active; // DRS status from BCU
bool autoshift; // Autoshift status from BCU
uint8_t p_wat; uint8_t p_wat;
uint8_t p_fuel; uint8_t p_fuel;
uint8_t p_oil; uint8_t p_oil;

View File

@ -85,6 +85,7 @@ void update_display() {
clearcounter += 1; clearcounter += 1;
} }
} }
// else für neue init?
} }
void display_mode() { void display_mode() {

View File

@ -11,10 +11,12 @@ FT_2018_STW_CAN.cpp
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, int leds[] = {led1, led2, led3, led4, led5, led6, led7, led8,
led9, led10, led11, led12, led13, led14, led15, led16}; 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 Can0.setNumTXBoxes(1); // reserves mailbox 0 for tx only 8 mailboxes are
// available (the other 7 mailboxes are for rx) // available (the other 7 mailboxes are for rx)
@ -23,8 +25,9 @@ void Init_Can_0() {
// allow us to receive BCU_APS_BRAKE, BCU_ETC and BCU_SHIFT_CTRL in the same // allow us to receive BCU_APS_BRAKE, BCU_ETC and BCU_SHIFT_CTRL in the same
// mailbox. It will also let through 0x506, but that shouldn't be much of an // mailbox. It will also let through 0x506, but that shouldn't be much of an
// issue. // issue.
/*
Can0.watchFor(CAN_ID_BCU_APS_BRAKE & CAN_ID_BCU_ETC & CAN_ID_BCU_SHIFT_CTRL, Can0.watchFor(CAN_ID_BCU_APS_BRAKE & CAN_ID_BCU_ETC & CAN_ID_BCU_SHIFT_CTRL,
0x7FC); 0x7F9);
Can0.watchFor(CAN_ID_BCU_TIRES); Can0.watchFor(CAN_ID_BCU_TIRES);
Can0.watchFor(CAN_ID_BCU_LAP_TIME); Can0.watchFor(CAN_ID_BCU_LAP_TIME);
Can0.watchFor(CAN_ID_MS4_IGN_REV_ATH); Can0.watchFor(CAN_ID_MS4_IGN_REV_ATH);
@ -33,6 +36,7 @@ void Init_Can_0() {
Can0.watchFor(CAN_ID_MS4_STATES_TEMP_PRESS); Can0.watchFor(CAN_ID_MS4_STATES_TEMP_PRESS);
Can0.setGeneralCallback(Receive_Can_0); Can0.setGeneralCallback(Receive_Can_0);
*/
Timer3.attachInterrupt(Send_0x110); // set send interrupt Timer3.attachInterrupt(Send_0x110); // set send interrupt
Timer3.start(10000); // Calls every 10ms Timer3.start(10000); // Calls every 10ms
@ -71,6 +75,8 @@ void Receive_Can_0(CAN_FRAME *temp_message) {
case CAN_ID_BCU_APS_BRAKE: { case CAN_ID_BCU_APS_BRAKE: {
Vehicle_data.p_brake_front = temp_message->data.byte[1]; Vehicle_data.p_brake_front = temp_message->data.byte[1];
Vehicle_data.p_brake_rear = temp_message->data.byte[2]; Vehicle_data.p_brake_rear = temp_message->data.byte[2];
Vehicle_data.drs_active = ((temp_message->data.byte[0] >> 7) & 0b00000001);
Vehicle_data.autoshift = ((temp_message->data.byte[7] >> 0) & 0b00000001);
break; break;
} }
case CAN_ID_BCU_ETC: { // eDrossel error bit case CAN_ID_BCU_ETC: { // eDrossel error bit
@ -138,6 +144,7 @@ void Receive_Can_0(CAN_FRAME *temp_message) {
} }
} }
void update_LED() { void update_LED() {
// Copyright Michael Dietzel // Copyright Michael Dietzel
// m.dietzel@fasttube.de // m.dietzel@fasttube.de
@ -154,13 +161,46 @@ void update_LED() {
((Vehicle_data.t_mot - 40) >= 0x69) and ((Vehicle_data.t_mot - 40) >= 0x69) and
((Vehicle_data.t_mot - 40) != 0xC8); // 105°C temp.water und !=200 ((Vehicle_data.t_mot - 40) != 0xC8); // 105°C temp.water und !=200
bool g_auto = Vehicle_data.g_auto; bool g_auto = Vehicle_data.drs_active;
bool u_batt = Vehicle_data.u_batt <= 0xA9; // 11.95V batt.spann. bool u_batt = Vehicle_data.u_batt <= 0xA9; // 11.95V batt.spann.
bool e_dros = Vehicle_data.e_thro; // error-bit bool e_dros = Vehicle_data.e_thro; // error-bit
bool rev_lim = Vehicle_data.rev_lim; bool rev_lim = Vehicle_data.rev_lim;
uint16_t rev = Vehicle_data.revol; uint16_t rev = Vehicle_data.revol;
//uint16_t clearcounter = 1;
// if (clearcounter>= 5000){
//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)
// We only have 7 mailboxes, but want to receive 9 messages. This trick should
// allow us to receive BCU_APS_BRAKE, BCU_ETC and BCU_SHIFT_CTRL in the same
// mailbox. It will also let through 0x506, but that shouldn't be much of an
// issue.
/* 10.09.2024 - auskommentiert, weil wieso hier nochmal watchfor? */
Can0.watchFor(CAN_ID_BCU_APS_BRAKE & CAN_ID_BCU_ETC & CAN_ID_BCU_SHIFT_CTRL, 0x7F9);
Can0.watchFor(CAN_ID_BCU_TIRES);
Can0.watchFor(CAN_ID_BCU_LAP_TIME);
Can0.watchFor(CAN_ID_MS4_IGN_REV_ATH);
Can0.watchFor(CAN_ID_MS4_SPEED);
Can0.watchFor(CAN_ID_MS4_ETC);
Can0.watchFor(CAN_ID_MS4_STATES_TEMP_PRESS);
//Can0.setGeneralCallback(Receive_Can_0);
//Timer3.attachInterrupt(Send_0x110); // set send interrupt
// Timer3.start(10000); // Calls every 10ms
// clearcounter = 0; //clearen des display nach definierter Zeit
// }
// clearcounter+=1;
/*if(Vehicle_data.rev_lim){ /*if(Vehicle_data.rev_lim){
for (int j = 0; j < 10; j++){ for (int j = 0; j < 10; j++){