Compare commits
No commits in common. "d362fdd639ea8e1698cbb62d4023943bba249c69" and "c8e94175d13ff688569406de09efc865bda6f6fc" have entirely different histories.
d362fdd639
...
c8e94175d1
6
.vscode/extensions.json
vendored
6
.vscode/extensions.json
vendored
@ -2,9 +2,7 @@
|
|||||||
// 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",
|
||||||
],
|
|
||||||
"unwantedRecommendations": [
|
|
||||||
"ms-vscode.cpptools-extension-pack"
|
"ms-vscode.cpptools-extension-pack"
|
||||||
]
|
],
|
||||||
}
|
}
|
||||||
|
@ -22,18 +22,16 @@ String bezeichnungen[] = {"T_mot", "T_oil", "P_oil", "% fa",
|
|||||||
int led_s[] = {led1, led2, led3, led4, led5, led6, led7, led8,
|
int led_s[] = {led1, led2, led3, led4, led5, led6, led7, led8,
|
||||||
led9, led10, led11, led12, led13, led14, led15, led16};
|
led9, led10, led11, led12, led13, led14, led15, led16};
|
||||||
|
|
||||||
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');
|
||||||
DataBox left_box(0, 25, 119, 94, 110, 25, EA_FONT6X8, 3, 8, 'R', false);
|
DataBox left_box(0, 0, 119, 94, 110, 12, EA_FONT7X12, 3, 8, 'R');
|
||||||
DataBox right_box(201, 25, 320, 94, 310, 25, EA_FONT6X8, 3, 8, 'R', false);
|
DataBox right_box(201, 0, 320, 94, 310, 12, EA_FONT7X12, 3, 8, 'R');
|
||||||
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);
|
||||||
@ -57,7 +55,6 @@ 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) {
|
||||||
@ -116,15 +113,6 @@ 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 "???";
|
||||||
}
|
}
|
||||||
@ -172,8 +160,6 @@ 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 "???";
|
||||||
}
|
}
|
||||||
@ -192,8 +178,7 @@ 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;
|
||||||
@ -256,18 +241,8 @@ void update_display() {
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
if (tft.disconnected) {
|
if (tft.disconnected) {
|
||||||
uint32_t now = millis();
|
|
||||||
if (now - last_cleared < 1000) {
|
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
digitalWrite(reset, LOW);
|
|
||||||
delay(100);
|
|
||||||
digitalWrite(reset, HIGH);
|
|
||||||
tft.disconnected = false;
|
|
||||||
tft.clear();
|
|
||||||
cleared = true;
|
|
||||||
last_cleared = now;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (check_enc_displays()) {
|
if (check_enc_displays()) {
|
||||||
cleared = true;
|
cleared = true;
|
||||||
@ -283,6 +258,7 @@ void update_display() {
|
|||||||
Stw_data.button4_rises = 0;
|
Stw_data.button4_rises = 0;
|
||||||
view = (DisplayView)((view + 1) % (VIEW_LAST + 1));
|
view = (DisplayView)((view + 1) % (VIEW_LAST + 1));
|
||||||
tft.clear();
|
tft.clear();
|
||||||
|
last_cleared = now;
|
||||||
cleared = true;
|
cleared = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -301,35 +277,6 @@ 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) {
|
||||||
@ -380,7 +327,6 @@ 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();
|
||||||
@ -388,7 +334,6 @@ 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--;
|
||||||
@ -409,36 +354,13 @@ void update_view_driver() {
|
|||||||
left_box.update_label(get_label(left_box_value));
|
left_box.update_label(get_label(left_box_value));
|
||||||
}
|
}
|
||||||
|
|
||||||
// These can change rapidly, which would lead to a lot of flickering if
|
gear_box.update_value(get_value(VAL_GEAR));
|
||||||
// rendered in the clear-redraw method. So instead, they're simply overwritten
|
left_box.update_value(get_value(left_box_value));
|
||||||
// with a black background.
|
right_box.update_value(get_value(VAL_RPM));
|
||||||
tft.setTextColor(EA_WHITE, EA_BLACK);
|
|
||||||
left_box.update_value(pad_left(get_value(left_box_value), 5));
|
|
||||||
right_box.update_value(pad_left(get_value(VAL_RPM), 5));
|
|
||||||
// Vehicle_data.autoshift = true;
|
|
||||||
if(Vehicle_data.autoshift == true){
|
|
||||||
tft.drawRectf(164+100, 184, 240+100, 230, TT_COL3);
|
|
||||||
}
|
|
||||||
else{
|
|
||||||
tft.drawRectf(164+100, 184, 240+100, 230, EA_BLACK);
|
|
||||||
}
|
|
||||||
autoshift_box.update_value(pad_left(String(Vehicle_data.autoshift), 5));
|
|
||||||
|
|
||||||
// These don't change as rapidly, and would overwrite adjacent elements
|
|
||||||
// (lines/labels) if rendered with a background because of the empty pixels
|
|
||||||
// above/below the characters. So they're rendered using the clear-redraw
|
|
||||||
// method.0
|
|
||||||
tft.setTextColor(EA_WHITE, EA_TRANSPARENT);
|
|
||||||
//gear_box.update_value(get_value(VAL_GEAR));
|
|
||||||
fl_box.update_value(get_value(VAL_TT_FL).toInt());
|
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() {
|
||||||
@ -506,11 +428,10 @@ void update_value_testing(int i) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
DataBox::DataBox(int x1, int y1, int x2, int y2, int text_x, int text_y,
|
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,
|
int font, int size_x, int size_y, uint8_t justification)
|
||||||
bool do_clear)
|
|
||||||
: x1{x1}, y1{y1}, x2{x2}, y2{y2}, text_x{text_x}, text_y{text_y},
|
: 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},
|
font{font}, size_x{size_x}, size_y{size_y},
|
||||||
justification{justification}, do_clear{do_clear}, value{""}, label{""} {}
|
justification{justification}, value{""}, label{""} {}
|
||||||
|
|
||||||
void DataBox::update_value(String val_new) {
|
void DataBox::update_value(String val_new) {
|
||||||
if (!val_new.equals(value)) {
|
if (!val_new.equals(value)) {
|
||||||
@ -535,9 +456,7 @@ void DataBox::redraw_value() {
|
|||||||
tft.setTextFont(font);
|
tft.setTextFont(font);
|
||||||
tft.setTextSize(size_x, size_y);
|
tft.setTextSize(size_x, size_y);
|
||||||
Serial.println("Redrawing value:");
|
Serial.println("Redrawing value:");
|
||||||
if (do_clear) {
|
|
||||||
tft.clearRect(x1, y1, x2, y2);
|
tft.clearRect(x1, y1, x2, y2);
|
||||||
}
|
|
||||||
tft.drawText(text_x, text_y, justification, value.c_str());
|
tft.drawText(text_x, text_y, justification, value.c_str());
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -553,8 +472,7 @@ TireTempBox::TireTempBox(int x1, int y1, int x2, int y2, int text_x, int text_y,
|
|||||||
int font, int size_x, int size_y,
|
int font, int size_x, int size_y,
|
||||||
uint8_t justification)
|
uint8_t justification)
|
||||||
: DataBox{x1, y1, x2, y2, text_x,
|
: DataBox{x1, y1, x2, y2, text_x,
|
||||||
text_y, font, size_x, size_y, justification,
|
text_y, font, size_x, size_y, justification},
|
||||||
false},
|
|
||||||
num_value{-1} {}
|
num_value{-1} {}
|
||||||
|
|
||||||
void TireTempBox::update_value(int val_new) {
|
void TireTempBox::update_value(int val_new) {
|
||||||
|
@ -46,9 +46,8 @@ 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_BBAL
|
VAL_LAST = VAL_SPEED
|
||||||
};
|
};
|
||||||
String get_value(Value val);
|
String get_value(Value val);
|
||||||
String get_label(Value val);
|
String get_label(Value val);
|
||||||
@ -74,7 +73,7 @@ void update_value_testing(int i);
|
|||||||
class DataBox {
|
class DataBox {
|
||||||
public:
|
public:
|
||||||
DataBox(int x1, int y1, int x2, int y2, int text_x, int text_y, int font,
|
DataBox(int x1, int y1, int x2, int y2, int text_x, int text_y, int font,
|
||||||
int size_x, int size_y, uint8_t justification, bool do_clear);
|
int size_x, int size_y, uint8_t justification);
|
||||||
|
|
||||||
void update_value(String val_new);
|
void update_value(String val_new);
|
||||||
void update_label(String label_new);
|
void update_label(String label_new);
|
||||||
@ -86,7 +85,6 @@ public:
|
|||||||
protected:
|
protected:
|
||||||
int x1, y1, x2, y2, text_x, text_y, font, size_x, size_y;
|
int x1, y1, x2, y2, text_x, text_y, font, size_x, size_y;
|
||||||
uint8_t justification;
|
uint8_t justification;
|
||||||
bool do_clear;
|
|
||||||
String value;
|
String value;
|
||||||
String label;
|
String label;
|
||||||
};
|
};
|
||||||
@ -95,7 +93,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 40
|
#define TT_THRESH1 50
|
||||||
#define TT_THRESH2 60
|
#define TT_THRESH2 60
|
||||||
#define TT_THRESH3 70
|
#define TT_THRESH3 70
|
||||||
|
|
||||||
|
@ -48,11 +48,8 @@ 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].isPressed(); //Hold to open DRS
|
Stw_data.Stw_auto_shift = debouncer[2].rose();
|
||||||
// 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 6000
|
#define RPM_THRES_1 1000
|
||||||
#define RPM_THRES_2 12000
|
#define RPM_THRES_2 6000
|
||||||
#define RPM_THRES_3 12800
|
#define RPM_THRES_3 7000
|
||||||
#define RPM_THRES_4 13600
|
#define RPM_THRES_4 8000
|
||||||
#define RPM_THRES_5 14400
|
#define RPM_THRES_5 10000
|
||||||
#define RPM_THRES_6 15200
|
#define RPM_THRES_6 14000
|
||||||
#define RPM_THRES_7 16000
|
#define RPM_THRES_7 17000
|
||||||
#define RPM_THRES_8 16800
|
#define RPM_THRES_8 18000
|
||||||
#define RPM_THRES_9 18000
|
#define RPM_THRES_9 20000
|
||||||
#define RPM_THRES_10 18000
|
#define RPM_THRES_10 20000
|
||||||
|
|
||||||
void set_pins(void);
|
void set_pins(void);
|
||||||
void read_buttons(void);
|
void read_buttons(void);
|
||||||
@ -88,8 +88,6 @@ 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;
|
||||||
|
@ -85,7 +85,6 @@ void update_display() {
|
|||||||
clearcounter += 1;
|
clearcounter += 1;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
// else für neue init?
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void display_mode() {
|
void display_mode() {
|
||||||
|
@ -11,12 +11,10 @@ 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)
|
||||||
@ -25,9 +23,8 @@ 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);
|
0x7FC);
|
||||||
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);
|
||||||
@ -36,7 +33,6 @@ 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
|
||||||
@ -75,8 +71,6 @@ 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
|
||||||
@ -115,7 +109,7 @@ void Receive_Can_0(CAN_FRAME *temp_message) {
|
|||||||
}
|
}
|
||||||
case CAN_ID_MS4_IGN_REV_ATH: { // rpm
|
case CAN_ID_MS4_IGN_REV_ATH: { // rpm
|
||||||
Vehicle_data.revol =
|
Vehicle_data.revol =
|
||||||
(temp_message->data.byte[4] | temp_message->data.byte[3] << 8);
|
(temp_message->data.byte[5] | temp_message->data.byte[4] << 8);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case CAN_ID_MS4_SPEED: { // speed
|
case CAN_ID_MS4_SPEED: { // speed
|
||||||
@ -144,7 +138,6 @@ 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
|
||||||
@ -161,46 +154,13 @@ 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.drs_active;
|
bool g_auto = Vehicle_data.g_auto;
|
||||||
bool u_batt = Vehicle_data.u_batt <= 0xA9; // 11.95V batt.spann.
|
bool u_batt = Vehicle_data.u_batt <= 0xB1; // 12.5V 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++){
|
||||||
|
Loading…
x
Reference in New Issue
Block a user