mirror of
https://github.com/dalathegreat/Battery-Emulator.git
synced 2025-10-04 18:29:48 +02:00
Add battery text to datalayer
This commit is contained in:
parent
59a58f45c9
commit
edb6dcd39b
26 changed files with 101 additions and 155 deletions
|
@ -1118,9 +1118,9 @@ void send_can_battery() {
|
||||||
}
|
}
|
||||||
|
|
||||||
void setup_battery(void) { // Performs one time setup at startup
|
void setup_battery(void) { // Performs one time setup at startup
|
||||||
#ifdef DEBUG_VIA_USB
|
strncpy(datalayer.system.info.battery_protocol, "BMW i3", sizeof(datalayer.system.info.battery_protocol) - 1);
|
||||||
Serial.println("BMW i3 battery selected");
|
datalayer.system.info.battery_protocol[sizeof(datalayer.system.info.battery_protocol) - 1] =
|
||||||
#endif //DEBUG_VIA_USB
|
'\0'; // Ensure null termination
|
||||||
|
|
||||||
//Before we have started up and detected which battery is in use, use 60AH values
|
//Before we have started up and detected which battery is in use, use 60AH values
|
||||||
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_60AH;
|
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_60AH;
|
||||||
|
@ -1129,9 +1129,6 @@ void setup_battery(void) { // Performs one time setup at startup
|
||||||
datalayer.system.status.battery_allows_contactor_closing = true;
|
datalayer.system.status.battery_allows_contactor_closing = true;
|
||||||
|
|
||||||
#ifdef DOUBLE_BATTERY
|
#ifdef DOUBLE_BATTERY
|
||||||
#ifdef DEBUG_VIA_USB
|
|
||||||
Serial.println("Another BMW i3 battery also selected!");
|
|
||||||
#endif //DEBUG_VIA_USB
|
|
||||||
datalayer.battery2.info.max_design_voltage_dV = datalayer.battery.info.max_design_voltage_dV;
|
datalayer.battery2.info.max_design_voltage_dV = datalayer.battery.info.max_design_voltage_dV;
|
||||||
datalayer.battery2.info.min_design_voltage_dV = datalayer.battery.info.min_design_voltage_dV;
|
datalayer.battery2.info.min_design_voltage_dV = datalayer.battery.info.min_design_voltage_dV;
|
||||||
datalayer.battery2.info.max_cell_voltage_deviation_mV = datalayer.battery.info.max_cell_voltage_deviation_mV;
|
datalayer.battery2.info.max_cell_voltage_deviation_mV = datalayer.battery.info.max_cell_voltage_deviation_mV;
|
||||||
|
|
|
@ -778,9 +778,10 @@ void send_can_battery() {
|
||||||
//} //We can always send CAN as the iX BMS will wake up on vehicle comms
|
//} //We can always send CAN as the iX BMS will wake up on vehicle comms
|
||||||
|
|
||||||
void setup_battery(void) { // Performs one time setup at startup
|
void setup_battery(void) { // Performs one time setup at startup
|
||||||
#ifdef DEBUG_VIA_USB
|
strncpy(datalayer.system.info.battery_protocol, "BMW iX and i4-7 platform",
|
||||||
Serial.println("BMW iX battery selected");
|
sizeof(datalayer.system.info.battery_protocol) - 1);
|
||||||
#endif //DEBUG_VIA_USB
|
datalayer.system.info.battery_protocol[sizeof(datalayer.system.info.battery_protocol) - 1] =
|
||||||
|
'\0'; // Ensure null termination
|
||||||
|
|
||||||
//Before we have started up and detected which battery is in use, use 108S values
|
//Before we have started up and detected which battery is in use, use 108S values
|
||||||
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_DV;
|
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_DV;
|
||||||
|
|
|
@ -399,9 +399,9 @@ void send_can_battery() {
|
||||||
}
|
}
|
||||||
|
|
||||||
void setup_battery(void) { // Performs one time setup at startup
|
void setup_battery(void) { // Performs one time setup at startup
|
||||||
#ifdef DEBUG_VIA_USB
|
strncpy(datalayer.system.info.battery_protocol, "BYD Atto 3", sizeof(datalayer.system.info.battery_protocol) - 1);
|
||||||
Serial.println("BYD Atto 3 battery selected");
|
datalayer.system.info.battery_protocol[sizeof(datalayer.system.info.battery_protocol) - 1] =
|
||||||
#endif
|
'\0'; // Ensure null termination
|
||||||
datalayer.battery.info.number_of_cells = 126;
|
datalayer.battery.info.number_of_cells = 126;
|
||||||
datalayer.battery.info.chemistry = battery_chemistry_enum::LFP;
|
datalayer.battery.info.chemistry = battery_chemistry_enum::LFP;
|
||||||
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_DV;
|
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_DV;
|
||||||
|
|
|
@ -333,9 +333,9 @@ void send_can_battery() {
|
||||||
}
|
}
|
||||||
|
|
||||||
void setup_battery(void) { // Performs one time setup at startup
|
void setup_battery(void) { // Performs one time setup at startup
|
||||||
#ifdef DEBUG_VIA_USB
|
strncpy(datalayer.system.info.battery_protocol, "Cellpower BMS", sizeof(datalayer.system.info.battery_protocol) - 1);
|
||||||
Serial.println("Cellpower BMS selected");
|
datalayer.system.info.battery_protocol[sizeof(datalayer.system.info.battery_protocol) - 1] =
|
||||||
#endif
|
'\0'; // Ensure null termination
|
||||||
datalayer.system.status.battery_allows_contactor_closing = true;
|
datalayer.system.status.battery_allows_contactor_closing = true;
|
||||||
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_DV;
|
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_DV;
|
||||||
datalayer.battery.info.min_design_voltage_dV = MIN_PACK_VOLTAGE_DV;
|
datalayer.battery.info.min_design_voltage_dV = MIN_PACK_VOLTAGE_DV;
|
||||||
|
|
|
@ -1031,9 +1031,11 @@ void handle_chademo_sequence() {
|
||||||
}
|
}
|
||||||
|
|
||||||
void setup_battery(void) { // Performs one time setup at startup
|
void setup_battery(void) { // Performs one time setup at startup
|
||||||
#ifdef DEBUG_VIA_USB
|
|
||||||
Serial.println("Chademo battery selected");
|
strncpy(datalayer.system.info.battery_protocol, "Chademo V2X mode",
|
||||||
#endif
|
sizeof(datalayer.system.info.battery_protocol) - 1);
|
||||||
|
datalayer.system.info.battery_protocol[sizeof(datalayer.system.info.battery_protocol) - 1] =
|
||||||
|
'\0'; // Ensure null termination
|
||||||
|
|
||||||
CHADEMO_Status = CHADEMO_IDLE;
|
CHADEMO_Status = CHADEMO_IDLE;
|
||||||
|
|
||||||
|
|
|
@ -224,9 +224,10 @@ void send_can_battery() {
|
||||||
}
|
}
|
||||||
|
|
||||||
void setup_battery(void) { // Performs one time setup at startup
|
void setup_battery(void) { // Performs one time setup at startup
|
||||||
#ifdef DEBUG_VIA_USB
|
strncpy(datalayer.system.info.battery_protocol, "I-Miev / C-Zero / Ion Triplet",
|
||||||
Serial.println("Mitsubishi i-MiEV / Citroen C-Zero / Peugeot Ion battery selected");
|
sizeof(datalayer.system.info.battery_protocol) - 1);
|
||||||
#endif
|
datalayer.system.info.battery_protocol[sizeof(datalayer.system.info.battery_protocol) - 1] =
|
||||||
|
'\0'; // Ensure null termination
|
||||||
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_DV;
|
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_DV;
|
||||||
datalayer.battery.info.min_design_voltage_dV = MIN_PACK_VOLTAGE_DV;
|
datalayer.battery.info.min_design_voltage_dV = MIN_PACK_VOLTAGE_DV;
|
||||||
datalayer.battery.info.max_cell_voltage_mV = MAX_CELL_VOLTAGE_MV;
|
datalayer.battery.info.max_cell_voltage_mV = MAX_CELL_VOLTAGE_MV;
|
||||||
|
|
|
@ -254,9 +254,9 @@ void send_can_battery() {
|
||||||
}
|
}
|
||||||
|
|
||||||
void setup_battery(void) { // Performs one time setup at startup
|
void setup_battery(void) { // Performs one time setup at startup
|
||||||
#ifdef DEBUG_VIA_USB
|
strncpy(datalayer.system.info.battery_protocol, "Jaguar I-PACE", sizeof(datalayer.system.info.battery_protocol) - 1);
|
||||||
Serial.println("Jaguar iPace 90kWh battery selected");
|
datalayer.system.info.battery_protocol[sizeof(datalayer.system.info.battery_protocol) - 1] =
|
||||||
#endif
|
'\0'; // Ensure null termination
|
||||||
|
|
||||||
datalayer.battery.info.number_of_cells = 108;
|
datalayer.battery.info.number_of_cells = 108;
|
||||||
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_DV;
|
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_DV;
|
||||||
|
|
|
@ -1037,14 +1037,14 @@ void send_can_battery() {
|
||||||
}
|
}
|
||||||
|
|
||||||
void setup_battery(void) { // Performs one time setup at startup
|
void setup_battery(void) { // Performs one time setup at startup
|
||||||
#ifdef DEBUG_VIA_USB
|
strncpy(datalayer.system.info.battery_protocol, "Kia/Hyundai EGMP platform",
|
||||||
Serial.println("Hyundai E-GMP (Electric Global Modular Platform) battery selected");
|
sizeof(datalayer.system.info.battery_protocol) - 1);
|
||||||
#endif
|
datalayer.system.info.battery_protocol[sizeof(datalayer.system.info.battery_protocol) - 1] =
|
||||||
|
'\0'; // Ensure null termination
|
||||||
|
|
||||||
startMillis = millis(); // Record the starting time
|
startMillis = millis(); // Record the starting time
|
||||||
|
|
||||||
datalayer.system.status.battery_allows_contactor_closing = true;
|
datalayer.system.status.battery_allows_contactor_closing = true;
|
||||||
|
|
||||||
datalayer.battery.info.number_of_cells = 192; // TODO: will vary depending on battery
|
datalayer.battery.info.number_of_cells = 192; // TODO: will vary depending on battery
|
||||||
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_DV;
|
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_DV;
|
||||||
datalayer.battery.info.min_design_voltage_dV = MIN_PACK_VOLTAGE_DV;
|
datalayer.battery.info.min_design_voltage_dV = MIN_PACK_VOLTAGE_DV;
|
||||||
|
|
|
@ -534,9 +534,10 @@ void send_can_battery() {
|
||||||
}
|
}
|
||||||
|
|
||||||
void setup_battery(void) { // Performs one time setup at startup
|
void setup_battery(void) { // Performs one time setup at startup
|
||||||
#ifdef DEBUG_VIA_USB
|
strncpy(datalayer.system.info.battery_protocol, "Kia/Hyundai 64/40kWh battery",
|
||||||
Serial.println("Kia Niro / Hyundai Kona 64kWh battery selected");
|
sizeof(datalayer.system.info.battery_protocol) - 1);
|
||||||
#endif
|
datalayer.system.info.battery_protocol[sizeof(datalayer.system.info.battery_protocol) - 1] =
|
||||||
|
'\0'; // Ensure null termination
|
||||||
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_98S_DV; //Start with 98S value. Precised later
|
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_98S_DV; //Start with 98S value. Precised later
|
||||||
datalayer.battery.info.min_design_voltage_dV = MIN_PACK_VOLTAGE_90S_DV; //Start with 90S value. Precised later
|
datalayer.battery.info.min_design_voltage_dV = MIN_PACK_VOLTAGE_90S_DV; //Start with 90S value. Precised later
|
||||||
datalayer.battery.info.max_cell_voltage_mV = MAX_CELL_VOLTAGE_MV;
|
datalayer.battery.info.max_cell_voltage_mV = MAX_CELL_VOLTAGE_MV;
|
||||||
|
|
|
@ -257,9 +257,11 @@ void send_can_battery() {
|
||||||
}
|
}
|
||||||
|
|
||||||
void setup_battery(void) { // Performs one time setup at startup
|
void setup_battery(void) { // Performs one time setup at startup
|
||||||
#ifdef DEBUG_VIA_USB
|
strncpy(datalayer.system.info.battery_protocol, "Kia/Hyundai Hybrid",
|
||||||
Serial.println("Kia/Hyundai Hybrid battery selected");
|
sizeof(datalayer.system.info.battery_protocol) - 1);
|
||||||
#endif
|
datalayer.system.info.battery_protocol[sizeof(datalayer.system.info.battery_protocol) - 1] =
|
||||||
|
'\0'; // Ensure null termination
|
||||||
|
|
||||||
datalayer.battery.info.number_of_cells = 56; // HEV , TODO: Make dynamic according to HEV/PHEV
|
datalayer.battery.info.number_of_cells = 56; // HEV , TODO: Make dynamic according to HEV/PHEV
|
||||||
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_DV;
|
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_DV;
|
||||||
datalayer.battery.info.min_design_voltage_dV = MIN_PACK_VOLTAGE_DV;
|
datalayer.battery.info.min_design_voltage_dV = MIN_PACK_VOLTAGE_DV;
|
||||||
|
|
|
@ -135,9 +135,9 @@ void send_can_battery() {
|
||||||
}
|
}
|
||||||
|
|
||||||
void setup_battery(void) { // Performs one time setup at startup
|
void setup_battery(void) { // Performs one time setup at startup
|
||||||
#ifdef DEBUG_VIA_USB
|
strncpy(datalayer.system.info.battery_protocol, "MG 5 battery", sizeof(datalayer.system.info.battery_protocol) - 1);
|
||||||
Serial.println("MG 5 battery selected");
|
datalayer.system.info.battery_protocol[sizeof(datalayer.system.info.battery_protocol) - 1] =
|
||||||
#endif
|
'\0'; // Ensure null termination
|
||||||
|
|
||||||
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_DV;
|
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_DV;
|
||||||
datalayer.battery.info.min_design_voltage_dV = MIN_PACK_VOLTAGE_DV;
|
datalayer.battery.info.min_design_voltage_dV = MIN_PACK_VOLTAGE_DV;
|
||||||
|
|
|
@ -1224,9 +1224,10 @@ uint16_t Temp_fromRAW_to_F(uint16_t temperature) { //This function feels horrib
|
||||||
}
|
}
|
||||||
|
|
||||||
void setup_battery(void) { // Performs one time setup at startup
|
void setup_battery(void) { // Performs one time setup at startup
|
||||||
#ifdef DEBUG_VIA_USB
|
strncpy(datalayer.system.info.battery_protocol, "Nissan LEAF battery",
|
||||||
Serial.println("Nissan LEAF battery selected");
|
sizeof(datalayer.system.info.battery_protocol) - 1);
|
||||||
#endif
|
datalayer.system.info.battery_protocol[sizeof(datalayer.system.info.battery_protocol) - 1] =
|
||||||
|
'\0'; // Ensure null termination
|
||||||
|
|
||||||
datalayer.battery.info.number_of_cells = 96;
|
datalayer.battery.info.number_of_cells = 96;
|
||||||
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_DV;
|
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_DV;
|
||||||
|
|
|
@ -175,9 +175,10 @@ void send_can_battery() {
|
||||||
}
|
}
|
||||||
|
|
||||||
void setup_battery(void) { // Performs one time setup at startup
|
void setup_battery(void) { // Performs one time setup at startup
|
||||||
#ifdef DEBUG_VIA_USB
|
strncpy(datalayer.system.info.battery_protocol, "Pylon compatible battery",
|
||||||
Serial.println("Pylon battery selected");
|
sizeof(datalayer.system.info.battery_protocol) - 1);
|
||||||
#endif
|
datalayer.system.info.battery_protocol[sizeof(datalayer.system.info.battery_protocol) - 1] =
|
||||||
|
'\0'; // Ensure null termination
|
||||||
|
|
||||||
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_DV;
|
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_DV;
|
||||||
datalayer.battery.info.min_design_voltage_dV = MIN_PACK_VOLTAGE_DV;
|
datalayer.battery.info.min_design_voltage_dV = MIN_PACK_VOLTAGE_DV;
|
||||||
|
|
|
@ -313,9 +313,10 @@ void send_can_battery() {
|
||||||
}
|
}
|
||||||
|
|
||||||
void setup_battery(void) { // Performs one time setup at startup
|
void setup_battery(void) { // Performs one time setup at startup
|
||||||
#ifdef DEBUG_VIA_USB
|
strncpy(datalayer.system.info.battery_protocol, "Range Rover 13kWh PHEV battery (L494/L405)",
|
||||||
Serial.println("Range Rover PHEV battery (L494 / L405) selected");
|
sizeof(datalayer.system.info.battery_protocol) - 1);
|
||||||
#endif //DEBUG_VIA_USB
|
datalayer.system.info.battery_protocol[sizeof(datalayer.system.info.battery_protocol) - 1] =
|
||||||
|
'\0'; // Ensure null termination
|
||||||
|
|
||||||
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_DV;
|
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_DV;
|
||||||
datalayer.battery.info.min_design_voltage_dV = MIN_PACK_VOLTAGE_DV;
|
datalayer.battery.info.min_design_voltage_dV = MIN_PACK_VOLTAGE_DV;
|
||||||
|
|
|
@ -234,9 +234,10 @@ void send_can_battery() {
|
||||||
}
|
}
|
||||||
|
|
||||||
void setup_battery(void) { // Performs one time setup at startup
|
void setup_battery(void) { // Performs one time setup at startup
|
||||||
#ifdef DEBUG_VIA_USB
|
|
||||||
Serial.println("Renault Kangoo battery selected");
|
strncpy(datalayer.system.info.battery_protocol, "Renault Kangoo", sizeof(datalayer.system.info.battery_protocol) - 1);
|
||||||
#endif
|
datalayer.system.info.battery_protocol[sizeof(datalayer.system.info.battery_protocol) - 1] =
|
||||||
|
'\0'; // Ensure null termination
|
||||||
|
|
||||||
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_DV;
|
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_DV;
|
||||||
datalayer.battery.info.min_design_voltage_dV = MIN_PACK_VOLTAGE_DV;
|
datalayer.battery.info.min_design_voltage_dV = MIN_PACK_VOLTAGE_DV;
|
||||||
|
|
|
@ -132,10 +132,9 @@ void send_can_battery() {
|
||||||
}
|
}
|
||||||
|
|
||||||
void setup_battery(void) { // Performs one time setup at startup
|
void setup_battery(void) { // Performs one time setup at startup
|
||||||
#ifdef DEBUG_VIA_USB
|
strncpy(datalayer.system.info.battery_protocol, "Renault Twizy", sizeof(datalayer.system.info.battery_protocol) - 1);
|
||||||
Serial.println("Renault Twizy battery selected");
|
datalayer.system.info.battery_protocol[sizeof(datalayer.system.info.battery_protocol) - 1] =
|
||||||
#endif
|
'\0'; // Ensure null termination
|
||||||
|
|
||||||
datalayer.battery.info.number_of_cells = 14;
|
datalayer.battery.info.number_of_cells = 14;
|
||||||
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_DV;
|
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_DV;
|
||||||
datalayer.battery.info.min_design_voltage_dV = MIN_PACK_VOLTAGE_DV;
|
datalayer.battery.info.min_design_voltage_dV = MIN_PACK_VOLTAGE_DV;
|
||||||
|
|
|
@ -518,9 +518,10 @@ void send_can_battery() {
|
||||||
}
|
}
|
||||||
|
|
||||||
void setup_battery(void) { // Performs one time setup at startup
|
void setup_battery(void) { // Performs one time setup at startup
|
||||||
#ifdef DEBUG_VIA_USB
|
strncpy(datalayer.system.info.battery_protocol, "Renault Zoe Gen1 22/40kWh",
|
||||||
Serial.println("Renault Zoe 22/40kWh battery selected");
|
sizeof(datalayer.system.info.battery_protocol) - 1);
|
||||||
#endif
|
datalayer.system.info.battery_protocol[sizeof(datalayer.system.info.battery_protocol) - 1] =
|
||||||
|
'\0'; // Ensure null termination
|
||||||
datalayer.system.status.battery_allows_contactor_closing = true;
|
datalayer.system.status.battery_allows_contactor_closing = true;
|
||||||
datalayer.battery.info.number_of_cells = 96;
|
datalayer.battery.info.number_of_cells = 96;
|
||||||
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_DV;
|
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_DV;
|
||||||
|
|
|
@ -385,9 +385,10 @@ void send_can_battery() {
|
||||||
}
|
}
|
||||||
|
|
||||||
void setup_battery(void) { // Performs one time setup at startup
|
void setup_battery(void) { // Performs one time setup at startup
|
||||||
#ifdef DEBUG_VIA_USB
|
strncpy(datalayer.system.info.battery_protocol, "Renault Zoe Gen2 50kWh",
|
||||||
Serial.println("Renault Zoe 50kWh battery selected");
|
sizeof(datalayer.system.info.battery_protocol) - 1);
|
||||||
#endif
|
datalayer.system.info.battery_protocol[sizeof(datalayer.system.info.battery_protocol) - 1] =
|
||||||
|
'\0'; // Ensure null termination
|
||||||
datalayer.system.status.battery_allows_contactor_closing = true;
|
datalayer.system.status.battery_allows_contactor_closing = true;
|
||||||
datalayer.battery.info.number_of_cells = 96;
|
datalayer.battery.info.number_of_cells = 96;
|
||||||
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_DV;
|
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_DV;
|
||||||
|
|
|
@ -570,10 +570,10 @@ void send_can_battery() {
|
||||||
}
|
}
|
||||||
|
|
||||||
void setup_battery(void) { // Performs one time setup at startup
|
void setup_battery(void) { // Performs one time setup at startup
|
||||||
#ifdef DEBUG_VIA_USB
|
strncpy(datalayer.system.info.battery_protocol, "RJXZS BMS, DIY battery",
|
||||||
Serial.println("RJXZS BMS selected");
|
sizeof(datalayer.system.info.battery_protocol) - 1);
|
||||||
#endif
|
datalayer.system.info.battery_protocol[sizeof(datalayer.system.info.battery_protocol) - 1] =
|
||||||
|
'\0'; // Ensure null termination
|
||||||
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_DV;
|
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_DV;
|
||||||
datalayer.battery.info.min_design_voltage_dV = MIN_PACK_VOLTAGE_DV;
|
datalayer.battery.info.min_design_voltage_dV = MIN_PACK_VOLTAGE_DV;
|
||||||
datalayer.battery.info.max_cell_voltage_mV = MAX_CELL_VOLTAGE_MV;
|
datalayer.battery.info.max_cell_voltage_mV = MAX_CELL_VOLTAGE_MV;
|
||||||
|
|
|
@ -402,9 +402,9 @@ uint8_t CalculateCRC8(CAN_frame rx_frame) {
|
||||||
}
|
}
|
||||||
|
|
||||||
void setup_battery(void) { // Performs one time setup at startup
|
void setup_battery(void) { // Performs one time setup at startup
|
||||||
#ifdef DEBUG_VIA_USB
|
strncpy(datalayer.system.info.battery_protocol, "Santa Fe PHEV", sizeof(datalayer.system.info.battery_protocol) - 1);
|
||||||
Serial.println("Hyundai Santa Fe PHEV battery selected");
|
datalayer.system.info.battery_protocol[sizeof(datalayer.system.info.battery_protocol) - 1] =
|
||||||
#endif
|
'\0'; // Ensure null termination
|
||||||
datalayer.battery.info.number_of_cells = 96;
|
datalayer.battery.info.number_of_cells = 96;
|
||||||
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_DV;
|
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_DV;
|
||||||
datalayer.battery.info.min_design_voltage_dV = MIN_PACK_VOLTAGE_DV;
|
datalayer.battery.info.min_design_voltage_dV = MIN_PACK_VOLTAGE_DV;
|
||||||
|
|
|
@ -219,7 +219,10 @@ void update_values_serial_link() {
|
||||||
}
|
}
|
||||||
|
|
||||||
void setup_battery(void) {
|
void setup_battery(void) {
|
||||||
Serial.println("SERIAL_DATA_LINK_RECEIVER selected");
|
strncpy(datalayer.system.info.battery_protocol, "Serial link to another LilyGo board",
|
||||||
|
sizeof(datalayer.system.info.battery_protocol) - 1);
|
||||||
|
datalayer.system.info.battery_protocol[sizeof(datalayer.system.info.battery_protocol) - 1] =
|
||||||
|
'\0'; // Ensure null termination
|
||||||
}
|
}
|
||||||
// Needed to make the compiler happy
|
// Needed to make the compiler happy
|
||||||
void update_values_battery() {}
|
void update_values_battery() {}
|
||||||
|
|
|
@ -1249,13 +1249,13 @@ void printDebugIfActive(uint8_t symbol, const char* message) {
|
||||||
}
|
}
|
||||||
|
|
||||||
void setup_battery(void) { // Performs one time setup at startup
|
void setup_battery(void) { // Performs one time setup at startup
|
||||||
#ifdef DEBUG_VIA_USB
|
|
||||||
Serial.println("Tesla Model S/3/X/Y battery selected");
|
|
||||||
#endif
|
|
||||||
|
|
||||||
datalayer.system.status.battery_allows_contactor_closing = true;
|
datalayer.system.status.battery_allows_contactor_closing = true;
|
||||||
|
|
||||||
#ifdef TESLA_MODEL_SX_BATTERY // Always use NCM/A mode on S/X packs
|
#ifdef TESLA_MODEL_SX_BATTERY // Always use NCM/A mode on S/X packs
|
||||||
|
strncpy(datalayer.system.info.battery_protocol, "Tesla Model S/X",
|
||||||
|
sizeof(datalayer.system.info.battery_protocol) - 1);
|
||||||
|
datalayer.system.info.battery_protocol[sizeof(datalayer.system.info.battery_protocol) - 1] =
|
||||||
|
'\0'; // Ensure null termination
|
||||||
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_SX_NCMA;
|
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_SX_NCMA;
|
||||||
datalayer.battery.info.min_design_voltage_dV = MIN_PACK_VOLTAGE_SX_NCMA;
|
datalayer.battery.info.min_design_voltage_dV = MIN_PACK_VOLTAGE_SX_NCMA;
|
||||||
datalayer.battery.info.max_cell_voltage_mV = MAX_CELL_VOLTAGE_NCA_NCM;
|
datalayer.battery.info.max_cell_voltage_mV = MAX_CELL_VOLTAGE_NCA_NCM;
|
||||||
|
@ -1271,6 +1271,10 @@ void setup_battery(void) { // Performs one time setup at startup
|
||||||
#endif // TESLA_MODEL_SX_BATTERY
|
#endif // TESLA_MODEL_SX_BATTERY
|
||||||
|
|
||||||
#ifdef TESLA_MODEL_3Y_BATTERY // Model 3/Y can be either LFP or NCM/A
|
#ifdef TESLA_MODEL_3Y_BATTERY // Model 3/Y can be either LFP or NCM/A
|
||||||
|
strncpy(datalayer.system.info.battery_protocol, "Tesla Model 3/Y",
|
||||||
|
sizeof(datalayer.system.info.battery_protocol) - 1);
|
||||||
|
datalayer.system.info.battery_protocol[sizeof(datalayer.system.info.battery_protocol) - 1] =
|
||||||
|
'\0'; // Ensure null termination
|
||||||
#ifdef LFP_CHEMISTRY
|
#ifdef LFP_CHEMISTRY
|
||||||
datalayer.battery.info.chemistry = battery_chemistry_enum::LFP;
|
datalayer.battery.info.chemistry = battery_chemistry_enum::LFP;
|
||||||
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_3Y_LFP;
|
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_3Y_LFP;
|
||||||
|
|
|
@ -145,9 +145,10 @@ void send_can_battery() {
|
||||||
void setup_battery(void) { // Performs one time setup at startup
|
void setup_battery(void) { // Performs one time setup at startup
|
||||||
randomSeed(analogRead(0));
|
randomSeed(analogRead(0));
|
||||||
|
|
||||||
#ifdef DEBUG_VIA_USB
|
strncpy(datalayer.system.info.battery_protocol, "Fake battery for testing purposes",
|
||||||
Serial.println("Test mode with fake battery selected");
|
sizeof(datalayer.system.info.battery_protocol) - 1);
|
||||||
#endif
|
datalayer.system.info.battery_protocol[sizeof(datalayer.system.info.battery_protocol) - 1] =
|
||||||
|
'\0'; // Ensure null termination
|
||||||
|
|
||||||
datalayer.battery.info.max_design_voltage_dV =
|
datalayer.battery.info.max_design_voltage_dV =
|
||||||
4040; // 404.4V, over this, charging is not possible (goes into forced discharge)
|
4040; // 404.4V, over this, charging is not possible (goes into forced discharge)
|
||||||
|
|
|
@ -332,10 +332,10 @@ void send_can_battery() {
|
||||||
}
|
}
|
||||||
|
|
||||||
void setup_battery(void) { // Performs one time setup at startup
|
void setup_battery(void) { // Performs one time setup at startup
|
||||||
#ifdef DEBUG_VIA_USB
|
strncpy(datalayer.system.info.battery_protocol, "Volvo / Polestar 78kWh battery",
|
||||||
Serial.println("Volvo SPA XC40 Recharge / Polestar2 78kWh battery selected");
|
sizeof(datalayer.system.info.battery_protocol) - 1);
|
||||||
#endif
|
datalayer.system.info.battery_protocol[sizeof(datalayer.system.info.battery_protocol) - 1] =
|
||||||
|
'\0'; // Ensure null termination
|
||||||
datalayer.battery.info.number_of_cells = 108;
|
datalayer.battery.info.number_of_cells = 108;
|
||||||
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_DV;
|
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_DV;
|
||||||
datalayer.battery.info.min_design_voltage_dV = MIN_PACK_VOLTAGE_DV;
|
datalayer.battery.info.min_design_voltage_dV = MIN_PACK_VOLTAGE_DV;
|
||||||
|
|
|
@ -127,7 +127,10 @@ typedef struct {
|
||||||
} DATALAYER_SHUNT_TYPE;
|
} DATALAYER_SHUNT_TYPE;
|
||||||
|
|
||||||
typedef struct {
|
typedef struct {
|
||||||
// TODO
|
/** array with type of battery used, for displaying on webserver */
|
||||||
|
char battery_protocol[64] = {0};
|
||||||
|
/** array with type of inverter used, for displaying on webserver */
|
||||||
|
char inverter_protocol[64] = {0};
|
||||||
} DATALAYER_SYSTEM_INFO_TYPE;
|
} DATALAYER_SYSTEM_INFO_TYPE;
|
||||||
|
|
||||||
typedef struct {
|
typedef struct {
|
||||||
|
|
|
@ -486,6 +486,7 @@ String processor(const String& var) {
|
||||||
|
|
||||||
// Display which components are used
|
// Display which components are used
|
||||||
content += "<h4 style='color: white;'>Inverter protocol: ";
|
content += "<h4 style='color: white;'>Inverter protocol: ";
|
||||||
|
content += datalayer.system.info.inverter_protocol;
|
||||||
#ifdef BYD_CAN
|
#ifdef BYD_CAN
|
||||||
content += "BYD Battery-Box Premium HVS over CAN Bus";
|
content += "BYD Battery-Box Premium HVS over CAN Bus";
|
||||||
#endif // BYD_CAN
|
#endif // BYD_CAN
|
||||||
|
@ -514,83 +515,8 @@ String processor(const String& var) {
|
||||||
content += "SolaX Triple Power LFP over CAN bus";
|
content += "SolaX Triple Power LFP over CAN bus";
|
||||||
#endif // SOLAX_CAN
|
#endif // SOLAX_CAN
|
||||||
content += "</h4>";
|
content += "</h4>";
|
||||||
|
|
||||||
content += "<h4 style='color: white;'>Battery protocol: ";
|
content += "<h4 style='color: white;'>Battery protocol: ";
|
||||||
#ifdef BMW_I3_BATTERY
|
content += datalayer.system.info.battery_protocol;
|
||||||
content += "BMW i3";
|
|
||||||
#endif // BMW_I3_BATTERY
|
|
||||||
#ifdef BMW_IX_BATTERY
|
|
||||||
content += "BMW iX and i4-7 platform";
|
|
||||||
#endif // BMW_IX_BATTERY
|
|
||||||
#ifdef BYD_ATTO_3_BATTERY
|
|
||||||
content += "BYD Atto 3";
|
|
||||||
#endif // BYD_ATTO_3_BATTERY
|
|
||||||
#ifdef CELLPOWER_BMS
|
|
||||||
content += "Cellpower BMS";
|
|
||||||
#endif // CELLPOWER_BMS
|
|
||||||
#ifdef CHADEMO_BATTERY
|
|
||||||
content += "Chademo V2X mode";
|
|
||||||
#endif // CHADEMO_BATTERY
|
|
||||||
#ifdef IMIEV_CZERO_ION_BATTERY
|
|
||||||
content += "I-Miev / C-Zero / Ion Triplet";
|
|
||||||
#endif // IMIEV_CZERO_ION_BATTERY
|
|
||||||
#ifdef JAGUAR_IPACE_BATTERY
|
|
||||||
content += "Jaguar I-PACE";
|
|
||||||
#endif // JAGUAR_IPACE_BATTERY
|
|
||||||
#ifdef KIA_HYUNDAI_64_BATTERY
|
|
||||||
content += "Kia/Hyundai 64kWh";
|
|
||||||
#endif // KIA_HYUNDAI_64_BATTERY
|
|
||||||
#ifdef KIA_E_GMP_BATTERY
|
|
||||||
content += "Kia/Hyundai EGMP platform";
|
|
||||||
#endif // KIA_E_GMP_BATTERY
|
|
||||||
#ifdef KIA_HYUNDAI_HYBRID_BATTERY
|
|
||||||
content += "Kia/Hyundai Hybrid";
|
|
||||||
#endif // KIA_HYUNDAI_HYBRID_BATTERY
|
|
||||||
#ifdef MG_5_BATTERY
|
|
||||||
content += "MG 5";
|
|
||||||
#endif // MG_5_BATTERY
|
|
||||||
#ifdef NISSAN_LEAF_BATTERY
|
|
||||||
content += "Nissan LEAF";
|
|
||||||
#endif // NISSAN_LEAF_BATTERY
|
|
||||||
#ifdef PYLON_BATTERY
|
|
||||||
content += "Pylon compatible battery";
|
|
||||||
#endif // PYLON_BATTERY
|
|
||||||
#ifdef RJXZS_BMS
|
|
||||||
content += "RJXZS BMS, DIY battery";
|
|
||||||
#endif // RJXZS_BMS
|
|
||||||
#ifdef RANGE_ROVER_PHEV_BATTERY
|
|
||||||
content += "Range Rover 13kWh PHEV battery (L494/L405)";
|
|
||||||
#endif //RANGE_ROVER_PHEV_BATTERY
|
|
||||||
#ifdef RENAULT_KANGOO_BATTERY
|
|
||||||
content += "Renault Kangoo";
|
|
||||||
#endif // RENAULT_KANGOO_BATTERY
|
|
||||||
#ifdef RENAULT_TWIZY_BATTERY
|
|
||||||
content += "Renault Twizy";
|
|
||||||
#endif // RENAULT_TWIZY_BATTERY
|
|
||||||
#ifdef RENAULT_ZOE_GEN1_BATTERY
|
|
||||||
content += "Renault Zoe Gen1 22/40";
|
|
||||||
#endif // RENAULT_ZOE_GEN1_BATTERY
|
|
||||||
#ifdef RENAULT_ZOE_GEN2_BATTERY
|
|
||||||
content += "Renault Zoe Gen2 50";
|
|
||||||
#endif // RENAULT_ZOE_GEN2_BATTERY
|
|
||||||
#ifdef SANTA_FE_PHEV_BATTERY
|
|
||||||
content += "Santa Fe PHEV";
|
|
||||||
#endif // SANTA_FE_PHEV_BATTERY
|
|
||||||
#ifdef SERIAL_LINK_RECEIVER
|
|
||||||
content += "Serial link to another LilyGo board";
|
|
||||||
#endif // SERIAL_LINK_RECEIVER
|
|
||||||
#ifdef TESLA_MODEL_SX_BATTERY
|
|
||||||
content += "Tesla Model S/X";
|
|
||||||
#endif // TESLA_MODEL_SX_BATTERY
|
|
||||||
#ifdef TESLA_MODEL_3Y_BATTERY
|
|
||||||
content += "Tesla Model 3/Y";
|
|
||||||
#endif // TESLA_MODEL_3Y_BATTERY
|
|
||||||
#ifdef VOLVO_SPA_BATTERY
|
|
||||||
content += "Volvo / Polestar 78kWh battery";
|
|
||||||
#endif // VOLVO_SPA_BATTERY
|
|
||||||
#ifdef TEST_FAKE_BATTERY
|
|
||||||
content += "Fake battery for testing purposes";
|
|
||||||
#endif // TEST_FAKE_BATTERY
|
|
||||||
#ifdef DOUBLE_BATTERY
|
#ifdef DOUBLE_BATTERY
|
||||||
content += " (Double battery)";
|
content += " (Double battery)";
|
||||||
if (datalayer.battery.info.chemistry == battery_chemistry_enum::LFP) {
|
if (datalayer.battery.info.chemistry == battery_chemistry_enum::LFP) {
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue