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;
};
enum class FaultType {
HardFault, MemManage, BusFault, UsageFault
};
enum class FaultType { HardFault, MemManage, BusFault, UsageFault };
struct FlashDump {
FaultType type;
@ -43,22 +41,23 @@ const FlashDump *flash_dump_get_fault(uint32_t n);
void uart_wait_for_txrdy();
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);
void print_dumped_faults(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_dumped_faults(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);
FaultStatusRegisters get_current_fsr();
const char* get_fault_type_name(FaultType type);
void fault_handler(uint32_t *stack_addr, FaultType fault_type,
const int *leds, unsigned n_leds);
const char *get_fault_type_name(FaultType type);
void fault_handler(uint32_t *stack_addr, FaultType fault_type, const int *leds,
unsigned n_leds);
void inline busy_wait(size_t iterations) {
for (size_t i = 0; i < iterations; i++) {
// Does nothing, but ensures the compiler doesn't optimize the loop away.
__ASM ("" ::: "memory");
__ASM("" ::: "memory");
}
}

View File

@ -1,14 +1,17 @@
#include "FT18_STW_DISPLAY.h"
#include "Arduino.h"
#include "EDIPTFT.h"
#include "FT_2018_STW_CAN.h"
#include "FT18_STW_INIT.h"
#include "FT18_STW_DISPLAY.h"
#include "FT_2018_STW_CAN.h"
EDIPTFT tft(true,false);
String bezeichnungen[]={"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"};
EDIPTFT tft(true, false);
String bezeichnungen[] = {"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"};
//"Drehzahl","P_fuel","Index"
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,
led9, led10, led11, led12, led13, led14, led15, led16};
DataBox gear_box(121, 0, 199, 94, 160, 0, EA_SWISS30B, 4, 4, 'C');
DataBox left_box(0, 0, 119, 94, 110, 12, EA_FONT7X12, 3, 8, 'R');
@ -29,13 +32,13 @@ void init_display() {
digitalWrite(MOSI, HIGH);
digitalWrite(MISO, HIGH);
digitalWrite(reset, LOW);
digitalWrite(reset,HIGH);
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.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));
@ -73,9 +76,9 @@ String get_value(Value val) {
case VAL_ERR_TYPE:
return String(Stw_data.error_type);
case VAL_PWAT:
return String(0.0514*Vehicle_data.p_wat, 2);
return String(0.0514 * Vehicle_data.p_wat, 2);
case VAL_POIL:
return String(0.0514*Vehicle_data.p_oil, 2);
return String(0.0514 * Vehicle_data.p_oil, 2);
case VAL_PBF:
return String(Vehicle_data.p_brake_front);
case VAL_PBR:
@ -142,7 +145,8 @@ bool check_alarms() {
if (Vehicle_data.p_oil >= POIL_ALARM_THRESH || Vehicle_data.speed == 0) {
poil_last_valid = now;
}
if (Vehicle_data.t_mot <= TMOT_ALARM_THRESH || Vehicle_data.t_mot == TMOT_SAFE_VALUE) {
if (Vehicle_data.t_mot <= TMOT_ALARM_THRESH ||
Vehicle_data.t_mot == TMOT_SAFE_VALUE) {
tmot_last_valid = now;
}
if (Vehicle_data.t_oil <= TOIL_ALARM_THRESH) {
@ -155,9 +159,12 @@ bool check_alarms() {
if (alarm_active) {
String alarm_text = "";
if (poil_alarm) alarm_text += "PO";
if (tmot_alarm) alarm_text += "TM";
if (toil_alarm) alarm_text += "TO";
if (poil_alarm)
alarm_text += "PO";
if (tmot_alarm)
alarm_text += "TM";
if (toil_alarm)
alarm_text += "TO";
alarm(alarm_text);
}
@ -169,11 +176,14 @@ bool check_enc_displays() {
static bool display_trc, display_mode;
static uint32_t display_trc_begin, display_mode_begin;
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");
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_display(uint8_t& val_old, uint8_t val_new, bool& active, uint32_t& begin, const String& title) {
bool check_display(uint8_t& val_old, uint8_t val_new, bool& active,
uint32_t& begin, const String& title) {
if (val_old != val_new) {
active = true;
begin = millis();
@ -181,7 +191,7 @@ bool check_display(uint8_t& val_old, uint8_t val_new, bool& active, uint32_t& be
tft.clear();
tft.fillDisplayColor(EA_RED);
tft.setTextColor(EA_WHITE, EA_RED);
tft.setTextSize(7,8);
tft.setTextSize(7, 8);
String text = title + ":" + val_new;
char text_arr[16];
text.toCharArray(text_arr, 16);
@ -195,7 +205,7 @@ bool check_display(uint8_t& val_old, uint8_t val_new, bool& active, uint32_t& be
return active;
}
void update_display(){
void update_display() {
static DisplayPage page = PAGE_DRIVER;
static uint32_t last_cleared;
static bool cleared = true;
@ -217,10 +227,10 @@ void update_display(){
// 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 (Stw_data.buttonState1 && Stw_data.buttonState4 &&
(Stw_data.button1_rises > 0|| Stw_data.button4_rises > 0)){
(Stw_data.button1_rises > 0 || Stw_data.button4_rises > 0)) {
Stw_data.button1_rises = 0;
Stw_data.button4_rises = 0;
page = (DisplayPage) ((page + 1) % DISPLAY_PAGES);
page = (DisplayPage)((page + 1) % DISPLAY_PAGES);
tft.clear();
last_cleared = now;
cleared = true;
@ -249,33 +259,34 @@ void update_display(){
}
}
void alarm(String textstr){
uint8_t x = 1;;
void alarm(String textstr) {
uint8_t x = 1;
;
char text[7];
textstr.toCharArray(text,7);
tft.setTextSize(8,8);
while(x==1){
if(!tft.disconnected){
tft.setTextColor(EA_BLACK,EA_RED);
textstr.toCharArray(text, 7);
tft.setTextSize(8, 8);
while (x == 1) {
if (!tft.disconnected) {
tft.setTextColor(EA_BLACK, EA_RED);
tft.fillDisplayColor(EA_RED);
tft.drawText(5,68,'L',text);
tft.drawText(5, 68, 'L', text);
}
for (int j = 0; j < 16; j++){
for (int j = 0; j < 16; j++) {
digitalWrite(led_s[j], HIGH);
}
delay(100);
if(!tft.disconnected){
tft.setTextColor(EA_BLACK,EA_WHITE);
if (!tft.disconnected) {
tft.setTextColor(EA_BLACK, EA_WHITE);
tft.fillDisplayColor(EA_WHITE);
tft.drawText(5,68,'L',text);
tft.drawText(5, 68, 'L', text);
}
for (int j = 0; j < 16; j++){
for (int j = 0; j < 16; j++) {
digitalWrite(led_s[j], LOW);
}
delay(100);
if(Stw_data.buttonState1 & Stw_data.buttonState4){
x=0;
tft.setTextColor(EA_WHITE,EA_TRANSPARENT);
if (Stw_data.buttonState1 & Stw_data.buttonState4) {
x = 0;
tft.setTextColor(EA_WHITE, EA_TRANSPARENT);
}
}
}
@ -307,15 +318,16 @@ void update_page_driver() {
if (left_box_value == VAL_LAST) {
left_box_value = VAL_FIRST_LEFT_BOX;
} else {
left_box_value = (Value) (left_box_value + 1);
left_box_value = (Value)(left_box_value + 1);
}
left_box.update_label(get_label(left_box_value));
}
if (Stw_data.button1_rises > 0) {
Stw_data.button1_rises--;
if (left_box_value == VAL_FIRST_LEFT_BOX) {
left_box_value = VAL_LAST;
} else {
left_box_value = (Value) (left_box_value - 1);
left_box_value = (Value)(left_box_value - 1);
}
left_box.update_label(get_label(left_box_value));
}
@ -330,13 +342,27 @@ void update_page_driver() {
}
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() {}
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)
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{""} {}
@ -377,8 +403,11 @@ void DataBox::redraw_label() {
}
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} {}
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) {

View File

@ -1,7 +1,7 @@
#include "Arduino.h"
#include "EDIPTFT.h"
#include "FT_2018_STW_CAN.h"
#include "FT18_STW_INIT.h"
#include "FT_2018_STW_CAN.h"
#ifndef FT18_STW_DISPLAY_h
#define FT18_STW_DISPLAY_h
@ -12,8 +12,7 @@
#define reset 43
#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 TMOT_ALARM_THRESH (40 + 105)
#define TMOT_SAFE_VALUE (40 + 200)
@ -22,14 +21,31 @@
#define TOIL_ALARM_TIME 10000 // ms
#define ENC_DISPLAY_TIME 1000 // ms
enum DisplayPage {PAGE_DRIVER, PAGE_TESTING};
enum DisplayPage { PAGE_DRIVER, PAGE_TESTING };
#define DISPLAY_PAGES 2
enum Value {
VAL_GEAR, VAL_RPM, VAL_TT_FL, VAL_TT_FR, VAL_TT_RL, VAL_TT_RR, VAL_LAPTIME,
VAL_UBATT, VAL_TMOT, VAL_TAIR, VAL_TOIL, VAL_ERR_TYPE, VAL_PWAT, VAL_POIL,
VAL_PBF, VAL_PBR, VAL_SPEED_FL, VAL_SPEED_FR, VAL_SPEED,
VAL_FIRST_LEFT_BOX = VAL_LAPTIME, VAL_LAST = VAL_SPEED
VAL_GEAR,
VAL_RPM,
VAL_TT_FL,
VAL_TT_FR,
VAL_TT_RL,
VAL_TT_RR,
VAL_LAPTIME,
VAL_UBATT,
VAL_TMOT,
VAL_TAIR,
VAL_TOIL,
VAL_ERR_TYPE,
VAL_PWAT,
VAL_POIL,
VAL_PBF,
VAL_PBR,
VAL_SPEED_FL,
VAL_SPEED_FR,
VAL_SPEED,
VAL_FIRST_LEFT_BOX = VAL_LAPTIME,
VAL_LAST = VAL_SPEED
};
String get_value(Value val);
String get_label(Value val);
@ -44,7 +60,8 @@ void alarm(String text);
bool check_alarms();
bool check_enc_displays();
bool check_display(uint8_t& val_old, uint8_t val_new, bool& active, uint32_t& begin, const String& title);
bool check_display(uint8_t& val_old, uint8_t val_new, bool& active,
uint32_t& begin, const String& title);
void redraw_page_driver();
void update_page_driver();
@ -80,8 +97,8 @@ protected:
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);
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);

View File

@ -4,42 +4,44 @@
#include <Bounce2.h>
#include <RotaryEncoder.h>
volatile stw_data_type Stw_data = {0}; //alles mit 0 initialisieren
volatile vehicle_data_type Vehicle_data = {0}; //alles mit 0 initialisieren
bool enc1PinALast,enc1PinANow,enc2PinALast,enc2PinANow;
int led[] = {led1,led2,led3,led4,led5,led6,led7,led8,led9,led10,led11,led12,led13,led14,led15,led16};
volatile stw_data_type Stw_data = {0}; // alles mit 0 initialisieren
volatile vehicle_data_type Vehicle_data = {0}; // alles mit 0 initialisieren
bool enc1PinALast, enc1PinANow, enc2PinALast, enc2PinANow;
int led[] = {led1, led2, led3, led4, led5, led6, led7, led8,
led9, led10, led11, led12, led13, led14, led15, led16};
bool entprell;
int buttons[] = {button1,button2,button3,button4,button5,button6,enc1PinS,enc2PinS};
constexpr size_t N_BUTTONS = sizeof(buttons)/sizeof(buttons[0]);
int buttons[] = {button1, button2, button3, button4,
button5, button6, enc1PinS, enc2PinS};
constexpr size_t N_BUTTONS = sizeof(buttons) / sizeof(buttons[0]);
Bounce2::Button debouncer[N_BUTTONS];
double val = 0;
double val2 = 0;
RotaryEncoder encoder(enc1PinA,enc1PinB,1,1,50);
RotaryEncoder encoder2(enc2PinA,enc2PinB,1,1,50);
RotaryEncoder encoder(enc1PinA, enc1PinB, 1, 1, 50);
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(l, OUTPUT);
for (int thisLed = 0; thisLed < sizeof(led) / sizeof(int); thisLed++) {
pinMode(led[thisLed], OUTPUT);
}
pinMode(enc1PinA, INPUT);
pinMode(enc1PinB, INPUT);
pinMode(enc2PinA, INPUT);
pinMode(enc2PinB, INPUT);
enc1PinALast=LOW;
enc1PinANow=LOW;
enc2PinALast=LOW;
enc2PinANow=LOW;
for(int i = 0; i < N_BUTTONS; i++){
enc1PinALast = LOW;
enc1PinANow = LOW;
enc2PinALast = LOW;
enc2PinANow = LOW;
for (int i = 0; i < N_BUTTONS; i++) {
debouncer[i].attach(buttons[i], INPUT);
debouncer[i].interval(10);
}
}
void read_buttons(){
void read_buttons() {
for (int i = 0; i < N_BUTTONS; i++) {
debouncer[i].update();
}
@ -69,17 +71,17 @@ void read_buttons(){
}
}
void read_rotary(){
void read_rotary() {
int enc = encoder.readEncoder();
int enc2 = encoder2.readEncoder();
if(enc != 0){
val = val +0.5*enc;
if (val==1 or val ==-1){
if(Stw_data.trc==0 and enc<0){
if (enc != 0) {
val = val + 0.5 * enc;
if (val == 1 or val == -1) {
if (Stw_data.trc == 0 and enc < 0) {
Stw_data.trc = 11;
}else if(Stw_data.trc==11 and enc>0){
Stw_data.trc=0;
}else{
} else if (Stw_data.trc == 11 and enc > 0) {
Stw_data.trc = 0;
} else {
Stw_data.trc = Stw_data.trc + enc;
}
val = 0;
@ -106,17 +108,17 @@ void read_rotary(){
/*if (Stw_data.buttonStateEnc1 == HIGH){
digitalWrite(led[Stw_data.i], HIGH);
}*/
if(enc2 != 0){
val2 = val2 +0.5*enc2;
if(val2==1 or val2==-1){
if((Stw_data.mode==1 or Stw_data.mode==0) and enc2<0){
if (enc2 != 0) {
val2 = val2 + 0.5 * enc2;
if (val2 == 1 or val2 == -1) {
if ((Stw_data.mode == 1 or Stw_data.mode == 0) and enc2 < 0) {
Stw_data.mode = 5;
}else if(Stw_data.mode==5 and enc2>0){
Stw_data.mode=1;
}else{
} else if (Stw_data.mode == 5 and enc2 > 0) {
Stw_data.mode = 1;
} else {
Stw_data.mode = Stw_data.mode + enc2;
}
val2=0;
val2 = 0;
}
}
/*if ((enc2PinALast == LOW) && (enc2PinANow == HIGH)) {

View File

@ -2,29 +2,29 @@
#ifndef FT18_STW_Init
#define FT18_STW_Init
#define l 78 //test_led
#define led1 12//PD8
#define led2 11//PD7
#define led3 9//PC21
#define led4 8//PC22
#define led5 7//PC23
#define led6 6//PC24
#define led7 5//PC25
#define led8 4//PC26 und PA29
#define led9 3//PC28
#define led10 2//PB25
#define led11 10//PC29 und PA28
#define led12 22//PB26
#define led13 19//PA10
#define led14 13//PB27
#define led15 17//PA12
#define led16 18//PA11
#define button1 48//bl
#define button2 47//gl
#define button3 44//gr
#define button4 46//br
#define button5 45//sl
#define button6 49//sr
#define l 78 // test_led
#define led1 12 // PD8
#define led2 11 // PD7
#define led3 9 // PC21
#define led4 8 // PC22
#define led5 7 // PC23
#define led6 6 // PC24
#define led7 5 // PC25
#define led8 4 // PC26 und PA29
#define led9 3 // PC28
#define led10 2 // PB25
#define led11 10 // PC29 und PA28
#define led12 22 // PB26
#define led13 19 // PA10
#define led14 13 // PB27
#define led15 17 // PA12
#define led16 18 // PA11
#define button1 48 // bl
#define button2 47 // gl
#define button3 44 // gr
#define button4 46 // br
#define button5 45 // sl
#define button6 49 // sr
#define enc1PinA 37
#define enc1PinB 38
#define enc1PinS 35
@ -32,40 +32,39 @@
#define enc2PinB 41
#define enc2PinS 39
// define Drehzahlgrenzen TODOOOO
#define RPM_THRES_1 1000
#define RPM_THRES_2 6000
#define RPM_THRES_3 7000
#define RPM_THRES_4 8000
#define RPM_THRES_5 10000
#define RPM_THRES_6 14000
#define RPM_THRES_7 17000
#define RPM_THRES_8 18000
#define RPM_THRES_9 20000
#define RPM_THRES_10 20000
#define RPM_THRES_1 1000
#define RPM_THRES_2 6000
#define RPM_THRES_3 7000
#define RPM_THRES_4 8000
#define RPM_THRES_5 10000
#define RPM_THRES_6 14000
#define RPM_THRES_7 17000
#define RPM_THRES_8 18000
#define RPM_THRES_9 20000
#define RPM_THRES_10 20000
void set_pins(void);
void read_buttons(void);
void read_rotary(void); // read rotary switches
typedef struct
{
typedef struct {
uint8_t Stw_shift_up; // 1 Bit 0
uint8_t Stw_shift_down; // 1 Bit 1
uint8_t Stw_neutral; // 1 Bit 2
uint8_t Stw_auto_shift; // 1 Bit 3
uint8_t buttonState1; // 1 Bit 4
uint8_t buttonState4; // 1 Bit 5
//bool CAN_toggle;
//bool CAN_check;
//uint8_t i; //Index linker Drehschalter
// bool CAN_toggle;
// bool CAN_check;
// uint8_t i; //Index
// linker Drehschalter
uint8_t buttonStateEnc1; // button
//uint8_t br; //test mode : mittlere Drehschalter position
uint8_t buttonStateEnc2; //button
uint8_t displayindex; //index für Displayanzeige
uint8_t error_type; //Extrainfos über Error-LED
// uint8_t br; //test mode : mittlere
// Drehschalter position
uint8_t buttonStateEnc2; // button
uint8_t displayindex; // index für Displayanzeige
uint8_t error_type; // Extrainfos über Error-LED
uint8_t trc;
uint8_t mode;
@ -73,10 +72,9 @@ typedef struct
uint8_t button4_rises;
uint8_t enc1_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 gear; // Gang
@ -95,11 +93,9 @@ typedef struct
uint8_t speed_fr;
uint8_t speed;
} vehicle_data_type;
extern volatile stw_data_type Stw_data;
extern volatile vehicle_data_type Vehicle_data;
} vehicle_data_type;
extern volatile stw_data_type Stw_data;
extern volatile vehicle_data_type Vehicle_data;
#endif

View File

@ -1,8 +1,8 @@
#include "FT18e_STW_DISPLAY.h"
#include "Arduino.h"
#include "EDIPTFT.h"
#include "FT_2018e_STW_CAN.h"
#include "FT18e_STW_INIT.h"
#include "FT18e_STW_DISPLAY.h"
#include "FT_2018e_STW_CAN.h"
EDIPTFT tft(true, false);
String bezeichnungen[] = {"Batterieleistung", "Moment", "Batterietemp"};
@ -26,7 +26,8 @@ uint8_t trccounter; // = Stw_data.trc;
uint8_t modecounter; // = Stw_data.mode;
bool trctimer;
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,
led9, led10, led11, led12, led13, led14, led15, led16};
unsigned long poiltimer;
unsigned long tmottimer;
unsigned long toiltimer;
@ -34,22 +35,21 @@ bool poilbool = true;
bool tmotbool = true;
bool toilbool = true;
void init_display()
{
void init_display() {
pinMode(writeprotect, OUTPUT);
digitalWrite(writeprotect, HIGH);
pinMode(reset, OUTPUT);
pinMode(disp_cs, OUTPUT);
pinMode(MOSI, OUTPUT);
pinMode(MISO, OUTPUT);
//pinMode(CLK, INPUT);
// pinMode(CLK, INPUT);
digitalWrite(disp_cs, HIGH);
digitalWrite(MOSI, HIGH);
digitalWrite(MISO, HIGH);
digitalWrite(reset, LOW);
//edip.smallProtoSelect(7);
//edip.setNewColor(EA_GREY, 0xe3, 0xe3,0xe3); // redefine r-g-b-values of EA_GREY
//edip.drawImage(0,50,FASTTUBE_LOGO_PNG);
// edip.smallProtoSelect(7);
// edip.setNewColor(EA_GREY, 0xe3, 0xe3,0xe3); // redefine r-g-b-values
// of EA_GREY edip.drawImage(0,50,FASTTUBE_LOGO_PNG);
digitalWrite(reset, HIGH);
tft.begin(115200); // start display communication
/*int h = 20;
@ -61,33 +61,24 @@ void init_display()
tft.terminalOn(false);
tft.setDisplayColor(EA_WHITE, EA_BLACK);
tft.setTextColor(EA_WHITE, EA_BLACK);
//tft.setTextFont('4');
// tft.setTextFont('4');
tft.setTextSize(5, 8);
tft.clear();
//tft.displayLight('30');
tft.drawText(0, 14, 'C', "FaSTTUBe"); //draw some text
//tft.loadImage(0,0,1);
//delay(2000);
// tft.displayLight('30');
tft.drawText(0, 14, 'C', "FaSTTUBe"); // draw some text
// tft.loadImage(0,0,1);
// delay(2000);
}
double get_value(int a)
{
return 0;
}
double get_value(int a) { return 0; }
void update_display()
{
if (!tft.disconnected)
{
void update_display() {
if (!tft.disconnected) {
tft.cursorOn(false);
if (modealt != Stw_data.mode || modetimer == true)
{
if (modealt != Stw_data.mode || modetimer == true) {
display_mode();
}
else
{
if (clearcounter >= 56)
{
} else {
if (clearcounter >= 56) {
tft.clear();
clearcounter = 0;
}
@ -96,10 +87,8 @@ void update_display()
}
}
void display_mode()
{
if (modealt != Stw_data.mode)
{
void display_mode() {
if (modealt != Stw_data.mode) {
tft.clear();
tft.setTextSize(6, 8);
tft.setDisplayColor(EA_WHITE, EA_RED);
@ -116,54 +105,43 @@ void display_mode()
modecounter = 0;
modealt = Stw_data.mode;
modetimer = true;
}
else if (modecounter >= 255)
{
} else if (modecounter >= 255) {
tft.setDisplayColor(EA_WHITE, EA_BLACK);
tft.setTextColor(EA_WHITE, EA_BLACK);
tft.clear();
modetimer = false;
}
else
{
} else {
modecounter += 1;
delay(5);
}
}
void alarm(String textstr)
{
void alarm(String textstr) {
uint8_t x = 1;
;
char text[7];
textstr.toCharArray(text, 7);
tft.setTextSize(8, 8);
while (x == 1)
{
if (!tft.disconnected)
{
while (x == 1) {
if (!tft.disconnected) {
tft.setTextColor(EA_BLACK, EA_RED);
tft.fillDisplayColor(EA_RED);
tft.drawText(5, 68, 'L', text);
}
for (int j = 0; j < 16; j++)
{
for (int j = 0; j < 16; j++) {
digitalWrite(led_s[j], HIGH);
}
delay(100);
if (!tft.disconnected)
{
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++)
{
for (int j = 0; j < 16; j++) {
digitalWrite(led_s[j], LOW);
}
delay(100);
if (Stw_data.button_ll & Stw_data.button_rr)
{
if (Stw_data.button_ll & Stw_data.button_rr) {
x = 0;
tft.setTextColor(EA_WHITE, EA_BLACK);
}

View File

@ -1,7 +1,7 @@
#include "Arduino.h"
#include "EDIPTFT.h"
#include "FT_2018e_STW_CAN.h"
#include "FT18e_STW_INIT.h"
#include "FT_2018e_STW_CAN.h"
#ifndef FT18e_STW_DISPLAY_h
#define FT18e_STW_DISPLAY_h

View File

@ -1,14 +1,16 @@
#include "Arduino.h"
#include "FT18e_STW_INIT.h"
#include "Arduino.h"
#include "Bounce2.h"
#include "RotaryEncoder.h"
volatile stw_data_type Stw_data = {0}; //alles mit 0 initialisieren
volatile vehicle_data_type Vehicle_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
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,
led9, led10, led11, led12, led13, led14, led15, led16};
bool entprell;
int buttons[] = {PIN_BUTTON_LL, PIN_BUTTON_LR, PIN_BUTTON_RL, PIN_BUTTON_RR, enc1PinS, enc2PinS};
int buttons[] = {PIN_BUTTON_LL, PIN_BUTTON_LR, PIN_BUTTON_RL,
PIN_BUTTON_RR, enc1PinS, enc2PinS};
Bounce debouncer[8];
double val = 0;
double val2 = 0;
@ -18,10 +20,8 @@ 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(l, OUTPUT);
@ -33,49 +33,39 @@ void set_pins()
pinMode(button6, INPUT);*/
pinMode(enc1PinA, INPUT);
pinMode(enc1PinB, INPUT);
//pinMode(enc1PinS, INPUT);
// pinMode(enc1PinS, INPUT);
pinMode(enc2PinA, INPUT);
pinMode(enc2PinB, INPUT);
//pinMode(enc2PinS, INPUT);
//Stw_data.i=0;
// pinMode(enc2PinS, INPUT);
// Stw_data.i=0;
enc1PinALast = LOW;
enc1PinANow = LOW;
enc2PinALast = 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);
debouncer[i].attach(buttons[i]);
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_rl = digitalRead(PIN_BUTTON_RL);
Stw_data.button_rr = digitalRead(PIN_BUTTON_RR);
}
void read_rotary()
{
void read_rotary() {
int enc2 = encoder2.readEncoder();
if (enc2 != 0)
{
if (enc2 != 0) {
val2 = val2 + 0.5 * enc2;
if (val2 == 1 or val2 == -1)
{
if ((Stw_data.mode == 1 or Stw_data.mode == 0) and enc2 < 0)
{
if (val2 == 1 or val2 == -1) {
if ((Stw_data.mode == 1 or Stw_data.mode == 0) and enc2 < 0) {
Stw_data.mode = 5;
}
else if (Stw_data.mode == 5 and enc2 > 0)
{
} else if (Stw_data.mode == 5 and enc2 > 0) {
Stw_data.mode = 1;
}
else
{
} else {
Stw_data.mode = Stw_data.mode + enc2;
}
val2 = 0;

View File

@ -2,23 +2,23 @@
#ifndef FT18e_STW_Init
#define FT18e_STW_Init
#define l 78 //test_led
#define led1 12 //PD8
#define led2 11 //PD7
#define led3 9 //PC21
#define led4 8 //PC22
#define led5 7 //PC23
#define led6 6 //PC24
#define led7 5 //PC25
#define led8 4 //PC26 und PA29
#define led9 3 //PC28
#define led10 2 //PB25
#define led11 10 //PC29 und PA28
#define led12 22 //PB26
#define led13 19 //PA10
#define led14 13 //PB27
#define led15 17 //PA12
#define led16 18 //PA11
#define l 78 // test_led
#define led1 12 // PD8
#define led2 11 // PD7
#define led3 9 // PC21
#define led4 8 // PC22
#define led5 7 // PC23
#define led6 6 // PC24
#define led7 5 // PC25
#define led8 4 // PC26 und PA29
#define led9 3 // PC28
#define led10 2 // PB25
#define led11 10 // PC29 und PA28
#define led12 22 // PB26
#define led13 19 // PA10
#define led14 13 // PB27
#define led15 17 // PA12
#define led16 18 // PA11
#define enc1PinA 37
#define enc1PinB 38
#define enc1PinS 35
@ -51,20 +51,18 @@ void set_pins(void);
void read_buttons(void);
void read_rotary(void); // read rotary switches
typedef struct
{
typedef struct {
bool button_ll; // Left side, left button
bool button_lr; // Left side, right button
bool button_rl; // Right side, left button
bool button_rr; // Right side, right button
uint8_t mode;
uint8_t displayindex; //index für Displayanzeige
uint8_t error_type; //Extrainfos über Error-LED
uint8_t displayindex; // index für Displayanzeige
uint8_t error_type; // Extrainfos über Error-LED
} stw_data_type;
struct InverterData
{
struct InverterData {
bool ready;
bool derating;
bool warning;
@ -75,8 +73,7 @@ struct InverterData
bool ts_active;
};
typedef struct
{
typedef struct {
uint16_t u_cell_min; // Minimale Zellspannung
uint16_t u_batt; // Batteriespannung (pre-AIR-voltage)
int16_t t_mot_l; // Motor-Wasser-Temperatur Links

View File

@ -2,35 +2,40 @@
FT_2018_STW_CAN.cpp
*/
#include "FT_2018_STW_CAN.h"
#include "Arduino.h"
#include "DueTimer.h"
#include "due_can.h"
#include "FT_2018_STW_CAN.h"
#include "FT18_STW_INIT.h"
#include "due_can.h"
CAN_FRAME can_0_msg;
//can_1_msg.id = 0x110;
// can_1_msg.id = 0x110;
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.setNumTXBoxes(1); // reserves mailbox 0 for tx only 8 mailboxes are available (the other 7 mailboxes are for rx)
Can0.watchFor(0x502); // set CAN RX filter for ID 0x502 and reserves mailbox 1 for rx
Can0.setNumTXBoxes(1); // reserves mailbox 0 for tx only 8 mailboxes are
// available (the other 7 mailboxes are for rx)
Can0.watchFor(
0x502); // set CAN RX filter for ID 0x502 and reserves mailbox 1 for rx
Can0.watchFor(0x504);
Can0.watchFor(0x500);
Can0.watchFor(0x773); // set CAN RX filter for ID 0x773 and reserves mailbox 3 for rx
Can0.watchFor(
0x773); // set CAN RX filter for ID 0x773 and reserves mailbox 3 for rx
Can0.watchFor(0x775);
// Can0.watchFor(0x777); // set CAN RX filter for ID 0x777 and reserves mailbox 5 for rx
Can0.watchFor(0x779); // set CAN RX filter for ID 0x779 and reserves mailbox 6 for rx
// Can0.watchFor(0x777); // set CAN RX filter
//for ID 0x777 and reserves mailbox 5 for rx
Can0.watchFor(
0x779); // set CAN RX filter for ID 0x779 and reserves mailbox 6 for rx
Can0.watchFor(0x77A);
Can0.setGeneralCallback(Receive_Can_0);
Timer3.attachInterrupt(Send_0x110); // set send interrupt
Timer3.start(10000); // Calls every 10ms
}
void Send_0x110(){
void Send_0x110() {
read_buttons();
read_rotary();
can_0_msg.id = 0x110;
@ -44,80 +49,87 @@ void Send_0x110(){
can_0_temp_data |= Stw_data.Stw_shift_down << 1 & 0b00000010;
can_0_temp_data |= Stw_data.Stw_neutral << 2 & 0b00000100;
can_0_temp_data |= Stw_data.Stw_auto_shift << 3 & 0b00001000;
can_0_temp_data |= Stw_data.buttonStateEnc1 << 5 & 0b00100000; //pitlane
can_0_temp_data |= Stw_data.buttonStateEnc1 << 5 & 0b00100000; // pitlane
can_0_msg.data.byte[0] = can_0_temp_data;
can_0_msg.data.byte[1] = Stw_data.trc & 0b00001111;
can_0_msg.data.byte[2] = Stw_data.mode & 0b00000111;
if ((Stw_data.Stw_auto_shift << 3 & 0b00001000)){
if(Vehicle_data.g_auto){
if ((Stw_data.Stw_auto_shift << 3 & 0b00001000)) {
if (Vehicle_data.g_auto) {
Vehicle_data.g_auto = false;
}else{
} else {
Vehicle_data.g_auto = true;
}
}
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) {
//g_auto
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
// g_auto
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
if(temp_message->data.byte[0] & 0x80){
Stw_data.error_type = 1;//"pc_error";
if (temp_message->data.byte[0] & 0x80) {
Stw_data.error_type = 1; //"pc_error";
}
if(temp_message->data.byte[0] & 0x40){
Stw_data.error_type = 2;//"bse_error";
if (temp_message->data.byte[0] & 0x40) {
Stw_data.error_type = 2; //"bse_error";
}
if(temp_message->data.byte[0] & 0x20){
Stw_data.error_type = 3;//"aps_error";
if (temp_message->data.byte[0] & 0x20) {
Stw_data.error_type = 3; //"aps_error";
}
if(temp_message->data.byte[0] & 0x10){
Stw_data.error_type = 4;//"etb_error";
if (temp_message->data.byte[0] & 0x10) {
Stw_data.error_type = 4; //"etb_error";
}
//can_1_temp_data |= g_etb_e << 4;
//can_1_temp_data |= g_aps_e << 5;
//can_1_temp_data |= g_bse_e << 6;
//can_1_temp_data |= g_pc_e << 7;
// can_1_temp_data |= g_etb_e << 4;
// can_1_temp_data |= g_aps_e << 5;
// can_1_temp_data |= g_bse_e << 6;
// can_1_temp_data |= g_pc_e << 7;
break;
}
case 0x504:{ //autoshift+gear
//Vehicle_data.g_auto = (temp_message->data.byte[1]) >> 4;
case 0x504: { // autoshift+gear
// Vehicle_data.g_auto =
// (temp_message->data.byte[1])
// >> 4;
Vehicle_data.gear = (temp_message->data.byte[1]) >> 5;
break;
}
case 0x773:{ // rpm
Vehicle_data.revol = (temp_message->data.byte[4] | temp_message->data.byte[3] << 8);
case 0x773: { // rpm
Vehicle_data.revol =
(temp_message->data.byte[4] | temp_message->data.byte[3] << 8);
break;
}
case 0x779:{ // battery voltage
case 0x779: { // battery voltage
Vehicle_data.u_batt = temp_message->data.byte[6];
break;
}
/*case 0x77A: // revolution limit bit
Vehicle_data.rev_lim = (temp_message->data.byte[3] & 0x20) >> 4;
Vehicle_data.rev_lim =
(temp_message->data.byte[3] & 0x20) >> 4;
switch(temp_message->data.byte[0]) {
case 0x02: // temp. intercooler
Vehicle_data.t_air = temp_message->data.byte[7];
break;
case 0x05: // temp. water
Vehicle_data.t_mot = temp_message->data.byte[4];
break;
case 0x04: // temp. oil
Vehicle_data.t_oil = temp_message->data.byte[5];
case 0x01: {
Vehicle_data.p_wat = temp_message->data.byte[6];
Vehicle_data.p_fuel = temp_message->data.byte[7];
Vehicle_data.p_oil = temp_message->data.byte[5];
break;
Vehicle_data.t_air =
temp_message->data.byte[7]; break; case 0x05: // temp. water
Vehicle_data.t_mot =
temp_message->data.byte[4]; break; case 0x04: // temp. oil
Vehicle_data.t_oil =
temp_message->data.byte[5]; case 0x01: {
Vehicle_data.p_wat =
temp_message->data.byte[6]; Vehicle_data.p_fuel =
temp_message->data.byte[7]; Vehicle_data.p_oil =
temp_message->data.byte[5]; break;
}
}
break;*/
case 0x77A:{//temp und p
//g_ms4_idle_b = (temp_message->data.byte[2] & 0b10000000) >> 7;
//g_ms4_engine_status = (temp_message->data.byte[3] & 0b01000000) >> 6;
//g_ms4_ignoff_b = (temp_message->data.byte[3] & 0b10000000) >> 7;
case 0x77A: { // temp und p
// g_ms4_idle_b = (temp_message->data.byte[2] &
// 0b10000000)
// >> 7; g_ms4_engine_status = (temp_message->data.byte[3] &
// 0b01000000) >> 6; g_ms4_ignoff_b =
// (temp_message->data.byte[3] & 0b10000000) >> 7;
// Serial.println("CAN 77A");
// for (int i = 0; i < 8; i++) {
// Serial.print('[');
@ -126,32 +138,29 @@ void Receive_Can_0(CAN_FRAME *temp_message){
// Serial.println(temp_message->data.byte[i], HEX);
// }
if ( temp_message->data.byte[0] == 1){
if (temp_message->data.byte[0] == 1) {
Vehicle_data.p_oil = temp_message->data.byte[5];
Vehicle_data.p_fuel = temp_message->data.byte[7];
}
else if ( temp_message->data.byte[0] == 2){
} else if (temp_message->data.byte[0] == 2) {
Vehicle_data.t_air = temp_message->data.byte[7];
}
else if ( temp_message->data.byte[0] == 4){
} else if (temp_message->data.byte[0] == 4) {
Vehicle_data.t_oil = temp_message->data.byte[5];
}
else if ( temp_message->data.byte[0] == 5){
} else if (temp_message->data.byte[0] == 5) {
Vehicle_data.t_mot = temp_message->data.byte[4];
}
break;
}
case 0x775:{//speed
Vehicle_data.speed_fl = 2*(temp_message->data.byte[2]);
Vehicle_data.speed_fr = 2*(temp_message->data.byte[3]);
Vehicle_data.speed = (Vehicle_data.speed_fl+Vehicle_data.speed_fr)/2;
case 0x775: { // speed
Vehicle_data.speed_fl = 2 * (temp_message->data.byte[2]);
Vehicle_data.speed_fr = 2 * (temp_message->data.byte[3]);
Vehicle_data.speed = (Vehicle_data.speed_fl + Vehicle_data.speed_fr) / 2;
break;
}
/*case 0x777:{//m4_gear
Vehicle_data.gear = temp_message->data.byte[0];
break;
Vehicle_data.gear =
temp_message->data.byte[0]; break;
}*/
case 0x500:{
case 0x500: {
Vehicle_data.p_brake_front = temp_message->data.byte[1];
Vehicle_data.p_brake_rear = temp_message->data.byte[2];
break;
@ -159,19 +168,21 @@ void Receive_Can_0(CAN_FRAME *temp_message){
}
}
void update_LED(){
//Copyright Michael Dietzel
//m.dietzel@fasttube.de
//Edit Michael Witt 05-2015
//m.witt@fasttube.de
void update_LED() {
// Copyright Michael Dietzel
// m.dietzel@fasttube.de
// Edit Michael Witt 05-2015
// m.witt@fasttube.de
//EDIT BAHA ZARROUKI 05-2107
//z.baha@fasttube.de
// EDIT BAHA ZARROUKI 05-2107
// z.baha@fasttube.de
// alle Werte als Hex-Werte angegeben
// alle Werte als Hex-Werte angegeben
bool t_oil = (Vehicle_data.t_oil - 40) >= 0x96; // 150°C temp.oil
bool t_air = (Vehicle_data.t_air - 40) >= 0x3C; // 60°C temp.llk
bool t_mot = ((Vehicle_data.t_mot - 40) >= 0x69) and ((Vehicle_data.t_mot - 40)!=0xC8); // 105°C temp.water und !=200
bool t_mot =
((Vehicle_data.t_mot - 40) >= 0x69) and
((Vehicle_data.t_mot - 40) != 0xC8); // 105°C temp.water und !=200
bool g_auto = Vehicle_data.g_auto;
bool u_batt = Vehicle_data.u_batt <= 0xB1; // 12.5V batt.spann.
@ -184,7 +195,8 @@ void update_LED(){
/*if(Vehicle_data.rev_lim){
for (int j = 0; j < 10; j++){
digitalWrite(leds[j], HIGH);
//analogWrite(leds[j], STW_data.br); //nur eine der zwei zeilen
//analogWrite(leds[j], STW_data.br); //nur eine der zwei
zeilen
}
delay(100);
for (int j = 0; j < 10; j++){

View File

@ -2,22 +2,23 @@
FT_2018_STW_CAN.cpp
*/
#include "FT_2018e_STW_CAN.h"
#include "Arduino.h"
#include "DueTimer.h"
#include "due_can.h"
#include "FT_2018e_STW_CAN.h"
#include "FT18e_STW_INIT.h"
#include "due_can.h"
CAN_FRAME can_0_msg;
//can_1_msg.id = 0x110;
// can_1_msg.id = 0x110;
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);
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
// available (the other 7 mailboxes are for rx)
Can0.watchFor(CAN_CELL_STATS_ID);
Can0.watchFor(CAN_BATTERY_STATS_ID);
Can0.watchFor(CAN_COOLING_STATS_ID);
@ -27,8 +28,7 @@ void Init_Can_0()
Timer3.start(10000); // Calls every 10ms
}
void Send_0x110()
{
void Send_0x110() {
read_buttons();
read_rotary();
can_0_msg.id = 0x110;
@ -47,10 +47,8 @@ void Send_0x110()
Can0.sendFrame(can_0_msg);
}
void Receive_Can_0(CAN_FRAME *temp_message)
{
switch (temp_message->id)
{
void Receive_Can_0(CAN_FRAME *temp_message) {
switch (temp_message->id) {
case CAN_CELL_STATS_ID:
process_cell_stats(temp_message);
break;
@ -70,21 +68,18 @@ void Receive_Can_0(CAN_FRAME *temp_message)
}
}
void process_cell_stats(CAN_FRAME *frame)
{
void process_cell_stats(CAN_FRAME *frame) {
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)
{
void process_battery_stats(CAN_FRAME *frame) {
BatteryStats *data = (BatteryStats *)&frame->data;
Vehicle_data.u_batt = data->pre_air_voltage;
}
void process_cooling_stats(CAN_FRAME *frame)
{
void process_cooling_stats(CAN_FRAME *frame) {
CoolingStats *data = (CoolingStats *)&frame->data;
Vehicle_data.p_wat = data->water_pressure;
Vehicle_data.t_wat = data->water_temp;
@ -92,8 +87,7 @@ void process_cooling_stats(CAN_FRAME *frame)
Vehicle_data.t_mot_r = data->motor_r_temp;
}
void process_inverter_stats(CAN_FRAME *frame)
{
void process_inverter_stats(CAN_FRAME *frame) {
InverterStats *data = (InverterStats *)&frame->data;
uint8_t status = data->status;
Vehicle_data.inverter.ready = status & CAN_INVERTER_STATS_READY;
@ -109,9 +103,9 @@ void process_inverter_stats(CAN_FRAME *frame)
Vehicle_data.wheel_speed = data->wheel_speed;
}
void update_LED()
{
bool t_mot = (Vehicle_data.t_mot_l > LED_THRESH_T_MOT) || (Vehicle_data.t_mot_r > LED_THRESH_T_MOT);
void update_LED() {
bool t_mot = (Vehicle_data.t_mot_l > LED_THRESH_T_MOT) ||
(Vehicle_data.t_mot_r > LED_THRESH_T_MOT);
bool t_inv = Vehicle_data.t_inv > LED_THRESH_T_INV;
bool t_bat = Vehicle_data.t_cell_max > LED_THRESH_T_BAT;

View File

@ -31,32 +31,28 @@ void process_cooling_stats(CAN_FRAME *frame);
void process_inverter_stats(CAN_FRAME *frame);
void update_LED(void);
struct CellStats
{
struct CellStats {
uint16_t sum_cell_voltage;
int16_t max_cell_temp;
uint16_t max_cell_voltage;
uint16_t min_cell_voltage;
};
struct BatteryStats
{
struct BatteryStats {
uint16_t battery_current;
uint16_t pre_air_voltage;
uint16_t post_air_voltage;
uint16_t battery_power;
};
struct CoolingStats
{
struct CoolingStats {
int16_t water_pressure;
int16_t water_temp;
int16_t motor_l_temp;
int16_t motor_r_temp;
};
struct InverterStats
{
struct InverterStats {
uint8_t status;
uint8_t _reserved;
uint16_t temp;

File diff suppressed because it is too large Load Diff

View File

@ -26,15 +26,15 @@
#include "Arduino.h"
//Devices
// Devices
#define EDIP128 1
#define EDIP160 1
#define EDIP240 1
#define EDIP320 2
//Set your device
// Set your device
#define DEVICE EDIP320
#define COORD_SIZE DEVICE //Byte count for coordinates
#define COORD_SIZE DEVICE // Byte count for coordinates
#define SERIAL_DEV Serial3
#define EA_TRANSPARENT 0
@ -72,11 +72,11 @@
#define uint unsigned int
class EDIPTFT {
public:
EDIPTFT(boolean smallprotocol=true, boolean disconnected=false);
public:
EDIPTFT(boolean smallprotocol = true, boolean disconnected = false);
boolean disconnected;
void begin(long baud=115200);
void begin(long baud = 115200);
// helper functions
char readByte();
@ -208,8 +208,8 @@ class EDIPTFT {
void deleteBargraph(char no, char n1);
// Instrument
void defineInstrument(char no, int x1, int y1, char image,
char angle, char sv, char ev);
void defineInstrument(char no, int x1, int y1, char image, char angle,
char sv, char ev);
void updateInstrument(char no, char val);
void redrawInstrument(char no);
void deleteInstrument(char no, char n1, char n2);
@ -266,7 +266,8 @@ class EDIPTFT {
* 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);
void drawTextInRect(int x1, int y1, int x2, int y2, uint8_t align,
const char* text);
// Rectangle and Line
void setLineColor(char fg, char bg);
@ -309,8 +310,8 @@ class EDIPTFT {
* \param up return/touchmacro (1-255) if released
* \param text label of the touch key
*/
void defineTouchKey(int x1, int y1, int x2, int y2,
char down, char up, const char* text);
void defineTouchKey(int x1, int y1, int x2, int y2, char down, char up,
const char* text);
/*! \brief Define touch switch
*
@ -324,8 +325,8 @@ class EDIPTFT {
* \param up return/touchmacro (1-255) if released
* \param text label of the touch key
*/
void defineTouchSwitch(int x1, int y1, int x2, int y2,
char down, char up, const char* text);
void defineTouchSwitch(int x1, int y1, int x2, int y2, char down, char up,
const char* text);
/*! \brief Define touch switch with image
*
@ -339,8 +340,8 @@ class EDIPTFT {
* \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 defineTouchSwitch(int x, int y, int img, char downcode, char upcode,
const char* text);
/*! \brief Set touch switch
*
@ -350,10 +351,9 @@ class EDIPTFT {
* \param code Return code of the switch
* \param value `value=0`: OFF, `value=1`: ON
*/
void setTouchSwitch(char code,char value);
void setTouchSwitch(char code, char value);
void setTouchkeyColors(char n1, char n2, char n3,
char s1, char s2, char s3);
void setTouchkeyColors(char n1, char n2, char n3, char s1, char s2, char s3);
/*! \brief Label font
*
@ -361,7 +361,7 @@ class EDIPTFT {
*/
void setTouchkeyFont(char font);
void setTouchkeyLabelColors(char nf,char sf);
void setTouchkeyLabelColors(char nf, char sf);
/*! \brief Radio group for switches
*
@ -382,7 +382,7 @@ class EDIPTFT {
* \param n1 n1==0: the area remains visible on the display,
* n1==1: the area is deleted
*/
void removeTouchArea(char code,char n1);
void removeTouchArea(char code, char n1);
// Macro Calls
/*! \brief Run macro
@ -406,21 +406,23 @@ class EDIPTFT {
/*! \brief Define touch key with menu function
*
* Define the area from *x1*, *y1* to *x2*, *y2* as a menu key.
* The first character determines the direction in which the menu opens (R=right,L=left,O=up,U=down)
* The second character determines the alignment of the touch text (C=center,L=left-,R=right justified)
* The menu items are separated by the character '|' ($7C,dec:124) (e.g. "UCkey|item1|item2|item3".
* 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
* 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) 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);
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 Send *open* signal after a Menu open request has been sent from
* TFT.
*
* If a touch menu is not set to open automatically the TFT sends a
* request 'ESC T 0'. This function sends 'ESC N T 2' to open the menu.
@ -441,7 +443,7 @@ class EDIPTFT {
*/
void setTouchMenuAutomation(bool val);
private:
private:
boolean _smallprotocol;
int _counter;
unsigned char bytesAvailable();