TEDü Getac Changes
This commit is contained in:
parent
661e1a2274
commit
d362fdd639
|
@ -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"
|
||||||
|
]
|
||||||
}
|
}
|
||||||
|
|
|
@ -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) {
|
||||||
|
@ -298,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) {
|
||||||
|
@ -348,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();
|
||||||
|
@ -355,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--;
|
||||||
|
@ -381,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() {
|
||||||
|
|
|
@ -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();
|
||||||
|
|
||||||
|
|
|
@ -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);
|
||||||
|
@ -89,6 +89,7 @@ typedef struct {
|
||||||
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 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;
|
||||||
|
|
|
@ -85,6 +85,7 @@ void update_display() {
|
||||||
clearcounter += 1;
|
clearcounter += 1;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
// else für neue init?
|
||||||
}
|
}
|
||||||
|
|
||||||
void display_mode() {
|
void display_mode() {
|
||||||
|
|
|
@ -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,6 +25,7 @@ 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,
|
||||||
0x7F9);
|
0x7F9);
|
||||||
Can0.watchFor(CAN_ID_BCU_TIRES);
|
Can0.watchFor(CAN_ID_BCU_TIRES);
|
||||||
|
@ -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
|
||||||
|
@ -72,6 +76,7 @@ void Receive_Can_0(CAN_FRAME *temp_message) {
|
||||||
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.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
|
||||||
|
@ -139,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
|
||||||
|
@ -162,6 +168,39 @@ void update_LED() {
|
||||||
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++){
|
||||||
|
|
Loading…
Reference in New Issue