Merge branch 'main' into library/acanfd-update

This commit is contained in:
Daniel Öster 2025-08-31 14:21:49 +03:00
commit a7f9d32c3a
81 changed files with 3022 additions and 1737 deletions

View file

@ -90,6 +90,8 @@ const char* name_for_battery_type(BatteryType type) {
return KiaEGmpBattery::Name;
case BatteryType::KiaHyundai64:
return KiaHyundai64Battery::Name;
case BatteryType::Kia64FD:
return Kia64FDBattery::Name;
case BatteryType::KiaHyundaiHybrid:
return KiaHyundaiHybridBattery::Name;
case BatteryType::Meb:
@ -108,6 +110,8 @@ const char* name_for_battery_type(BatteryType type) {
return RjxzsBms::Name;
case BatteryType::RangeRoverPhev:
return RangeRoverPhevBattery::Name;
case BatteryType::RelionBattery:
return RelionBattery::Name;
case BatteryType::RenaultKangoo:
return RenaultKangooBattery::Name;
case BatteryType::RenaultTwizy:
@ -187,6 +191,8 @@ Battery* create_battery(BatteryType type) {
return new ImievCZeroIonBattery();
case BatteryType::JaguarIpace:
return new JaguarIpaceBattery();
case BatteryType::Kia64FD:
return new Kia64FDBattery();
case BatteryType::KiaEGmp:
return new KiaEGmpBattery();
case BatteryType::KiaHyundai64:
@ -209,6 +215,8 @@ Battery* create_battery(BatteryType type) {
return new RjxzsBms();
case BatteryType::RangeRoverPhev:
return new RangeRoverPhevBattery();
case BatteryType::RelionBattery:
return new RelionBattery();
case BatteryType::RenaultKangoo:
return new RenaultKangooBattery();
case BatteryType::RenaultTwizy:
@ -313,6 +321,14 @@ void setup_battery() {
}
#endif
/* User-selected Tesla settings */
bool user_selected_tesla_digital_HVIL = false;
uint16_t user_selected_tesla_GTW_country = 17477;
bool user_selected_tesla_GTW_rightHandDrive = true;
uint16_t user_selected_tesla_GTW_mapRegion = 2;
uint16_t user_selected_tesla_GTW_chassisType = 2;
uint16_t user_selected_tesla_GTW_packEnergy = 1;
/* User-selected voltages used for custom-BMS batteries (RJXZS etc.) */
#if defined(MAX_CUSTOM_PACK_VOLTAGE_DV) && defined(MIN_CUSTOM_PACK_VOLTAGE_DV) && \
defined(MAX_CUSTOM_CELL_VOLTAGE_MV) && defined(MIN_CUSTOM_CELL_VOLTAGE_MV)

View file

@ -29,6 +29,7 @@ void setup_can_shunt();
#include "HYUNDAI-IONIQ-28-BATTERY.h"
#include "IMIEV-CZERO-ION-BATTERY.h"
#include "JAGUAR-IPACE-BATTERY.h"
#include "KIA-64FD-BATTERY.h"
#include "KIA-E-GMP-BATTERY.h"
#include "KIA-HYUNDAI-64-BATTERY.h"
#include "KIA-HYUNDAI-HYBRID-BATTERY.h"
@ -39,6 +40,7 @@ void setup_can_shunt();
#include "ORION-BMS.h"
#include "PYLON-BATTERY.h"
#include "RANGE-ROVER-PHEV-BATTERY.h"
#include "RELION-LV-BATTERY.h"
#include "RENAULT-KANGOO-BATTERY.h"
#include "RENAULT-TWIZY.h"
#include "RENAULT-ZOE-GEN1-BATTERY.h"
@ -60,4 +62,11 @@ extern uint16_t user_selected_min_pack_voltage_dV;
extern uint16_t user_selected_max_cell_voltage_mV;
extern uint16_t user_selected_min_cell_voltage_mV;
extern bool user_selected_tesla_digital_HVIL;
extern uint16_t user_selected_tesla_GTW_country;
extern bool user_selected_tesla_GTW_rightHandDrive;
extern uint16_t user_selected_tesla_GTW_mapRegion;
extern uint16_t user_selected_tesla_GTW_chassisType;
extern uint16_t user_selected_tesla_GTW_packEnergy;
#endif

View file

@ -307,9 +307,7 @@ void BmwIXBattery::handle_incoming_can_frame(CAN_frame rx_frame) {
if ((rx_frame.data.u8[6] << 8 | rx_frame.data.u8[7]) == 10000 ||
(rx_frame.data.u8[8] << 8 | rx_frame.data.u8[9]) == 10000) { //Qualifier Invalid Mode - Request Reboot
#ifdef DEBUG_LOG
logging.println("Cell MinMax Qualifier Invalid - Requesting BMS Reset");
#endif // DEBUG_LOG
//set_event(EVENT_BATTERY_VALUE_UNAVAILABLE, (millis())); //Eventually need new Info level event type
transmit_can_frame(&BMWiX_6F4_REQUEST_HARD_RESET);
} else { //Only ingest values if they are not the 10V Error state
@ -378,15 +376,11 @@ void BmwIXBattery::transmit_can(unsigned long currentMillis) {
// Detect edge
if (ContactorCloseRequest.previous == false && ContactorCloseRequest.present == true) {
// Rising edge detected
#ifdef DEBUG_LOG
logging.println("Rising edge detected. Resetting 10ms counter.");
#endif // DEBUG_LOG
counter_10ms = 0; // reset counter
} else if (ContactorCloseRequest.previous == true && ContactorCloseRequest.present == false) {
// Dropping edge detected
#ifdef DEBUG_LOG
logging.println("Dropping edge detected. Resetting 10ms counter.");
#endif // DEBUG_LOG
counter_10ms = 0; // reset counter
}
ContactorCloseRequest.previous = ContactorCloseRequest.present;
@ -465,12 +459,10 @@ void BmwIXBattery::setup(void) { // Performs one time setup at startup
void BmwIXBattery::HandleIncomingUserRequest(void) {
// Debug user request to open or close the contactors
#ifdef DEBUG_LOG
logging.print("User request: contactor close: ");
logging.print(userRequestContactorClose);
logging.print(" User request: contactor open: ");
logging.println(userRequestContactorOpen);
#endif // DEBUG_LOG
if ((userRequestContactorClose == false) && (userRequestContactorOpen == false)) {
// do nothing
} else if ((userRequestContactorClose == true) && (userRequestContactorOpen == false)) {
@ -487,11 +479,9 @@ void BmwIXBattery::HandleIncomingUserRequest(void) {
// set user request to false
userRequestContactorClose = false;
userRequestContactorOpen = false;
// print error, as both these flags shall not be true at the same time
#ifdef DEBUG_LOG
// print error, as both these flags shall not be true at the same time
logging.println(
"Error: user requested contactors to close and open at the same time. Contactors have been opened.");
#endif // DEBUG_LOG
}
}
@ -499,16 +489,12 @@ void BmwIXBattery::HandleIncomingInverterRequest(void) {
InverterContactorCloseRequest.present = datalayer.system.status.inverter_allows_contactor_closing;
// Detect edge
if (InverterContactorCloseRequest.previous == false && InverterContactorCloseRequest.present == true) {
// Rising edge detected
#ifdef DEBUG_LOG
// Rising edge detected
logging.println("Inverter requests to close contactors");
#endif // DEBUG_LOG
BmwIxCloseContactors();
} else if (InverterContactorCloseRequest.previous == true && InverterContactorCloseRequest.present == false) {
// Falling edge detected
#ifdef DEBUG_LOG
// Falling edge detected
logging.println("Inverter requests to open contactors");
#endif // DEBUG_LOG
BmwIxOpenContactors();
} // else: do nothing
@ -517,16 +503,12 @@ void BmwIXBattery::HandleIncomingInverterRequest(void) {
}
void BmwIXBattery::BmwIxCloseContactors(void) {
#ifdef DEBUG_LOG
logging.println("Closing contactors");
#endif // DEBUG_LOG
contactorCloseReq = true;
}
void BmwIXBattery::BmwIxOpenContactors(void) {
#ifdef DEBUG_LOG
logging.println("Opening contactors");
#endif // DEBUG_LOG
contactorCloseReq = false;
counter_100ms = 0; // reset counter, such that keep contactors closed message sequence starts from the beginning
}
@ -552,46 +534,34 @@ void BmwIXBattery::HandleBmwIxCloseContactorsRequest(uint16_t counter_10ms) {
if (counter_10ms == 0) {
// @0 ms
transmit_can_frame(&BMWiX_510);
#ifdef DEBUG_LOG
logging.println("Transmitted 0x510 - 1/6");
#endif // DEBUG_LOG
} else if (counter_10ms == 5) {
// @50 ms
transmit_can_frame(&BMWiX_276);
#ifdef DEBUG_LOG
logging.println("Transmitted 0x276 - 2/6");
#endif // DEBUG_LOG
} else if (counter_10ms == 10) {
// @100 ms
BMWiX_510.data.u8[2] = 0x04; // TODO: check if needed
transmit_can_frame(&BMWiX_510);
#ifdef DEBUG_LOG
logging.println("Transmitted 0x510 - 3/6");
#endif // DEBUG_LOG
} else if (counter_10ms == 20) {
// @200 ms
BMWiX_510.data.u8[2] = 0x10; // TODO: check if needed
BMWiX_510.data.u8[5] = 0x80; // needed to close contactors
transmit_can_frame(&BMWiX_510);
#ifdef DEBUG_LOG
logging.println("Transmitted 0x510 - 4/6");
#endif // DEBUG_LOG
} else if (counter_10ms == 30) {
// @300 ms
BMWiX_16E.data.u8[0] = 0x6A;
BMWiX_16E.data.u8[1] = 0xAD;
transmit_can_frame(&BMWiX_16E);
#ifdef DEBUG_LOG
logging.println("Transmitted 0x16E - 5/6");
#endif // DEBUG_LOG
} else if (counter_10ms == 50) {
// @500 ms
BMWiX_16E.data.u8[0] = 0x03;
BMWiX_16E.data.u8[1] = 0xA9;
transmit_can_frame(&BMWiX_16E);
#ifdef DEBUG_LOG
logging.println("Transmitted 0x16E - 6/6");
#endif // DEBUG_LOG
ContactorState.closed = true;
ContactorState.open = false;
}
@ -613,9 +583,7 @@ void BmwIXBattery::BmwIxKeepContactorsClosed(uint8_t counter_100ms) {
0xC9, 0x3A, 0xF7}; // Explicit declaration, to prevent modification by other functions
if (counter_100ms == 0) {
#ifdef DEBUG_LOG
logging.println("Sending keep contactors closed messages started");
#endif // DEBUG_LOG
// @0 ms
transmit_can_frame(&BMWiX_510);
} else if (counter_100ms == 7) {
@ -631,9 +599,7 @@ void BmwIXBattery::BmwIxKeepContactorsClosed(uint8_t counter_100ms) {
BMWiX_16E.data.u8[0] = 0x02;
BMWiX_16E.data.u8[1] = 0xA7;
transmit_can_frame(&BMWiX_16E);
#ifdef DEBUG_LOG
logging.println("Sending keep contactors closed messages finished");
#endif // DEBUG_LOG
} else if (counter_100ms == 140) {
// @14000 ms
// reset counter (outside of this function)

View file

@ -122,9 +122,7 @@ bool BmwPhevBattery::storeUDSPayload(const uint8_t* payload, uint8_t length) {
if (gUDSContext.UDS_bytesReceived + length > sizeof(gUDSContext.UDS_buffer)) {
// Overflow => abort
gUDSContext.UDS_inProgress = false;
#ifdef DEBUG_LOG
logging.println("UDS Payload Overflow");
#endif // DEBUG_LOG
return false;
}
memcpy(&gUDSContext.UDS_buffer[gUDSContext.UDS_bytesReceived], payload, length);
@ -134,9 +132,7 @@ bool BmwPhevBattery::storeUDSPayload(const uint8_t* payload, uint8_t length) {
// If weve reached or exceeded the expected length, mark complete
if (gUDSContext.UDS_bytesReceived >= gUDSContext.UDS_expectedLength) {
gUDSContext.UDS_inProgress = false;
// #ifdef DEBUG_LOG
// logging.println("Recived all expected UDS bytes");
// #endif // DEBUG_LOG
}
return true;
}
@ -196,9 +192,7 @@ void BmwPhevBattery::wake_battery_via_canbus() {
change_can_speed(original_speed);
#ifdef DEBUG_LOG
logging.println("Sent magic wakeup packet to SME at 100kbps...");
#endif
}
void BmwPhevBattery::update_values() { //This function maps all the values fetched via CAN to the battery datalayer
@ -246,9 +240,7 @@ void BmwPhevBattery::update_values() { //This function maps all the values fetc
datalayer.battery.status.cell_min_voltage_mV = 9999; //Stale values force stop
datalayer.battery.status.cell_max_voltage_mV = 9999; //Stale values force stop
set_event(EVENT_STALE_VALUE, 0);
#ifdef DEBUG_LOG
logging.println("Stale Min/Max voltage values detected during charge/discharge sending - 9999mV...");
#endif // DEBUG_LOG
} else {
datalayer.battery.status.cell_min_voltage_mV = min_cell_voltage; //Value is alive
@ -398,11 +390,7 @@ void BmwPhevBattery::handle_incoming_can_frame(CAN_frame rx_frame) {
rx_frame.data.u8[4] ==
0xAD) { //Balancing Status 01 Active 03 Not Active 7DLC F1 05 71 03 AD 6B 01
balancing_status = (rx_frame.data.u8[6]);
// #ifdef DEBUG_LOG
// logging.println("Balancing Status received");
// #endif // DEBUG_LOG
//logging.println("Balancing Status received");
}
break;
@ -525,7 +513,6 @@ void BmwPhevBattery::handle_incoming_can_frame(CAN_frame rx_frame) {
battery_current = ((int32_t)((gUDSContext.UDS_buffer[3] << 24) | (gUDSContext.UDS_buffer[4] << 16) |
(gUDSContext.UDS_buffer[5] << 8) | gUDSContext.UDS_buffer[6])) *
0.1;
#ifdef DEBUG_LOG
logging.print("Received current/amps measurement data: ");
logging.print(battery_current);
logging.print(" - ");
@ -538,7 +525,6 @@ void BmwPhevBattery::handle_incoming_can_frame(CAN_frame rx_frame) {
logging.print(" ");
}
logging.println(); // new line at the end
#endif // DEBUG_LOG
}
//Cell Min/Max
@ -553,7 +539,6 @@ void BmwPhevBattery::handle_incoming_can_frame(CAN_frame rx_frame) {
min_cell_voltage = (gUDSContext.UDS_buffer[9] << 8 | gUDSContext.UDS_buffer[10]) / 10;
max_cell_voltage = (gUDSContext.UDS_buffer[11] << 8 | gUDSContext.UDS_buffer[12]) / 10;
} else {
#ifdef DEBUG_LOG
logging.println("Cell Min Max Invalid 65535 or 0...");
logging.print("Received data: ");
for (uint16_t i = 0; i < gUDSContext.UDS_bytesReceived; i++) {
@ -565,7 +550,6 @@ void BmwPhevBattery::handle_incoming_can_frame(CAN_frame rx_frame) {
logging.print(" ");
}
logging.println(); // new line at the end
#endif // DEBUG_LOG
}
}
@ -618,16 +602,12 @@ void BmwPhevBattery::handle_incoming_can_frame(CAN_frame rx_frame) {
if (rx_frame.data.u8[6] > 0 && rx_frame.data.u8[6] < 255) {
battery_temperature_min = (rx_frame.data.u8[6] - 50);
} else {
#ifdef DEBUG_LOG
logging.println("Pre parsed Cell Temp Min is Invalid ");
#endif
}
if (rx_frame.data.u8[7] > 0 && rx_frame.data.u8[7] < 255) {
battery_temperature_max = (rx_frame.data.u8[7] - 50);
} else {
#ifdef DEBUG_LOG
logging.println("Pre parsed Cell Temp Max is Invalid ");
#endif
}
break;

View file

@ -2,6 +2,7 @@
#include <Arduino.h>
#include "../communication/can/comm_can.h"
#include "../datalayer/datalayer.h"
#include "../devboard/utils/logging.h"
uint8_t reverse_bits(uint8_t byte) {
uint8_t reversed = 0;
@ -122,9 +123,7 @@ void BmwSbox::transmit_can(unsigned long currentMillis) {
SBOX_100.data.u8[0] = 0x86; // Precharge relay only
prechargeStartTime = currentMillis;
contactorStatus = NEGATIVE;
#ifdef DEBUG_VIA_USB
Serial.println("S-BOX Precharge relay engaged");
#endif
logging.println("S-BOX Precharge relay engaged");
break;
case NEGATIVE:
if (currentMillis - prechargeStartTime >= CONTACTOR_CONTROL_T1) {
@ -132,9 +131,7 @@ void BmwSbox::transmit_can(unsigned long currentMillis) {
negativeStartTime = currentMillis;
contactorStatus = POSITIVE;
datalayer.shunt.precharging = true;
#ifdef DEBUG_VIA_USB
Serial.println("S-BOX Negative relay engaged");
#endif
logging.println("S-BOX Negative relay engaged");
}
break;
case POSITIVE:
@ -145,18 +142,14 @@ void BmwSbox::transmit_can(unsigned long currentMillis) {
positiveStartTime = currentMillis;
contactorStatus = PRECHARGE_OFF;
datalayer.shunt.precharging = false;
#ifdef DEBUG_VIA_USB
Serial.println("S-BOX Positive relay engaged");
#endif
logging.println("S-BOX Positive relay engaged");
}
break;
case PRECHARGE_OFF:
if (currentMillis - positiveStartTime >= CONTACTOR_CONTROL_T3) {
SBOX_100.data.u8[0] = 0x6A; // Negative + Positive
contactorStatus = COMPLETED;
#ifdef DEBUG_VIA_USB
Serial.println("S-BOX Precharge relay released");
#endif
logging.println("S-BOX Precharge relay released");
datalayer.shunt.contactors_engaged = true;
}
break;

View file

@ -4,12 +4,6 @@
#include "../datalayer/datalayer_extended.h"
#include "../devboard/utils/events.h"
/* Notes
SOC% by default is now ESTIMATED.
If you have a crash-locked pack, See the Wiki for more info on how to attempt an unlock
After battery has been unlocked, you can remove the "USE_ESTIMATED_SOC" from the BYD-ATTO-3-BATTERY.h file
*/
#define POLL_FOR_BATTERY_VOLTAGE 0x0008
#define POLL_FOR_BATTERY_CURRENT 0x0009
#define POLL_FOR_LOWEST_TEMP_CELL 0x002f
@ -142,6 +136,16 @@ uint16_t estimateSOCstandard(uint16_t packVoltage) { // Linear interpolation fu
return 0; // Default return for safety, should never reach here
}
uint8_t compute441Checksum(const uint8_t* u8) // Computes the 441 checksum byte
{
int sum = 0;
for (int i = 0; i < 7; ++i) {
sum += u8[i];
}
uint8_t lsb = static_cast<uint8_t>(sum & 0xFF);
return static_cast<uint8_t>(~lsb & 0xFF);
}
void BydAttoBattery::
update_values() { //This function maps all the values fetched via CAN to the correct parameters used for modbus
@ -389,6 +393,7 @@ void BydAttoBattery::handle_incoming_can_frame(CAN_frame rx_frame) {
datalayer_battery->status.CAN_battery_still_alive = CAN_STILL_ALIVE;
battery_voltage = ((rx_frame.data.u8[1] & 0x0F) << 8) | rx_frame.data.u8[0];
//battery_temperature_something = rx_frame.data.u8[7] - 40; resides in frame 7
BMS_voltage_available = true;
break;
case 0x445:
datalayer_battery->status.CAN_battery_still_alive = CAN_STILL_ALIVE;
@ -538,10 +543,17 @@ void BydAttoBattery::transmit_can(unsigned long currentMillis) {
}
if (counter_100ms > 3) {
ATTO_3_441.data.u8[4] = 0x9D;
ATTO_3_441.data.u8[5] = 0x01;
ATTO_3_441.data.u8[6] = 0xFF;
ATTO_3_441.data.u8[7] = 0xF5;
if (BMS_voltage_available) { // Transmit battery voltage back to BMS when confirmed it's available, this closes the contactors
ATTO_3_441.data.u8[4] = (uint8_t)(battery_voltage - 1);
ATTO_3_441.data.u8[5] = ((battery_voltage - 1) >> 8);
ATTO_3_441.data.u8[6] = 0xFF;
ATTO_3_441.data.u8[7] = compute441Checksum(ATTO_3_441.data.u8);
} else {
ATTO_3_441.data.u8[4] = 0x0C;
ATTO_3_441.data.u8[5] = 0x00;
ATTO_3_441.data.u8[6] = 0xFF;
ATTO_3_441.data.u8[7] = 0x87;
}
}
transmit_can_frame(&ATTO_3_441);

View file

@ -7,8 +7,12 @@
#include "BYD-ATTO-3-HTML.h"
#include "CanBattery.h"
#define USE_ESTIMATED_SOC // If enabled, SOC is estimated from pack voltage. Useful for locked packs. \
// Comment out this only if you know your BMS is unlocked and able to send SOC%
/* Notes
SOC% by default is now MEASURED by BMS.
If you have a crash-locked pack, See the Wiki for more info on how to attempt an unlock.
Remove the comment from "USE_ESTIMATED_SOC" below if you still decide to use a locked battery and want to use estimated SOC.
*/
//#define USE_ESTIMATED_SOC
//Uncomment and configure this line, if you want to filter out a broken temperature sensor (1-10)
//Make sure you understand risks associated with disabling. Values can be read via "More Battery info"
@ -94,6 +98,7 @@ class BydAttoBattery : public CanBattery {
unsigned long previousMillis100 = 0; // will store last time a 100ms CAN Message was send
unsigned long previousMillis200 = 0; // will store last time a 200ms CAN Message was send
bool SOC_method = false;
bool BMS_voltage_available = false;
uint8_t counter_50ms = 0;
uint8_t counter_100ms = 0;
uint8_t frame6_counter = 0xB;

View file

@ -45,6 +45,8 @@ enum class BatteryType {
MgHsPhev = 37,
SamsungSdiLv = 38,
HyundaiIoniq28 = 39,
Kia64FD = 40,
RelionBattery = 41,
Highest
};
@ -73,6 +75,7 @@ class Battery {
virtual bool supports_clear_isolation() { return false; }
virtual bool supports_reset_BMS() { return false; }
virtual bool supports_reset_SOC() { return false; }
virtual bool supports_reset_crash() { return false; }
virtual bool supports_reset_NVROL() { return false; }
virtual bool supports_reset_DTC() { return false; }
@ -91,6 +94,7 @@ class Battery {
virtual void clear_isolation() {}
virtual void reset_BMS() {}
virtual void reset_SOC() {}
virtual void reset_crash() {}
virtual void reset_contactor() {}
virtual void reset_NVROL() {}

View file

@ -116,7 +116,6 @@ void ChademoBattery::process_vehicle_charging_session(CAN_frame rx_frame) {
x102_chg_session.ChargingCurrentRequest = newChargingCurrentRequest;
x102_chg_session.TargetBatteryVoltage = newTargetBatteryVoltage;
#ifdef DEBUG_LOG
//Note on p131
uint8_t chargingrate = 0;
if (x100_chg_lim.ConstantOfChargingRateIndication > 0) {
@ -124,7 +123,6 @@ void ChademoBattery::process_vehicle_charging_session(CAN_frame rx_frame) {
logging.print("Charge Rate (kW): ");
logging.println(chargingrate);
}
#endif
//Table A.26—Charge control termination command patterns -- should echo x108 handling
@ -136,41 +134,31 @@ void ChademoBattery::process_vehicle_charging_session(CAN_frame rx_frame) {
*/
if ((CHADEMO_Status == CHADEMO_INIT && vehicle_permission) ||
(x102_chg_session.s.status.StatusVehicleChargingEnabled && !vehicle_permission)) {
#ifdef DEBUG_LOG
logging.println("Inconsistent charge/discharge state.");
#endif
CHADEMO_Status = CHADEMO_FAULT;
return;
}
if (x102_chg_session.f.fault.FaultBatteryOverVoltage) {
#ifdef DEBUG_LOG
logging.println("Vehicle indicates fault, battery over voltage.");
#endif
CHADEMO_Status = CHADEMO_STOP;
return;
}
if (x102_chg_session.f.fault.FaultBatteryUnderVoltage) {
#ifdef DEBUG_LOG
logging.println("Vehicle indicates fault, battery under voltage.");
#endif
CHADEMO_Status = CHADEMO_STOP;
return;
}
if (x102_chg_session.f.fault.FaultBatteryCurrentDeviation) {
#ifdef DEBUG_LOG
logging.println("Vehicle indicates fault, battery current deviation. Possible EVSE issue?");
#endif
CHADEMO_Status = CHADEMO_STOP;
return;
}
if (x102_chg_session.f.fault.FaultBatteryVoltageDeviation) {
#ifdef DEBUG_LOG
logging.println("Vehicle indicates fault, battery voltage deviation. Possible EVSE issue?");
#endif
CHADEMO_Status = CHADEMO_STOP;
return;
}
@ -183,18 +171,14 @@ void ChademoBattery::process_vehicle_charging_session(CAN_frame rx_frame) {
//FIXME condition nesting or more stanzas needed here for clear determination of cessation reason
if (CHADEMO_Status == CHADEMO_POWERFLOW && EVSE_mode == CHADEMO_CHARGE && !vehicle_permission) {
#ifdef DEBUG_LOG
logging.println("State of charge ceiling reached or charging interrupted, stop charging");
#endif
CHADEMO_Status = CHADEMO_STOP;
return;
}
if (vehicle_permission && CHADEMO_Status == CHADEMO_NEGOTIATE) {
CHADEMO_Status = CHADEMO_EV_ALLOWED;
#ifdef DEBUG_LOG
logging.println("STATE shift to CHADEMO_EV_ALLOWED in process_vehicle_charging_session()");
#endif
return;
}
@ -203,23 +187,17 @@ void ChademoBattery::process_vehicle_charging_session(CAN_frame rx_frame) {
// consider relocating
if (vehicle_permission && CHADEMO_Status == CHADEMO_EVSE_PREPARE && priorTargetBatteryVoltage == 0 &&
newTargetBatteryVoltage > 0 && x102_chg_session.s.status.StatusVehicleChargingEnabled) {
#ifdef DEBUG_LOG
logging.println("STATE SHIFT to EVSE_START reached in process_vehicle_charging_session()");
#endif
CHADEMO_Status = CHADEMO_EVSE_START;
return;
}
if (vehicle_permission && evse_permission && CHADEMO_Status == CHADEMO_POWERFLOW) {
#ifdef DEBUG_LOG
logging.println("updating vehicle request in process_vehicle_charging_session()");
#endif
return;
}
#ifdef DEBUG_LOG
logging.println("UNHANDLED CHADEMO STATE, try unplugging chademo cable, reboot emulator, and retry!");
#endif
return;
}
@ -231,8 +209,7 @@ void ChademoBattery::process_vehicle_charging_limits(CAN_frame rx_frame) {
x200_discharge_limits.MinimumBatteryDischargeLevel = rx_frame.data.u8[6];
x200_discharge_limits.MaxRemainingCapacityForCharging = rx_frame.data.u8[7];
#ifdef DEBUG_LOG
/* unsigned long currentMillis = millis();
/* unsigned long currentMillis = millis();
if (currentMillis - previousMillis5000 >= INTERVAL_5_S) {
previousMillis5000 = currentMillis;
logging.println("x200 Max remaining capacity for charging/discharging:");
@ -240,16 +217,13 @@ void ChademoBattery::process_vehicle_charging_limits(CAN_frame rx_frame) {
logging.println(0xFF - x200_discharge_limits.MaxRemainingCapacityForCharging);
}
*/
#endif
if (get_measured_voltage() <= x200_discharge_limits.MinimumDischargeVoltage && CHADEMO_Status > CHADEMO_NEGOTIATE) {
#ifdef DEBUG_LOG
logging.println("x200 minimum discharge voltage met or exceeded, stopping.");
logging.print("Measured: ");
logging.print(get_measured_voltage());
logging.print("Minimum voltage: ");
logging.print(x200_discharge_limits.MinimumDischargeVoltage);
#endif
CHADEMO_Status = CHADEMO_STOP;
}
}
@ -264,7 +238,6 @@ void ChademoBattery::process_vehicle_discharge_estimate(CAN_frame rx_frame) {
x201_discharge_estimate.ApproxDischargeCompletionTime = ((rx_frame.data.u8[2] << 8) | rx_frame.data.u8[1]);
x201_discharge_estimate.AvailableVehicleEnergy = ((rx_frame.data.u8[4] << 8) | rx_frame.data.u8[3]);
#ifdef DEBUG_LOG
if (currentMillis - previousMillis5000 >= INTERVAL_5_S) {
previousMillis5000 = currentMillis;
logging.print("x201 availabile vehicle energy, completion time: ");
@ -272,7 +245,6 @@ void ChademoBattery::process_vehicle_discharge_estimate(CAN_frame rx_frame) {
logging.print("x201 approx vehicle completion time: ");
logging.println(x201_discharge_estimate.ApproxDischargeCompletionTime);
}
#endif
}
void ChademoBattery::process_vehicle_dynamic_control(CAN_frame rx_frame) {
@ -615,10 +587,8 @@ void ChademoBattery::transmit_can(unsigned long currentMillis) {
// TODO need an update_evse_dynamic_control(..) function above before we send 118
// 110.0.0
if (x102_chg_session.ControlProtocolNumberEV >= 0x03) { //Only send the following on Chademo 2.0 vehicles?
#ifdef DEBUG_LOG
//FIXME REMOVE
logging.println("REMOVE: proto 2.0");
#endif
transmit_can_frame(&CHADEMO_118);
}
}
@ -656,16 +626,12 @@ void ChademoBattery::handle_chademo_sequence() {
/* ------------------- State override conditions checks ------------------- */
/* ------------------------------------------------------------------------------ */
if (CHADEMO_Status >= CHADEMO_EV_ALLOWED && x102_chg_session.s.status.StatusVehicleShifterPosition) {
#ifdef DEBUG_LOG
logging.println("Vehicle is not parked, abort.");
#endif
CHADEMO_Status = CHADEMO_STOP;
}
if (CHADEMO_Status >= CHADEMO_EV_ALLOWED && !vehicle_permission) {
#ifdef DEBUG_LOG
logging.println("Vehicle charge/discharge permission ended, stop.");
#endif
CHADEMO_Status = CHADEMO_STOP;
}
@ -678,25 +644,19 @@ void ChademoBattery::handle_chademo_sequence() {
plug_inserted = digitalRead(pin7);
if (!plug_inserted) {
#ifdef DEBUG_LOG
// Commented unless needed for debug
// logging.println("CHADEMO plug is not inserted.");
#endif
// Commented unless needed for debug
// logging.println("CHADEMO plug is not inserted.");
return;
}
CHADEMO_Status = CHADEMO_CONNECTED;
#ifdef DEBUG_LOG
logging.println("CHADEMO plug is inserted. Provide EVSE power to vehicle to trigger initialization.");
#endif
break;
case CHADEMO_CONNECTED:
#ifdef DEBUG_LOG
// Commented unless needed for debug
//logging.println("CHADEMO_CONNECTED State");
#endif
/* plug_inserted is .. essentially a volatile of sorts, so verify */
if (plug_inserted) {
/* If connection is detectable, jumpstart handshake by
@ -729,17 +689,13 @@ void ChademoBattery::handle_chademo_sequence() {
/* Vehicle and EVSE dance */
//TODO if pin 4 / j goes high,
#ifdef DEBUG_LOG
// Commented unless needed for debug
// logging.println("CHADEMO_NEGOTIATE State");
#endif
// Commented unless needed for debug
// logging.println("CHADEMO_NEGOTIATE State");
x109_evse_state.s.status.ChgDischStopControl = 1;
break;
case CHADEMO_EV_ALLOWED:
#ifdef DEBUG_LOG
// Commented unless needed for debug
logging.println("CHADEMO_EV_ALLOWED State");
#endif
// If we are in this state, vehicle_permission was already set to true...but re-verify
// that pin 4 (j) reads high
if (vehicle_permission) {
@ -754,10 +710,8 @@ void ChademoBattery::handle_chademo_sequence() {
}
break;
case CHADEMO_EVSE_PREPARE:
#ifdef DEBUG_LOG
// Commented unless needed for debug
logging.println("CHADEMO_EVSE_PREPARE State");
#endif
/* TODO voltage check of output < 20v
* insulation test hypothetically happens here before triggering PIN 10 high
* see Table A.28Requirements for the insulation test for output DC circuit
@ -790,19 +744,15 @@ void ChademoBattery::handle_chademo_sequence() {
//state changes to CHADEMO_EVSE_START only upon receipt of charging session request
break;
case CHADEMO_EVSE_START:
#ifdef DEBUG_LOG
// Commented unless needed for debug
logging.println("CHADEMO_EVSE_START State");
#endif
datalayer.system.status.battery_allows_contactor_closing = true;
x109_evse_state.s.status.ChgDischStopControl = 1;
x109_evse_state.s.status.EVSE_status = 0;
CHADEMO_Status = CHADEMO_EVSE_CONTACTORS_ENABLED;
#ifdef DEBUG_LOG
logging.println("Initiating contactors");
#endif
/* break rather than fall through because contactors are not instantaneous;
* worth giving it a cycle to finish
@ -810,18 +760,14 @@ void ChademoBattery::handle_chademo_sequence() {
break;
case CHADEMO_EVSE_CONTACTORS_ENABLED:
#ifdef DEBUG_LOG
// Commented unless needed for debug
logging.println("CHADEMO_EVSE_CONTACTORS State");
#endif
/* check whether contactors ready, because externally dependent upon inverter allow during discharge */
if (contactors_ready) {
#ifdef DEBUG_LOG
logging.println("Contactors ready");
logging.print("Voltage: ");
logging.println(get_measured_voltage());
#endif
/* transition to POWERFLOW state if discharge compatible on both sides */
if (x109_evse_state.discharge_compatible && x102_chg_session.s.status.StatusVehicleDischargeCompatible &&
(EVSE_mode == CHADEMO_DISCHARGE || EVSE_mode == CHADEMO_BIDIRECTIONAL)) {
@ -840,10 +786,8 @@ void ChademoBattery::handle_chademo_sequence() {
/* break or fall through ? TODO */
break;
case CHADEMO_POWERFLOW:
#ifdef DEBUG_LOG
// Commented unless needed for debug
logging.println("CHADEMO_POWERFLOW State");
#endif
/* POWERFLOW for charging, discharging, and bidirectional */
/* Interpretation */
if (x102_chg_session.s.status.StatusVehicleShifterPosition) {
@ -860,9 +804,7 @@ void ChademoBattery::handle_chademo_sequence() {
}
if (get_measured_voltage() <= x200_discharge_limits.MinimumDischargeVoltage) {
#ifdef DEBUG_LOG
logging.println("x200 minimum discharge voltage met or exceeded, stopping.");
#endif
CHADEMO_Status = CHADEMO_STOP;
}
@ -871,10 +813,8 @@ void ChademoBattery::handle_chademo_sequence() {
x109_evse_state.s.status.EVSE_status = 1;
break;
case CHADEMO_STOP:
#ifdef DEBUG_LOG
// Commented unless needed for debug
logging.println("CHADEMO_STOP State");
#endif
/* back to CHADEMO_IDLE after teardown */
x109_evse_state.s.status.ChgDischStopControl = 1;
x109_evse_state.s.status.EVSE_status = 0;
@ -899,17 +839,13 @@ void ChademoBattery::handle_chademo_sequence() {
break;
case CHADEMO_FAULT:
#ifdef DEBUG_LOG
// Commented unless needed for debug
logging.println("CHADEMO_FAULT State");
#endif
/* Once faulted, never departs CHADEMO_FAULT state unless device is power cycled as a safety measure */
x109_evse_state.s.status.EVSE_error = 1;
x109_evse_state.s.status.ChgDischError = 1;
x109_evse_state.s.status.ChgDischStopControl = 1;
#ifdef DEBUG_LOG
logging.println("CHADEMO fault encountered, tearing down to make safe");
#endif
digitalWrite(pin10, LOW);
digitalWrite(pin2, LOW);
evse_permission = false;
@ -919,9 +855,7 @@ void ChademoBattery::handle_chademo_sequence() {
break;
default:
#ifdef DEBUG_LOG
logging.println("UNHANDLED CHADEMO_STATE, setting FAULT");
#endif
CHADEMO_Status = CHADEMO_FAULT;
break;
}

View file

@ -108,18 +108,16 @@ uint32_t decode_uint32be(uint8_t data[8], uint8_t offset) {
((uint32_t)data[offset + 3]);
}
#ifdef DEBUG_VIA_USB
void dump_buff(const char* msg, uint8_t* buff, uint8_t len) {
Serial.print("[DALY-BMS] ");
Serial.print(msg);
logging.print("[DALY-BMS] ");
logging.print(msg);
for (int i = 0; i < len; i++) {
Serial.print(buff[i] >> 4, HEX);
Serial.print(buff[i] & 0xf, HEX);
Serial.print(" ");
logging.print(buff[i] >> 4, HEX);
logging.print(buff[i] & 0xf, HEX);
logging.print(" ");
}
Serial.println();
logging.println();
}
#endif
void decode_packet(uint8_t command, uint8_t data[8]) {
datalayer.battery.status.CAN_battery_still_alive = CAN_STILL_ALIVE;
@ -180,9 +178,7 @@ void DalyBms::transmit_rs485(unsigned long currentMillis) {
tx_buff[2] = nextCommand;
tx_buff[3] = 8;
tx_buff[12] = calculate_checksum(tx_buff);
#ifdef DEBUG_VIA_USB
dump_buff("transmitting: ", tx_buff, 13);
#endif
Serial2.write(tx_buff, 13);
nextCommand++;
if (nextCommand > 0x98)
@ -202,17 +198,12 @@ void DalyBms::receive() {
if (recv_len > 0 && recv_buff[0] != 0xA5 || recv_len > 1 && recv_buff[1] != 0x01 ||
recv_len > 2 && (recv_buff[2] < 0x90 || recv_buff[2] > 0x98) || recv_len > 3 && recv_buff[3] != 8 ||
recv_len > 12 && recv_buff[12] != calculate_checksum(recv_buff)) {
#ifdef DEBUG_VIA_USB
dump_buff("dropping partial rx: ", recv_buff, recv_len);
#endif
recv_len = 0;
}
if (recv_len > 12) {
#ifdef DEBUG_VIA_USB
dump_buff("decoding successfull rx: ", recv_buff, recv_len);
#endif
decode_packet(recv_buff[2], &recv_buff[4]);
recv_len = 0;
lastPacket = millis();

View file

@ -75,12 +75,9 @@ void ImievCZeroIonBattery::
}
if (!BMU_Detected) {
#ifdef DEBUG_LOG
logging.println("BMU not detected, check wiring!");
#endif
}
#ifdef DEBUG_LOG
logging.println("Battery Values");
logging.print("BMU SOC: ");
logging.print(BMU_SOC);
@ -90,15 +87,6 @@ void ImievCZeroIonBattery::
logging.print(BMU_PackVoltage);
logging.print(" BMU_Power: ");
logging.print(BMU_Power);
logging.print(" Cell max voltage: ");
logging.print(max_volt_cel);
logging.print(" Cell min voltage: ");
logging.print(min_volt_cel);
logging.print(" Cell max temp: ");
logging.print(max_temp_cel);
logging.print(" Cell min temp: ");
logging.println(min_temp_cel);
#endif
}
void ImievCZeroIonBattery::handle_incoming_can_frame(CAN_frame rx_frame) {

View file

@ -102,21 +102,6 @@ void JaguarIpaceBattery::update_values() {
} else {
clear_event(EVENT_BATTERY_ISOLATION);
}
/*Finally print out values to serial if configured to do so*/
#ifdef DEBUG_LOG
logging.println("Values going to inverter");
print_units("SOH%: ", (datalayer.battery.status.soh_pptt * 0.01), "% ");
print_units(", SOC%: ", (datalayer.battery.status.reported_soc * 0.01), "% ");
print_units(", Voltage: ", (datalayer.battery.status.voltage_dV * 0.1), "V ");
print_units(", Max discharge power: ", datalayer.battery.status.max_discharge_power_W, "W ");
print_units(", Max charge power: ", datalayer.battery.status.max_charge_power_W, "W ");
print_units(", Max temp: ", (datalayer.battery.status.temperature_max_dC * 0.1), "°C ");
print_units(", Min temp: ", (datalayer.battery.status.temperature_min_dC * 0.1), "°C ");
print_units(", Max cell voltage: ", datalayer.battery.status.cell_max_voltage_mV, "mV ");
print_units(", Min cell voltage: ", datalayer.battery.status.cell_min_voltage_mV, "mV ");
logging.println("");
#endif
}
void JaguarIpaceBattery::handle_incoming_can_frame(CAN_frame rx_frame) {

View file

@ -0,0 +1,423 @@
#include "KIA-64FD-BATTERY.h"
#include "../communication/can/comm_can.h"
#include "../datalayer/datalayer.h"
#include "../devboard/utils/events.h"
#include "../devboard/utils/logging.h"
#include "../system_settings.h"
// Function to estimate SOC based on cell voltage
uint16_t Kia64FDBattery::estimateSOCFromCell(uint16_t cellVoltage) {
if (cellVoltage >= voltage[0]) {
return SOC[0];
}
if (cellVoltage <= voltage[numPoints - 1]) {
return SOC[numPoints - 1];
}
for (int i = 1; i < numPoints; ++i) {
if (cellVoltage >= voltage[i]) {
// Cast to float for proper division
float t = (float)(cellVoltage - voltage[i]) / (float)(voltage[i - 1] - voltage[i]);
// Calculate interpolated SOC value
uint16_t socDiff = SOC[i - 1] - SOC[i];
uint16_t interpolatedValue = SOC[i] + (uint16_t)(t * socDiff);
return interpolatedValue;
}
}
return 0; // Default return for safety, should never reach here
}
// Simplified version of the pack-based SOC estimation with compensation
uint16_t Kia64FDBattery::estimateSOC(uint16_t packVoltage, uint16_t cellCount, int16_t currentAmps) {
if (cellCount == 0) {
return 0;
}
// Convert pack voltage (decivolts) to millivolts
uint32_t packVoltageMv = packVoltage * 100;
// Apply internal resistance compensation
// Current is in deciamps (-150 = -15.0A, 150 = 15.0A)
// Resistance is in milliohms
int32_t voltageDrop = (currentAmps * PACK_INTERNAL_RESISTANCE_MOHM) / 10;
// Compensate the pack voltage (add the voltage drop)
uint32_t compensatedPackVoltageMv = packVoltageMv + voltageDrop;
// Calculate average cell voltage in millivolts
uint16_t avgCellVoltage = compensatedPackVoltageMv / cellCount;
// Use the cell voltage lookup table to estimate SOC
return estimateSOCFromCell(avgCellVoltage);
}
// Fix: Change parameter types to uint16_t to match SOC values
uint16_t Kia64FDBattery::selectSOC(uint16_t SOC_low, uint16_t SOC_high) {
if (SOC_low == 0 || SOC_high == 0) {
return 0; // If either value is 0, return 0
}
if (SOC_low == 10000 || SOC_high == 10000) {
return 10000; // If either value is 100%, return 100%
}
return (SOC_low < SOC_high) ? SOC_low : SOC_high; // Otherwise, return the lowest value
}
void write_cell_voltages(CAN_frame rx_frame, int start, int length, int startCell) {
for (size_t i = 0; i < length; i++) {
if ((rx_frame.data.u8[start + i] * 20) > 1000) {
datalayer.battery.status.cell_voltages_mV[startCell + i] = (rx_frame.data.u8[start + i] * 20);
}
}
}
uint8_t Kia64FDBattery::calculateCRC(CAN_frame rx_frame, uint8_t length, uint8_t initial_value) {
uint8_t crc = initial_value;
for (uint8_t j = 1; j < length; j++) { //start at 1, since 0 is the CRC
crc = crc8_table[(crc ^ static_cast<uint8_t>(rx_frame.data.u8[j])) % 256];
}
return crc;
}
void Kia64FDBattery::update_values() {
#ifdef ESTIMATE_SOC_FROM_CELLVOLTAGE
// Use the simplified pack-based SOC estimation with proper compensation
datalayer.battery.status.real_soc = estimateSOC(batteryVoltage, datalayer.battery.info.number_of_cells, batteryAmps);
// For comparison or fallback, we can still calculate from min/max cell voltages
SOC_estimated_lowest = estimateSOCFromCell(CellVoltMin_mV);
SOC_estimated_highest = estimateSOCFromCell(CellVoltMax_mV);
#else
datalayer.battery.status.real_soc = (SOC_Display * 10); //increase SOC range from 0-100.0 -> 100.00
#endif
datalayer.battery.status.soh_pptt = (batterySOH * 10); //Increase decimals from 100.0% -> 100.00%
datalayer.battery.status.voltage_dV = batteryVoltage; //value is *10 (3700 = 370.0)
datalayer.battery.status.current_dA = -batteryAmps; //value is *10 (150 = 15.0)
datalayer.battery.status.remaining_capacity_Wh = static_cast<uint32_t>(
(static_cast<double>(datalayer.battery.status.real_soc) / 10000) * datalayer.battery.info.total_capacity_Wh);
//datalayer.battery.status.max_charge_power_W = (uint16_t)allowedChargePower * 10; //From kW*100 to Watts
//The allowed charge power is not available. We estimate this value for now
if (datalayer.battery.status.real_soc > 9900) {
datalayer.battery.status.max_charge_power_W = 0;
} else if (datalayer.battery.status.real_soc >
RAMPDOWN_SOC) { // When real SOC is between 90-99%, ramp the value between Max<->0
datalayer.battery.status.max_charge_power_W =
RAMPDOWNPOWERALLOWED * (1 - (datalayer.battery.status.real_soc - RAMPDOWN_SOC) / (10000.0 - RAMPDOWN_SOC));
} else { // No limits, max charging power allowed
datalayer.battery.status.max_charge_power_W = MAXCHARGEPOWERALLOWED;
}
//datalayer.battery.status.max_discharge_power_W = (uint16_t)allowedDischargePower * 10; //From kW*100 to Watts
//The allowed discharge power is not available. We hardcode this value for now
datalayer.battery.status.max_discharge_power_W = MAXDISCHARGEPOWERALLOWED;
datalayer.battery.status.temperature_min_dC = (int8_t)temperatureMin * 10; //Increase decimals, 17C -> 17.0C
datalayer.battery.status.temperature_max_dC = (int8_t)temperatureMax * 10; //Increase decimals, 18C -> 18.0C
datalayer.battery.status.cell_max_voltage_mV = CellVoltMax_mV;
datalayer.battery.status.cell_min_voltage_mV = CellVoltMin_mV;
if (leadAcidBatteryVoltage < 110) {
set_event(EVENT_12V_LOW, leadAcidBatteryVoltage);
}
}
void Kia64FDBattery::handle_incoming_can_frame(CAN_frame rx_frame) {
startedUp = true;
switch (rx_frame.ID) {
case 0x055:
datalayer.battery.status.CAN_battery_still_alive = CAN_STILL_ALIVE;
break;
case 0x150:
datalayer.battery.status.CAN_battery_still_alive = CAN_STILL_ALIVE;
break;
case 0x1F5:
datalayer.battery.status.CAN_battery_still_alive = CAN_STILL_ALIVE;
break;
case 0x215:
datalayer.battery.status.CAN_battery_still_alive = CAN_STILL_ALIVE;
break;
case 0x21A:
datalayer.battery.status.CAN_battery_still_alive = CAN_STILL_ALIVE;
break;
case 0x235:
datalayer.battery.status.CAN_battery_still_alive = CAN_STILL_ALIVE;
break;
case 0x245:
datalayer.battery.status.CAN_battery_still_alive = CAN_STILL_ALIVE;
break;
case 0x25A:
datalayer.battery.status.CAN_battery_still_alive = CAN_STILL_ALIVE;
break;
case 0x275:
datalayer.battery.status.CAN_battery_still_alive = CAN_STILL_ALIVE;
break;
case 0x2FA:
datalayer.battery.status.CAN_battery_still_alive = CAN_STILL_ALIVE;
break;
case 0x325:
datalayer.battery.status.CAN_battery_still_alive = CAN_STILL_ALIVE;
break;
case 0x330:
datalayer.battery.status.CAN_battery_still_alive = CAN_STILL_ALIVE;
break;
case 0x335:
datalayer.battery.status.CAN_battery_still_alive = CAN_STILL_ALIVE;
break;
case 0x360:
datalayer.battery.status.CAN_battery_still_alive = CAN_STILL_ALIVE;
break;
case 0x365:
datalayer.battery.status.CAN_battery_still_alive = CAN_STILL_ALIVE;
break;
case 0x3BA:
datalayer.battery.status.CAN_battery_still_alive = CAN_STILL_ALIVE;
break;
case 0x3F5:
datalayer.battery.status.CAN_battery_still_alive = CAN_STILL_ALIVE;
break;
case 0x7EC:
// print_canfd_frame(frame);
switch (rx_frame.data.u8[0]) {
case 0x10: //"PID Header"
// logging.println ("Send ack");
poll_data_pid = rx_frame.data.u8[4];
// if (rx_frame.data.u8[4] == poll_data_pid) {
transmit_can_frame(&KIA64FD_ack); //Send ack to BMS if the same frame is sent as polled
// }
break;
case 0x21: //First frame in PID group
if (poll_data_pid == 1) {
allowedChargePower = ((rx_frame.data.u8[3] << 8) + rx_frame.data.u8[4]);
allowedDischargePower = ((rx_frame.data.u8[5] << 8) + rx_frame.data.u8[6]);
SOC_BMS = rx_frame.data.u8[2] * 5; //100% = 200 ( 200 * 5 = 1000 )
} else if (poll_data_pid == 2) {
// set cell voltages data, start bite, data length from start, start cell
write_cell_voltages(rx_frame, 2, 6, 0);
} else if (poll_data_pid == 3) {
write_cell_voltages(rx_frame, 2, 6, 32);
} else if (poll_data_pid == 4) {
write_cell_voltages(rx_frame, 2, 6, 64);
} else if (poll_data_pid == 0x0A) {
write_cell_voltages(rx_frame, 2, 6, 96);
} else if (poll_data_pid == 0x0B) {
write_cell_voltages(rx_frame, 2, 6, 128);
} else if (poll_data_pid == 0x0C) {
write_cell_voltages(rx_frame, 2, 6, 160);
}
break;
case 0x22: //Second datarow in PID group
if (poll_data_pid == 1) {
batteryVoltage = (rx_frame.data.u8[3] << 8) + rx_frame.data.u8[4];
batteryAmps = (rx_frame.data.u8[1] << 8) + rx_frame.data.u8[2];
temperatureMax = rx_frame.data.u8[5];
temperatureMin = rx_frame.data.u8[6];
// temp1 = rx_frame.data.u8[7];
} else if (poll_data_pid == 2) {
write_cell_voltages(rx_frame, 1, 7, 6);
} else if (poll_data_pid == 3) {
write_cell_voltages(rx_frame, 1, 7, 38);
} else if (poll_data_pid == 4) {
write_cell_voltages(rx_frame, 1, 7, 70);
} else if (poll_data_pid == 0x0A) {
write_cell_voltages(rx_frame, 1, 7, 102);
} else if (poll_data_pid == 0x0B) {
write_cell_voltages(rx_frame, 1, 7, 134);
} else if (poll_data_pid == 0x0C) {
write_cell_voltages(rx_frame, 1, 7, 166);
} else if (poll_data_pid == 6) {
batteryManagementMode = rx_frame.data.u8[5];
}
break;
case 0x23: //Third datarow in PID group
if (poll_data_pid == 1) {
temperature_water_inlet = rx_frame.data.u8[6];
CellVoltMax_mV = (rx_frame.data.u8[7] * 20); //(volts *50) *20 =mV
// temp2 = rx_frame.data.u8[1];
// temp3 = rx_frame.data.u8[2];
// temp4 = rx_frame.data.u8[3];
} else if (poll_data_pid == 2) {
write_cell_voltages(rx_frame, 1, 7, 13);
} else if (poll_data_pid == 3) {
write_cell_voltages(rx_frame, 1, 7, 45);
} else if (poll_data_pid == 4) {
write_cell_voltages(rx_frame, 1, 7, 77);
} else if (poll_data_pid == 0x0A) {
write_cell_voltages(rx_frame, 1, 7, 109);
} else if (poll_data_pid == 0x0B) {
write_cell_voltages(rx_frame, 1, 7, 141);
} else if (poll_data_pid == 0x0C) {
write_cell_voltages(rx_frame, 1, 7, 173);
} else if (poll_data_pid == 5) {
// ac = rx_frame.data.u8[3];
// Vdiff = rx_frame.data.u8[4];
// airbag = rx_frame.data.u8[6];
heatertemp = rx_frame.data.u8[7];
}
break;
case 0x24: //Fourth datarow in PID group
if (poll_data_pid == 1) {
CellVmaxNo = rx_frame.data.u8[1];
CellVoltMin_mV = (rx_frame.data.u8[2] * 20); //(volts *50) *20 =mV
CellVminNo = rx_frame.data.u8[3];
// fanMod = rx_frame.data.u8[4];
// fanSpeed = rx_frame.data.u8[5];
leadAcidBatteryVoltage = rx_frame.data.u8[6]; //12v Battery Volts
//cumulative_charge_current[0] = rx_frame.data.u8[7];
} else if (poll_data_pid == 2) {
write_cell_voltages(rx_frame, 1, 7, 20);
} else if (poll_data_pid == 3) {
write_cell_voltages(rx_frame, 1, 7, 52);
} else if (poll_data_pid == 4) {
write_cell_voltages(rx_frame, 1, 7, 84);
} else if (poll_data_pid == 0x0A) {
write_cell_voltages(rx_frame, 1, 7, 116);
} else if (poll_data_pid == 0x0B) {
write_cell_voltages(rx_frame, 1, 7, 148);
} else if (poll_data_pid == 0x0C) {
write_cell_voltages(rx_frame, 1, 7, 180);
} else if (poll_data_pid == 5) {
batterySOH = ((rx_frame.data.u8[2] << 8) + rx_frame.data.u8[3]);
// maxDetCell = rx_frame.data.u8[4];
// minDet = (rx_frame.data.u8[5] << 8) + rx_frame.data.u8[6];
// minDetCell = rx_frame.data.u8[7];
}
break;
case 0x25: //Fifth datarow in PID group
if (poll_data_pid == 1) {
//cumulative_charge_current[1] = rx_frame.data.u8[1];
//cumulative_charge_current[2] = rx_frame.data.u8[2];
//cumulative_charge_current[3] = rx_frame.data.u8[3];
//cumulative_discharge_current[0] = rx_frame.data.u8[4];
//cumulative_discharge_current[1] = rx_frame.data.u8[5];
//cumulative_discharge_current[2] = rx_frame.data.u8[6];
//cumulative_discharge_current[3] = rx_frame.data.u8[7];
//set_cumulative_charge_current();
//set_cumulative_discharge_current();
} else if (poll_data_pid == 2) {
write_cell_voltages(rx_frame, 1, 5, 27);
} else if (poll_data_pid == 3) {
write_cell_voltages(rx_frame, 1, 5, 59);
} else if (poll_data_pid == 4) {
write_cell_voltages(rx_frame, 1, 5, 91);
} else if (poll_data_pid == 0x0A) {
write_cell_voltages(rx_frame, 1, 5, 123);
} else if (poll_data_pid == 0x0B) {
write_cell_voltages(rx_frame, 1, 5, 155);
} else if (poll_data_pid == 0x0C) {
write_cell_voltages(rx_frame, 1, 5, 187);
//set_cell_count();
} else if (poll_data_pid == 5) {
// datalayer.battery.info.number_of_cells = 98;
SOC_Display = rx_frame.data.u8[1] * 5;
}
break;
case 0x26: //Sixth datarow in PID group
if (poll_data_pid == 1) {
//cumulative_energy_charged[0] = rx_frame.data.u8[1];
// cumulative_energy_charged[1] = rx_frame.data.u8[2];
//cumulative_energy_charged[2] = rx_frame.data.u8[3];
//cumulative_energy_charged[3] = rx_frame.data.u8[4];
//cumulative_energy_discharged[0] = rx_frame.data.u8[5];
//cumulative_energy_discharged[1] = rx_frame.data.u8[6];
//cumulative_energy_discharged[2] = rx_frame.data.u8[7];
// set_cumulative_energy_charged();
}
break;
case 0x27: //Seventh datarow in PID group
if (poll_data_pid == 1) {
//cumulative_energy_discharged[3] = rx_frame.data.u8[1];
//opTimeBytes[0] = rx_frame.data.u8[2];
//opTimeBytes[1] = rx_frame.data.u8[3];
//opTimeBytes[2] = rx_frame.data.u8[4];
//opTimeBytes[3] = rx_frame.data.u8[5];
BMS_ign = rx_frame.data.u8[6];
inverterVoltageFrameHigh = rx_frame.data.u8[7]; // BMS Capacitoir
// set_cumulative_energy_discharged();
// set_opTime();
}
break;
case 0x28: //Eighth datarow in PID group
if (poll_data_pid == 1) {
inverterVoltage = (inverterVoltageFrameHigh << 8) + rx_frame.data.u8[1]; // BMS Capacitoir
}
break;
}
break;
default:
break;
}
}
void Kia64FDBattery::transmit_can(unsigned long currentMillis) {
if (startedUp) {
//Send Contactor closing message loop
// Check if we still have messages to send
if (messageIndex < sizeof(messageDelays) / sizeof(messageDelays[0])) {
// Check if it's time to send the next message
if (currentMillis - startMillis >= messageDelays[messageIndex]) {
// Transmit the current message
transmit_can_frame(messages[messageIndex]);
// Move to the next message
messageIndex++;
}
}
if (messageIndex >= 63) {
startMillis = currentMillis; // Start over!
messageIndex = 0;
}
//Send 200ms CANFD message
if (currentMillis - previousMillis200ms >= INTERVAL_200_MS) {
previousMillis200ms = currentMillis;
KIA64FD_7E4.data.u8[3] = KIA_7E4_COUNTER;
if (ok_start_polling_battery) {
transmit_can_frame(&KIA64FD_7E4);
}
KIA_7E4_COUNTER++;
if (KIA_7E4_COUNTER > 0x0D) { // gets up to 0x010C before repeating
KIA_7E4_COUNTER = 0x01;
}
}
//Send 10s CANFD message
if (currentMillis - previousMillis10s >= INTERVAL_10_S) {
previousMillis10s = currentMillis;
ok_start_polling_battery = true;
}
}
}
void Kia64FDBattery::setup(void) { // Performs one time setup at startup
strncpy(datalayer.system.info.battery_protocol, Name, 63);
datalayer.system.info.battery_protocol[63] = '\0';
datalayer.system.status.battery_allows_contactor_closing = true;
datalayer.battery.info.number_of_cells = 96;
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.max_cell_voltage_mV = MAX_CELL_VOLTAGE_MV;
datalayer.battery.info.min_cell_voltage_mV = MIN_CELL_VOLTAGE_MV;
datalayer.battery.info.max_cell_voltage_deviation_mV = MAX_CELL_DEVIATION_MV;
}

View file

@ -0,0 +1,635 @@
#ifndef KIA_64_FD_BATTERY_H
#define KIA_64_FD_BATTERY_H
#include <Arduino.h>
#include "CanBattery.h"
#define ESTIMATE_SOC_FROM_CELLVOLTAGE
#ifdef KIA_HYUNDAI_64_FD_BATTERY
#define SELECTED_BATTERY_CLASS Kia64FDBattery
#endif
class Kia64FDBattery : public CanBattery {
public:
virtual void setup(void);
virtual void handle_incoming_can_frame(CAN_frame rx_frame);
virtual void update_values();
virtual void transmit_can(unsigned long currentMillis);
static constexpr const char* Name = "Kia 64kWh FD battery";
private:
uint16_t estimateSOC(uint16_t packVoltage, uint16_t cellCount, int16_t currentAmps);
uint16_t estimateSOCFromCell(uint16_t cellVoltage);
uint8_t calculateCRC(CAN_frame rx_frame, uint8_t length, uint8_t initial_value);
uint16_t selectSOC(uint16_t SOC_low, uint16_t SOC_high);
static const int MAX_PACK_VOLTAGE_DV = 4032; //5000 = 500.0V
static const int MIN_PACK_VOLTAGE_DV = 2400;
static const int MAX_CELL_DEVIATION_MV = 150;
static const int MAX_CELL_VOLTAGE_MV = 4250; //Battery is put into emergency stop if one cell goes over this value
static const int MIN_CELL_VOLTAGE_MV = 2950; //Battery is put into emergency stop if one cell goes below this value
static const int MAXCHARGEPOWERALLOWED = 10000;
static const int MAXDISCHARGEPOWERALLOWED = 10000;
static const int RAMPDOWN_SOC = 9000; // 90.00 SOC% to start ramping down from max charge power towards 0 at 100.00%
static const int RAMPDOWNPOWERALLOWED = 10000; // What power we ramp down from towards top balancing
// Used for SoC compensation - Define internal resistance value in milliohms for the entire pack
// How to calculate: voltage_drop_under_known_load [Volts] / load [Amps] = Resistance
static const int PACK_INTERNAL_RESISTANCE_MOHM = 200; // 200 milliohms for the whole pack
unsigned long previousMillis200ms = 0; // will store last time a 200ms CAN Message was send
unsigned long previousMillis10s = 0; // will store last time a 10s CAN Message was send
uint16_t inverterVoltageFrameHigh = 0;
uint16_t inverterVoltage = 0;
uint16_t soc_calculated = 0;
uint16_t SOC_BMS = 0;
uint16_t SOC_Display = 0;
uint16_t SOC_estimated_lowest = 0;
uint16_t SOC_estimated_highest = 0;
uint16_t batterySOH = 1000;
uint16_t CellVoltMax_mV = 3700;
uint16_t CellVoltMin_mV = 3700;
uint16_t batteryVoltage = 0;
int16_t leadAcidBatteryVoltage = 120;
int16_t batteryAmps = 0;
int16_t temperatureMax = 0;
int16_t temperatureMin = 0;
int16_t allowedDischargePower = 0;
int16_t allowedChargePower = 0;
int16_t poll_data_pid = 0;
uint8_t CellVmaxNo = 0;
uint8_t CellVminNo = 0;
uint8_t batteryManagementMode = 0;
uint8_t BMS_ign = 0;
bool startedUp = false;
bool ok_start_polling_battery = false;
uint8_t KIA_7E4_COUNTER = 0x01;
int8_t temperature_water_inlet = 0;
int8_t heatertemp = 0;
unsigned long startMillis = 0;
uint8_t messageIndex = 0;
const unsigned char crc8_table[256] = {
// CRC8_SAE_J1850_ZER0 formula,0x1D Poly,initial value 0x3F,Final XOR value varies
0x00, 0x1D, 0x3A, 0x27, 0x74, 0x69, 0x4E, 0x53, 0xE8, 0xF5, 0xD2, 0xCF, 0x9C, 0x81, 0xA6, 0xBB, 0xCD, 0xD0, 0xF7,
0xEA, 0xB9, 0xA4, 0x83, 0x9E, 0x25, 0x38, 0x1F, 0x02, 0x51, 0x4C, 0x6B, 0x76, 0x87, 0x9A, 0xBD, 0xA0, 0xF3, 0xEE,
0xC9, 0xD4, 0x6F, 0x72, 0x55, 0x48, 0x1B, 0x06, 0x21, 0x3C, 0x4A, 0x57, 0x70, 0x6D, 0x3E, 0x23, 0x04, 0x19, 0xA2,
0xBF, 0x98, 0x85, 0xD6, 0xCB, 0xEC, 0xF1, 0x13, 0x0E, 0x29, 0x34, 0x67, 0x7A, 0x5D, 0x40, 0xFB, 0xE6, 0xC1, 0xDC,
0x8F, 0x92, 0xB5, 0xA8, 0xDE, 0xC3, 0xE4, 0xF9, 0xAA, 0xB7, 0x90, 0x8D, 0x36, 0x2B, 0x0C, 0x11, 0x42, 0x5F, 0x78,
0x65, 0x94, 0x89, 0xAE, 0xB3, 0xE0, 0xFD, 0xDA, 0xC7, 0x7C, 0x61, 0x46, 0x5B, 0x08, 0x15, 0x32, 0x2F, 0x59, 0x44,
0x63, 0x7E, 0x2D, 0x30, 0x17, 0x0A, 0xB1, 0xAC, 0x8B, 0x96, 0xC5, 0xD8, 0xFF, 0xE2, 0x26, 0x3B, 0x1C, 0x01, 0x52,
0x4F, 0x68, 0x75, 0xCE, 0xD3, 0xF4, 0xE9, 0xBA, 0xA7, 0x80, 0x9D, 0xEB, 0xF6, 0xD1, 0xCC, 0x9F, 0x82, 0xA5, 0xB8,
0x03, 0x1E, 0x39, 0x24, 0x77, 0x6A, 0x4D, 0x50, 0xA1, 0xBC, 0x9B, 0x86, 0xD5, 0xC8, 0xEF, 0xF2, 0x49, 0x54, 0x73,
0x6E, 0x3D, 0x20, 0x07, 0x1A, 0x6C, 0x71, 0x56, 0x4B, 0x18, 0x05, 0x22, 0x3F, 0x84, 0x99, 0xBE, 0xA3, 0xF0, 0xED,
0xCA, 0xD7, 0x35, 0x28, 0x0F, 0x12, 0x41, 0x5C, 0x7B, 0x66, 0xDD, 0xC0, 0xE7, 0xFA, 0xA9, 0xB4, 0x93, 0x8E, 0xF8,
0xE5, 0xC2, 0xDF, 0x8C, 0x91, 0xB6, 0xAB, 0x10, 0x0D, 0x2A, 0x37, 0x64, 0x79, 0x5E, 0x43, 0xB2, 0xAF, 0x88, 0x95,
0xC6, 0xDB, 0xFC, 0xE1, 0x5A, 0x47, 0x60, 0x7D, 0x2E, 0x33, 0x14, 0x09, 0x7F, 0x62, 0x45, 0x58, 0x0B, 0x16, 0x31,
0x2C, 0x97, 0x8A, 0xAD, 0xB0, 0xE3, 0xFE, 0xD9, 0xC4};
// Define the data points for %SOC depending on cell voltage
const uint8_t numPoints = 100;
const uint16_t SOC[101] = {10000, 9900, 9800, 9700, 9600, 9500, 9400, 9300, 9200, 9100, 9000, 8900, 8800, 8700, 8600,
8500, 8400, 8300, 8200, 8100, 8000, 7900, 7800, 7700, 7600, 7500, 7400, 7300, 7200, 7100,
7000, 6900, 6800, 6700, 6600, 6500, 6400, 6300, 6200, 6100, 6000, 5900, 5800, 5700, 5600,
5500, 5400, 5300, 5200, 5100, 5000, 4900, 4800, 4700, 4600, 4500, 4400, 4300, 4200, 4100,
4000, 3900, 3800, 3700, 3600, 3500, 3400, 3300, 3200, 3100, 3000, 2900, 2800, 2700, 2600,
2500, 2400, 2300, 2200, 2100, 2000, 1900, 1800, 1700, 1600, 1500, 1400, 1300, 1200, 1100,
1000, 900, 800, 700, 600, 500, 400, 300, 200, 100, 0};
const uint16_t voltage[101] = {
4200, 4173, 4148, 4124, 4102, 4080, 4060, 4041, 4023, 4007, 3993, 3980, 3969, 3959, 3953, 3950, 3941,
3932, 3924, 3915, 3907, 3898, 3890, 3881, 3872, 3864, 3855, 3847, 3838, 3830, 3821, 3812, 3804, 3795,
3787, 3778, 3770, 3761, 3752, 3744, 3735, 3727, 3718, 3710, 3701, 3692, 3684, 3675, 3667, 3658, 3650,
3641, 3632, 3624, 3615, 3607, 3598, 3590, 3581, 3572, 3564, 3555, 3547, 3538, 3530, 3521, 3512, 3504,
3495, 3487, 3478, 3470, 3461, 3452, 3444, 3435, 3427, 3418, 3410, 3401, 3392, 3384, 3375, 3367, 3358,
3350, 3338, 3325, 3313, 3299, 3285, 3271, 3255, 3239, 3221, 3202, 3180, 3156, 3127, 3090, 3000};
/* These messages are needed for contactor closing */
uint8_t messageDelays[63] = {0, 0, 5, 10, 10, 15, 19, 19, 20, 20, 25, 30, 30, 35, 40, 40,
45, 49, 49, 50, 50, 52, 53, 53, 54, 55, 60, 60, 65, 67, 67, 70,
70, 75, 77, 77, 80, 80, 85, 90, 90, 95, 100, 100, 105, 110, 110, 115,
119, 119, 120, 120, 125, 130, 130, 135, 140, 140, 145, 149, 149, 150, 150};
static constexpr CAN_frame message_1 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0x62, 0x36, 0x8c, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_2 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x120,
.data = {0xd4, 0x1b, 0x8c, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x37, 0x35, 0x37, 0x37,
0xc9, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_3 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x19A,
.data = {0x24, 0x9b, 0x7b, 0x55, 0x44, 0x64, 0xd8, 0x1b, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x11, 0x52,
0x00, 0x12, 0x02, 0x64, 0x00, 0x00, 0x00, 0x08, 0x13, 0x00, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00}};
static constexpr CAN_frame message_4 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0x24, 0x6f, 0x8d, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_5 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x120,
.data = {0x92, 0x42, 0x8d, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x37, 0x35, 0x37, 0x37,
0xc9, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_6 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x19A,
.data = {0xd7, 0x05, 0x7c, 0x55, 0x44, 0x64, 0xd8, 0x1b, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x11, 0x52,
0x00, 0x12, 0x02, 0x64, 0x00, 0x00, 0x00, 0x08, 0x13, 0x00, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00}};
static constexpr CAN_frame message_7 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x30A,
.data = {0xb1, 0xe0, 0x26, 0x08, 0x54, 0x01, 0x04, 0x15, 0x00, 0x1a, 0x76, 0x00, 0x25, 0x01, 0x10, 0x27,
0x4f, 0x06, 0x18, 0x04, 0x33, 0x15, 0x34, 0x28, 0x00, 0x00, 0x10, 0x06, 0x21, 0x00, 0x4b, 0x06}};
static constexpr CAN_frame message_8 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x320,
.data = {0xc6, 0xab, 0x26, 0x41, 0x00, 0x00, 0x01, 0x3c, 0xac, 0x0d, 0x40, 0x20, 0x05, 0xc8, 0xa0, 0x03,
0x40, 0x20, 0x2b, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_9 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0xee, 0x84, 0x8e, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_10 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x120,
.data = {0x58, 0xa9, 0x8e, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x37, 0x35, 0x37, 0x37,
0xc9, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_11 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x19A,
.data = {0x91, 0x5c, 0x7d, 0x55, 0x44, 0x64, 0xd8, 0x1b, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x11, 0x52,
0x00, 0x12, 0x02, 0x64, 0x00, 0x00, 0x00, 0x08, 0x13, 0x00, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00}};
static constexpr CAN_frame message_12 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0xa8, 0xdd, 0x8f, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_13 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x120,
.data = {0x1e, 0xf0, 0x8f, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x37, 0x35, 0x37, 0x37,
0xc9, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_14 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x19A,
.data = {0x5b, 0xb7, 0x7e, 0x55, 0x44, 0x64, 0xd8, 0x1b, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x11, 0x52,
0x00, 0x12, 0x02, 0x64, 0x00, 0x00, 0x00, 0x08, 0x13, 0x00, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00}};
static constexpr CAN_frame message_15 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0xec, 0x6d, 0x90, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_16 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x120,
.data = {0x5a, 0x40, 0x90, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x37, 0x35, 0x37, 0x37,
0xc9, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_17 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x19A,
.data = {0x1d, 0xee, 0x7f, 0x55, 0x44, 0x64, 0xd8, 0x1b, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x11, 0x52,
0x00, 0x12, 0x02, 0x64, 0x00, 0x00, 0x00, 0x08, 0x13, 0x00, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00}};
static constexpr CAN_frame message_18 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x2B5,
.data = {0xbd, 0xb2, 0x42, 0x00, 0x00, 0x00, 0x00, 0x80, 0x59, 0x00, 0x2b, 0x00, 0x00, 0x04, 0x00, 0x00,
0xfa, 0xd0, 0x07, 0x00, 0x00, 0x00, 0x00, 0x00, 0x8f, 0x06, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_19 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x2E0,
.data = {0xc1, 0xf2, 0x42, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7e, 0x00, 0x00,
0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x70, 0x01, 0x0f, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_20 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0xaa, 0x34, 0x91, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_21 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x120,
.data = {0x1c, 0x19, 0x91, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x37, 0x35, 0x37, 0x37,
0xc9, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_22 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x2D5,
.data = {0x79, 0xfb, 0xa0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0b, 0x00, 0x00, 0x03, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0x34, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_23 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x2EA,
.data = {0x6e, 0xbb, 0xa0, 0x0d, 0x04, 0x01, 0x00, 0x00, 0x38, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0xc7, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_24 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x306,
.data = {0x00, 0x00, 0x00, 0xd2, 0x06, 0x92, 0x05, 0x34, 0x07, 0x8e, 0x08, 0x73, 0x05, 0x80, 0x05, 0x83,
0x05, 0x73, 0x05, 0x80, 0x05, 0xed, 0x01, 0xdd, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_25 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x308,
.data = {0xbe, 0x84, 0xa0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xff,
0x75, 0x6c, 0x86, 0x0d, 0xfb, 0xdf, 0x03, 0x36, 0xc3, 0x86, 0x11, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_26 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x19A,
.data = {0x6b, 0xa2, 0x80, 0x55, 0x44, 0x64, 0xd8, 0x1b, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x11, 0x52,
0x00, 0x12, 0x02, 0x64, 0x00, 0x00, 0x00, 0x08, 0x13, 0x00, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00}};
static constexpr CAN_frame message_27 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0x60, 0xdf, 0x92, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_28 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x120,
.data = {0xd6, 0xf2, 0x92, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x37, 0x35, 0x37, 0x37,
0xc9, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_29 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x19A,
.data = {0x2d, 0xfb, 0x81, 0x55, 0x44, 0x64, 0xd8, 0x1b, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x11, 0x52,
0x00, 0x12, 0x02, 0x64, 0x00, 0x00, 0x00, 0x08, 0x13, 0x00, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00}};
static constexpr CAN_frame message_30 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x33A,
.data = {0x1a, 0x23, 0x26, 0x10, 0x27, 0x4f, 0x06, 0x00, 0xf8, 0x1b, 0x19, 0x04, 0x30, 0x01, 0x00, 0x06,
0x00, 0x00, 0x00, 0x2e, 0x2d, 0x81, 0x25, 0x20, 0x00, 0x42, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_31 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x350,
.data = {0x26, 0x82, 0x26, 0xf4, 0x01, 0x00, 0x00, 0x50, 0x90, 0x15, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_32 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0x26, 0x86, 0x93, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_33 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x120,
.data = {0x90, 0xab, 0x93, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x37, 0x35, 0x37, 0x37,
0xc9, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_34 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x19A,
.data = {0xe7, 0x10, 0x82, 0x55, 0x44, 0x64, 0xd8, 0x1b, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x11, 0x52,
0x00, 0x12, 0x02, 0x64, 0x00, 0x00, 0x00, 0x08, 0x13, 0x00, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00}};
static constexpr CAN_frame message_35 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x2E5,
.data = {0x69, 0x8a, 0x3f, 0x01, 0x00, 0x00, 0x00, 0x15, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_36 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x3B5,
.data = {0xa3, 0xc8, 0x9f, 0x00, 0x00, 0x00, 0x00, 0x36, 0x37, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0xc7, 0x02, 0x00, 0x00, 0x00, 0x00, 0x6a, 0x09, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_37 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0xd5, 0x18, 0x94, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_38 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x120,
.data = {0x63, 0x35, 0x94, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x37, 0x35, 0x37, 0x37,
0xc9, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_39 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x19A,
.data = {0xa1, 0x49, 0x83, 0x55, 0x44, 0x64, 0xd8, 0x1b, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x11, 0x52,
0x00, 0x12, 0x02, 0x64, 0x00, 0x00, 0x00, 0x08, 0x13, 0x00, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00}};
static constexpr CAN_frame message_40 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0x93, 0x41, 0x95, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_41 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x120,
.data = {0x25, 0x6c, 0x95, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x37, 0x35, 0x37, 0x37,
0xc9, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_42 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x19A,
.data = {0x52, 0xd7, 0x84, 0x55, 0x44, 0x64, 0xd8, 0x1b, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x11, 0x52,
0x00, 0x12, 0x02, 0x64, 0x00, 0x00, 0x00, 0x08, 0x13, 0x00, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00}};
static constexpr CAN_frame message_43 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0x59, 0xaa, 0x96, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_44 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x120,
.data = {0xef, 0x87, 0x96, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x37, 0x35, 0x37, 0x37,
0xc9, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_45 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x19A,
.data = {0x14, 0x8e, 0x85, 0x55, 0x44, 0x64, 0xd8, 0x1b, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x11, 0x52,
0x00, 0x12, 0x02, 0x64, 0x00, 0x00, 0x00, 0x08, 0x13, 0x00, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00}};
static constexpr CAN_frame message_46 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0x1f, 0xf3, 0x97, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_47 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x120,
.data = {0xa9, 0xde, 0x97, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x37, 0x35, 0x37, 0x37,
0xc9, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_48 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x19A,
.data = {0xde, 0x65, 0x86, 0x55, 0x44, 0x64, 0xd8, 0x1b, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x11, 0x52,
0x00, 0x12, 0x02, 0x64, 0x00, 0x00, 0x00, 0x08, 0x13, 0x00, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00}};
static constexpr CAN_frame message_49 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x30A,
.data = {0xd3, 0x11, 0x27, 0x08, 0x54, 0x01, 0x04, 0x15, 0x00, 0x1a, 0x76, 0x00, 0x25, 0x01, 0x10, 0x27,
0x4f, 0x06, 0x19, 0x04, 0x33, 0x15, 0x34, 0x28, 0x00, 0x00, 0x10, 0x06, 0x21, 0x00, 0x4b, 0x06}};
static constexpr CAN_frame message_50 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x320,
.data = {0x80, 0xf2, 0x27, 0x41, 0x00, 0x00, 0x01, 0x3c, 0xac, 0x0d, 0x40, 0x20, 0x05, 0xc8, 0xa0, 0x03,
0x40, 0x20, 0x2b, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_51 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0x9e, 0x87, 0x98, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_52 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x120,
.data = {0x28, 0xaa, 0x98, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x37, 0x35, 0x37, 0x37,
0xc9, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_53 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x19A,
.data = {0x98, 0x3c, 0x87, 0x55, 0x44, 0x64, 0xd8, 0x1b, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x11, 0x52,
0x00, 0x12, 0x02, 0x64, 0x00, 0x00, 0x00, 0x08, 0x13, 0x00, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00}};
static constexpr CAN_frame message_54 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0xd8, 0xde, 0x99, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_55 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x120,
.data = {0x6e, 0xf3, 0x99, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x37, 0x35, 0x37, 0x37,
0xc9, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_56 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x19A,
.data = {0x19, 0x48, 0x88, 0x55, 0x44, 0x64, 0xd8, 0x1b, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x11, 0x52,
0x00, 0x12, 0x02, 0x64, 0x00, 0x00, 0x00, 0x08, 0x13, 0x00, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00}};
static constexpr CAN_frame message_57 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0x12, 0x35, 0x9a, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_58 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x120,
.data = {0xa4, 0x18, 0x9a, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x37, 0x35, 0x37, 0x37,
0xc9, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_59 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x19A,
.data = {0x5f, 0x11, 0x89, 0x55, 0x44, 0x64, 0xd8, 0x1b, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x11, 0x52,
0x00, 0x12, 0x02, 0x64, 0x00, 0x00, 0x00, 0x08, 0x13, 0x00, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00}};
static constexpr CAN_frame message_60 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x2B5,
.data = {0xfb, 0xeb, 0x43, 0x00, 0x00, 0x00, 0x00, 0x80, 0x59, 0x00, 0x2b, 0x00, 0x00, 0x04, 0x00, 0x00,
0xfa, 0xd0, 0x07, 0x00, 0x00, 0x00, 0x00, 0x00, 0x8f, 0x06, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_61 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x2C0,
.data = {0xcc, 0xcd, 0xa2, 0x21, 0x00, 0xa1, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7d, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_62 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x2E0,
.data = {0x87, 0xab, 0x43, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7e, 0x00, 0x00,
0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x70, 0x01, 0x0f, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_63 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0x54, 0x6c, 0x9b, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
const CAN_frame* messages[64] = {
&message_1, &message_2, &message_3, &message_4, &message_5, &message_6, &message_7, &message_8,
&message_9, &message_10, &message_11, &message_12, &message_13, &message_14, &message_15, &message_16,
&message_17, &message_18, &message_19, &message_20, &message_21, &message_22, &message_23, &message_24,
&message_25, &message_26, &message_27, &message_28, &message_29, &message_30, &message_31, &message_32,
&message_33, &message_34, &message_35, &message_36, &message_37, &message_38, &message_39, &message_40,
&message_41, &message_42, &message_43, &message_44, &message_45, &message_46, &message_47, &message_48,
&message_49, &message_50, &message_51, &message_52, &message_53, &message_54, &message_55, &message_56,
&message_57, &message_58, &message_59, &message_60, &message_61, &message_62, &message_63};
/* PID polling messages */
CAN_frame KIA64FD_7E4 = {.FD = true,
.ext_ID = false,
.DLC = 8,
.ID = 0x7E4,
.data = {0x03, 0x22, 0x01, 0x01, 0x00, 0x00, 0x00, 0x00}}; //Poll PID 03 22 01 01
CAN_frame KIA64FD_ack = {
.FD = true,
.ext_ID = false,
.DLC = 8,
.ID = 0x7E4,
.data = {0x30, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}}; //Ack frame, correct PID is returned
};
#endif

View file

@ -6,45 +6,8 @@
#include "../devboard/utils/logging.h"
#include "../system_settings.h"
const unsigned char crc8_table[256] =
{ // CRC8_SAE_J1850_ZER0 formula,0x1D Poly,initial value 0x3F,Final XOR value varies
0x00, 0x1D, 0x3A, 0x27, 0x74, 0x69, 0x4E, 0x53, 0xE8, 0xF5, 0xD2, 0xCF, 0x9C, 0x81, 0xA6, 0xBB, 0xCD, 0xD0,
0xF7, 0xEA, 0xB9, 0xA4, 0x83, 0x9E, 0x25, 0x38, 0x1F, 0x02, 0x51, 0x4C, 0x6B, 0x76, 0x87, 0x9A, 0xBD, 0xA0,
0xF3, 0xEE, 0xC9, 0xD4, 0x6F, 0x72, 0x55, 0x48, 0x1B, 0x06, 0x21, 0x3C, 0x4A, 0x57, 0x70, 0x6D, 0x3E, 0x23,
0x04, 0x19, 0xA2, 0xBF, 0x98, 0x85, 0xD6, 0xCB, 0xEC, 0xF1, 0x13, 0x0E, 0x29, 0x34, 0x67, 0x7A, 0x5D, 0x40,
0xFB, 0xE6, 0xC1, 0xDC, 0x8F, 0x92, 0xB5, 0xA8, 0xDE, 0xC3, 0xE4, 0xF9, 0xAA, 0xB7, 0x90, 0x8D, 0x36, 0x2B,
0x0C, 0x11, 0x42, 0x5F, 0x78, 0x65, 0x94, 0x89, 0xAE, 0xB3, 0xE0, 0xFD, 0xDA, 0xC7, 0x7C, 0x61, 0x46, 0x5B,
0x08, 0x15, 0x32, 0x2F, 0x59, 0x44, 0x63, 0x7E, 0x2D, 0x30, 0x17, 0x0A, 0xB1, 0xAC, 0x8B, 0x96, 0xC5, 0xD8,
0xFF, 0xE2, 0x26, 0x3B, 0x1C, 0x01, 0x52, 0x4F, 0x68, 0x75, 0xCE, 0xD3, 0xF4, 0xE9, 0xBA, 0xA7, 0x80, 0x9D,
0xEB, 0xF6, 0xD1, 0xCC, 0x9F, 0x82, 0xA5, 0xB8, 0x03, 0x1E, 0x39, 0x24, 0x77, 0x6A, 0x4D, 0x50, 0xA1, 0xBC,
0x9B, 0x86, 0xD5, 0xC8, 0xEF, 0xF2, 0x49, 0x54, 0x73, 0x6E, 0x3D, 0x20, 0x07, 0x1A, 0x6C, 0x71, 0x56, 0x4B,
0x18, 0x05, 0x22, 0x3F, 0x84, 0x99, 0xBE, 0xA3, 0xF0, 0xED, 0xCA, 0xD7, 0x35, 0x28, 0x0F, 0x12, 0x41, 0x5C,
0x7B, 0x66, 0xDD, 0xC0, 0xE7, 0xFA, 0xA9, 0xB4, 0x93, 0x8E, 0xF8, 0xE5, 0xC2, 0xDF, 0x8C, 0x91, 0xB6, 0xAB,
0x10, 0x0D, 0x2A, 0x37, 0x64, 0x79, 0x5E, 0x43, 0xB2, 0xAF, 0x88, 0x95, 0xC6, 0xDB, 0xFC, 0xE1, 0x5A, 0x47,
0x60, 0x7D, 0x2E, 0x33, 0x14, 0x09, 0x7F, 0x62, 0x45, 0x58, 0x0B, 0x16, 0x31, 0x2C, 0x97, 0x8A, 0xAD, 0xB0,
0xE3, 0xFE, 0xD9, 0xC4};
// Define the data points for %SOC depending on cell voltage
const uint8_t numPoints = 100;
const uint16_t SOC[] = {10000, 9900, 9800, 9700, 9600, 9500, 9400, 9300, 9200, 9100, 9000, 8900, 8800, 8700, 8600,
8500, 8400, 8300, 8200, 8100, 8000, 7900, 7800, 7700, 7600, 7500, 7400, 7300, 7200, 7100,
7000, 6900, 6800, 6700, 6600, 6500, 6400, 6300, 6200, 6100, 6000, 5900, 5800, 5700, 5600,
5500, 5400, 5300, 5200, 5100, 5000, 4900, 4800, 4700, 4600, 4500, 4400, 4300, 4200, 4100,
4000, 3900, 3800, 3700, 3600, 3500, 3400, 3300, 3200, 3100, 3000, 2900, 2800, 2700, 2600,
2500, 2400, 2300, 2200, 2100, 2000, 1900, 1800, 1700, 1600, 1500, 1400, 1300, 1200, 1100,
1000, 900, 800, 700, 600, 500, 400, 300, 200, 100, 0};
const uint16_t voltage[] = {4200, 4173, 4148, 4124, 4102, 4080, 4060, 4041, 4023, 4007, 3993, 3980, 3969, 3959, 3953,
3950, 3941, 3932, 3924, 3915, 3907, 3898, 3890, 3881, 3872, 3864, 3855, 3847, 3838, 3830,
3821, 3812, 3804, 3795, 3787, 3778, 3770, 3761, 3752, 3744, 3735, 3727, 3718, 3710, 3701,
3692, 3684, 3675, 3667, 3658, 3650, 3641, 3632, 3624, 3615, 3607, 3598, 3590, 3581, 3572,
3564, 3555, 3547, 3538, 3530, 3521, 3512, 3504, 3495, 3487, 3478, 3470, 3461, 3452, 3444,
3435, 3427, 3418, 3410, 3401, 3392, 3384, 3375, 3367, 3358, 3350, 3338, 3325, 3313, 3299,
3285, 3271, 3255, 3239, 3221, 3202, 3180, 3156, 3127, 3090, 3000};
// Function to estimate SOC based on cell voltage
uint16_t estimateSOCFromCell(uint16_t cellVoltage) {
uint16_t KiaEGmpBattery::estimateSOCFromCell(uint16_t cellVoltage) {
if (cellVoltage >= voltage[0]) {
return SOC[0];
}
@ -92,7 +55,6 @@ uint16_t KiaEGmpBattery::estimateSOC(uint16_t packVoltage, uint16_t cellCount, i
// Calculate average cell voltage in millivolts
uint16_t avgCellVoltage = compensatedPackVoltageMv / cellCount;
#ifdef DEBUG_LOG
logging.print("Pack: ");
logging.print(packVoltage / 10.0);
logging.print("V, Current: ");
@ -104,14 +66,13 @@ uint16_t KiaEGmpBattery::estimateSOC(uint16_t packVoltage, uint16_t cellCount, i
logging.print("V, Avg Cell: ");
logging.print(avgCellVoltage);
logging.println("mV");
#endif
// Use the cell voltage lookup table to estimate SOC
return estimateSOCFromCell(avgCellVoltage);
}
// Fix: Change parameter types to uint16_t to match SOC values
uint16_t selectSOC(uint16_t SOC_low, uint16_t SOC_high) {
uint16_t KiaEGmpBattery::selectSOC(uint16_t SOC_low, uint16_t SOC_high) {
if (SOC_low == 0 || SOC_high == 0) {
return 0; // If either value is 0, return 0
}
@ -121,534 +82,7 @@ uint16_t selectSOC(uint16_t SOC_low, uint16_t SOC_high) {
return (SOC_low < SOC_high) ? SOC_low : SOC_high; // Otherwise, return the lowest value
}
/* These messages are needed for contactor closing */
unsigned long startMillis = 0;
uint8_t messageIndex = 0;
uint8_t messageDelays[63] = {0, 0, 5, 10, 10, 15, 19, 19, 20, 20, 25, 30, 30, 35, 40, 40,
45, 49, 49, 50, 50, 52, 53, 53, 54, 55, 60, 60, 65, 67, 67, 70,
70, 75, 77, 77, 80, 80, 85, 90, 90, 95, 100, 100, 105, 110, 110, 115,
119, 119, 120, 120, 125, 130, 130, 135, 140, 140, 145, 149, 149, 150, 150};
static constexpr CAN_frame message_1 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0x62, 0x36, 0x8c, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_2 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x120,
.data = {0xd4, 0x1b, 0x8c, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x37, 0x35, 0x37, 0x37,
0xc9, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_3 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x19A,
.data = {0x24, 0x9b, 0x7b, 0x55, 0x44, 0x64, 0xd8, 0x1b, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x11, 0x52,
0x00, 0x12, 0x02, 0x64, 0x00, 0x00, 0x00, 0x08, 0x13, 0x00, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00}};
static constexpr CAN_frame message_4 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0x24, 0x6f, 0x8d, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_5 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x120,
.data = {0x92, 0x42, 0x8d, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x37, 0x35, 0x37, 0x37,
0xc9, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_6 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x19A,
.data = {0xd7, 0x05, 0x7c, 0x55, 0x44, 0x64, 0xd8, 0x1b, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x11, 0x52,
0x00, 0x12, 0x02, 0x64, 0x00, 0x00, 0x00, 0x08, 0x13, 0x00, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00}};
static constexpr CAN_frame message_7 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x30A,
.data = {0xb1, 0xe0, 0x26, 0x08, 0x54, 0x01, 0x04, 0x15, 0x00, 0x1a, 0x76, 0x00, 0x25, 0x01, 0x10, 0x27,
0x4f, 0x06, 0x18, 0x04, 0x33, 0x15, 0x34, 0x28, 0x00, 0x00, 0x10, 0x06, 0x21, 0x00, 0x4b, 0x06}};
static constexpr CAN_frame message_8 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x320,
.data = {0xc6, 0xab, 0x26, 0x41, 0x00, 0x00, 0x01, 0x3c, 0xac, 0x0d, 0x40, 0x20, 0x05, 0xc8, 0xa0, 0x03,
0x40, 0x20, 0x2b, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_9 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0xee, 0x84, 0x8e, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_10 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x120,
.data = {0x58, 0xa9, 0x8e, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x37, 0x35, 0x37, 0x37,
0xc9, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_11 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x19A,
.data = {0x91, 0x5c, 0x7d, 0x55, 0x44, 0x64, 0xd8, 0x1b, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x11, 0x52,
0x00, 0x12, 0x02, 0x64, 0x00, 0x00, 0x00, 0x08, 0x13, 0x00, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00}};
static constexpr CAN_frame message_12 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0xa8, 0xdd, 0x8f, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_13 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x120,
.data = {0x1e, 0xf0, 0x8f, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x37, 0x35, 0x37, 0x37,
0xc9, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_14 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x19A,
.data = {0x5b, 0xb7, 0x7e, 0x55, 0x44, 0x64, 0xd8, 0x1b, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x11, 0x52,
0x00, 0x12, 0x02, 0x64, 0x00, 0x00, 0x00, 0x08, 0x13, 0x00, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00}};
static constexpr CAN_frame message_15 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0xec, 0x6d, 0x90, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_16 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x120,
.data = {0x5a, 0x40, 0x90, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x37, 0x35, 0x37, 0x37,
0xc9, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_17 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x19A,
.data = {0x1d, 0xee, 0x7f, 0x55, 0x44, 0x64, 0xd8, 0x1b, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x11, 0x52,
0x00, 0x12, 0x02, 0x64, 0x00, 0x00, 0x00, 0x08, 0x13, 0x00, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00}};
static constexpr CAN_frame message_18 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x2B5,
.data = {0xbd, 0xb2, 0x42, 0x00, 0x00, 0x00, 0x00, 0x80, 0x59, 0x00, 0x2b, 0x00, 0x00, 0x04, 0x00, 0x00,
0xfa, 0xd0, 0x07, 0x00, 0x00, 0x00, 0x00, 0x00, 0x8f, 0x06, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_19 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x2E0,
.data = {0xc1, 0xf2, 0x42, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7e, 0x00, 0x00,
0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x70, 0x01, 0x0f, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_20 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0xaa, 0x34, 0x91, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_21 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x120,
.data = {0x1c, 0x19, 0x91, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x37, 0x35, 0x37, 0x37,
0xc9, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_22 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x2D5,
.data = {0x79, 0xfb, 0xa0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0b, 0x00, 0x00, 0x03, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0x34, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_23 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x2EA,
.data = {0x6e, 0xbb, 0xa0, 0x0d, 0x04, 0x01, 0x00, 0x00, 0x38, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0xc7, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_24 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x306,
.data = {0x00, 0x00, 0x00, 0xd2, 0x06, 0x92, 0x05, 0x34, 0x07, 0x8e, 0x08, 0x73, 0x05, 0x80, 0x05, 0x83,
0x05, 0x73, 0x05, 0x80, 0x05, 0xed, 0x01, 0xdd, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_25 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x308,
.data = {0xbe, 0x84, 0xa0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xff,
0x75, 0x6c, 0x86, 0x0d, 0xfb, 0xdf, 0x03, 0x36, 0xc3, 0x86, 0x11, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_26 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x19A,
.data = {0x6b, 0xa2, 0x80, 0x55, 0x44, 0x64, 0xd8, 0x1b, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x11, 0x52,
0x00, 0x12, 0x02, 0x64, 0x00, 0x00, 0x00, 0x08, 0x13, 0x00, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00}};
static constexpr CAN_frame message_27 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0x60, 0xdf, 0x92, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_28 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x120,
.data = {0xd6, 0xf2, 0x92, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x37, 0x35, 0x37, 0x37,
0xc9, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_29 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x19A,
.data = {0x2d, 0xfb, 0x81, 0x55, 0x44, 0x64, 0xd8, 0x1b, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x11, 0x52,
0x00, 0x12, 0x02, 0x64, 0x00, 0x00, 0x00, 0x08, 0x13, 0x00, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00}};
static constexpr CAN_frame message_30 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x33A,
.data = {0x1a, 0x23, 0x26, 0x10, 0x27, 0x4f, 0x06, 0x00, 0xf8, 0x1b, 0x19, 0x04, 0x30, 0x01, 0x00, 0x06,
0x00, 0x00, 0x00, 0x2e, 0x2d, 0x81, 0x25, 0x20, 0x00, 0x42, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_31 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x350,
.data = {0x26, 0x82, 0x26, 0xf4, 0x01, 0x00, 0x00, 0x50, 0x90, 0x15, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_32 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0x26, 0x86, 0x93, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_33 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x120,
.data = {0x90, 0xab, 0x93, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x37, 0x35, 0x37, 0x37,
0xc9, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_34 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x19A,
.data = {0xe7, 0x10, 0x82, 0x55, 0x44, 0x64, 0xd8, 0x1b, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x11, 0x52,
0x00, 0x12, 0x02, 0x64, 0x00, 0x00, 0x00, 0x08, 0x13, 0x00, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00}};
static constexpr CAN_frame message_35 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x2E5,
.data = {0x69, 0x8a, 0x3f, 0x01, 0x00, 0x00, 0x00, 0x15, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_36 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x3B5,
.data = {0xa3, 0xc8, 0x9f, 0x00, 0x00, 0x00, 0x00, 0x36, 0x37, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0xc7, 0x02, 0x00, 0x00, 0x00, 0x00, 0x6a, 0x09, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_37 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0xd5, 0x18, 0x94, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_38 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x120,
.data = {0x63, 0x35, 0x94, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x37, 0x35, 0x37, 0x37,
0xc9, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_39 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x19A,
.data = {0xa1, 0x49, 0x83, 0x55, 0x44, 0x64, 0xd8, 0x1b, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x11, 0x52,
0x00, 0x12, 0x02, 0x64, 0x00, 0x00, 0x00, 0x08, 0x13, 0x00, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00}};
static constexpr CAN_frame message_40 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0x93, 0x41, 0x95, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_41 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x120,
.data = {0x25, 0x6c, 0x95, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x37, 0x35, 0x37, 0x37,
0xc9, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_42 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x19A,
.data = {0x52, 0xd7, 0x84, 0x55, 0x44, 0x64, 0xd8, 0x1b, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x11, 0x52,
0x00, 0x12, 0x02, 0x64, 0x00, 0x00, 0x00, 0x08, 0x13, 0x00, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00}};
static constexpr CAN_frame message_43 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0x59, 0xaa, 0x96, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_44 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x120,
.data = {0xef, 0x87, 0x96, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x37, 0x35, 0x37, 0x37,
0xc9, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_45 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x19A,
.data = {0x14, 0x8e, 0x85, 0x55, 0x44, 0x64, 0xd8, 0x1b, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x11, 0x52,
0x00, 0x12, 0x02, 0x64, 0x00, 0x00, 0x00, 0x08, 0x13, 0x00, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00}};
static constexpr CAN_frame message_46 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0x1f, 0xf3, 0x97, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_47 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x120,
.data = {0xa9, 0xde, 0x97, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x37, 0x35, 0x37, 0x37,
0xc9, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_48 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x19A,
.data = {0xde, 0x65, 0x86, 0x55, 0x44, 0x64, 0xd8, 0x1b, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x11, 0x52,
0x00, 0x12, 0x02, 0x64, 0x00, 0x00, 0x00, 0x08, 0x13, 0x00, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00}};
static constexpr CAN_frame message_49 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x30A,
.data = {0xd3, 0x11, 0x27, 0x08, 0x54, 0x01, 0x04, 0x15, 0x00, 0x1a, 0x76, 0x00, 0x25, 0x01, 0x10, 0x27,
0x4f, 0x06, 0x19, 0x04, 0x33, 0x15, 0x34, 0x28, 0x00, 0x00, 0x10, 0x06, 0x21, 0x00, 0x4b, 0x06}};
static constexpr CAN_frame message_50 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x320,
.data = {0x80, 0xf2, 0x27, 0x41, 0x00, 0x00, 0x01, 0x3c, 0xac, 0x0d, 0x40, 0x20, 0x05, 0xc8, 0xa0, 0x03,
0x40, 0x20, 0x2b, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_51 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0x9e, 0x87, 0x98, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_52 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x120,
.data = {0x28, 0xaa, 0x98, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x37, 0x35, 0x37, 0x37,
0xc9, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_53 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x19A,
.data = {0x98, 0x3c, 0x87, 0x55, 0x44, 0x64, 0xd8, 0x1b, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x11, 0x52,
0x00, 0x12, 0x02, 0x64, 0x00, 0x00, 0x00, 0x08, 0x13, 0x00, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00}};
static constexpr CAN_frame message_54 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0xd8, 0xde, 0x99, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_55 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x120,
.data = {0x6e, 0xf3, 0x99, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x37, 0x35, 0x37, 0x37,
0xc9, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_56 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x19A,
.data = {0x19, 0x48, 0x88, 0x55, 0x44, 0x64, 0xd8, 0x1b, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x11, 0x52,
0x00, 0x12, 0x02, 0x64, 0x00, 0x00, 0x00, 0x08, 0x13, 0x00, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00}};
static constexpr CAN_frame message_57 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0x12, 0x35, 0x9a, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_58 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x120,
.data = {0xa4, 0x18, 0x9a, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x37, 0x35, 0x37, 0x37,
0xc9, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_59 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x19A,
.data = {0x5f, 0x11, 0x89, 0x55, 0x44, 0x64, 0xd8, 0x1b, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x11, 0x52,
0x00, 0x12, 0x02, 0x64, 0x00, 0x00, 0x00, 0x08, 0x13, 0x00, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00}};
static constexpr CAN_frame message_60 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x2B5,
.data = {0xfb, 0xeb, 0x43, 0x00, 0x00, 0x00, 0x00, 0x80, 0x59, 0x00, 0x2b, 0x00, 0x00, 0x04, 0x00, 0x00,
0xfa, 0xd0, 0x07, 0x00, 0x00, 0x00, 0x00, 0x00, 0x8f, 0x06, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_61 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x2C0,
.data = {0xcc, 0xcd, 0xa2, 0x21, 0x00, 0xa1, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7d, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_62 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x2E0,
.data = {0x87, 0xab, 0x43, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7e, 0x00, 0x00,
0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x70, 0x01, 0x0f, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_63 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0x54, 0x6c, 0x9b, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static const CAN_frame* messages[] = {
&message_1, &message_2, &message_3, &message_4, &message_5, &message_6, &message_7, &message_8,
&message_9, &message_10, &message_11, &message_12, &message_13, &message_14, &message_15, &message_16,
&message_17, &message_18, &message_19, &message_20, &message_21, &message_22, &message_23, &message_24,
&message_25, &message_26, &message_27, &message_28, &message_29, &message_30, &message_31, &message_32,
&message_33, &message_34, &message_35, &message_36, &message_37, &message_38, &message_39, &message_40,
&message_41, &message_42, &message_43, &message_44, &message_45, &message_46, &message_47, &message_48,
&message_49, &message_50, &message_51, &message_52, &message_53, &message_54, &message_55, &message_56,
&message_57, &message_58, &message_59, &message_60, &message_61, &message_62, &message_63};
/* PID polling messages */
CAN_frame EGMP_7E4 = {.FD = true,
.ext_ID = false,
.DLC = 8,
.ID = 0x7E4,
.data = {0x03, 0x22, 0x01, 0x01, 0x00, 0x00, 0x00, 0x00}}; //Poll PID 03 22 01 01
static constexpr CAN_frame EGMP_7E4_ack = {
.FD = true,
.ext_ID = false,
.DLC = 8,
.ID = 0x7E4,
.data = {0x30, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}}; //Ack frame, correct PID is returned
void set_cell_voltages(CAN_frame rx_frame, int start, int length, int startCell) {
void KiaEGmpBattery::set_cell_voltages(CAN_frame rx_frame, int start, int length, int startCell) {
for (size_t i = 0; i < length; i++) {
if ((rx_frame.data.u8[start + i] * 20) > 1000) {
datalayer.battery.status.cell_voltages_mV[startCell + i] = (rx_frame.data.u8[start + i] * 20);
@ -682,7 +116,7 @@ void KiaEGmpBattery::set_voltage_minmax_limits() {
}
}
static uint8_t calculateCRC(CAN_frame rx_frame, uint8_t length, uint8_t initial_value) {
uint8_t KiaEGmpBattery::calculateCRC(CAN_frame rx_frame, uint8_t length, uint8_t initial_value) {
uint8_t crc = initial_value;
for (uint8_t j = 1; j < length; j++) { //start at 1, since 0 is the CRC
crc = crc8_table[(crc ^ static_cast<uint8_t>(rx_frame.data.u8[j])) % 256];
@ -690,8 +124,7 @@ static uint8_t calculateCRC(CAN_frame rx_frame, uint8_t length, uint8_t initial_
return crc;
}
void KiaEGmpBattery::
update_values() { //This function maps all the values fetched via CAN to the correct parameters used for modbus
void KiaEGmpBattery::update_values() {
#ifdef ESTIMATE_SOC_FROM_CELLVOLTAGE
// Use the simplified pack-based SOC estimation with proper compensation
@ -752,7 +185,6 @@ void KiaEGmpBattery::
/* Safeties verified. Perform USB serial printout if configured to do so */
#ifdef DEBUG_LOG
logging.println(); //sepatator
logging.println("Values from battery: ");
logging.print("SOC BMS: ");
@ -809,7 +241,6 @@ void KiaEGmpBattery::
logging.print(" | Inverter ");
logging.print(inverterVoltage);
logging.println(" Volts");
#endif
}
// Getter implementations for HTML renderer

View file

@ -30,6 +30,10 @@ class KiaEGmpBattery : public CanBattery {
private:
KiaEGMPHtmlRenderer renderer;
uint16_t estimateSOC(uint16_t packVoltage, uint16_t cellCount, int16_t currentAmps);
uint16_t selectSOC(uint16_t SOC_low, uint16_t SOC_high);
uint16_t estimateSOCFromCell(uint16_t cellVoltage);
uint8_t calculateCRC(CAN_frame rx_frame, uint8_t length, uint8_t initial_value);
void set_cell_voltages(CAN_frame rx_frame, int start, int length, int startCell);
void set_voltage_minmax_limits();
static const int MAX_PACK_VOLTAGE_DV = 8064; //5000 = 500.0V
@ -81,9 +85,510 @@ class KiaEGmpBattery : public CanBattery {
int8_t powerRelayTemperature = 10;
int8_t heatertemp = 20;
bool set_voltage_limits = false;
uint8_t ticks_200ms_counter = 0;
uint8_t EGMP_1CF_counter = 0;
uint8_t EGMP_3XF_counter = 0;
const unsigned char crc8_table[256] = {
// CRC8_SAE_J1850_ZER0 formula,0x1D Poly,initial value 0x3F,Final XOR value varies
0x00, 0x1D, 0x3A, 0x27, 0x74, 0x69, 0x4E, 0x53, 0xE8, 0xF5, 0xD2, 0xCF, 0x9C, 0x81, 0xA6, 0xBB, 0xCD, 0xD0, 0xF7,
0xEA, 0xB9, 0xA4, 0x83, 0x9E, 0x25, 0x38, 0x1F, 0x02, 0x51, 0x4C, 0x6B, 0x76, 0x87, 0x9A, 0xBD, 0xA0, 0xF3, 0xEE,
0xC9, 0xD4, 0x6F, 0x72, 0x55, 0x48, 0x1B, 0x06, 0x21, 0x3C, 0x4A, 0x57, 0x70, 0x6D, 0x3E, 0x23, 0x04, 0x19, 0xA2,
0xBF, 0x98, 0x85, 0xD6, 0xCB, 0xEC, 0xF1, 0x13, 0x0E, 0x29, 0x34, 0x67, 0x7A, 0x5D, 0x40, 0xFB, 0xE6, 0xC1, 0xDC,
0x8F, 0x92, 0xB5, 0xA8, 0xDE, 0xC3, 0xE4, 0xF9, 0xAA, 0xB7, 0x90, 0x8D, 0x36, 0x2B, 0x0C, 0x11, 0x42, 0x5F, 0x78,
0x65, 0x94, 0x89, 0xAE, 0xB3, 0xE0, 0xFD, 0xDA, 0xC7, 0x7C, 0x61, 0x46, 0x5B, 0x08, 0x15, 0x32, 0x2F, 0x59, 0x44,
0x63, 0x7E, 0x2D, 0x30, 0x17, 0x0A, 0xB1, 0xAC, 0x8B, 0x96, 0xC5, 0xD8, 0xFF, 0xE2, 0x26, 0x3B, 0x1C, 0x01, 0x52,
0x4F, 0x68, 0x75, 0xCE, 0xD3, 0xF4, 0xE9, 0xBA, 0xA7, 0x80, 0x9D, 0xEB, 0xF6, 0xD1, 0xCC, 0x9F, 0x82, 0xA5, 0xB8,
0x03, 0x1E, 0x39, 0x24, 0x77, 0x6A, 0x4D, 0x50, 0xA1, 0xBC, 0x9B, 0x86, 0xD5, 0xC8, 0xEF, 0xF2, 0x49, 0x54, 0x73,
0x6E, 0x3D, 0x20, 0x07, 0x1A, 0x6C, 0x71, 0x56, 0x4B, 0x18, 0x05, 0x22, 0x3F, 0x84, 0x99, 0xBE, 0xA3, 0xF0, 0xED,
0xCA, 0xD7, 0x35, 0x28, 0x0F, 0x12, 0x41, 0x5C, 0x7B, 0x66, 0xDD, 0xC0, 0xE7, 0xFA, 0xA9, 0xB4, 0x93, 0x8E, 0xF8,
0xE5, 0xC2, 0xDF, 0x8C, 0x91, 0xB6, 0xAB, 0x10, 0x0D, 0x2A, 0x37, 0x64, 0x79, 0x5E, 0x43, 0xB2, 0xAF, 0x88, 0x95,
0xC6, 0xDB, 0xFC, 0xE1, 0x5A, 0x47, 0x60, 0x7D, 0x2E, 0x33, 0x14, 0x09, 0x7F, 0x62, 0x45, 0x58, 0x0B, 0x16, 0x31,
0x2C, 0x97, 0x8A, 0xAD, 0xB0, 0xE3, 0xFE, 0xD9, 0xC4};
// Define the data points for %SOC depending on cell voltage
const uint8_t numPoints = 100;
const uint16_t SOC[101] = {10000, 9900, 9800, 9700, 9600, 9500, 9400, 9300, 9200, 9100, 9000, 8900, 8800, 8700, 8600,
8500, 8400, 8300, 8200, 8100, 8000, 7900, 7800, 7700, 7600, 7500, 7400, 7300, 7200, 7100,
7000, 6900, 6800, 6700, 6600, 6500, 6400, 6300, 6200, 6100, 6000, 5900, 5800, 5700, 5600,
5500, 5400, 5300, 5200, 5100, 5000, 4900, 4800, 4700, 4600, 4500, 4400, 4300, 4200, 4100,
4000, 3900, 3800, 3700, 3600, 3500, 3400, 3300, 3200, 3100, 3000, 2900, 2800, 2700, 2600,
2500, 2400, 2300, 2200, 2100, 2000, 1900, 1800, 1700, 1600, 1500, 1400, 1300, 1200, 1100,
1000, 900, 800, 700, 600, 500, 400, 300, 200, 100, 0};
const uint16_t voltage[101] = {
4200, 4173, 4148, 4124, 4102, 4080, 4060, 4041, 4023, 4007, 3993, 3980, 3969, 3959, 3953, 3950, 3941,
3932, 3924, 3915, 3907, 3898, 3890, 3881, 3872, 3864, 3855, 3847, 3838, 3830, 3821, 3812, 3804, 3795,
3787, 3778, 3770, 3761, 3752, 3744, 3735, 3727, 3718, 3710, 3701, 3692, 3684, 3675, 3667, 3658, 3650,
3641, 3632, 3624, 3615, 3607, 3598, 3590, 3581, 3572, 3564, 3555, 3547, 3538, 3530, 3521, 3512, 3504,
3495, 3487, 3478, 3470, 3461, 3452, 3444, 3435, 3427, 3418, 3410, 3401, 3392, 3384, 3375, 3367, 3358,
3350, 3338, 3325, 3313, 3299, 3285, 3271, 3255, 3239, 3221, 3202, 3180, 3156, 3127, 3090, 3000};
/* These messages are needed for contactor closing */
unsigned long startMillis = 0;
uint8_t messageIndex = 0;
uint8_t messageDelays[63] = {0, 0, 5, 10, 10, 15, 19, 19, 20, 20, 25, 30, 30, 35, 40, 40,
45, 49, 49, 50, 50, 52, 53, 53, 54, 55, 60, 60, 65, 67, 67, 70,
70, 75, 77, 77, 80, 80, 85, 90, 90, 95, 100, 100, 105, 110, 110, 115,
119, 119, 120, 120, 125, 130, 130, 135, 140, 140, 145, 149, 149, 150, 150};
static constexpr CAN_frame message_1 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0x62, 0x36, 0x8c, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_2 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x120,
.data = {0xd4, 0x1b, 0x8c, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x37, 0x35, 0x37, 0x37,
0xc9, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_3 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x19A,
.data = {0x24, 0x9b, 0x7b, 0x55, 0x44, 0x64, 0xd8, 0x1b, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x11, 0x52,
0x00, 0x12, 0x02, 0x64, 0x00, 0x00, 0x00, 0x08, 0x13, 0x00, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00}};
static constexpr CAN_frame message_4 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0x24, 0x6f, 0x8d, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_5 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x120,
.data = {0x92, 0x42, 0x8d, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x37, 0x35, 0x37, 0x37,
0xc9, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_6 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x19A,
.data = {0xd7, 0x05, 0x7c, 0x55, 0x44, 0x64, 0xd8, 0x1b, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x11, 0x52,
0x00, 0x12, 0x02, 0x64, 0x00, 0x00, 0x00, 0x08, 0x13, 0x00, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00}};
static constexpr CAN_frame message_7 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x30A,
.data = {0xb1, 0xe0, 0x26, 0x08, 0x54, 0x01, 0x04, 0x15, 0x00, 0x1a, 0x76, 0x00, 0x25, 0x01, 0x10, 0x27,
0x4f, 0x06, 0x18, 0x04, 0x33, 0x15, 0x34, 0x28, 0x00, 0x00, 0x10, 0x06, 0x21, 0x00, 0x4b, 0x06}};
static constexpr CAN_frame message_8 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x320,
.data = {0xc6, 0xab, 0x26, 0x41, 0x00, 0x00, 0x01, 0x3c, 0xac, 0x0d, 0x40, 0x20, 0x05, 0xc8, 0xa0, 0x03,
0x40, 0x20, 0x2b, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_9 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0xee, 0x84, 0x8e, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_10 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x120,
.data = {0x58, 0xa9, 0x8e, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x37, 0x35, 0x37, 0x37,
0xc9, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_11 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x19A,
.data = {0x91, 0x5c, 0x7d, 0x55, 0x44, 0x64, 0xd8, 0x1b, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x11, 0x52,
0x00, 0x12, 0x02, 0x64, 0x00, 0x00, 0x00, 0x08, 0x13, 0x00, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00}};
static constexpr CAN_frame message_12 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0xa8, 0xdd, 0x8f, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_13 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x120,
.data = {0x1e, 0xf0, 0x8f, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x37, 0x35, 0x37, 0x37,
0xc9, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_14 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x19A,
.data = {0x5b, 0xb7, 0x7e, 0x55, 0x44, 0x64, 0xd8, 0x1b, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x11, 0x52,
0x00, 0x12, 0x02, 0x64, 0x00, 0x00, 0x00, 0x08, 0x13, 0x00, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00}};
static constexpr CAN_frame message_15 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0xec, 0x6d, 0x90, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_16 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x120,
.data = {0x5a, 0x40, 0x90, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x37, 0x35, 0x37, 0x37,
0xc9, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_17 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x19A,
.data = {0x1d, 0xee, 0x7f, 0x55, 0x44, 0x64, 0xd8, 0x1b, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x11, 0x52,
0x00, 0x12, 0x02, 0x64, 0x00, 0x00, 0x00, 0x08, 0x13, 0x00, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00}};
static constexpr CAN_frame message_18 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x2B5,
.data = {0xbd, 0xb2, 0x42, 0x00, 0x00, 0x00, 0x00, 0x80, 0x59, 0x00, 0x2b, 0x00, 0x00, 0x04, 0x00, 0x00,
0xfa, 0xd0, 0x07, 0x00, 0x00, 0x00, 0x00, 0x00, 0x8f, 0x06, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_19 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x2E0,
.data = {0xc1, 0xf2, 0x42, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7e, 0x00, 0x00,
0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x70, 0x01, 0x0f, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_20 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0xaa, 0x34, 0x91, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_21 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x120,
.data = {0x1c, 0x19, 0x91, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x37, 0x35, 0x37, 0x37,
0xc9, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_22 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x2D5,
.data = {0x79, 0xfb, 0xa0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0b, 0x00, 0x00, 0x03, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0x34, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_23 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x2EA,
.data = {0x6e, 0xbb, 0xa0, 0x0d, 0x04, 0x01, 0x00, 0x00, 0x38, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0xc7, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_24 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x306,
.data = {0x00, 0x00, 0x00, 0xd2, 0x06, 0x92, 0x05, 0x34, 0x07, 0x8e, 0x08, 0x73, 0x05, 0x80, 0x05, 0x83,
0x05, 0x73, 0x05, 0x80, 0x05, 0xed, 0x01, 0xdd, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_25 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x308,
.data = {0xbe, 0x84, 0xa0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xff,
0x75, 0x6c, 0x86, 0x0d, 0xfb, 0xdf, 0x03, 0x36, 0xc3, 0x86, 0x11, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_26 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x19A,
.data = {0x6b, 0xa2, 0x80, 0x55, 0x44, 0x64, 0xd8, 0x1b, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x11, 0x52,
0x00, 0x12, 0x02, 0x64, 0x00, 0x00, 0x00, 0x08, 0x13, 0x00, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00}};
static constexpr CAN_frame message_27 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0x60, 0xdf, 0x92, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_28 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x120,
.data = {0xd6, 0xf2, 0x92, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x37, 0x35, 0x37, 0x37,
0xc9, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_29 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x19A,
.data = {0x2d, 0xfb, 0x81, 0x55, 0x44, 0x64, 0xd8, 0x1b, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x11, 0x52,
0x00, 0x12, 0x02, 0x64, 0x00, 0x00, 0x00, 0x08, 0x13, 0x00, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00}};
static constexpr CAN_frame message_30 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x33A,
.data = {0x1a, 0x23, 0x26, 0x10, 0x27, 0x4f, 0x06, 0x00, 0xf8, 0x1b, 0x19, 0x04, 0x30, 0x01, 0x00, 0x06,
0x00, 0x00, 0x00, 0x2e, 0x2d, 0x81, 0x25, 0x20, 0x00, 0x42, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_31 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x350,
.data = {0x26, 0x82, 0x26, 0xf4, 0x01, 0x00, 0x00, 0x50, 0x90, 0x15, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_32 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0x26, 0x86, 0x93, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_33 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x120,
.data = {0x90, 0xab, 0x93, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x37, 0x35, 0x37, 0x37,
0xc9, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_34 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x19A,
.data = {0xe7, 0x10, 0x82, 0x55, 0x44, 0x64, 0xd8, 0x1b, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x11, 0x52,
0x00, 0x12, 0x02, 0x64, 0x00, 0x00, 0x00, 0x08, 0x13, 0x00, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00}};
static constexpr CAN_frame message_35 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x2E5,
.data = {0x69, 0x8a, 0x3f, 0x01, 0x00, 0x00, 0x00, 0x15, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_36 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x3B5,
.data = {0xa3, 0xc8, 0x9f, 0x00, 0x00, 0x00, 0x00, 0x36, 0x37, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0xc7, 0x02, 0x00, 0x00, 0x00, 0x00, 0x6a, 0x09, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_37 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0xd5, 0x18, 0x94, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_38 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x120,
.data = {0x63, 0x35, 0x94, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x37, 0x35, 0x37, 0x37,
0xc9, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_39 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x19A,
.data = {0xa1, 0x49, 0x83, 0x55, 0x44, 0x64, 0xd8, 0x1b, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x11, 0x52,
0x00, 0x12, 0x02, 0x64, 0x00, 0x00, 0x00, 0x08, 0x13, 0x00, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00}};
static constexpr CAN_frame message_40 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0x93, 0x41, 0x95, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_41 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x120,
.data = {0x25, 0x6c, 0x95, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x37, 0x35, 0x37, 0x37,
0xc9, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_42 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x19A,
.data = {0x52, 0xd7, 0x84, 0x55, 0x44, 0x64, 0xd8, 0x1b, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x11, 0x52,
0x00, 0x12, 0x02, 0x64, 0x00, 0x00, 0x00, 0x08, 0x13, 0x00, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00}};
static constexpr CAN_frame message_43 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0x59, 0xaa, 0x96, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_44 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x120,
.data = {0xef, 0x87, 0x96, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x37, 0x35, 0x37, 0x37,
0xc9, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_45 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x19A,
.data = {0x14, 0x8e, 0x85, 0x55, 0x44, 0x64, 0xd8, 0x1b, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x11, 0x52,
0x00, 0x12, 0x02, 0x64, 0x00, 0x00, 0x00, 0x08, 0x13, 0x00, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00}};
static constexpr CAN_frame message_46 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0x1f, 0xf3, 0x97, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_47 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x120,
.data = {0xa9, 0xde, 0x97, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x37, 0x35, 0x37, 0x37,
0xc9, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_48 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x19A,
.data = {0xde, 0x65, 0x86, 0x55, 0x44, 0x64, 0xd8, 0x1b, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x11, 0x52,
0x00, 0x12, 0x02, 0x64, 0x00, 0x00, 0x00, 0x08, 0x13, 0x00, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00}};
static constexpr CAN_frame message_49 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x30A,
.data = {0xd3, 0x11, 0x27, 0x08, 0x54, 0x01, 0x04, 0x15, 0x00, 0x1a, 0x76, 0x00, 0x25, 0x01, 0x10, 0x27,
0x4f, 0x06, 0x19, 0x04, 0x33, 0x15, 0x34, 0x28, 0x00, 0x00, 0x10, 0x06, 0x21, 0x00, 0x4b, 0x06}};
static constexpr CAN_frame message_50 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x320,
.data = {0x80, 0xf2, 0x27, 0x41, 0x00, 0x00, 0x01, 0x3c, 0xac, 0x0d, 0x40, 0x20, 0x05, 0xc8, 0xa0, 0x03,
0x40, 0x20, 0x2b, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_51 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0x9e, 0x87, 0x98, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_52 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x120,
.data = {0x28, 0xaa, 0x98, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x37, 0x35, 0x37, 0x37,
0xc9, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_53 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x19A,
.data = {0x98, 0x3c, 0x87, 0x55, 0x44, 0x64, 0xd8, 0x1b, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x11, 0x52,
0x00, 0x12, 0x02, 0x64, 0x00, 0x00, 0x00, 0x08, 0x13, 0x00, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00}};
static constexpr CAN_frame message_54 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0xd8, 0xde, 0x99, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_55 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x120,
.data = {0x6e, 0xf3, 0x99, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x37, 0x35, 0x37, 0x37,
0xc9, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_56 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x19A,
.data = {0x19, 0x48, 0x88, 0x55, 0x44, 0x64, 0xd8, 0x1b, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x11, 0x52,
0x00, 0x12, 0x02, 0x64, 0x00, 0x00, 0x00, 0x08, 0x13, 0x00, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00}};
static constexpr CAN_frame message_57 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0x12, 0x35, 0x9a, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_58 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x120,
.data = {0xa4, 0x18, 0x9a, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x37, 0x35, 0x37, 0x37,
0xc9, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_59 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x19A,
.data = {0x5f, 0x11, 0x89, 0x55, 0x44, 0x64, 0xd8, 0x1b, 0x40, 0x20, 0x00, 0x00, 0x00, 0x00, 0x11, 0x52,
0x00, 0x12, 0x02, 0x64, 0x00, 0x00, 0x00, 0x08, 0x13, 0x00, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00}};
static constexpr CAN_frame message_60 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x2B5,
.data = {0xfb, 0xeb, 0x43, 0x00, 0x00, 0x00, 0x00, 0x80, 0x59, 0x00, 0x2b, 0x00, 0x00, 0x04, 0x00, 0x00,
0xfa, 0xd0, 0x07, 0x00, 0x00, 0x00, 0x00, 0x00, 0x8f, 0x06, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_61 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x2C0,
.data = {0xcc, 0xcd, 0xa2, 0x21, 0x00, 0xa1, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7d, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_62 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x2E0,
.data = {0x87, 0xab, 0x43, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7e, 0x00, 0x00,
0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x70, 0x01, 0x0f, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}};
static constexpr CAN_frame message_63 = {
.FD = true,
.ext_ID = false,
.DLC = 32,
.ID = 0x10A,
.data = {0x54, 0x6c, 0x9b, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0x01, 0x00, 0x00, 0x36, 0x39, 0x35, 0x35,
0xc9, 0x02, 0x00, 0x00, 0x10, 0x00, 0x00, 0x35, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00}};
const CAN_frame* messages[63] = {
&message_1, &message_2, &message_3, &message_4, &message_5, &message_6, &message_7, &message_8,
&message_9, &message_10, &message_11, &message_12, &message_13, &message_14, &message_15, &message_16,
&message_17, &message_18, &message_19, &message_20, &message_21, &message_22, &message_23, &message_24,
&message_25, &message_26, &message_27, &message_28, &message_29, &message_30, &message_31, &message_32,
&message_33, &message_34, &message_35, &message_36, &message_37, &message_38, &message_39, &message_40,
&message_41, &message_42, &message_43, &message_44, &message_45, &message_46, &message_47, &message_48,
&message_49, &message_50, &message_51, &message_52, &message_53, &message_54, &message_55, &message_56,
&message_57, &message_58, &message_59, &message_60, &message_61, &message_62, &message_63};
/* PID polling messages */
CAN_frame EGMP_7E4 = {.FD = true,
.ext_ID = false,
.DLC = 8,
.ID = 0x7E4,
.data = {0x03, 0x22, 0x01, 0x01, 0x00, 0x00, 0x00, 0x00}}; //Poll PID 03 22 01 01
static constexpr CAN_frame EGMP_7E4_ack = {
.FD = true,
.ext_ID = false,
.DLC = 8,
.ID = 0x7E4,
.data = {0x30, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}}; //Ack frame, correct PID is returned
};
#endif

View file

@ -70,7 +70,7 @@ class KiaHyundai64Battery : public CanBattery {
uint16_t CellVoltMin_mV = 3700;
uint16_t allowedDischargePower = 0;
uint16_t allowedChargePower = 0;
uint16_t batteryVoltage = 0;
uint16_t batteryVoltage = 3700;
uint16_t inverterVoltageFrameHigh = 0;
uint16_t inverterVoltage = 0;
uint16_t cellvoltages_mv[98];

View file

@ -171,9 +171,7 @@ uint8_t vw_crc_calc(uint8_t* inputBytes, uint8_t length, uint32_t address) {
magicByte = MB16A954A6[counter];
break;
default: // this won't lead to correct CRC checksums
#ifdef DEBUG_LOG
logging.println("Checksum request unknown");
#endif
magicByte = 0x00;
break;
}
@ -310,9 +308,7 @@ void MebBattery::
void MebBattery::handle_incoming_can_frame(CAN_frame rx_frame) {
last_can_msg_timestamp = millis();
if (first_can_msg == 0) {
#ifdef DEBUG_LOG
logging.printf("MEB: First CAN msg received\n");
#endif
first_can_msg = last_can_msg_timestamp;
}
@ -326,9 +322,7 @@ void MebBattery::handle_incoming_can_frame(CAN_frame rx_frame) {
if (rx_frame.data.u8[0] !=
vw_crc_calc(rx_frame.data.u8, rx_frame.DLC, rx_frame.ID)) { //If CRC does not match calc
datalayer.battery.status.CAN_error_counter++;
#ifdef DEBUG_LOG
logging.printf("MEB: Msg 0x%04X CRC error\n", rx_frame.ID);
#endif
return;
}
default:
@ -700,29 +694,23 @@ void MebBattery::handle_incoming_can_frame(CAN_frame rx_frame) {
case 3: // EXTERN CHARGING
case 4: // AC_CHARGING
case 6: // DC_CHARGING
#ifdef DEBUG_LOG
if (!datalayer.system.status.battery_allows_contactor_closing)
logging.printf("MEB: Contactors closed\n");
#endif
if (datalayer.battery.status.real_bms_status != BMS_FAULT)
datalayer.battery.status.real_bms_status = BMS_ACTIVE;
datalayer.system.status.battery_allows_contactor_closing = true;
hv_requested = false;
break;
case 5: // Error
#ifdef DEBUG_LOG
if (datalayer.system.status.battery_allows_contactor_closing)
logging.printf("MEB: Contactors opened\n");
#endif
datalayer.battery.status.real_bms_status = BMS_FAULT;
datalayer.system.status.battery_allows_contactor_closing = false;
hv_requested = false;
break;
case 7: // Init
#ifdef DEBUG_LOG
if (datalayer.system.status.battery_allows_contactor_closing)
logging.printf("MEB: Contactors opened\n");
#endif
if (datalayer.battery.status.real_bms_status != BMS_FAULT)
datalayer.battery.status.real_bms_status = BMS_STANDBY;
datalayer.system.status.battery_allows_contactor_closing = false;
@ -730,10 +718,8 @@ void MebBattery::handle_incoming_can_frame(CAN_frame rx_frame) {
break;
case 2: // BALANCING
default:
#ifdef DEBUG_LOG
if (datalayer.system.status.battery_allows_contactor_closing)
logging.printf("MEB: Contactors opened\n");
#endif
if (datalayer.battery.status.real_bms_status != BMS_FAULT)
datalayer.battery.status.real_bms_status = BMS_STANDBY;
datalayer.system.status.battery_allows_contactor_closing = false;
@ -1276,10 +1262,8 @@ void MebBattery::handle_incoming_can_frame(CAN_frame rx_frame) {
handle_obd_frame(rx_frame);
break;
default:
#ifdef DEBUG_LOG
logging.printf("Unknown CAN frame received:\n");
dump_can_frame(rx_frame, MSG_RX);
#endif
break;
}
datalayer.battery.status.CAN_battery_still_alive = CAN_STILL_ALIVE;
@ -1292,10 +1276,8 @@ void MebBattery::handle_incoming_can_frame(CAN_frame rx_frame) {
void MebBattery::transmit_can(unsigned long currentMillis) {
if (currentMillis - last_can_msg_timestamp > 500) {
#ifdef DEBUG_LOG
if (first_can_msg)
logging.printf("MEB: No CAN msg received for 500ms\n");
#endif
can_msg_received = RX_DEFAULT;
first_can_msg = 0;
if (datalayer.battery.status.real_bms_status != BMS_FAULT) {
@ -1373,7 +1355,6 @@ void MebBattery::transmit_can(unsigned long currentMillis) {
((int32_t)datalayer_extended.meb.BMS_voltage_intermediate_dV)) < 200))))) {
hv_requested = true;
datalayer.system.settings.start_precharging = false;
#ifdef DEBUG_LOG
if (MEB_503.data.u8[3] == BMS_TARGET_HV_OFF) {
logging.printf("MEB: Requesting HV\n");
}
@ -1385,7 +1366,6 @@ void MebBattery::transmit_can(unsigned long currentMillis) {
logging.printf("MEB: Precharge bit set to inactive\n");
}
}
#endif
MEB_503.data.u8[1] =
0x30 | (datalayer.system.status.precharge_status == AUTO_PRECHARGE_PRECHARGING ? 0x80 : 0x00);
MEB_503.data.u8[3] = BMS_TARGET_AC_CHARGING;
@ -1399,7 +1379,6 @@ void MebBattery::transmit_can(unsigned long currentMillis) {
datalayer.system.settings.start_precharging = true;
}
#ifdef DEBUG_LOG
if (MEB_503.data.u8[3] != BMS_TARGET_HV_OFF) {
logging.printf("MEB: Requesting HV_OFF\n");
}
@ -1411,7 +1390,6 @@ void MebBattery::transmit_can(unsigned long currentMillis) {
logging.printf("MEB: Precharge bit set to inactive\n");
}
}
#endif
MEB_503.data.u8[1] =
0x10 | (datalayer.system.status.precharge_status == AUTO_PRECHARGE_PRECHARGING ? 0x80 : 0x00);
MEB_503.data.u8[3] = BMS_TARGET_HV_OFF;

View file

@ -147,11 +147,9 @@ void MgHsPHEVBattery::handle_incoming_can_frame(CAN_frame rx_frame) {
// 15 = isolation fault
// 0/8 = checking
#ifdef DEBUG_LOG
if (rx_frame.data.u8[1] != previousState) {
logging.printf("MG_HS_PHEV: Battery status changed to %d (%d)\n", rx_frame.data.u8[1], rx_frame.data.u8[0]);
}
#endif
if (rx_frame.data.u8[1] == 0xf && previousState != 0xf) {
// Isolation fault, set event
@ -168,18 +166,14 @@ void MgHsPHEVBattery::handle_incoming_can_frame(CAN_frame rx_frame) {
// A weird 'stuck' state where the battery won't reconnect
datalayer.system.status.battery_allows_contactor_closing = false;
if (!datalayer.system.status.BMS_startup_in_progress) {
#ifdef DEBUG_LOG
logging.printf("MG_HS_PHEV: Stuck, resetting.\n");
#endif
start_bms_reset();
}
} else if (rx_frame.data.u8[1] == 0xf) {
// A fault state (likely isolation failure)
datalayer.system.status.battery_allows_contactor_closing = false;
if (!datalayer.system.status.BMS_startup_in_progress) {
#ifdef DEBUG_LOG
logging.printf("MG_HS_PHEV: Fault, resetting.\n");
#endif
start_bms_reset();
}
} else {

View file

@ -0,0 +1,155 @@
#include "RELION-LV-BATTERY.h"
#include "../battery/BATTERIES.h"
#include "../communication/can/comm_can.h"
#include "../datalayer/datalayer.h"
#include "../devboard/utils/events.h"
/*CAN Type:CAN2.0(Extended)
BPS:250kbps
Data Length: 8
Data Encoded Format:Motorola*/
void RelionBattery::update_values() {
datalayer.battery.status.real_soc = battery_soc * 100;
datalayer.battery.status.remaining_capacity_Wh = static_cast<uint32_t>(
(static_cast<double>(datalayer.battery.status.real_soc) / 10000) * datalayer.battery.info.total_capacity_Wh);
datalayer.battery.status.soh_pptt = battery_soh * 100;
datalayer.battery.status.voltage_dV = battery_total_voltage;
datalayer.battery.status.current_dA = battery_total_current; //Charging negative, discharge positive
datalayer.battery.status.max_charge_power_W =
((battery_total_voltage / 10) * charge_current_A); //90A recommended charge current
datalayer.battery.status.max_discharge_power_W =
((battery_total_voltage / 10) * discharge_current_A); //150A max continous discharge current
datalayer.battery.status.temperature_min_dC = max_cell_temperature * 10;
datalayer.battery.status.temperature_max_dC = max_cell_temperature * 10;
datalayer.battery.status.cell_max_voltage_mV = max_cell_voltage;
datalayer.battery.status.cell_min_voltage_mV = min_cell_voltage;
}
void RelionBattery::handle_incoming_can_frame(CAN_frame rx_frame) {
switch (rx_frame.ID) {
case 0x02018100: //ID1 (Example frame 10 08 01 F0 00 00 00 00)
datalayer.battery.status.CAN_battery_still_alive = CAN_STILL_ALIVE;
battery_total_voltage = ((rx_frame.data.u8[2] << 8) | rx_frame.data.u8[3]);
break;
case 0x02028100: //ID2 (Example frame 00 00 00 63 64 10 00 00)
datalayer.battery.status.CAN_battery_still_alive = CAN_STILL_ALIVE;
battery_total_current = ((rx_frame.data.u8[0] << 8) | rx_frame.data.u8[1]);
system_state = rx_frame.data.u8[2];
battery_soc = rx_frame.data.u8[3];
battery_soh = rx_frame.data.u8[4];
most_serious_fault = rx_frame.data.u8[5];
break;
case 0x02038100: //ID3 (Example frame 0C F9 01 04 0C A7 01 0F)
datalayer.battery.status.CAN_battery_still_alive = CAN_STILL_ALIVE;
max_cell_voltage = ((rx_frame.data.u8[0] << 8) | rx_frame.data.u8[1]);
min_cell_voltage = ((rx_frame.data.u8[4] << 8) | rx_frame.data.u8[5]);
break;
case 0x02648100: //Charging limitis
datalayer.battery.status.CAN_battery_still_alive = CAN_STILL_ALIVE;
charge_current_A = ((rx_frame.data.u8[0] << 8) | rx_frame.data.u8[1]) - 800;
regen_charge_current_A = ((rx_frame.data.u8[2] << 8) | rx_frame.data.u8[3]) - 800;
discharge_current_A = ((rx_frame.data.u8[2] << 8) | rx_frame.data.u8[3]) - 800;
break;
case 0x02048100: ///Temperatures min/max 2048100 [8] 47 01 01 47 01 01 00 00
datalayer.battery.status.CAN_battery_still_alive = CAN_STILL_ALIVE;
max_cell_temperature = rx_frame.data.u8[0] - 50;
min_cell_temperature = rx_frame.data.u8[2] - 50;
break;
case 0x02468100: ///Raw temperatures 2468100 [8] 47 47 47 47 47 47 47 47
datalayer.battery.status.CAN_battery_still_alive = CAN_STILL_ALIVE;
break;
case 0x02478100: ///? 2478100 [8] 32 32 32 32 32 32 32 32
datalayer.battery.status.CAN_battery_still_alive = CAN_STILL_ALIVE;
break;
//ID6 = 0x02108100 ~ 0x023F8100****** Cell Voltage 1~192******
case 0x02108100: ///Cellvoltages 1 2108100 [8] 0C F9 0C F8 0C F8 0C F9
datalayer.battery.status.cell_voltages_mV[0] = ((rx_frame.data.u8[0] << 8) | rx_frame.data.u8[1]);
datalayer.battery.status.cell_voltages_mV[1] = ((rx_frame.data.u8[2] << 8) | rx_frame.data.u8[3]);
datalayer.battery.status.cell_voltages_mV[2] = ((rx_frame.data.u8[4] << 8) | rx_frame.data.u8[5]);
datalayer.battery.status.cell_voltages_mV[3] = ((rx_frame.data.u8[6] << 8) | rx_frame.data.u8[7]);
datalayer.battery.status.CAN_battery_still_alive = CAN_STILL_ALIVE;
break;
case 0x02118100: ///Cellvoltages 2 2118100 [8] 0C F8 0C F8 0C F9 0C F8
datalayer.battery.status.cell_voltages_mV[4] = ((rx_frame.data.u8[0] << 8) | rx_frame.data.u8[1]);
datalayer.battery.status.cell_voltages_mV[5] = ((rx_frame.data.u8[2] << 8) | rx_frame.data.u8[3]);
datalayer.battery.status.cell_voltages_mV[6] = ((rx_frame.data.u8[4] << 8) | rx_frame.data.u8[5]);
datalayer.battery.status.cell_voltages_mV[7] = ((rx_frame.data.u8[6] << 8) | rx_frame.data.u8[7]);
datalayer.battery.status.CAN_battery_still_alive = CAN_STILL_ALIVE;
break;
case 0x02128100: ///Cellvoltages 3 2128100 [8] 0C F8 0C F8 0C F9 0C F8
datalayer.battery.status.cell_voltages_mV[8] = ((rx_frame.data.u8[0] << 8) | rx_frame.data.u8[1]);
datalayer.battery.status.cell_voltages_mV[9] = ((rx_frame.data.u8[2] << 8) | rx_frame.data.u8[3]);
datalayer.battery.status.cell_voltages_mV[10] = ((rx_frame.data.u8[4] << 8) | rx_frame.data.u8[5]);
datalayer.battery.status.cell_voltages_mV[11] = ((rx_frame.data.u8[6] << 8) | rx_frame.data.u8[7]);
datalayer.battery.status.CAN_battery_still_alive = CAN_STILL_ALIVE;
break;
case 0x02138100: ///Cellvoltages 4 2138100 [8] 0C F9 0C CD 0C A7 00 00
datalayer.battery.status.cell_voltages_mV[12] = ((rx_frame.data.u8[0] << 8) | rx_frame.data.u8[1]);
datalayer.battery.status.cell_voltages_mV[13] = ((rx_frame.data.u8[2] << 8) | rx_frame.data.u8[3]);
datalayer.battery.status.cell_voltages_mV[14] = ((rx_frame.data.u8[4] << 8) | rx_frame.data.u8[5]);
datalayer.battery.status.CAN_battery_still_alive = CAN_STILL_ALIVE;
break;
case 0x02058100: ///? 2058100 [8] 00 0C 00 00 00 00 00 00
datalayer.battery.status.CAN_battery_still_alive = CAN_STILL_ALIVE;
break;
case 0x02068100: ///? 2068100 [8] 00 00 00 00 00 00 00 00
datalayer.battery.status.CAN_battery_still_alive = CAN_STILL_ALIVE;
break;
case 0x02148100: ///? 2148100 [8] 00 00 00 00 00 00 00 00
datalayer.battery.status.CAN_battery_still_alive = CAN_STILL_ALIVE;
break;
case 0x02508100: ///? 2508100 [8] 00 00 00 00 00 00 00 00
datalayer.battery.status.CAN_battery_still_alive = CAN_STILL_ALIVE;
break;
case 0x02518100: ///? 2518100 [8] 00 00 00 00 00 00 00 00
datalayer.battery.status.CAN_battery_still_alive = CAN_STILL_ALIVE;
break;
case 0x02528100: ///? 2528100 [8] 00 00 00 00 00 00 00 00
datalayer.battery.status.CAN_battery_still_alive = CAN_STILL_ALIVE;
break;
case 0x02548100: ///? 2548100 [8] 00 00 00 00 00 00 00 00
datalayer.battery.status.CAN_battery_still_alive = CAN_STILL_ALIVE;
break;
case 0x024A8100: ///? 24A8100 [8] 00 00 00 00 00 00 00 00
datalayer.battery.status.CAN_battery_still_alive = CAN_STILL_ALIVE;
break;
case 0x02558100: ///? 2558100 [8] 00 00 00 00 00 00 00 00
datalayer.battery.status.CAN_battery_still_alive = CAN_STILL_ALIVE;
break;
case 0x02538100: ///? 2538100 [8] 00 00 00 00 00 00 00 00
datalayer.battery.status.CAN_battery_still_alive = CAN_STILL_ALIVE;
break;
case 0x02568100: ///? 2568100 [8] 00 00 00 00 00 00 00 00
datalayer.battery.status.CAN_battery_still_alive = CAN_STILL_ALIVE;
break;
default:
break;
}
}
void RelionBattery::transmit_can(unsigned long currentMillis) {
// No periodic sending for this protocol
}
void RelionBattery::setup(void) { // Performs one time setup at startup
strncpy(datalayer.system.info.battery_protocol, Name, 63);
datalayer.system.info.battery_protocol[63] = '\0';
datalayer.battery.info.chemistry = LFP;
datalayer.battery.info.number_of_cells = 16;
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.max_cell_voltage_mV = MAX_CELL_VOLTAGE_MV;
datalayer.battery.info.min_cell_voltage_mV = MIN_CELL_VOLTAGE_MV;
datalayer.system.status.battery_allows_contactor_closing = true;
}

View file

@ -0,0 +1,43 @@
#ifndef RELION_BATTERY_H
#define RELION_BATTERY_H
#include "../system_settings.h"
#include "CanBattery.h"
#ifdef RELION_BATTERY
#define SELECTED_BATTERY_CLASS RelionBattery
#endif
class RelionBattery : public CanBattery {
public:
RelionBattery() : CanBattery(CAN_Speed::CAN_SPEED_250KBPS) {}
virtual void setup(void);
virtual void handle_incoming_can_frame(CAN_frame rx_frame);
virtual void update_values();
virtual void transmit_can(unsigned long currentMillis);
static constexpr const char* Name = "Relion LV protocol via 250kbps CAN";
private:
static const int MAX_PACK_VOLTAGE_DV = 584; //58.4V recommended charge voltage. BMS protection steps in at 60.8V
static const int MIN_PACK_VOLTAGE_DV = 440; //44.0V Recommended LV disconnect. BMS protection steps in at 40.0V
static const int MAX_CELL_DEVIATION_MV = 300;
static const int MAX_CELL_VOLTAGE_MV = 3800; //Battery is put into emergency stop if one cell goes over this value
static const int MIN_CELL_VOLTAGE_MV = 2700; //Battery is put into emergency stop if one cell goes below this value
uint16_t battery_total_voltage = 500;
int16_t battery_total_current = 0;
uint8_t system_state = 0;
uint8_t battery_soc = 50;
uint8_t battery_soh = 99;
uint8_t most_serious_fault = 0;
uint16_t max_cell_voltage = 3300;
uint16_t min_cell_voltage = 3300;
int16_t max_cell_temperature = 0;
int16_t min_cell_temperature = 0;
int16_t charge_current_A = 0;
int16_t regen_charge_current_A = 0;
int16_t discharge_current_A = 0;
};
#endif

View file

@ -51,39 +51,6 @@ void RenaultKangooBattery::
datalayer.battery.status.cell_min_voltage_mV = LB_Cell_Min_Voltage;
datalayer.battery.status.cell_max_voltage_mV = LB_Cell_Max_Voltage;
#ifdef DEBUG_LOG
logging.println("Values going to inverter:");
logging.print("SOH%: ");
logging.print(datalayer.battery.status.soh_pptt);
logging.print(", SOC% scaled: ");
logging.print(datalayer.battery.status.reported_soc);
logging.print(", Voltage: ");
logging.print(datalayer.battery.status.voltage_dV);
logging.print(", Max discharge power: ");
logging.print(datalayer.battery.status.max_discharge_power_W);
logging.print(", Max charge power: ");
logging.print(datalayer.battery.status.max_charge_power_W);
logging.print(", Max temp: ");
logging.print(datalayer.battery.status.temperature_max_dC);
logging.print(", Min temp: ");
logging.print(datalayer.battery.status.temperature_min_dC);
logging.print(", BMS Status (3=OK): ");
logging.print(datalayer.battery.status.bms_status);
logging.println("Battery values: ");
logging.print("Real SOC: ");
logging.print(LB_SOC);
logging.print(", Current: ");
logging.print(LB_Current);
logging.print(", kWh remain: ");
logging.print(LB_kWh_Remaining);
logging.print(", max mV: ");
logging.print(LB_Cell_Max_Voltage);
logging.print(", min mV: ");
logging.print(LB_Cell_Min_Voltage);
#endif
}
void RenaultKangooBattery::handle_incoming_can_frame(CAN_frame rx_frame) {

View file

@ -676,39 +676,39 @@ void TeslaBattery::
clear_event(EVENT_BATTERY_FUSE);
}
#ifdef TESLA_MODEL_3Y_BATTERY
// Autodetect algoritm for chemistry on 3/Y packs.
// NCM/A batteries have 96s, LFP has 102-108s
// Drawback with this check is that it takes 3-5minutes before all cells have been counted!
if (datalayer.battery.info.number_of_cells > 101) {
datalayer.battery.info.chemistry = battery_chemistry_enum::LFP;
}
if (user_selected_tesla_GTW_chassisType > 1) { //{{0, "Model S"}, {1, "Model X"}, {2, "Model 3"}, {3, "Model Y"}};
// Autodetect algoritm for chemistry on 3/Y packs.
// NCM/A batteries have 96s, LFP has 102-108s
// Drawback with this check is that it takes 3-5minutes before all cells have been counted!
if (datalayer.battery.info.number_of_cells > 101) {
datalayer.battery.info.chemistry = battery_chemistry_enum::LFP;
}
//Once cell chemistry is determined, set maximum and minimum total pack voltage safety limits
if (datalayer.battery.info.chemistry == battery_chemistry_enum::LFP) {
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_3Y_LFP;
datalayer.battery.info.min_design_voltage_dV = MIN_PACK_VOLTAGE_3Y_LFP;
datalayer.battery.info.max_cell_voltage_mV = MAX_CELL_VOLTAGE_LFP;
datalayer.battery.info.min_cell_voltage_mV = MIN_CELL_VOLTAGE_LFP;
datalayer.battery.info.max_cell_voltage_deviation_mV = MAX_CELL_DEVIATION_LFP;
} else { // NCM/A chemistry
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_3Y_NCMA;
datalayer.battery.info.min_design_voltage_dV = MIN_PACK_VOLTAGE_3Y_NCMA;
datalayer.battery.info.max_cell_voltage_mV = MAX_CELL_VOLTAGE_NCA_NCM;
datalayer.battery.info.min_cell_voltage_mV = MIN_CELL_VOLTAGE_NCA_NCM;
datalayer.battery.info.max_cell_voltage_deviation_mV = MAX_CELL_DEVIATION_NCA_NCM;
}
//Once cell chemistry is determined, set maximum and minimum total pack voltage safety limits
if (datalayer.battery.info.chemistry == battery_chemistry_enum::LFP) {
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_3Y_LFP;
datalayer.battery.info.min_design_voltage_dV = MIN_PACK_VOLTAGE_3Y_LFP;
datalayer.battery.info.max_cell_voltage_mV = MAX_CELL_VOLTAGE_LFP;
datalayer.battery.info.min_cell_voltage_mV = MIN_CELL_VOLTAGE_LFP;
datalayer.battery.info.max_cell_voltage_deviation_mV = MAX_CELL_DEVIATION_LFP;
} else { // NCM/A chemistry
datalayer.battery.info.max_design_voltage_dV = MAX_PACK_VOLTAGE_3Y_NCMA;
datalayer.battery.info.min_design_voltage_dV = MIN_PACK_VOLTAGE_3Y_NCMA;
datalayer.battery.info.max_cell_voltage_mV = MAX_CELL_VOLTAGE_NCA_NCM;
datalayer.battery.info.min_cell_voltage_mV = MIN_CELL_VOLTAGE_NCA_NCM;
datalayer.battery.info.max_cell_voltage_deviation_mV = MAX_CELL_DEVIATION_NCA_NCM;
}
// During forced balancing request via webserver, we allow the battery to exceed normal safety parameters
if (datalayer.battery.settings.user_requests_balancing) {
datalayer.battery.status.real_soc = 9900; //Force battery to show up as 99% when balancing
datalayer.battery.info.max_design_voltage_dV = datalayer.battery.settings.balancing_max_pack_voltage_dV;
datalayer.battery.info.max_cell_voltage_mV = datalayer.battery.settings.balancing_max_cell_voltage_mV;
datalayer.battery.info.max_cell_voltage_deviation_mV =
datalayer.battery.settings.balancing_max_deviation_cell_voltage_mV;
datalayer.battery.status.max_charge_power_W = datalayer.battery.settings.balancing_float_power_W;
// During forced balancing request via webserver, we allow the battery to exceed normal safety parameters
if (datalayer.battery.settings.user_requests_balancing) {
datalayer.battery.status.real_soc = 9900; //Force battery to show up as 99% when balancing
datalayer.battery.info.max_design_voltage_dV = datalayer.battery.settings.balancing_max_pack_voltage_dV;
datalayer.battery.info.max_cell_voltage_mV = datalayer.battery.settings.balancing_max_cell_voltage_mV;
datalayer.battery.info.max_cell_voltage_deviation_mV =
datalayer.battery.settings.balancing_max_deviation_cell_voltage_mV;
datalayer.battery.status.max_charge_power_W = datalayer.battery.settings.balancing_float_power_W;
}
}
#endif // TESLA_MODEL_3Y_BATTERY
// Check if user requests some action
if (datalayer.battery.settings.user_requests_tesla_isolation_clear) {
@ -720,17 +720,25 @@ void TeslaBattery::
//Start the BMS ECU reset statemachine, only if contactors are OPEN and BMS ECU allows it
stateMachineBMSReset = 0;
datalayer.battery.settings.user_requests_tesla_bms_reset = false;
#ifdef DEBUG_LOG
logging.println("BMS reset requested");
#endif //DEBUG_LOG
} else {
#ifdef DEBUG_LOG
logging.println("ERROR: BMS reset failed due to contactors not being open, or BMS ECU not allowing it");
#endif //DEBUG_LOG
stateMachineBMSReset = 0;
stateMachineBMSReset = 0xFF;
datalayer.battery.settings.user_requests_tesla_bms_reset = false;
}
}
if (datalayer.battery.settings.user_requests_tesla_soc_reset) {
if (datalayer.battery.status.real_soc < 1500 || datalayer.battery.status.real_soc > 9000) {
//Start the SOC reset statemachine, only if SOC < 15% or > 90%
stateMachineSOCReset = 0;
datalayer.battery.settings.user_requests_tesla_soc_reset = false;
logging.println("SOC reset requested");
} else {
logging.println("ERROR: SOC reset failed due to SOC not being less than 15 or greater than 90");
stateMachineSOCReset = 0xFF;
datalayer.battery.settings.user_requests_tesla_soc_reset = false;
}
}
//Update 0x333 UI_chargeTerminationPct (bit 16, width 10) value to SOC max value - expose via UI?
//One firmware version this was seen at bit 17 width 11
@ -986,8 +994,6 @@ void TeslaBattery::
}
}
#ifdef DEBUG_LOG
printFaultCodesIfActive();
logging.print("BMS Contactors State: ");
logging.print(getBMSContactorState(battery_contactor)); // Display what state the BMS thinks the contactors are in
@ -1045,7 +1051,6 @@ void TeslaBattery::
logging.printf("PCS_ambientTemp: %.2f°C, DCDC_Temp: %.2f°C, ChgPhA: %.2f°C, ChgPhB: %.2f°C, ChgPhC: %.2f°C.\n",
PCS_ambientTemp * 0.1 + 40, PCS_dcdcTemp * 0.1 + 40, PCS_chgPhATemp * 0.1 + 40,
PCS_chgPhBTemp * 0.1 + 40, PCS_chgPhCTemp * 0.1 + 40);
#endif //DEBUG_LOG
}
void TeslaBattery::handle_incoming_can_frame(CAN_frame rx_frame) {
@ -1895,9 +1900,7 @@ void TeslaBattery::handle_incoming_can_frame(CAN_frame rx_frame) {
if (stateMachineBMSQuery != 0xFF && stateMachineBMSReset == 0xFF) {
if (memcmp(rx_frame.data.u8, "\x02\x50\x03\xAA\xAA\xAA\xAA\xAA", 8) == 0) {
//Received initial response, proceed to actual query
#ifdef DEBUG_LOG
logging.println("CAN UDS: Received BMS query initial handshake reply");
#endif //DEBUG_LOG
stateMachineBMSQuery = 1;
break;
}
@ -1906,9 +1909,7 @@ void TeslaBattery::handle_incoming_can_frame(CAN_frame rx_frame) {
battery_partNumber[0] = rx_frame.data.u8[5];
battery_partNumber[1] = rx_frame.data.u8[6];
battery_partNumber[2] = rx_frame.data.u8[7];
#ifdef DEBUG_LOG
logging.println("CAN UDS: Received BMS query data frame");
#endif //DEBUG_LOG
stateMachineBMSQuery = 2;
break;
}
@ -1921,32 +1922,25 @@ void TeslaBattery::handle_incoming_can_frame(CAN_frame rx_frame) {
battery_partNumber[7] = rx_frame.data.u8[5];
battery_partNumber[8] = rx_frame.data.u8[6];
battery_partNumber[9] = rx_frame.data.u8[7];
#ifdef DEBUG_LOG
logging.println("CAN UDS: Received BMS query second data frame");
#endif //DEBUG_LOG
break;
}
if (memcmp(&rx_frame.data.u8[0], "\x22", 1) == 0) {
//Final part of part number
battery_partNumber[10] = rx_frame.data.u8[1];
battery_partNumber[11] = rx_frame.data.u8[2];
#ifdef DEBUG_LOG
logging.println("CAN UDS: Received BMS query final data frame");
#endif //DEBUG_LOG
break;
}
if (memcmp(rx_frame.data.u8, "\x23\x00\x00\x00\xAA\xAA\xAA\xAA", 8) == 0) {
//Received final frame
#ifdef DEBUG_LOG
logging.println("CAN UDS: Received BMS query termination frame");
#endif //DEBUG_LOG
parsed_battery_partNumber = true;
stateMachineBMSQuery = 0xFF;
break;
}
}
//BMS Reset
#ifdef DEBUG_LOG
if (stateMachineBMSQuery == 0xFF) { // Make sure this is reset request not query
if (memcmp(rx_frame.data.u8, "\x02\x67\x06\xAA\xAA\xAA\xAA\xAA", 8) == 0) {
logging.println("CAN UDS: ECU unlocked");
@ -1956,7 +1950,6 @@ void TeslaBattery::handle_incoming_can_frame(CAN_frame rx_frame) {
logging.println("CAN UDS: ECU reset positive response, 1 second downtime");
}
}
#endif //DEBUG_LOG
break;
default:
break;
@ -1999,7 +1992,7 @@ int index_118 = 0;
void TeslaBattery::transmit_can(unsigned long currentMillis) {
if (operate_contactors) { //Special S/X mode
if (user_selected_tesla_digital_HVIL) { //Special S/X? mode for 2024+ batteries
if ((datalayer.system.status.inverter_allows_contactor_closing) && (datalayer.battery.status.bms_status != FAULT)) {
if (currentMillis - lastSend1CF >= 10) {
transmit_can_frame(&can_msg_1CF[index_1CF]);
@ -2312,31 +2305,66 @@ void TeslaBattery::transmit_can(unsigned long currentMillis) {
break;
}
}
if (stateMachineSOCReset != 0xFF) {
//This implementation should be rewritten to actually reply to the UDS responses sent by the BMS
//While this may work, it is not the correct way to implement this
switch (stateMachineSOCReset) {
case 0:
TESLA_602.data = {0x02, 0x27, 0x05, 0x00, 0x00, 0x00, 0x00, 0x00};
transmit_can_frame(&TESLA_602);
stateMachineSOCReset = 1;
break;
case 1:
TESLA_602.data = {0x30, 0x00, 0x0A, 0x00, 0x00, 0x00, 0x00, 0x00};
transmit_can_frame(&TESLA_602);
stateMachineSOCReset = 2;
break;
case 2:
TESLA_602.data = {0x10, 0x12, 0x27, 0x06, 0x35, 0x34, 0x37, 0x36};
transmit_can_frame(&TESLA_602);
stateMachineSOCReset = 3;
break;
case 3:
TESLA_602.data = {0x21, 0x31, 0x30, 0x33, 0x32, 0x3D, 0x3C, 0x3F};
transmit_can_frame(&TESLA_602);
stateMachineSOCReset = 4;
break;
case 4:
TESLA_602.data = {0x22, 0x3E, 0x39, 0x38, 0x3B, 0x3A, 0x00, 0x00};
transmit_can_frame(&TESLA_602);
//Should generate a CAN UDS log message indicating ECU unlocked
stateMachineSOCReset = 5;
break;
case 5:
TESLA_602.data = {0x04, 0x31, 0x01, 0x04, 0x07, 0x00, 0x00, 0x00};
transmit_can_frame(&TESLA_602);
stateMachineSOCReset = 0xFF;
break;
default:
//Something went wrong. Reset all and cancel
stateMachineSOCReset = 0xFF;
break;
}
}
if (stateMachineBMSQuery != 0xFF) {
//This implementation should be rewritten to actually reply to the UDS responses sent by the BMS
//While this may work, it is not the correct way to implement this query logic
switch (stateMachineBMSQuery) {
case 0:
//Initial request
#ifdef DEBUG_LOG
logging.println("CAN UDS: Sending BMS query initial handshake");
#endif //DEBUG_LOG
TESLA_602.data = {0x02, 0x10, 0x03, 0x00, 0x00, 0x00, 0x00, 0x00};
transmit_can_frame(&TESLA_602);
break;
case 1:
//Send query
#ifdef DEBUG_LOG
logging.println("CAN UDS: Sending BMS query for pack part number");
#endif //DEBUG_LOG
TESLA_602.data = {0x03, 0x22, 0xF0, 0x14, 0x00, 0x00, 0x00, 0x00};
transmit_can_frame(&TESLA_602);
break;
case 2:
//Flow control
#ifdef DEBUG_LOG
logging.println("CAN UDS: Sending BMS query flow control");
#endif //DEBUG_LOG
TESLA_602.data = {0x30, 0x00, 0x0A, 0x00, 0x00, 0x00, 0x00, 0x00};
transmit_can_frame(&TESLA_602);
break;
@ -2571,12 +2599,12 @@ void TeslaModel3YBattery::setup(void) { // Performs one time setup at startup
//0x7FF GTW CAN frame values
//Mux1
write_signal_value(&TESLA_7FF_Mux1, 16, 16, GTW_country, false);
write_signal_value(&TESLA_7FF_Mux1, 11, 1, GTW_rightHandDrive, false);
write_signal_value(&TESLA_7FF_Mux1, 16, 16, user_selected_tesla_GTW_country, false);
write_signal_value(&TESLA_7FF_Mux1, 11, 1, user_selected_tesla_GTW_country, false);
//Mux3
write_signal_value(&TESLA_7FF_Mux3, 8, 4, GTW_mapRegion, false);
write_signal_value(&TESLA_7FF_Mux3, 18, 3, GTW_chassisType, false);
write_signal_value(&TESLA_7FF_Mux3, 32, 5, GTW_packEnergy, false);
write_signal_value(&TESLA_7FF_Mux3, 8, 4, user_selected_tesla_GTW_mapRegion, false);
write_signal_value(&TESLA_7FF_Mux3, 18, 3, user_selected_tesla_GTW_chassisType, false);
write_signal_value(&TESLA_7FF_Mux3, 32, 5, user_selected_tesla_GTW_packEnergy, false);
strncpy(datalayer.system.info.battery_protocol, Name, 63);
datalayer.system.info.battery_protocol[63] = '\0';

View file

@ -11,12 +11,14 @@
#define SELECTED_BATTERY_CLASS TeslaModelSXBattery
#endif
/*NOTE! IMPORTANT INFORMATION!
Be sure to scroll down in this file and configure all "GTW_" parameters to suit your battery.
Failure to configure these will result in VCFRONT and GTW MIA errors
*/
//#define EXP_TESLA_BMS_DIGITAL_HVIL // Experimental parameter. Forces the transmission of additional CAN frames for experimental purposes, to test potential HVIL issues in 3/Y packs with newer firmware.
// 0x7FF gateway config, "Gen3" vehicles only, not applicable to Gen2 "classic" Model S and Model X
// These are user configurable from the Webserver UI
extern bool user_selected_tesla_digital_HVIL;
extern uint16_t user_selected_tesla_GTW_country;
extern bool user_selected_tesla_GTW_rightHandDrive;
extern uint16_t user_selected_tesla_GTW_mapRegion;
extern uint16_t user_selected_tesla_GTW_chassisType;
extern uint16_t user_selected_tesla_GTW_packEnergy;
class TeslaBattery : public CanBattery {
public:
@ -33,6 +35,9 @@ class TeslaBattery : public CanBattery {
bool supports_reset_BMS() { return true; }
void reset_BMS() { datalayer.battery.settings.user_requests_tesla_bms_reset = true; }
bool supports_reset_SOC() { return true; }
void reset_SOC() { datalayer.battery.settings.user_requests_tesla_soc_reset = true; }
bool supports_charged_energy() { return true; }
BatteryHtmlRenderer& get_status_renderer() { return renderer; }
@ -50,21 +55,6 @@ class TeslaBattery : public CanBattery {
// Set this to true to try to close contactors/full startup even with no inverter defined/connected
bool batteryTestOverride = false;
// 0x7FF gateway config, "Gen3" vehicles only, not applicable to Gen2 "classic" Model S and Model X
//
// ** MANUALLY SET FOR NOW **, TODO: change based on USER_SETTINGS.h or preset
//
static const uint16_t GTW_country =
18242; // "US" (USA): 21843, "CA" (Canada): 17217, "GB" (UK & N Ireland): 18242, "DK" (Denmark): 17483, "DE" (Germany): 17477, "AU" (Australia): 16725 [HVP shows errors if EU/US region mismatch for example]
// GTW_country is ISO 3166-1 Alpha-2 code, each letter converted to binary (8-bit chunks), those 8-bit chunks concatenated and then converted to decimal
static const uint8_t GTW_rightHandDrive =
1; // Left: 0, Right: 1 (not sure this matters but there for consistency in emulating the car - make sure correct for GTW_country, e.g. 0 for USA)
static const uint8_t GTW_mapRegion =
1; // "ME": 8, "NONE": 2, "CN": 3, "TW": 6, "JP": 5, "US": 0, "KR": 7, "AU": 4, "EU": 1 (not sure this matters but there for consistency)
static const uint8_t GTW_chassisType =
2; // "MODEL_3_CHASSIS": 2, "MODEL_Y_CHASSIS": 3 ("MODEL_S_CHASSIS": 0, "MODEL_X_CHASSIS": 1)
static const uint8_t GTW_packEnergy = 1; // "PACK_50_KWH": 0, "PACK_74_KWH": 1, "PACK_62_KWH": 2, "PACK_100_KWH": 3
/* Do not change anything below this line! */
static const int RAMPDOWN_SOC = 900; // 90.0 SOC% to start ramping down from max charge power towards 0 at 100.00%
static const int RAMPDOWNPOWERALLOWED = 10000; // What power we ramp down from towards top balancing
@ -486,6 +476,7 @@ class TeslaBattery : public CanBattery {
uint8_t stateMachineClearIsolationFault = 0xFF;
uint8_t stateMachineBMSReset = 0xFF;
uint8_t stateMachineSOCReset = 0xFF;
uint8_t stateMachineBMSQuery = 0xFF;
uint16_t sendContactorClosingMessagesStill = 300;
uint16_t battery_cell_max_v = 3300;
@ -922,19 +913,14 @@ class TeslaBattery : public CanBattery {
class TeslaModel3YBattery : public TeslaBattery {
public:
TeslaModel3YBattery(battery_chemistry_enum chemistry) {
datalayer.battery.info.chemistry = chemistry;
#ifdef EXP_TESLA_BMS_DIGITAL_HVIL
operate_contactors = true;
#endif
}
TeslaModel3YBattery(battery_chemistry_enum chemistry) { datalayer.battery.info.chemistry = chemistry; }
static constexpr const char* Name = "Tesla Model 3/Y";
virtual void setup(void);
};
class TeslaModelSXBattery : public TeslaBattery {
public:
TeslaModelSXBattery() { operate_contactors = true; }
TeslaModelSXBattery() {}
static constexpr const char* Name = "Tesla Model S/X";
virtual void setup(void);
};

View file

@ -42,21 +42,6 @@ void TestFakeBattery::
//Fake that we get CAN messages
datalayer_battery->status.CAN_battery_still_alive = CAN_STILL_ALIVE;
/*Finally print out values to serial if configured to do so*/
#ifdef DEBUG_LOG
logging.println("FAKE Values going to inverter");
print_units("SOH%: ", (datalayer_battery->status.soh_pptt * 0.01), "% ");
print_units(", SOC%: ", (datalayer_battery->status.reported_soc * 0.01), "% ");
print_units(", Voltage: ", (datalayer_battery->status.voltage_dV * 0.1), "V ");
print_units(", Max discharge power: ", datalayer_battery->status.max_discharge_power_W, "W ");
print_units(", Max charge power: ", datalayer_battery->status.max_charge_power_W, "W ");
print_units(", Max temp: ", (datalayer_battery->status.temperature_max_dC * 0.1), "°C ");
print_units(", Min temp: ", (datalayer_battery->status.temperature_min_dC * 0.1), "°C ");
print_units(", Max cell voltage: ", datalayer_battery->status.cell_max_voltage_mV, "mV ");
print_units(", Min cell voltage: ", datalayer_battery->status.cell_min_voltage_mV, "mV ");
logging.println("");
#endif
}
void TestFakeBattery::handle_incoming_can_frame(CAN_frame rx_frame) {

View file

@ -7,7 +7,6 @@
void VolvoSpaBattery::
update_values() { //This function maps all the values fetched via CAN to the correct parameters used for the inverter
uint8_t cnt = 0;
// Update webserver datalayer
datalayer_extended.VolvoPolestar.soc_bms = SOC_BMS;
@ -86,49 +85,6 @@ void VolvoSpaBattery::
datalayer.battery.info.total_capacity_Wh = 69511;
}
}
#ifdef DEBUG_LOG
logging.print("BMS reported SOC%: ");
logging.println(SOC_BMS);
logging.print("Calculated SOC%: ");
logging.println(SOC_CALC);
logging.print("Rescaled SOC%: ");
logging.println(datalayer.battery.status.reported_soc / 100);
logging.print("Battery current: ");
logging.println(BATT_I);
logging.print("Battery voltage: ");
logging.println(BATT_U);
logging.print("Battery maximum voltage limit: ");
logging.println(MAX_U);
logging.print("Battery minimum voltage limit: ");
logging.println(MIN_U);
logging.print("Discharge limit: ");
logging.println(HvBattPwrLimDchaSoft);
logging.print("Battery Error Indication: ");
logging.println(BATT_ERR_INDICATION);
logging.print("Maximum battery temperature: ");
logging.println(BATT_T_MAX / 10);
logging.print("Minimum battery temperature: ");
logging.println(BATT_T_MIN / 10);
logging.print("Average battery temperature: ");
logging.println(BATT_T_AVG / 10);
logging.print("BMS Highest cell voltage: ");
logging.println(CELL_U_MAX * 10);
logging.print("BMS Lowest cell voltage: ");
logging.println(CELL_U_MIN * 10);
logging.print("BMS Highest cell nr: ");
logging.println(CELL_ID_U_MAX);
logging.print("Highest cell voltage: ");
logging.println(min_max_voltage[1]);
logging.print("Lowest cell voltage: ");
logging.println(min_max_voltage[0]);
logging.print("Cell voltage,");
while (cnt < 108) {
logging.print(cell_voltages[cnt++]);
logging.print(",");
}
logging.println(";");
#endif
}
void VolvoSpaBattery::handle_incoming_can_frame(CAN_frame rx_frame) {
@ -139,9 +95,7 @@ void VolvoSpaBattery::handle_incoming_can_frame(CAN_frame rx_frame) {
BATT_I = (0 - ((((rx_frame.data.u8[6] & 0x7F) * 256.0 + rx_frame.data.u8[7]) * 0.1) - 1638));
else {
BATT_I = 0;
#ifdef DEBUG_LOG
logging.println("BATT_I not valid");
#endif
}
if ((rx_frame.data.u8[2] & 0x08) == 0x08)
@ -194,9 +148,7 @@ void VolvoSpaBattery::handle_incoming_can_frame(CAN_frame rx_frame) {
BATT_ERR_INDICATION = ((rx_frame.data.u8[0] & 0x40) >> 6);
else {
BATT_ERR_INDICATION = 0;
#ifdef DEBUG_LOG
logging.println("BATT_ERR_INDICATION not valid");
#endif
}
if ((rx_frame.data.u8[0] & 0x20) == 0x20) {
BATT_T_MAX = ((rx_frame.data.u8[2] & 0x1F) * 256.0 + rx_frame.data.u8[3]);
@ -206,9 +158,7 @@ void VolvoSpaBattery::handle_incoming_can_frame(CAN_frame rx_frame) {
BATT_T_MAX = 0;
BATT_T_MIN = 0;
BATT_T_AVG = 0;
#ifdef DEBUG_LOG
logging.println("BATT_T not valid");
#endif
}
break;
case 0x369:
@ -216,9 +166,7 @@ void VolvoSpaBattery::handle_incoming_can_frame(CAN_frame rx_frame) {
HvBattPwrLimDchaSoft = (((rx_frame.data.u8[6] & 0x03) * 256 + rx_frame.data.u8[6]) >> 2);
} else {
HvBattPwrLimDchaSoft = 0;
#ifdef DEBUG_LOG
logging.println("HvBattPwrLimDchaSoft not valid");
#endif
}
break;
case 0x175:
@ -245,9 +193,7 @@ void VolvoSpaBattery::handle_incoming_can_frame(CAN_frame rx_frame) {
SOC_BMS = ((rx_frame.data.u8[6] & 0x03) * 256 + rx_frame.data.u8[7]);
} else {
SOC_BMS = 0;
#ifdef DEBUG_LOG
logging.println("SOC_BMS not valid");
#endif
}
if ((rx_frame.data.u8[0] & 0x04) == 0x04) {
@ -272,18 +218,33 @@ void VolvoSpaBattery::handle_incoming_can_frame(CAN_frame rx_frame) {
(rx_frame.data.u8[3] == 0x42)) // BECM module voltage supply
{
datalayer_extended.VolvoPolestar.BECMsupplyVoltage = ((rx_frame.data.u8[4] << 8) | rx_frame.data.u8[5]);
transmit_can_frame(&VOLVO_BECM_HVIL_Status_Req); //Send HVIL status readout command
} else if ((rx_frame.data.u8[0] == 0x04) && (rx_frame.data.u8[1] == 0x62) && (rx_frame.data.u8[2] == 0x49) &&
(rx_frame.data.u8[3] == 0x1A)) // BECM HVIL status
{
datalayer_extended.VolvoPolestar.HVILstatusBits = (rx_frame.data.u8[4]);
transmit_can_frame(&VOLVO_DTCreadout); //Send DTC readout command
} else if ((rx_frame.data.u8[0] == 0x10) && (rx_frame.data.u8[1] == 0x0B) && (rx_frame.data.u8[2] == 0x62) &&
(rx_frame.data.u8[3] == 0x4B)) // First response frame of cell voltages
{
cell_voltages[battery_request_idx++] = ((rx_frame.data.u8[5] << 8) | rx_frame.data.u8[6]);
cell_voltages[battery_request_idx] = (rx_frame.data.u8[7] << 8);
transmit_can_frame(&VOLVO_FlowControl); // Send flow control
rxConsecutiveFrames = 1;
rxConsecutiveFrames = true;
} else if ((rx_frame.data.u8[0] == 0x10) && (rx_frame.data.u8[2] == 0x59) &&
(rx_frame.data.u8[3] == 0x03)) // First response frame for DTC with more than one code
{
datalayer_extended.VolvoPolestar.DTCcount = ((rx_frame.data.u8[1] - 2) / 4);
transmit_can_frame(&VOLVO_FlowControl); // Send flow control
} else if ((rx_frame.data.u8[0] == 0x21) && (rxConsecutiveFrames == 1)) {
} else if ((rx_frame.data.u8[1] == 0x59) &&
(rx_frame.data.u8[2] == 0x03)) // Response frame for DTC with 0 or 1 code
{
if (rx_frame.data.u8[0] != 0x02) {
datalayer_extended.VolvoPolestar.DTCcount = 1;
} else {
datalayer_extended.VolvoPolestar.DTCcount = 0;
}
} else if ((rx_frame.data.u8[0] == 0x21) && (rxConsecutiveFrames)) {
cell_voltages[battery_request_idx++] = cell_voltages[battery_request_idx] | rx_frame.data.u8[1];
cell_voltages[battery_request_idx++] = (rx_frame.data.u8[2] << 8) | rx_frame.data.u8[3];
cell_voltages[battery_request_idx++] = (rx_frame.data.u8[4] << 8) | rx_frame.data.u8[5];
@ -303,7 +264,7 @@ void VolvoSpaBattery::handle_incoming_can_frame(CAN_frame rx_frame) {
}
transmit_can_frame(&VOLVO_SOH_Req); //Send SOH read request
}
rxConsecutiveFrames = 0;
rxConsecutiveFrames = false;
}
break;
default:
@ -314,7 +275,7 @@ void VolvoSpaBattery::handle_incoming_can_frame(CAN_frame rx_frame) {
void VolvoSpaBattery::readCellVoltages() {
battery_request_idx = 0;
batteryModuleNumber = 0x10;
rxConsecutiveFrames = 0;
rxConsecutiveFrames = false;
VOLVO_CELL_U_Req.data.u8[3] = batteryModuleNumber++;
transmit_can_frame(&VOLVO_CELL_U_Req); //Send cell voltage read request for first module
}

View file

@ -64,7 +64,7 @@ class VolvoSpaBattery : public CanBattery {
uint16_t HvBattPwrLimChrgSlowAgi = 0; //0x177
uint8_t batteryModuleNumber = 0x10; // First battery module
uint8_t battery_request_idx = 0;
uint8_t rxConsecutiveFrames = 0;
bool rxConsecutiveFrames = false;
uint16_t min_max_voltage[2]; //contains cell min[0] and max[1] values in mV
uint8_t cellcounter = 0;
uint16_t cell_voltages[108]; //array with all the cellvoltages
@ -75,21 +75,17 @@ class VolvoSpaBattery : public CanBattery {
.ext_ID = false,
.DLC = 8,
.ID = 0x536,
//.data = {0x00, 0x40, 0xFF, 0x00, 0x00, 0x00, 0x00, 0x00}}; //Network manage frame
.data = {0x00, 0x40, 0x40, 0x01, 0x00, 0x00, 0x00, 0x00}}; //Network manage frame
CAN_frame VOLVO_140_CLOSE = {.FD = false,
.ext_ID = false,
.DLC = 8,
.ID = 0x140,
.data = {0x00, 0x02, 0x00, 0xB7, 0xFF, 0x03, 0xFF, 0x82}}; //Close contactors message
CAN_frame VOLVO_140_OPEN = {.FD = false,
.ext_ID = false,
.DLC = 8,
.ID = 0x140,
.data = {0x00, 0x02, 0x00, 0x9E, 0xFF, 0x03, 0xFF, 0x82}}; //Open contactor message
CAN_frame VOLVO_372 = {
.FD = false,
.ext_ID = false,
@ -117,6 +113,12 @@ class VolvoSpaBattery : public CanBattery {
.DLC = 8,
.ID = 0x735,
.data = {0x03, 0x22, 0xF4, 0x42, 0x00, 0x00, 0x00, 0x00}}; //BECM supply voltage request frame
CAN_frame VOLVO_BECM_HVIL_Status_Req = {
.FD = false,
.ext_ID = false,
.DLC = 8,
.ID = 0x735,
.data = {0x03, 0x22, 0x49, 0x1A, 0x00, 0x00, 0x00, 0x00}}; //BECM HVIL status request frame
CAN_frame VOLVO_DTC_Erase = {.FD = false,
.ext_ID = false,
.DLC = 8,

View file

@ -9,11 +9,11 @@ class VolvoSpaHtmlRenderer : public BatteryHtmlRenderer {
public:
String get_status_html() {
String content;
content += "<h4>BECM reported SOC: " + String(datalayer_extended.VolvoPolestar.soc_bms) + "</h4>";
content += "<h4>Calculated SOC: " + String(datalayer_extended.VolvoPolestar.soc_calc) + "</h4>";
content += "<h4>Rescaled SOC: " + String(datalayer_extended.VolvoPolestar.soc_rescaled / 10) + "</h4>";
content += "<h4>BECM reported SOH: " + String(datalayer_extended.VolvoPolestar.soh_bms) + "</h4>";
content += "</h4><h4>BECM reported number of DTCs: " + String(datalayer_extended.VolvoPolestar.DTCcount) + "</h4>";
content += "<h4>BECM reported SOC: " + String(datalayer_extended.VolvoPolestar.soc_bms / 10.0) + " %</h4>";
content += "<h4>Calculated SOC: " + String(datalayer_extended.VolvoPolestar.soc_calc / 10.0) + " %</h4>";
content += "<h4>Rescaled SOC: " + String(datalayer_extended.VolvoPolestar.soc_rescaled / 10.0) + " %</h4>";
content += "<h4>BECM reported SOH: " + String(datalayer_extended.VolvoPolestar.soh_bms / 100.0) + " %</h4>";
content += "<h4>BECM supply voltage: " + String(datalayer_extended.VolvoPolestar.BECMsupplyVoltage) + " mV</h4>";
content += "<h4>HV voltage: " + String(datalayer_extended.VolvoPolestar.BECMBatteryVoltage) + " V</h4>";
@ -31,7 +31,54 @@ class VolvoSpaHtmlRenderer : public BatteryHtmlRenderer {
content +=
"<h4>Charge power limit slow aging: " + String(datalayer_extended.VolvoPolestar.HvBattPwrLimChrgSlowAgi) +
" kW</h4>";
content += "<h4>HVIL Circuit A status: ";
switch (datalayer_extended.VolvoPolestar.HVILstatusBits & 0x01) {
case 0x01:
content += String("Open");
break;
default:
content += String("Not valid");
}
content += "<h4>HVIL Circuit B status: ";
switch (datalayer_extended.VolvoPolestar.HVILstatusBits & 0x02) {
case 0x02:
content += String("Open");
break;
default:
content += String("Closed");
}
content += "<h4>HVIL Circuit C status: ";
switch (datalayer_extended.VolvoPolestar.HVILstatusBits & 0x04) {
case 0x04:
content += String("Open");
break;
default:
content += String("Closed");
}
content += "<h4>Precharge contactor status: ";
switch (datalayer_extended.VolvoPolestar.HVILstatusBits & 0x08) {
case 0x08:
content += String("Open");
break;
default:
content += String("Closed");
}
content += "<h4>Positive Contactor status: ";
switch (datalayer_extended.VolvoPolestar.HVILstatusBits & 0x10) {
case 0x10:
content += String("Open");
break;
default:
content += String("Closed");
}
content += "<h4>Negative Contactor status: ";
switch (datalayer_extended.VolvoPolestar.HVILstatusBits & 0x20) {
case 0x20:
content += String("Open");
break;
default:
content += String("Closed");
}
content += "<h4>HV system relay status: ";
switch (datalayer_extended.VolvoPolestar.HVSysRlySts) {
case 0:

View file

@ -70,51 +70,6 @@ void VolvoSpaHybridBattery::
for (int i = 0; i < 102; ++i) {
datalayer.battery.status.cell_voltages_mV[i] = cell_voltages[i];
}
#ifdef DEBUG_LOG
logging.print("BMS reported SOC%: ");
logging.println(SOC_BMS);
logging.print("Calculated SOC%: ");
logging.println(SOC_CALC);
logging.print("Rescaled SOC%: ");
logging.println(datalayer.battery.status.reported_soc / 100);
logging.print("Battery current: ");
logging.println(BATT_I);
logging.print("Battery voltage: ");
logging.println(BATT_U);
logging.print("Battery maximum voltage limit: ");
logging.println(MAX_U);
logging.print("Battery minimum voltage limit: ");
logging.println(MIN_U);
logging.print("Remaining Energy: ");
logging.println(remaining_capacity);
logging.print("Discharge limit: ");
logging.println(HvBattPwrLimDchaSoft);
logging.print("Battery Error Indication: ");
logging.println(BATT_ERR_INDICATION);
logging.print("Maximum battery temperature: ");
logging.println(BATT_T_MAX / 10);
logging.print("Minimum battery temperature: ");
logging.println(BATT_T_MIN / 10);
logging.print("Average battery temperature: ");
logging.println(BATT_T_AVG / 10);
logging.print("BMS Highest cell voltage: ");
logging.println(CELL_U_MAX);
logging.print("BMS Lowest cell voltage: ");
logging.println(CELL_U_MIN);
logging.print("BMS Highest cell nr: ");
logging.println(CELL_ID_U_MAX);
logging.print("Highest cell voltage: ");
logging.println(min_max_voltage[1]);
logging.print("Lowest cell voltage: ");
logging.println(min_max_voltage[0]);
logging.print("Cell voltage,");
while (cnt < 102) {
logging.print(cell_voltages[cnt++]);
logging.print(",");
}
logging.println(";");
#endif
}
void VolvoSpaHybridBattery::handle_incoming_can_frame(CAN_frame rx_frame) {
@ -125,9 +80,7 @@ void VolvoSpaHybridBattery::handle_incoming_can_frame(CAN_frame rx_frame) {
BATT_I = (0 - ((((rx_frame.data.u8[6] & 0x7F) * 256.0 + rx_frame.data.u8[7]) * 0.1) - 1638));
else {
BATT_I = 0;
#ifdef DEBUG_LOG
logging.println("BATT_I not valid");
#endif
}
if ((rx_frame.data.u8[2] & 0x08) == 0x08)
@ -148,9 +101,7 @@ void VolvoSpaHybridBattery::handle_incoming_can_frame(CAN_frame rx_frame) {
BATT_U = (((rx_frame.data.u8[0] & 0x07) * 256.0 + rx_frame.data.u8[1]) * 0.25);
else {
BATT_U = 0;
#ifdef DEBUG_LOG
logging.println("BATT_U not valid");
#endif
}
if ((rx_frame.data.u8[0] & 0x40) == 0x40)
@ -185,9 +136,7 @@ void VolvoSpaHybridBattery::handle_incoming_can_frame(CAN_frame rx_frame) {
BATT_ERR_INDICATION = ((rx_frame.data.u8[0] & 0x40) >> 6);
else {
BATT_ERR_INDICATION = 0;
#ifdef DEBUG_LOG
logging.println("BATT_ERR_INDICATION not valid");
#endif
}
if ((rx_frame.data.u8[0] & 0x20) == 0x20) {
BATT_T_MAX = ((rx_frame.data.u8[2] & 0x1F) * 256.0 + rx_frame.data.u8[3]);
@ -197,9 +146,7 @@ void VolvoSpaHybridBattery::handle_incoming_can_frame(CAN_frame rx_frame) {
BATT_T_MAX = 0;
BATT_T_MIN = 0;
BATT_T_AVG = 0;
#ifdef DEBUG_LOG
logging.println("BATT_T not valid");
#endif
}
break;
case 0x369:
@ -207,9 +154,7 @@ void VolvoSpaHybridBattery::handle_incoming_can_frame(CAN_frame rx_frame) {
HvBattPwrLimDchaSoft = (((rx_frame.data.u8[6] & 0x03) * 256 + rx_frame.data.u8[6]) >> 2);
} else {
HvBattPwrLimDchaSoft = 0;
#ifdef DEBUG_LOG
logging.println("HvBattPwrLimDchaSoft not valid");
#endif
}
break;
case 0x175:
@ -240,9 +185,7 @@ void VolvoSpaHybridBattery::handle_incoming_can_frame(CAN_frame rx_frame) {
SOC_BMS = ((rx_frame.data.u8[6] & 0x03) * 256 + rx_frame.data.u8[7]);
} else {
SOC_BMS = 0;
#ifdef DEBUG_LOG
logging.println("SOC_BMS not valid");
#endif
}
if ((rx_frame.data.u8[0] & 0x04) == 0x04)
@ -251,9 +194,7 @@ void VolvoSpaHybridBattery::handle_incoming_can_frame(CAN_frame rx_frame) {
else {
//CELL_U_MAX = 0;
;
#ifdef DEBUG_LOG
logging.println("CELL_U_MAX not valid");
#endif
}
if ((rx_frame.data.u8[0] & 0x02) == 0x02)
@ -262,9 +203,7 @@ void VolvoSpaHybridBattery::handle_incoming_can_frame(CAN_frame rx_frame) {
else {
//CELL_U_MIN = 0;
;
#ifdef DEBUG_LOG
logging.println("CELL_U_MIN not valid");
#endif
}
if ((rx_frame.data.u8[0] & 0x08) == 0x08)
@ -273,9 +212,7 @@ void VolvoSpaHybridBattery::handle_incoming_can_frame(CAN_frame rx_frame) {
else {
//CELL_ID_U_MAX = 0;
;
#ifdef DEBUG_LOG
logging.println("CELL_ID_U_MAX not valid");
#endif
}
break;
case 0x635: // Diag request response
@ -545,9 +482,7 @@ void VolvoSpaHybridBattery::transmit_can(unsigned long currentMillis) {
previousMillis60s = currentMillis;
if (true) {
readCellVoltages();
#ifdef DEBUG_LOG
logging.println("Requesting cell voltages");
#endif
}
}
}

View file

@ -71,9 +71,6 @@ void ChevyVoltCharger::map_can_frame_to_variable(CAN_frame rx_frame) {
datalayer.charger.CAN_charger_still_alive = CAN_STILL_ALIVE; // Let system know charger is sending CAN
break;
default:
#ifdef DEBUG_LOG
logging.printf("CAN Rcv unknown frame MsgID=%x\n", rx_frame.ID);
#endif
break;
}
}
@ -146,7 +143,6 @@ void ChevyVoltCharger::transmit_can(unsigned long currentMillis) {
transmit_can_frame(&charger_set_targets);
}
#ifdef DEBUG_LOG
/* Serial echo every 5s of charger stats */
if (currentMillis - previousMillis5000ms >= INTERVAL_5_S) {
previousMillis5000ms = currentMillis;
@ -156,5 +152,4 @@ void ChevyVoltCharger::transmit_can(unsigned long currentMillis) {
logging.printf("Charger mode=%s\n", (charger_mode > MODE_DISABLED) ? "Enabled" : "Disabled");
logging.printf("Charger HVset=%uV,%uA finishCurrent=%uA\n", setpoint_HV_VDC, setpoint_HV_IDC, setpoint_HV_IDC_END);
}
#endif
}

View file

@ -99,9 +99,7 @@ bool init_CAN() {
return false;
}
#ifdef DEBUG_LOG
logging.println("Dual CAN Bus (ESP32+MCP2515) selected");
#endif // DEBUG_LOG
gBuffer.initWithSize(25);
can2515 = new ACAN2515(cs_pin, SPI2515, int_pin);
@ -115,14 +113,10 @@ bool init_CAN() {
settings2515->mRequestedMode = ACAN2515Settings::NormalMode;
const uint16_t errorCode2515 = can2515->begin(*settings2515, [] { can2515->isr(); });
if (errorCode2515 == 0) {
#ifdef DEBUG_LOG
logging.println("Can ok");
#endif // DEBUG_LOG
} else {
#ifdef DEBUG_LOG
logging.print("Error Can: 0x");
logging.println(errorCode2515, HEX);
#endif // DEBUG_LOG
set_event(EVENT_CANMCP2515_INIT_FAILURE, (uint8_t)errorCode2515);
return false;
}
@ -147,9 +141,7 @@ bool init_CAN() {
canfd = new ACAN2517FD(cs_pin, SPI2517, int_pin);
#ifdef DEBUG_LOG
logging.println("CAN FD add-on (ESP32+MCP2517) selected");
#endif // DEBUG_LOG
SPI2517.begin(sck_pin, sdo_pin, sdi_pin);
auto bitRate = (int)speed * 1000UL;
settings2517 = new ACAN2517FDSettings(
@ -162,7 +154,6 @@ bool init_CAN() {
const uint32_t errorCode2517 = canfd->begin(*settings2517, [] { canfd->isr(); });
canfd->poll();
if (errorCode2517 == 0) {
#ifdef DEBUG_LOG
logging.print("Bit Rate prescaler: ");
logging.println(settings2517->mBitRatePrescaler);
logging.print("Arbitration Phase segment 1: ");
@ -179,12 +170,9 @@ bool init_CAN() {
logging.print("Arbitration Sample point: ");
logging.print(settings2517->arbitrationSamplePointFromBitStart());
logging.println("%");
#endif // DEBUG_LOG
} else {
#ifdef DEBUG_LOG
logging.print("CAN-FD Configuration error 0x");
logging.println(errorCode2517, HEX);
#endif // DEBUG_LOG
set_event(EVENT_CANMCP2517FD_INIT_FAILURE, (uint8_t)errorCode2517);
return false;
}
@ -332,23 +320,24 @@ void receive_frame_canfd_addon() { // This section checks if we have a complete
// Support functions
void print_can_frame(CAN_frame frame, frameDirection msgDir) {
#ifdef DEBUG_CAN_DATA // If enabled in user settings, print out the CAN messages via USB
uint8_t i = 0;
Serial.print("(");
Serial.print(millis() / 1000.0);
(msgDir == MSG_RX) ? Serial.print(") RX0 ") : Serial.print(") TX1 ");
Serial.print(frame.ID, HEX);
Serial.print(" [");
Serial.print(frame.DLC);
Serial.print("] ");
for (i = 0; i < frame.DLC; i++) {
Serial.print(frame.data.u8[i] < 16 ? "0" : "");
Serial.print(frame.data.u8[i], HEX);
if (i < frame.DLC - 1)
Serial.print(" ");
if (datalayer.system.info.CAN_usb_logging_active) {
uint8_t i = 0;
Serial.print("(");
Serial.print(millis() / 1000.0);
(msgDir == MSG_RX) ? Serial.print(") RX0 ") : Serial.print(") TX1 ");
Serial.print(frame.ID, HEX);
Serial.print(" [");
Serial.print(frame.DLC);
Serial.print("] ");
for (i = 0; i < frame.DLC; i++) {
Serial.print(frame.data.u8[i] < 16 ? "0" : "");
Serial.print(frame.data.u8[i], HEX);
if (i < frame.DLC - 1)
Serial.print(" ");
}
Serial.println("");
}
Serial.println("");
#endif // DEBUG_CAN_DATA
if (datalayer.system.info.can_logging_active) { // If user clicked on CAN Logging page in webserver, start recording
dump_can_frame(frame, msgDir);

View file

@ -24,7 +24,6 @@ void show_dtc(uint8_t byte0, uint8_t byte1) {
}
void handle_obd_frame(CAN_frame& rx_frame) {
#ifdef DEBUG_LOG
if (rx_frame.data.u8[1] == 0x7F) {
const char* error_str = "?";
switch (rx_frame.data.u8[3]) { // See https://automotive.wiki/index.php/ISO_14229
@ -107,7 +106,6 @@ void handle_obd_frame(CAN_frame& rx_frame) {
}
}
dump_can_frame(rx_frame, MSG_RX);
#endif
}
void transmit_obd_can_frame(unsigned int address, int interface, bool canFD) {

View file

@ -55,7 +55,7 @@ const int OFF = 0;
#define OFF 1
#endif //NC_CONTACTORS
#define MAX_ALLOWED_FAULT_TICKS 1000
#define MAX_ALLOWED_FAULT_TICKS 1000 //1000 = 10 seconds
#define NEGATIVE_CONTACTOR_TIME_MS \
500 // Time after negative contactor is turned on, to start precharge (not actual precharge time!)
#define PRECHARGE_COMPLETED_TIME_MS \
@ -147,12 +147,10 @@ bool init_contactors() {
}
static void dbg_contactors(const char* state) {
#ifdef DEBUG_LOG
logging.print("[");
logging.print(millis());
logging.print(" ms] contactors control: ");
logging.println(state);
#endif
}
// Main functions of the handle_contactors include checking if inverter allows for closing, checking battery 2, checking BMS power output, and actual contactor closing/precharge via GPIO
@ -192,7 +190,7 @@ void handle_contactors() {
set(negPin, OFF, PWM_OFF_DUTY);
set(posPin, OFF, PWM_OFF_DUTY);
set_event(EVENT_ERROR_OPEN_CONTACTOR, 0);
datalayer.system.status.contactors_engaged = false;
datalayer.system.status.contactors_engaged = 2;
return; // A fault scenario latches the contactor control. It is not possible to recover without a powercycle (and investigation why fault occured)
}
@ -201,10 +199,9 @@ void handle_contactors() {
set(prechargePin, OFF);
set(negPin, OFF, PWM_OFF_DUTY);
set(posPin, OFF, PWM_OFF_DUTY);
datalayer.system.status.contactors_engaged = false;
datalayer.system.status.contactors_engaged = 0;
if (datalayer.system.status.battery_allows_contactor_closing &&
datalayer.system.status.inverter_allows_contactor_closing &&
if (datalayer.system.status.inverter_allows_contactor_closing &&
!datalayer.system.settings.equipment_stop_active) {
contactorStatus = START_PRECHARGE;
}
@ -263,7 +260,7 @@ void handle_contactors() {
set(posPin, ON, PWM_HOLD_DUTY);
dbg_contactors("PRECHARGE_OFF");
contactorStatus = COMPLETED;
datalayer.system.status.contactors_engaged = true;
datalayer.system.status.contactors_engaged = 1;
}
break;
default:

View file

@ -96,6 +96,19 @@ void init_stored_settings() {
user_selected_min_pack_voltage_dV = settings.getUInt("BATTPVMIN", 0);
user_selected_max_cell_voltage_mV = settings.getUInt("BATTCVMAX", 0);
user_selected_min_cell_voltage_mV = settings.getUInt("BATTCVMIN", 0);
user_selected_inverter_cells = settings.getUInt("INVCELLS", 0);
user_selected_inverter_modules = settings.getUInt("INVMODULES", 0);
user_selected_inverter_cells_per_module = settings.getUInt("INVCELLSPER", 0);
user_selected_inverter_voltage_level = settings.getUInt("INVVLEVEL", 0);
user_selected_inverter_ah_capacity = settings.getUInt("INVAHCAPACITY", 0);
user_selected_inverter_battery_type = settings.getUInt("INVBTYPE", 0);
user_selected_inverter_ignore_contactors = settings.getBool("INVICNT", false);
user_selected_tesla_digital_HVIL = settings.getBool("DIGITALHVIL", false);
user_selected_tesla_GTW_country = settings.getUInt("GTWCOUNTRY", 0);
user_selected_tesla_GTW_rightHandDrive = settings.getBool("GTWRHD", false);
user_selected_tesla_GTW_mapRegion = settings.getUInt("GTWMAPREG", 0);
user_selected_tesla_GTW_chassisType = settings.getUInt("GTWCHASSIS", 0);
user_selected_tesla_GTW_packEnergy = settings.getUInt("GTWPACK", 0);
auto readIf = [](const char* settingName) {
auto batt1If = (comm_interface)settings.getUInt(settingName, (int)comm_interface::CanNative);
@ -128,6 +141,13 @@ void init_stored_settings() {
remote_bms_reset = settings.getBool("REMBMSRESET", false);
use_canfd_as_can = settings.getBool("CANFDASCAN", false);
datalayer.system.info.CAN_usb_logging_active = settings.getBool("CANLOGUSB", false);
datalayer.system.info.usb_logging_active = settings.getBool("USBENABLED", false);
datalayer.system.info.web_logging_active = settings.getBool("WEBENABLED", false);
datalayer.system.info.CAN_SD_logging_active = settings.getBool("CANLOGSD", false);
datalayer.system.info.SD_logging_active = settings.getBool("SDLOGENABLED", false);
datalayer.battery.status.led_mode = (led_mode_enum)settings.getUInt("LEDMODE", false);
// WIFI AP is enabled by default unless disabled in the settings
wifiap_enabled = settings.getBool("WIFIAPENABLED", true);
passwordAP = settings.getString("APPASSWORD", "123456789").c_str();
@ -193,10 +213,7 @@ void store_settings() {
if (!settings.putUInt("TARGETDISCHVOLT", datalayer.battery.settings.max_user_set_discharge_voltage_dV)) {
set_event(EVENT_PERSISTENT_SAVE_INFO, 11);
}
if (!settings.putUInt("SOFAR_ID", datalayer.battery.settings.sofar_user_specified_battery_id)) {
set_event(EVENT_PERSISTENT_SAVE_INFO, 12);
}
if (!settings.putUInt("BMSRESETDUR", datalayer.battery.settings.sofar_user_specified_battery_id)) {
if (!settings.putUInt("BMSRESETDUR", datalayer.battery.settings.user_set_bms_reset_duration_ms)) {
set_event(EVENT_PERSISTENT_SAVE_INFO, 13);
}

View file

@ -40,9 +40,7 @@ bool init_precharge_control() {
}
// Setup PWM Channel Frequency and Resolution
#ifdef DEBUG_LOG
logging.printf("Precharge control initialised\n");
#endif
auto hia4v1_pin = esp32hal->HIA4V1_PIN();
auto inverter_disconnect_contactor_pin = esp32hal->INVERTER_DISCONNECT_CONTACTOR_PIN();
@ -64,6 +62,14 @@ void handle_precharge_control(unsigned long currentMillis) {
auto hia4v1_pin = esp32hal->HIA4V1_PIN();
auto inverter_disconnect_contactor_pin = esp32hal->INVERTER_DISCONNECT_CONTACTOR_PIN();
// If we're in FAILURE state, completely disable any further precharge attempts
if (datalayer.system.status.precharge_status == AUTO_PRECHARGE_FAILURE) {
pinMode(hia4v1_pin, OUTPUT);
digitalWrite(hia4v1_pin, LOW);
digitalWrite(inverter_disconnect_contactor_pin, ON);
return; // Exit immediately - no further processing allowed. Reboot required to recover
}
int32_t target_voltage = datalayer.battery.status.voltage_dV;
int32_t external_voltage = datalayer_extended.meb.BMS_voltage_intermediate_dV;
@ -79,9 +85,7 @@ void handle_precharge_control(unsigned long currentMillis) {
ledcWriteTone(hia4v1_pin, freq); // Set frequency and set dutycycle to 50%
prechargeStartTime = currentMillis;
datalayer.system.status.precharge_status = AUTO_PRECHARGE_PRECHARGING;
#ifdef DEBUG_LOG
logging.printf("Precharge: Starting sequence\n");
#endif
digitalWrite(inverter_disconnect_contactor_pin, OFF);
break;
@ -106,10 +110,8 @@ void handle_precharge_control(unsigned long currentMillis) {
freq = Precharge_max_PWM_Freq;
if (freq < Precharge_min_PWM_Freq)
freq = Precharge_min_PWM_Freq;
#ifdef DEBUG_LOG
logging.printf("Precharge: Target: %d V Extern: %d V Frequency: %u\n", target_voltage / 10,
external_voltage / 10, freq);
#endif
ledcWriteTone(hia4v1_pin, freq);
}
@ -120,38 +122,31 @@ void handle_precharge_control(unsigned long currentMillis) {
digitalWrite(hia4v1_pin, LOW);
digitalWrite(inverter_disconnect_contactor_pin, ON);
datalayer.system.status.precharge_status = AUTO_PRECHARGE_IDLE;
#ifdef DEBUG_LOG
logging.printf("Precharge: Disabling Precharge bms not standby/active or equipment stop\n");
#endif
} else if (currentMillis - prechargeStartTime >= MAX_PRECHARGE_TIME_MS ||
datalayer.battery.status.real_bms_status == BMS_FAULT) {
pinMode(hia4v1_pin, OUTPUT);
digitalWrite(hia4v1_pin, LOW);
digitalWrite(inverter_disconnect_contactor_pin, ON);
datalayer.system.status.precharge_status = AUTO_PRECHARGE_OFF;
#ifdef DEBUG_LOG
logging.printf("Precharge: Disabled (timeout reached / BMS fault) -> AUTO_PRECHARGE_OFF\n");
#endif
datalayer.system.status.precharge_status = AUTO_PRECHARGE_FAILURE;
logging.printf("Precharge: CRITICAL FAILURE (timeout/BMS fault) -> REQUIRES REBOOT\n");
set_event(EVENT_AUTOMATIC_PRECHARGE_FAILURE, 0);
// Force stop any further precharge attempts
datalayer.system.settings.start_precharging = false;
// Add event
} else if (datalayer.system.status.battery_allows_contactor_closing) {
pinMode(hia4v1_pin, OUTPUT);
digitalWrite(hia4v1_pin, LOW);
digitalWrite(inverter_disconnect_contactor_pin, ON);
datalayer.system.status.precharge_status = AUTO_PRECHARGE_COMPLETED;
#ifdef DEBUG_LOG
logging.printf("Precharge: Disabled (contacts closed) -> COMPLETED\n");
#endif
}
break;
case AUTO_PRECHARGE_COMPLETED:
if (datalayer.system.settings.equipment_stop_active || datalayer.battery.status.bms_status != ACTIVE) {
datalayer.system.status.precharge_status = AUTO_PRECHARGE_IDLE;
#ifdef DEBUG_LOG
logging.printf("Precharge: equipment stop activated -> IDLE\n");
#endif
}
break;
@ -162,9 +157,7 @@ void handle_precharge_control(unsigned long currentMillis) {
datalayer.system.status.precharge_status = AUTO_PRECHARGE_IDLE;
pinMode(hia4v1_pin, OUTPUT);
digitalWrite(hia4v1_pin, LOW);
#ifdef DEBUG_LOG
logging.printf("Precharge: equipment stop activated -> IDLE\n");
#endif
}
break;

View file

@ -110,7 +110,7 @@ struct DATALAYER_BATTERY_STATUS_TYPE {
real_bms_status_enum real_bms_status = BMS_DISCONNECTED;
/** LED mode, customizable by user */
led_mode_enum led_mode = LED_MODE;
led_mode_enum led_mode = CLASSIC;
};
struct DATALAYER_BATTERY_SETTINGS_TYPE {
@ -152,6 +152,7 @@ struct DATALAYER_BATTERY_SETTINGS_TYPE {
bool user_requests_balancing = false;
bool user_requests_tesla_isolation_clear = false;
bool user_requests_tesla_bms_reset = false;
bool user_requests_tesla_soc_reset = false;
/* Forced balancing max time & start timestamp */
uint32_t balancing_time_ms = 3600000; //1h default, (60min*60sec*1000ms)
uint32_t balancing_start_time_ms = 0; //For keeping track when balancing started
@ -240,6 +241,16 @@ struct DATALAYER_SYSTEM_INFO_TYPE {
size_t logged_can_messages_offset = 0;
/** bool, determines if CAN messages should be logged for webserver */
bool can_logging_active = false;
/** bool, determines if USB serial logging should occur */
bool CAN_usb_logging_active = false;
/** bool, determines if USB serial logging should occur */
bool CAN_SD_logging_active = false;
/** bool, determines if USB serial logging should occur */
bool usb_logging_active = false;
/** bool, determines if general logging should be active for webserver */
bool web_logging_active = false;
/** bool, determines if general logging to SD card should be active */
bool SD_logging_active = false;
/** uint8_t, enumeration which CAN interface should be used for log playback */
uint8_t can_replay_interface = CAN_NATIVE;
/** bool, determines if CAN replay should loop or not */
@ -310,8 +321,8 @@ struct DATALAYER_SYSTEM_STATUS_TYPE {
/** True if the inverter allows for the contactors to close */
bool inverter_allows_contactor_closing = true;
/** True if the contactor controlled by battery-emulator is closed */
bool contactors_engaged = false;
/** 0 if starting up, 1 if contactors engaged, 2 if the contactors controlled by battery-emulator is opened */
uint8_t contactors_engaged = 0;
/** True if the contactor controlled by battery-emulator is closed. Determined by check_interconnect_available(); if voltage is OK */
bool contactors_battery2_engaged = false;

View file

@ -783,6 +783,8 @@ struct DATALAYER_INFO_VOLVO_POLESTAR {
uint8_t HVSysDCRlySts1 = 0;
uint8_t HVSysDCRlySts2 = 0;
uint8_t HVSysIsoRMonrSts = 0;
uint8_t DTCcount = 0;
uint8_t HVILstatusBits = 0;
/** User requesting DTC reset via WebUI*/
bool UserRequestDTCreset = false;
/** User requesting DTC readout via WebUI*/

View file

@ -38,7 +38,16 @@ class StarkHal : public Esp32Hal {
virtual gpio_num_t CAN_SE_PIN() { return GPIO_NUM_NC; }
// CANFD_ADDON defines for MCP2517
virtual gpio_num_t MCP2517_SCK() { return GPIO_NUM_17; }
// Stark CMR v1 has GPIO pin 16 for SCK, CMR v2 has GPIO pin 17. Only diff between the two boards
bool isStarkVersion1() {
size_t flashSize = ESP.getFlashChipSize();
if (flashSize == 4 * 1024 * 1024) {
return true;
} else { //v2
return false;
}
}
virtual gpio_num_t MCP2517_SCK() { return isStarkVersion1() ? GPIO_NUM_16 : GPIO_NUM_17; }
virtual gpio_num_t MCP2517_SDI() { return GPIO_NUM_5; }
virtual gpio_num_t MCP2517_SDO() { return GPIO_NUM_34; }
virtual gpio_num_t MCP2517_CS() { return GPIO_NUM_18; }

View file

@ -141,7 +141,9 @@ SensorConfig batterySensorConfigTemplate[] = {
{"balancing_active_cells", "Balancing Active Cells", "", "", "", always}};
SensorConfig globalSensorConfigTemplate[] = {{"bms_status", "BMS Status", "", "", "", always},
{"pause_status", "Pause Status", "", "", "", always}};
{"pause_status", "Pause Status", "", "", "", always},
{"event_level", "Event Level", "", "", "", always},
{"emulator_status", "Emulator Status", "", "", "", always}};
static std::list<SensorConfig> sensorConfigs;
@ -311,11 +313,13 @@ static bool publish_common_info(void) {
set_battery_attributes(doc, datalayer.battery2, "_2", battery2->supports_charged_energy());
}
}
doc["event_level"] = get_event_level_string(get_event_level());
doc["emulator_status"] = get_emulator_status_string(get_emulator_status());
serializeJson(doc, mqtt_msg);
if (mqtt_publish(state_topic.c_str(), mqtt_msg, false) == false) {
#ifdef DEBUG_LOG
logging.println("Common info MQTT msg could not be sent");
#endif // DEBUG_LOG
return false;
}
doc.clear();
@ -386,9 +390,7 @@ static bool publish_cell_voltages(void) {
serializeJson(doc, mqtt_msg, sizeof(mqtt_msg));
if (!mqtt_publish(state_topic.c_str(), mqtt_msg, false)) {
#ifdef DEBUG_LOG
logging.println("Cell voltage MQTT msg could not be sent");
#endif // DEBUG_LOG
return false;
}
doc.clear();
@ -407,9 +409,7 @@ static bool publish_cell_voltages(void) {
serializeJson(doc, mqtt_msg, sizeof(mqtt_msg));
if (!mqtt_publish(state_topic_2.c_str(), mqtt_msg, false)) {
#ifdef DEBUG_LOG
logging.println("Cell voltage MQTT msg could not be sent");
#endif // DEBUG_LOG
return false;
}
doc.clear();
@ -434,9 +434,7 @@ static bool publish_cell_balancing(void) {
serializeJson(doc, mqtt_msg, sizeof(mqtt_msg));
if (!mqtt_publish(state_topic.c_str(), mqtt_msg, false)) {
#ifdef DEBUG_LOG
logging.println("Cell balancing MQTT msg could not be sent");
#endif // DEBUG_LOG
return false;
}
doc.clear();
@ -454,9 +452,7 @@ static bool publish_cell_balancing(void) {
serializeJson(doc, mqtt_msg, sizeof(mqtt_msg));
if (!mqtt_publish(state_topic_2.c_str(), mqtt_msg, false)) {
#ifdef DEBUG_LOG
logging.println("Cell balancing MQTT msg could not be sent");
#endif // DEBUG_LOG
return false;
}
doc.clear();
@ -517,9 +513,7 @@ bool publish_events() {
serializeJson(doc, mqtt_msg);
if (!mqtt_publish(state_topic.c_str(), mqtt_msg, false)) {
#ifdef DEBUG_LOG
logging.println("Common info MQTT msg could not be sent");
#endif // DEBUG_LOG
return false;
} else {
set_event_MQTTpublished(event_handle);
@ -535,9 +529,7 @@ bool publish_events() {
static bool publish_buttons_discovery(void) {
if (ha_autodiscovery_enabled) {
if (ha_buttons_published == false) {
#ifdef DEBUG_LOG
logging.println("Publishing buttons discovery");
#endif // DEBUG_LOG
static JsonDocument doc;
for (int i = 0; i < sizeof(buttonConfigs) / sizeof(buttonConfigs[0]); i++) {
@ -567,16 +559,12 @@ void mqtt_message_received(char* topic_raw, int topic_len, char* data, int data_
char* topic = strndup(topic_raw, topic_len);
#ifdef DEBUG_LOG
logging.printf("MQTT message arrived: [%.*s]\n", topic_len, topic);
#endif // DEBUG_LOG
#ifdef REMOTE_BMS_RESET
const char* bmsreset_topic = generateButtonTopic("BMSRESET").c_str();
if (strcmp(topic, bmsreset_topic) == 0) {
#ifdef DEBUG_LOG
logging.println("Triggering BMS reset");
#endif // DEBUG_LOG
start_bms_reset();
}
#endif // REMOTE_BMS_RESET
@ -610,21 +598,16 @@ static void mqtt_event_handler(void* handler_args, esp_event_base_t base, int32_
publish_buttons_discovery();
subscribe();
#ifdef DEBUG_LOG
logging.println("MQTT connected");
#endif // DEBUG_LOG
break;
case MQTT_EVENT_DISCONNECTED:
set_event(EVENT_MQTT_DISCONNECT, 0);
#ifdef DEBUG_LOG
logging.println("MQTT disconnected!");
#endif // DEBUG_LOG
break;
case MQTT_EVENT_DATA:
mqtt_message_received(event->topic, event->topic_len, event->data, event->data_len);
break;
case MQTT_EVENT_ERROR:
#ifdef DEBUG_LOG
logging.println("MQTT_ERROR");
logging.print("reported from esp-tls");
logging.println(event->error_handle->esp_tls_last_esp_err);
@ -632,7 +615,6 @@ static void mqtt_event_handler(void* handler_args, esp_event_base_t base, int32_
logging.println(event->error_handle->esp_tls_stack_err);
logging.print("captured as transport's socket errno");
logging.println(strerror(event->error_handle->esp_transport_sock_errno));
#endif // DEBUG_LOG
break;
}
}
@ -717,9 +699,7 @@ void mqtt_loop(void) {
if (client_started == false) {
esp_mqtt_client_start(client);
client_started = true;
#ifdef DEBUG_LOG
logging.println("MQTT initialized");
#endif // DEBUG_LOG
return;
}

View file

@ -63,9 +63,7 @@ void add_can_frame_to_buffer(CAN_frame frame, frameDirection msgDir) {
currentTime / 1000, currentTime % 1000, (msgDir == MSG_RX ? "RX0" : "TX1"), frame.ID, frame.DLC);
if (xRingbufferSend(can_bufferHandle, &messagestr_buffer, size, pdMS_TO_TICKS(2)) != pdTRUE) {
#ifdef DEBUG_VIA_USB
Serial.println("Failed to send message to can ring buffer!");
#endif // DEBUG_VIA_USB
logging.println("Failed to send message to can ring buffer!");
return;
}
@ -77,9 +75,7 @@ void add_can_frame_to_buffer(CAN_frame frame, frameDirection msgDir) {
size = snprintf(messagestr_buffer, sizeof(messagestr_buffer), "%02X\n", frame.data.u8[i]);
if (xRingbufferSend(can_bufferHandle, &messagestr_buffer, size, pdMS_TO_TICKS(2)) != pdTRUE) {
#ifdef DEBUG_VIA_USB
Serial.println("Failed to send message to can ring buffer!");
#endif // DEBUG_VIA_USB
logging.println("Failed to send message to can ring buffer!");
return;
}
}
@ -127,9 +123,7 @@ void add_log_to_buffer(const uint8_t* buffer, size_t size) {
return;
if (xRingbufferSend(log_bufferHandle, buffer, size, pdMS_TO_TICKS(1)) != pdTRUE) {
#ifdef DEBUG_VIA_USB
Serial.println("Failed to send message to log ring buffer!");
#endif // DEBUG_VIA_USB
logging.println("Failed to send message to log ring buffer!");
return;
}
}
@ -161,25 +155,22 @@ void write_log_to_sdcard() {
}
void init_logging_buffers() {
#if defined(LOG_CAN_TO_SD)
can_bufferHandle = xRingbufferCreate(32 * 1024, RINGBUF_TYPE_BYTEBUF);
if (can_bufferHandle == NULL) {
#ifdef DEBUG_LOG
logging.println("Failed to create CAN ring buffer!");
#endif // DEBUG_LOG
return;
}
#endif // defined(LOG_CAN_TO_SD)
#if defined(LOG_TO_SD)
log_bufferHandle = xRingbufferCreate(1024, RINGBUF_TYPE_BYTEBUF);
if (log_bufferHandle == NULL) {
#ifdef DEBUG_LOG
logging.println("Failed to create log ring buffer!");
#endif // DEBUG_LOG
return;
if (datalayer.system.info.CAN_SD_logging_active) {
can_bufferHandle = xRingbufferCreate(32 * 1024, RINGBUF_TYPE_BYTEBUF);
if (can_bufferHandle == NULL) {
logging.println("Failed to create CAN ring buffer!");
return;
}
}
if (datalayer.system.info.SD_logging_active) {
log_bufferHandle = xRingbufferCreate(1024, RINGBUF_TYPE_BYTEBUF);
if (log_bufferHandle == NULL) {
logging.println("Failed to create log ring buffer!");
return;
}
}
#endif // defined(LOG_TO_SD)
}
bool init_sdcard() {
@ -196,22 +187,16 @@ bool init_sdcard() {
SD_MMC.setPins(sclk_pin, mosi_pin, miso_pin);
if (!SD_MMC.begin("/root", true, true, SDMMC_FREQ_HIGHSPEED)) {
set_event_latched(EVENT_SD_INIT_FAILED, 0);
#ifdef DEBUG_LOG
logging.println("SD Card initialization failed!");
#endif // DEBUG_LOG
return false;
}
clear_event(EVENT_SD_INIT_FAILED);
#ifdef DEBUG_LOG
logging.println("SD Card initialization successful.");
#endif // DEBUG_LOG
sd_card_active = true;
#ifdef DEBUG_LOG
log_sdcard_details();
#endif // DEBUG_LOG
return true;
}

View file

@ -14,6 +14,7 @@ typedef struct {
static EVENT_TYPE events;
static const char* EVENTS_ENUM_TYPE_STRING[] = {EVENTS_ENUM_TYPE(GENERATE_STRING)};
static const char* EVENTS_LEVEL_TYPE_STRING[] = {EVENTS_LEVEL_TYPE(GENERATE_STRING)};
static const char* EMULATOR_STATUS_STRING[] = {EMULATOR_STATUS(GENERATE_STRING)};
/* Local function prototypes */
static void set_event(EVENTS_ENUM_TYPE event, uint8_t data, bool latched);
@ -158,9 +159,6 @@ void reset_all_events() {
}
events.level = EVENT_LEVEL_INFO;
update_bms_status();
#ifdef DEBUG_LOG
logging.println("All events have been cleared.");
#endif
}
void set_event_MQTTpublished(EVENTS_ENUM_TYPE event) {
@ -262,7 +260,7 @@ String get_event_message_string(EVENTS_ENUM_TYPE event) {
case EVENT_PRECHARGE_FAILURE:
return "Battery failed to precharge. Check that capacitor is seated on high voltage output.";
case EVENT_AUTOMATIC_PRECHARGE_FAILURE:
return "Automatic precharge failed to reach target voltae.";
return "Automatic precharge FAILURE. Failed to reach target voltage or BMS timeout. Reboot emulator to retry!";
case EVENT_INTERNAL_OPEN_FAULT:
return "High voltage cable removed while battery running. Opening contactors!";
case EVENT_INVERTER_OPEN_CONTACTOR:
@ -270,8 +268,8 @@ String get_event_message_string(EVENTS_ENUM_TYPE event) {
case EVENT_INTERFACE_MISSING:
return "Configuration trying to use CAN interface not baked into the software. Recompile software!";
case EVENT_ERROR_OPEN_CONTACTOR:
return "Too much time spent in error state. Opening contactors, not safe to continue charging. "
"Check other error code for reason!";
return "Too much time spent in error state. Opening contactors, not safe to continue. "
"Check other active ERROR code for reason. Reboot emulator after problem is solved!";
case EVENT_MODBUS_INVERTER_MISSING:
return "Modbus inverter has not sent any data. Inspect communication wiring!";
case EVENT_NO_ENABLE_DETECTED:
@ -393,6 +391,11 @@ const char* get_event_level_string(EVENTS_ENUM_TYPE event) {
return EVENTS_LEVEL_TYPE_STRING[events.entries[event].level] + 12;
}
const char* get_event_level_string(EVENTS_LEVEL_TYPE event_level) {
// Return the event level but skip "EVENT_LEVEL_TYPE_" that should always be first
return EVENTS_LEVEL_TYPE_STRING[event_level] + 17;
}
const EVENTS_STRUCT_TYPE* get_event_pointer(EVENTS_ENUM_TYPE event) {
return &events.entries[event];
}
@ -401,6 +404,27 @@ EVENTS_LEVEL_TYPE get_event_level(void) {
return events.level;
}
EMULATOR_STATUS get_emulator_status() {
switch (events.level) {
case EVENT_LEVEL_DEBUG:
case EVENT_LEVEL_INFO:
return EMULATOR_STATUS::STATUS_OK;
case EVENT_LEVEL_WARNING:
return EMULATOR_STATUS::STATUS_WARNING;
case EVENT_LEVEL_UPDATE:
return EMULATOR_STATUS::STATUS_UPDATING;
case EVENT_LEVEL_ERROR:
return EMULATOR_STATUS::STATUS_ERROR;
default:
return EMULATOR_STATUS::STATUS_OK;
}
}
const char* get_emulator_status_string(EMULATOR_STATUS status) {
// Return the status string but skip "STATUS_" that should always be first
return EMULATOR_STATUS_STRING[status] + 7;
}
/* Local functions */
static void set_event(EVENTS_ENUM_TYPE event, uint8_t data, bool latched) {

View file

@ -126,6 +126,14 @@ typedef enum { EVENTS_ENUM_TYPE(GENERATE_ENUM) } EVENTS_ENUM_TYPE;
typedef enum { EVENTS_LEVEL_TYPE(GENERATE_ENUM) } EVENTS_LEVEL_TYPE;
#define EMULATOR_STATUS(XX) \
XX(STATUS_OK) \
XX(STATUS_WARNING) \
XX(STATUS_ERROR) \
XX(STATUS_UPDATING)
typedef enum { EMULATOR_STATUS(GENERATE_ENUM) } EMULATOR_STATUS;
typedef enum {
EVENT_STATE_PENDING = 0,
EVENT_STATE_INACTIVE,
@ -151,8 +159,11 @@ struct EventData {
const char* get_event_enum_string(EVENTS_ENUM_TYPE event);
String get_event_message_string(EVENTS_ENUM_TYPE event);
const char* get_event_level_string(EVENTS_ENUM_TYPE event);
const char* get_event_level_string(EVENTS_LEVEL_TYPE event_level);
EVENTS_LEVEL_TYPE get_event_level(void);
EMULATOR_STATUS get_emulator_status();
const char* get_emulator_status_string(EMULATOR_STATUS status);
void init_events(void);
void set_event_latched(EVENTS_ENUM_TYPE event, uint8_t data);

View file

@ -32,10 +32,6 @@ void led_exe(void) {
led->exe();
}
led_color led_get_color() {
return led->color;
}
void LED::exe(void) {
// Update brightness
@ -53,27 +49,21 @@ void LED::exe(void) {
}
// Set color
switch (get_event_level()) {
case EVENT_LEVEL_INFO:
color = led_color::GREEN;
switch (get_emulator_status()) {
case EMULATOR_STATUS::STATUS_OK:
pixels.setPixelColor(COLOR_GREEN(brightness)); // Green pulsing LED
break;
case EVENT_LEVEL_WARNING:
color = led_color::YELLOW;
case EMULATOR_STATUS::STATUS_WARNING:
pixels.setPixelColor(COLOR_YELLOW(brightness)); // Yellow pulsing LED
break;
case EVENT_LEVEL_DEBUG:
case EVENT_LEVEL_UPDATE:
color = led_color::BLUE;
pixels.setPixelColor(COLOR_BLUE(brightness)); // Blue pulsing LED
break;
case EVENT_LEVEL_ERROR:
color = led_color::RED;
case EMULATOR_STATUS::STATUS_ERROR:
pixels.setPixelColor(COLOR_RED(esp32hal->LED_MAX_BRIGHTNESS())); // Red LED full brightness
break;
default:
case EMULATOR_STATUS::STATUS_UPDATING:
pixels.setPixelColor(COLOR_BLUE(brightness)); // Blue pulsing LED
break;
}
pixels.show(); // This sends the updated pixel color to the hardware.
}

View file

@ -6,8 +6,6 @@
class LED {
public:
led_color color = led_color::GREEN;
LED(gpio_num_t pin, uint8_t maxBrightness)
: pixels(pin), max_brightness(maxBrightness), brightness(maxBrightness), mode(led_mode_enum::CLASSIC) {}
@ -27,10 +25,10 @@ class LED {
void heartbeat_run(void);
uint8_t up_down(float middle_point_f);
int LED_PERIOD_MS = 3000;
};
bool led_init(void);
void led_exe(void);
led_color led_get_color(void);
#endif // LED_H_

View file

@ -3,19 +3,17 @@
#include "../../datalayer/datalayer.h"
#include "../sdcard/sdcard.h"
#if defined(LOG_CAN_TO_SD) || defined(LOG_TO_SD)
#if !defined(HW_LILYGO)
#error The SD card logging feature is only available on LilyGo hardware
#endif
#endif
#define MAX_LINE_LENGTH_PRINTF 128
#define MAX_LENGTH_TIME_STR 14
bool previous_message_was_newline = true;
void Logging::add_timestamp(size_t size) {
#ifdef DEBUG_LOG
// Check if any logging is enabled at runtime
if (!datalayer.system.info.web_logging_active && !datalayer.system.info.usb_logging_active) {
return;
}
char* message_string = datalayer.system.info.logged_can_messages;
int offset = datalayer.system.info.logged_can_messages_offset; // Keeps track of the current position in the buffer
size_t message_string_size = sizeof(datalayer.system.info.logged_can_messages);
@ -23,43 +21,44 @@ void Logging::add_timestamp(size_t size) {
char* timestr;
static char timestr_buffer[MAX_LENGTH_TIME_STR];
#ifdef DEBUG_VIA_WEB
if (!datalayer.system.info.can_logging_active) {
/* If web debug is active and can logging is inactive,
* we use the debug logging memory directly for writing the timestring */
if (offset + size + MAX_LENGTH_TIME_STR > message_string_size) {
offset = 0;
if (datalayer.system.info.web_logging_active) {
if (!datalayer.system.info.can_logging_active) {
/* If web debug is active and can logging is inactive,
* we use the debug logging memory directly for writing the timestring */
if (offset + size + MAX_LENGTH_TIME_STR > message_string_size) {
offset = 0;
}
timestr = datalayer.system.info.logged_can_messages + offset;
} else {
timestr = timestr_buffer;
}
timestr = datalayer.system.info.logged_can_messages + offset;
} else {
timestr = timestr_buffer;
}
#else
timestr = timestr_buffer;
#endif // DEBUG_VIA_WEB
offset += min(MAX_LENGTH_TIME_STR - 1,
snprintf(timestr, MAX_LENGTH_TIME_STR, "%8lu.%03lu ", currentTime / 1000, currentTime % 1000));
#ifdef DEBUG_VIA_WEB
if (!datalayer.system.info.can_logging_active) {
if (datalayer.system.info.web_logging_active && !datalayer.system.info.can_logging_active) {
datalayer.system.info.logged_can_messages_offset = offset; // Update offset in buffer
}
#endif // DEBUG_VIA_WEB
// LOG_TO_SD remains as compile-time option for now
#ifdef LOG_TO_SD
add_log_to_buffer((uint8_t*)timestr, MAX_LENGTH_TIME_STR);
#endif // LOG_TO_SD
#ifdef DEBUG_VIA_USB
Serial.write(timestr);
#endif // DEBUG_VIA_USB
#endif // DEBUG_LOG
if (datalayer.system.info.usb_logging_active) {
Serial.write(timestr);
}
}
size_t Logging::write(const uint8_t* buffer, size_t size) {
#ifdef DEBUG_LOG
// Check if any logging is enabled at runtime
if (!datalayer.system.info.web_logging_active && !datalayer.system.info.usb_logging_active) {
return 0;
}
if (previous_message_was_newline) {
add_timestamp(size);
}
@ -67,11 +66,12 @@ size_t Logging::write(const uint8_t* buffer, size_t size) {
#ifdef LOG_TO_SD
add_log_to_buffer(buffer, size);
#endif
#ifdef DEBUG_VIA_USB
Serial.write(buffer, size);
#endif
#ifdef DEBUG_VIA_WEB
if (!datalayer.system.info.can_logging_active) {
if (datalayer.system.info.usb_logging_active) {
Serial.write(buffer, size);
}
if (datalayer.system.info.web_logging_active && !datalayer.system.info.can_logging_active) {
char* message_string = datalayer.system.info.logged_can_messages;
int offset = datalayer.system.info.logged_can_messages_offset; // Keeps track of the current position in the buffer
size_t message_string_size = sizeof(datalayer.system.info.logged_can_messages);
@ -82,16 +82,17 @@ size_t Logging::write(const uint8_t* buffer, size_t size) {
memcpy(message_string + offset, buffer, size);
datalayer.system.info.logged_can_messages_offset = offset + size; // Update offset in buffer
}
#endif // DEBUG_VIA_WEB
previous_message_was_newline = buffer[size - 1] == '\n';
return size;
#endif // DEBUG_LOG
return 0;
}
void Logging::printf(const char* fmt, ...) {
#ifdef DEBUG_LOG
// Check if any logging is enabled at runtime
if (!datalayer.system.info.web_logging_active && !datalayer.system.info.usb_logging_active) {
return;
}
if (previous_message_was_newline) {
add_timestamp(MAX_LINE_LENGTH_PRINTF);
}
@ -101,21 +102,22 @@ void Logging::printf(const char* fmt, ...) {
int offset = datalayer.system.info.logged_can_messages_offset; // Keeps track of the current position in the buffer
static char buffer[MAX_LINE_LENGTH_PRINTF];
char* message_buffer;
#ifdef DEBUG_VIA_WEB
if (!datalayer.system.info.can_logging_active) {
/* If web debug is active and can logging is inactive,
* we use the debug logging memory directly for writing the output */
if (offset + MAX_LINE_LENGTH_PRINTF > message_string_size) {
// Not enough space, reset and start from the beginning
offset = 0;
if (datalayer.system.info.web_logging_active) {
if (!datalayer.system.info.can_logging_active) {
/* If web debug is active and can logging is inactive,
* we use the debug logging memory directly for writing the output */
if (offset + MAX_LINE_LENGTH_PRINTF > message_string_size) {
// Not enough space, reset and start from the beginning
offset = 0;
}
message_buffer = message_string + offset;
} else {
message_buffer = buffer;
}
message_buffer = message_string + offset;
} else {
message_buffer = buffer;
}
#else
message_buffer = buffer;
#endif // DEBUG_VIA_WEB
va_list(args);
va_start(args, fmt);
@ -126,18 +128,15 @@ void Logging::printf(const char* fmt, ...) {
add_log_to_buffer((uint8_t*)message_buffer, size);
#endif // LOG_TO_SD
#ifdef DEBUG_VIA_USB
Serial.write(message_buffer, size);
#endif // DEBUG_VIA_USB
if (datalayer.system.info.usb_logging_active) {
Serial.write(message_buffer, size);
}
#ifdef DEBUG_VIA_WEB
if (!datalayer.system.info.can_logging_active) {
if (datalayer.system.info.web_logging_active && !datalayer.system.info.can_logging_active) {
// Data was already added to buffer, just move offset
datalayer.system.info.logged_can_messages_offset =
offset + size; // Keeps track of the current position in the buffer
}
#endif // DEBUG_VIA_WEB
previous_message_was_newline = message_buffer[size - 1] == '\n';
#endif // DEBUG_LOG
}

View file

@ -1,11 +1,15 @@
#ifndef __LOGGING_H__
#define __LOGGING_H__
#include <Print.h>
#include <inttypes.h>
#include "../../../USER_SETTINGS.h"
#include "../../datalayer/datalayer.h"
#include "types.h"
#ifndef UNIT_TEST
// Real implementation for production
#include <Print.h>
class Logging : public Print {
void add_timestamp(size_t size);
@ -13,18 +17,51 @@ class Logging : public Print {
virtual size_t write(const uint8_t* buffer, size_t size);
virtual size_t write(uint8_t) { return 0; }
void printf(const char* fmt, ...);
void log_bms_status(real_bms_status_enum bms_status);
Logging() {}
};
extern Logging logging;
// Production macros
#define DEBUG_PRINTF(fmt, ...) \
do { \
if (datalayer.system.info.web_logging_active || datalayer.system.info.usb_logging_active) { \
logging.printf(fmt, ##__VA_ARGS__); \
} \
} while (0)
#define DEBUG_PRINTLN(str) \
do { \
if (datalayer.system.info.web_logging_active || datalayer.system.info.usb_logging_active) { \
logging.println(str); \
} \
} while (0)
#ifdef DEBUG_LOG
#define DEBUG_PRINTF(fmt, ...) logging.printf(fmt, ##__VA_ARGS__)
#define DEBUG_PRINTLN(str) logging.println(str)
#else
// Mock implementation for tests
#include <cstdarg>
#include <cstdio>
class Logging {
public:
// Mock methods that do nothing
size_t write(const uint8_t* buffer, size_t size) { return size; }
size_t write(uint8_t) { return 0; }
static void printf(const char* fmt, ...) {
// Empty implementation - silence unused parameter warnings
(void)fmt;
}
static void println(const char* str) { (void)str; }
Logging() {}
};
// Test macros - empty implementations
#define DEBUG_PRINTF(fmt, ...) ((void)0)
#define DEBUG_PRINTLN(str) ((void)0)
#endif
extern Logging logging;
#endif // __LOGGING_H__

View file

@ -21,14 +21,14 @@ enum class comm_interface {
Highest
};
enum led_color { GREEN, YELLOW, RED, BLUE };
enum led_mode_enum { CLASSIC, FLOW, HEARTBEAT };
enum PrechargeState {
AUTO_PRECHARGE_IDLE,
AUTO_PRECHARGE_START,
AUTO_PRECHARGE_PRECHARGING,
AUTO_PRECHARGE_OFF,
AUTO_PRECHARGE_COMPLETED
AUTO_PRECHARGE_COMPLETED,
AUTO_PRECHARGE_FAILURE
};
#define DISCHARGING 1

View file

@ -25,6 +25,10 @@ std::vector<BatteryCommand> battery_commands = {
[](Battery* b) {
b->reset_BMS();
}},
{"resetSOC", "SOC reset", "reset SOC?", [](Battery* b) { return b && b->supports_reset_SOC(); },
[](Battery* b) {
b->reset_SOC();
}},
{"resetCrash", "Unlock crashed BMS",
"reset crash data? Note this will unlock your BMS and enable contactor closing and SOC calculation.",
[](Battery* b) { return b && b->supports_reset_crash(); },

View file

@ -3,7 +3,6 @@
#include "../../datalayer/datalayer.h"
#include "index_html.h"
#if defined(DEBUG_VIA_WEB) || defined(LOG_TO_SD)
char* strnchr(const char* s, int c, size_t n) {
// Like strchr, but only searches the first 'n' bytes of the string.
@ -54,13 +53,13 @@ String debug_logger_processor(void) {
".can-message { background-color: #404E57; margin-bottom: 5px; padding: 10px; border-radius: 5px; font-family: "
"monospace; }";
content += "</style>";
#ifdef DEBUG_VIA_WEB
content += "<button onclick='refreshPage()'>Refresh data</button> ";
#endif
if (datalayer.system.info.web_logging_active) {
content += "<button onclick='refreshPage()'>Refresh data</button> ";
}
content += "<button onclick='exportLog()'>Export to .txt</button> ";
#ifdef LOG_TO_SD
content += "<button onclick='deleteLog()'>Delete log file</button> ";
#endif
if (datalayer.system.info.SD_logging_active) {
content += "<button onclick='deleteLog()'>Delete log file</button> ";
}
content += "<button onclick='goToMainPage()'>Back to main page</button>";
// Start a new block for the debug log messages
@ -99,12 +98,11 @@ String debug_logger_processor(void) {
content += "<script>";
content += "function refreshPage(){ location.reload(true); }";
content += "function exportLog() { window.location.href = '/export_log'; }";
#ifdef LOG_TO_SD
content += "function deleteLog() { window.location.href = '/delete_log'; }";
#endif
if (datalayer.system.info.SD_logging_active) {
content += "function deleteLog() { window.location.href = '/delete_log'; }";
}
content += "function goToMainPage() { window.location.href = '/'; }";
content += "</script>";
content += index_html_footer;
return content;
}
#endif

View file

@ -46,12 +46,6 @@ String events_processor(const String& var) {
EVENTS_ENUM_TYPE event_handle = event.event_handle;
event_pointer = event.event_pointer;
#ifdef DEBUG_LOG
logging.println("Showing Event: " + String(get_event_enum_string(event_handle)) +
" count: " + String(event_pointer->occurences) + " seconds: " + String(event_pointer->timestamp) +
" data: " + String(event_pointer->data) +
" level: " + String(get_event_level_string(event_handle)));
#endif
content.concat("<div class='event'>");
content.concat("<div>" + String(get_event_enum_string(event_handle)) + "</div>");
content.concat("<div>" + String(get_event_level_string(event_handle)) + "</div>");

View file

@ -78,6 +78,35 @@ String options_for_enum(TEnum selected, Func name_for_type) {
return options;
}
template <typename TMap>
String options_from_map(int selected, const TMap& value_name_map) {
String options;
for (const auto& [value, name] : value_name_map) {
options += "<option value=\"" + String(value) + "\"";
if (selected == value) {
options += " selected";
}
options += ">";
options += name;
options += "</option>";
}
return options;
}
static const std::map<int, String> led_modes = {{0, "Classic"}, {1, "Energy Flow"}, {2, "Heartbeat"}};
static const std::map<int, String> tesla_countries = {
{21843, "US (USA)"}, {17217, "CA (Canada)"}, {18242, "GB (UK & N Ireland)"},
{17483, "DK (Denmark)"}, {17477, "DE (Germany)"}, {16725, "AU (Australia)"}};
static const std::map<int, String> tesla_mapregion = {
{8, "ME (Middle East)"}, {2, "NONE"}, {3, "CN (China)"}, {6, "TW (Taiwan)"}, {5, "JP (Japan)"},
{0, "US (USA)"}, {7, "KR (Korea)"}, {4, "AU (Australia)"}, {1, "EU (Europe)"}};
static const std::map<int, String> tesla_chassis = {{0, "Model S"}, {1, "Model X"}, {2, "Model 3"}, {3, "Model Y"}};
static const std::map<int, String> tesla_pack = {{0, "50 kWh"}, {2, "62 kWh"}, {1, "74 kWh"}, {3, "100 kWh"}};
const char* name_for_button_type(STOP_BUTTON_BEHAVIOR behavior) {
switch (behavior) {
case STOP_BUTTON_BEHAVIOR::LATCHING_SWITCH:
@ -254,6 +283,26 @@ String settings_processor(const String& var, BatteryEmulatorSettingsStore& setti
return settings.getBool("WIFIAPENABLED", wifiap_enabled) ? "checked" : "";
}
if (var == "CANLOGUSB") {
return settings.getBool("CANLOGUSB") ? "checked" : "";
}
if (var == "USBENABLED") {
return settings.getBool("USBENABLED") ? "checked" : "";
}
if (var == "WEBENABLED") {
return settings.getBool("WEBENABLED") ? "checked" : "";
}
if (var == "CANLOGSD") {
return settings.getBool("CANLOGSD") ? "checked" : "";
}
if (var == "SDLOGENABLED") {
return settings.getBool("SDLOGENABLED") ? "checked" : "";
}
if (var == "MQTTENABLED") {
return settings.getBool("MQTTENABLED") ? "checked" : "";
}
@ -468,6 +517,66 @@ String settings_processor(const String& var, BatteryEmulatorSettingsStore& setti
return String(datalayer.charger.charger_setpoint_HV_IDC, 1);
}
if (var == "SOFAR_ID") {
return String(settings.getUInt("SOFAR_ID", 0));
}
if (var == "INVCELLS") {
return String(settings.getUInt("INVCELLS", 0));
}
if (var == "INVMODULES") {
return String(settings.getUInt("INVMODULES", 0));
}
if (var == "INVCELLSPER") {
return String(settings.getUInt("INVCELLSPER", 0));
}
if (var == "INVVLEVEL") {
return String(settings.getUInt("INVVLEVEL", 0));
}
if (var == "INVCAPACITY") {
return String(settings.getUInt("INVCAPACITY", 0));
}
if (var == "INVBTYPE") {
return String(settings.getUInt("INVBTYPE", 0));
}
if (var == "INVICNT") {
return settings.getBool("INVICNT") ? "checked" : "";
}
if (var == "DIGITALHVIL") {
return settings.getBool("DIGITALHVIL") ? "checked" : "";
}
if (var == "GTWCOUNTRY") {
return options_from_map(settings.getUInt("GTWCOUNTRY", 0), tesla_countries);
}
if (var == "GTWRHD") {
return settings.getBool("GTWRHD") ? "checked" : "";
}
if (var == "GTWMAPREG") {
return options_from_map(settings.getUInt("GTWMAPREG", 0), tesla_mapregion);
}
if (var == "GTWCHASSIS") {
return options_from_map(settings.getUInt("GTWCHASSIS", 0), tesla_chassis);
}
if (var == "GTWPACK") {
return options_from_map(settings.getUInt("GTWPACK", 0), tesla_pack);
}
if (var == "LEDMODE") {
return options_from_map(settings.getUInt("LEDMODE", 0), led_modes);
}
return String();
}
@ -527,10 +636,6 @@ const char* getCANInterfaceName(CAN_Interface interface) {
function editPassword(){var value=prompt('Enter new password:');if(value!==null){var xhr=new
XMLHttpRequest();xhr.onload=editComplete;xhr.onerror=editError;xhr.open('GET','/updatePassword?value='+encodeURIComponent(value),true);xhr.send();}}
function editSofarID(){var value=prompt('For double battery setups. Which battery ID should this emulator send? Remember to reboot after configuring this! Enter new value between (0-15):');
if(value!==null){if(value>=0&&value<=15){var xhr=new XMLHttpRequest();xhr.onload=editComplete;xhr.onerror=editError;xhr.open('GET','/updateSofarID?value='+value,true);xhr.send();}
else {alert('Invalid value. Please enter a value between 0 and 15.');}}}
function editWh(){var value=prompt('How much energy the battery can store. Enter new Wh value (1-400000):');
if(value!==null){if(value>=1&&value<=400000){var xhr=new
XMLHttpRequest();xhr.onload=editComplete;xhr.onerror=editError;xhr.open('GET','/updateBatterySize?value='+value,true);xhr.send();}else{
@ -658,11 +763,31 @@ const char* getCANInterfaceName(CAN_Interface interface) {
display: contents;
}
form .if-tesla { display: none; }
form[data-battery="32"] .if-tesla, form[data-battery="33"] .if-tesla {
display: contents;
}
form .if-dblbtr { display: none; }
form[data-dblbtr="true"] .if-dblbtr {
display: contents;
}
form .if-sofar { display: none; }
form[data-inverter="17"] .if-sofar {
display: contents;
}
form .if-pylonish { display: none; }
form[data-inverter="4"] .if-pylonish, form[data-inverter="10"] .if-pylonish, form[data-inverter="19"] .if-pylonish {
display: contents;
}
form .if-solax { display: none; }
form[data-inverter="18"] .if-solax {
display: contents;
}
form .if-mqtt { display: none; }
form[data-mqttenabled="true"] .if-mqtt {
display: contents;
@ -692,6 +817,25 @@ const char* getCANInterfaceName(CAN_Interface interface) {
%BATTTYPE%
</select>
<div class="if-tesla">
<label>Digital HVIL (2024+): </label>
<input type='checkbox' name='DIGITALHVIL' value='on' style='margin-left: 0;' %DIGITALHVIL% />
<label>Right hand drive: </label>
<input type='checkbox' name='GTWRHD' value='on' style='margin-left: 0;' %GTWRHD% />
<label for='GTWCOUNTRY'>Country code: </label><select name='GTWCOUNTRY' id='GTWCOUNTRY'>
%GTWCOUNTRY%
</select>
<label for='GTWMAPREG'>Map region: </label><select name='GTWMAPREG' id='GTWMAPREG'>
%GTWMAPREG%
</select>
<label for='GTWCHASSIS'>Chassis type: </label><select name='GTWCHASSIS' id='GTWCHASSIS'>
%GTWCHASSIS%
</select>
<label for='GTWPACK'>Pack type: </label><select name='GTWPACK' id='GTWPACK'>
%GTWPACK%
</select>
</div>
<div class="if-battery">
<label for='BATTCOMM'>Battery comm I/F: </label><select name='BATTCOMM' id='BATTCOMM'>
%BATTCOMM%
@ -726,6 +870,40 @@ const char* getCANInterfaceName(CAN_Interface interface) {
</select>
</div>
<div class="if-sofar">
<label>Sofar Battery ID (0-15): </label>
<input name='SOFAR_ID' type='text' value="%SOFAR_ID%" pattern="^[0-9]{1,2}$" />
</div>
<div class="if-pylonish">
<label>Reported cell count (0 for default): </label>
<input name='INVCELLS' type='text' value="%INVCELLS%" pattern="^[0-9]+$" />
</div>
<div class="if-pylonish if-solax">
<label>Reported module count (0 for default): </label>
<input name='INVMODULES' type='text' value="%INVMODULES%" pattern="^[0-9]+$" />
</div>
<div class="if-pylonish">
<label>Reported cells per module (0 for default): </label>
<input name='INVCELLSPER' type='text' value="%INVCELLSPER%" pattern="^[0-9]+$" />
<label>Reported voltage level (0 for default): </label>
<input name='INVVLEVEL' type='text' value="%INVVLEVEL%" pattern="^[0-9]+$" />
<label>Reported Ah capacity (0 for default): </label>
<input name='INVCAPACITY' type='text' value="%INVCAPACITY%" pattern="^[0-9]+$" />
</div>
<div class="if-solax">
<label>Reported battery type (in decimal): </label>
<input name='INVBTYPE' type='text' value="%INVBTYPE%" pattern="^[0-9]+$" />
<label>Inverter should ignore contactors: </label>
<input type='checkbox' name='INVICNT' value='on' style='margin-left: 0;' %INVICNT% />
</div>
<label>Charger: </label><select name='charger'>
%CHGTYPE%
</select>
@ -785,6 +963,25 @@ const char* getCANInterfaceName(CAN_Interface interface) {
<label>Custom hostname: </label>
<input type='text' name='HOSTNAME' value="%HOSTNAME%" />
<label>Enable CAN logging via USB serial: </label>
<input type='checkbox' name='CANLOGUSB' value='on' style='margin-left: 0;' %CANLOGUSB% />
<label>Enable logging via USB serial: </label>
<input type='checkbox' name='USBENABLED' value='on' style='margin-left: 0;' %USBENABLED% />
<label>Enable logging via Webserver: </label>
<input type='checkbox' name='WEBENABLED' value='on' style='margin-left: 0;' %WEBENABLED% />
<label>Enable CAN logging via SD card: </label>
<input type='checkbox' name='CANLOGSD' value='on' style='margin-left: 0;' %CANLOGSD% />
<label>Enable logging via SD card: </label>
<input type='checkbox' name='SDLOGENABLED' value='on' style='margin-left: 0;' %SDLOGENABLED% />
<label for='LEDMODE'>Status LED pattern: </label><select name='LEDMODE' id='LEDMODE'>
%LEDMODE%
</select>
<label>Enable MQTT: </label>
<input type='checkbox' name='MQTTENABLED' value='on' style='margin-left: 0;' %MQTTENABLED% />
@ -826,8 +1023,6 @@ const char* getCANInterfaceName(CAN_Interface interface) {
<h4 style='color: white;' class="%BATTERY2CLASS%">Battery interface: <span id='Battery2'>%BATTERY2INTF%</span></h4>
<h4 style='color: white;' class="%INVCLASS%">Inverter interface: <span id='Inverter'>%INVINTF%</span></h4>
<h4 style='color: white;' class="%INVBIDCLASS%">Battery ID: <span>%INVBID%</span> <button onclick='editSofarID()'>Edit</button></h4>
<h4 style='color: white;' class="%SHUNTCLASS%">Shunt interface: <span id='Inverter'>%SHUNTINTF%</span></h4>

View file

@ -267,13 +267,13 @@ void init_webserver() {
}
});
#if defined(DEBUG_VIA_WEB) || defined(LOG_TO_SD)
// Route for going to debug logging web page
server.on("/log", HTTP_GET, [](AsyncWebServerRequest* request) {
AsyncWebServerResponse* response = request->beginResponse(200, "text/html", debug_logger_processor());
request->send(response);
});
#endif // DEBUG_VIA_WEB
if (datalayer.system.info.web_logging_active || datalayer.system.info.SD_logging_active) {
// Route for going to debug logging web page
server.on("/log", HTTP_GET, [](AsyncWebServerRequest* request) {
AsyncWebServerResponse* response = request->beginResponse(200, "text/html", debug_logger_processor());
request->send(response);
});
}
// Define the handler to stop can logging
server.on("/stop_can_logging", HTTP_GET, [](AsyncWebServerRequest* request) {
@ -289,93 +289,89 @@ void init_webserver() {
},
handleFileUpload);
#ifndef LOG_CAN_TO_SD
// Define the handler to export can log
server.on("/export_can_log", HTTP_GET, [](AsyncWebServerRequest* request) {
String logs = String(datalayer.system.info.logged_can_messages);
if (logs.length() == 0) {
logs = "No logs available.";
}
if (datalayer.system.info.CAN_SD_logging_active) {
// Define the handler to export can log
server.on("/export_can_log", HTTP_GET, [](AsyncWebServerRequest* request) {
pause_can_writing();
request->send(SD_MMC, CAN_LOG_FILE, String(), true);
resume_can_writing();
});
// Get the current time
time_t now = time(nullptr);
struct tm timeinfo;
localtime_r(&now, &timeinfo);
// Define the handler to delete can log
server.on("/delete_can_log", HTTP_GET, [](AsyncWebServerRequest* request) {
delete_can_log();
request->send(200, "text/plain", "Log file deleted");
});
} else {
// Define the handler to export can log
server.on("/export_can_log", HTTP_GET, [](AsyncWebServerRequest* request) {
String logs = String(datalayer.system.info.logged_can_messages);
if (logs.length() == 0) {
logs = "No logs available.";
}
// Ensure time retrieval was successful
char filename[32];
if (strftime(filename, sizeof(filename), "canlog_%H-%M-%S.txt", &timeinfo)) {
// Valid filename created
} else {
// Fallback filename if automatic timestamping failed
strcpy(filename, "battery_emulator_can_log.txt");
}
// Get the current time
time_t now = time(nullptr);
struct tm timeinfo;
localtime_r(&now, &timeinfo);
// Use request->send with dynamic headers
AsyncWebServerResponse* response = request->beginResponse(200, "text/plain", logs);
response->addHeader("Content-Disposition", String("attachment; filename=\"") + String(filename) + "\"");
request->send(response);
});
#endif
// Ensure time retrieval was successful
char filename[32];
if (strftime(filename, sizeof(filename), "canlog_%H-%M-%S.txt", &timeinfo)) {
// Valid filename created
} else {
// Fallback filename if automatic timestamping failed
strcpy(filename, "battery_emulator_can_log.txt");
}
#ifdef LOG_CAN_TO_SD
// Define the handler to export can log
server.on("/export_can_log", HTTP_GET, [](AsyncWebServerRequest* request) {
pause_can_writing();
request->send(SD_MMC, CAN_LOG_FILE, String(), true);
resume_can_writing();
});
// Use request->send with dynamic headers
AsyncWebServerResponse* response = request->beginResponse(200, "text/plain", logs);
response->addHeader("Content-Disposition", String("attachment; filename=\"") + String(filename) + "\"");
request->send(response);
});
}
// Define the handler to delete can log
server.on("/delete_can_log", HTTP_GET, [](AsyncWebServerRequest* request) {
delete_can_log();
request->send(200, "text/plain", "Log file deleted");
});
#endif
if (datalayer.system.info.SD_logging_active) {
// Define the handler to delete log file
server.on("/delete_log", HTTP_GET, [](AsyncWebServerRequest* request) {
delete_log();
request->send(200, "text/plain", "Log file deleted");
});
#ifdef LOG_TO_SD
// Define the handler to delete log file
server.on("/delete_log", HTTP_GET, [](AsyncWebServerRequest* request) {
delete_log();
request->send(200, "text/plain", "Log file deleted");
});
// Define the handler to export debug log
server.on("/export_log", HTTP_GET, [](AsyncWebServerRequest* request) {
pause_log_writing();
request->send(SD_MMC, LOG_FILE, String(), true);
resume_log_writing();
});
} else {
// Define the handler to export debug log
server.on("/export_log", HTTP_GET, [](AsyncWebServerRequest* request) {
String logs = String(datalayer.system.info.logged_can_messages);
if (logs.length() == 0) {
logs = "No logs available.";
}
// Define the handler to export debug log
server.on("/export_log", HTTP_GET, [](AsyncWebServerRequest* request) {
pause_log_writing();
request->send(SD_MMC, LOG_FILE, String(), true);
resume_log_writing();
});
#endif
// Get the current time
time_t now = time(nullptr);
struct tm timeinfo;
localtime_r(&now, &timeinfo);
#ifndef LOG_TO_SD
// Define the handler to export debug log
server.on("/export_log", HTTP_GET, [](AsyncWebServerRequest* request) {
String logs = String(datalayer.system.info.logged_can_messages);
if (logs.length() == 0) {
logs = "No logs available.";
}
// Ensure time retrieval was successful
char filename[32];
if (strftime(filename, sizeof(filename), "log_%H-%M-%S.txt", &timeinfo)) {
// Valid filename created
} else {
// Fallback filename if automatic timestamping failed
strcpy(filename, "battery_emulator_log.txt");
}
// Get the current time
time_t now = time(nullptr);
struct tm timeinfo;
localtime_r(&now, &timeinfo);
// Ensure time retrieval was successful
char filename[32];
if (strftime(filename, sizeof(filename), "log_%H-%M-%S.txt", &timeinfo)) {
// Valid filename created
} else {
// Fallback filename if automatic timestamping failed
strcpy(filename, "battery_emulator_log.txt");
}
// Use request->send with dynamic headers
AsyncWebServerResponse* response = request->beginResponse(200, "text/plain", logs);
response->addHeader("Content-Disposition", String("attachment; filename=\"") + String(filename) + "\"");
request->send(response);
});
#endif
// Use request->send with dynamic headers
AsyncWebServerResponse* response = request->beginResponse(200, "text/plain", logs);
response->addHeader("Content-Disposition", String("attachment; filename=\"") + String(filename) + "\"");
request->send(response);
});
}
// Route for going to cellmonitor web page
def_route_with_auth("/cellmonitor", server, HTTP_GET, [](AsyncWebServerRequest* request) {
@ -413,8 +409,9 @@ void init_webserver() {
};
const char* boolSettingNames[] = {
"DBLBTR", "CNTCTRL", "CNTCTRLDBL", "PWMCNTCTRL", "PERBMSRESET", "REMBMSRESET",
"CANFDASCAN", "WIFIAPENABLED", "MQTTENABLED", "HADISC", "MQTTTOPICS",
"DBLBTR", "CNTCTRL", "CNTCTRLDBL", "PWMCNTCTRL", "PERBMSRESET", "SDLOGENABLED", "REMBMSRESET",
"USBENABLED", "CANLOGUSB", "WEBENABLED", "CANFDASCAN", "CANLOGSD", "WIFIAPENABLED", "MQTTENABLED",
"HADISC", "MQTTTOPICS", "INVICNT", "GTWRHD", "DIGITALHVIL",
};
// Handles the form POST from UI to save settings of the common image
@ -494,6 +491,42 @@ void init_webserver() {
settings.saveString("MQTTDEVICENAME", p->value().c_str());
} else if (p->name() == "HADEVICEID") {
settings.saveString("HADEVICEID", p->value().c_str());
} else if (p->name() == "SOFAR_ID") {
auto type = atoi(p->value().c_str());
settings.saveUInt("SOFAR_ID", type);
} else if (p->name() == "INVCELLS") {
auto type = atoi(p->value().c_str());
settings.saveUInt("INVCELLS", type);
} else if (p->name() == "INVMODULES") {
auto type = atoi(p->value().c_str());
settings.saveUInt("INVMODULES", type);
} else if (p->name() == "INVCELLSPER") {
auto type = atoi(p->value().c_str());
settings.saveUInt("INVCELLSPER", type);
} else if (p->name() == "INVVLEVEL") {
auto type = atoi(p->value().c_str());
settings.saveUInt("INVVLEVEL", type);
} else if (p->name() == "INVCAPACITY") {
auto type = atoi(p->value().c_str());
settings.saveUInt("INVCAPACITY", type);
} else if (p->name() == "INVBTYPE") {
auto type = atoi(p->value().c_str());
settings.saveUInt("INVBTYPE", (int)type);
} else if (p->name() == "GTWCOUNTRY") {
auto type = atoi(p->value().c_str());
settings.saveUInt("GTWCOUNTRY", type);
} else if (p->name() == "GTWMAPREG") {
auto type = atoi(p->value().c_str());
settings.saveUInt("GTWMAPREG", type);
} else if (p->name() == "GTWCHASSIS") {
auto type = atoi(p->value().c_str());
settings.saveUInt("GTWCHASSIS", type);
} else if (p->name() == "GTWPACK") {
auto type = atoi(p->value().c_str());
settings.saveUInt("GTWPACK", type);
} else if (p->name() == "LEDMODE") {
auto type = atoi(p->value().c_str());
settings.saveUInt("LEDMODE", type);
}
for (auto& boolSetting : boolSettings) {
@ -579,10 +612,6 @@ void init_webserver() {
update_string_setting(route, [setter](String value) { setter(value.toInt()); });
};
// Route for editing Sofar ID
update_int_setting("/updateSofarID",
[](int value) { datalayer.battery.settings.sofar_user_specified_battery_id = value; });
// Route for editing Wh
update_int_setting("/updateBatterySize", [](int value) { datalayer.battery.info.total_capacity_Wh = value; });
@ -836,6 +865,28 @@ String processor(const String& var) {
content += "button:hover { background-color: #3A4A52; }";
content += "h2 { font-size: 1.2em; margin: 0.3em 0 0.5em 0; }";
content += "h4 { margin: 0.6em 0; line-height: 1.2; }";
//content += ".tooltip { position: relative; display: inline-block; }";
content += ".tooltip .tooltiptext {";
content += " visibility: hidden;";
content += " width: 200px;";
content += " background-color: #3A4A52;"; // Matching your button hover color
content += " color: white;";
content += " text-align: center;";
content += " border-radius: 6px;";
content += " padding: 8px;";
content += " position: absolute;";
content += " z-index: 1;";
content += " bottom: 125%;";
content += " left: 50%;";
content += " margin-left: -100px;";
content += " opacity: 0;";
content += " transition: opacity 0.3s;";
content += " font-size: 0.9em;";
content += " font-weight: normal;";
content += " line-height: 1.4;";
content += "}";
content += ".tooltip:hover .tooltiptext { visibility: visible; opacity: 1; }";
content += ".tooltip-icon { color: #505E67; cursor: help; }"; // Matching your button color
content += "</style>";
// Compact header
@ -943,21 +994,18 @@ String processor(const String& var) {
content += "<div style='background-color: ";
}
switch (led_get_color()) {
case led_color::GREEN:
switch (get_emulator_status()) {
case EMULATOR_STATUS::STATUS_OK:
content += "#2D3F2F;";
break;
case led_color::YELLOW:
case EMULATOR_STATUS::STATUS_WARNING:
content += "#F5CC00;";
break;
case led_color::BLUE:
content += "#2B35AF;"; // Blue in test mode
break;
case led_color::RED:
case EMULATOR_STATUS::STATUS_ERROR:
content += "#A70107;";
break;
default: // Some new color, make background green
content += "#2D3F2F;";
case EMULATOR_STATUS::STATUS_UPDATING:
content += "#2B35AF;"; // Blue in test mode
break;
}
@ -1115,58 +1163,6 @@ String processor(const String& var) {
}
}
content += "<h4>Battery allows contactor closing: ";
if (datalayer.system.status.battery_allows_contactor_closing == true) {
content += "<span>&#10003;</span>";
} else {
content += "<span style='color: red;'>&#10005;</span>";
}
content += " Inverter allows contactor closing: ";
if (datalayer.system.status.inverter_allows_contactor_closing == true) {
content += "<span>&#10003;</span></h4>";
} else {
content += "<span style='color: red;'>&#10005;</span></h4>";
}
if (emulator_pause_status == NORMAL)
content += "<h4>Power status: " + String(get_emulator_pause_status().c_str()) + " </h4>";
else
content += "<h4 style='color: red;'>Power status: " + String(get_emulator_pause_status().c_str()) + " </h4>";
if (contactor_control_enabled) {
content += "<h4>Contactors controlled by emulator, state: ";
if (datalayer.system.status.contactors_engaged) {
content += "<span style='color: green;'>ON</span>";
} else {
content += "<span style='color: red;'>OFF</span>";
}
content += "</h4>";
if (contactor_control_enabled_double_battery) {
if (pwm_contactor_control) {
content += "<h4>Cont. Neg.: ";
if (datalayer.system.status.contactors_battery2_engaged) {
content += "<span style='color: green;'>Economized</span>";
content += " Cont. Pos.: ";
content += "<span style='color: green;'>Economized</span>";
} else {
content += "<span style='color: red;'>&#10005;</span>";
content += " Cont. Pos.: ";
content += "<span style='color: red;'>&#10005;</span>";
}
} else if (
esp32hal->SECOND_BATTERY_CONTACTORS_PIN() !=
GPIO_NUM_NC) { // No PWM_CONTACTOR_CONTROL , we can read the pin and see feedback. Helpful if channel overloaded
content += "<h4>Cont. Neg.: ";
if (digitalRead(esp32hal->SECOND_BATTERY_CONTACTORS_PIN()) == HIGH) {
content += "<span style='color: green;'>&#10003;</span>";
} else {
content += "<span style='color: red;'>&#10005;</span>";
}
} //no PWM_CONTACTOR_CONTROL
content += "</h4>";
}
}
// Close the block
content += "</div>";
@ -1264,71 +1260,85 @@ String processor(const String& var) {
} else { // > 0
content += "<h4>Battery charging!</h4>";
}
content += "<h4>Automatic contactor closing allowed:</h4>";
content += "<h4>Battery: ";
if (datalayer.system.status.battery2_allowed_contactor_closing == true) {
content += "<span>&#10003;</span>";
} else {
content += "<span style='color: red;'>&#10005;</span>";
}
content += " Inverter: ";
if (datalayer.system.status.inverter_allows_contactor_closing == true) {
content += "<span>&#10003;</span></h4>";
} else {
content += "<span style='color: red;'>&#10005;</span></h4>";
}
if (emulator_pause_status == NORMAL)
content += "<h4>Power status: " + String(get_emulator_pause_status().c_str()) + " </h4>";
else
content += "<h4 style='color: red;'>Power status: " + String(get_emulator_pause_status().c_str()) + " </h4>";
if (contactor_control_enabled) {
content += "<h4>Contactors controlled by emulator, state: ";
if (datalayer.system.status.contactors_battery2_engaged) {
content += "<span style='color: green;'>ON</span>";
} else {
content += "<span style='color: red;'>OFF</span>";
}
content += "</h4>";
if (contactor_control_enabled_double_battery) {
content += "<h4>Cont. Neg.: ";
if (pwm_contactor_control) {
if (datalayer.system.status.contactors_battery2_engaged) {
content += "<span style='color: green;'>Economized</span>";
content += " Cont. Pos.: ";
content += "<span style='color: green;'>Economized</span>";
} else {
content += "<span style='color: red;'>&#10005;</span>";
content += " Cont. Pos.: ";
content += "<span style='color: red;'>&#10005;</span>";
}
} else { // No PWM_CONTACTOR_CONTROL , we can read the pin and see feedback. Helpful if channel overloaded
#if defined(SECOND_POSITIVE_CONTACTOR_PIN) && defined(SECOND_NEGATIVE_CONTACTOR_PIN)
if (digitalRead(SECOND_NEGATIVE_CONTACTOR_PIN) == HIGH) {
content += "<span style='color: green;'>&#10003;</span>";
} else {
content += "<span style='color: red;'>&#10005;</span>";
}
content += " Cont. Pos.: ";
if (digitalRead(SECOND_POSITIVE_CONTACTOR_PIN) == HIGH) {
content += "<span style='color: green;'>&#10003;</span>";
} else {
content += "<span style='color: red;'>&#10005;</span>";
}
#endif
}
content += "</h4>";
}
}
content += "</div>";
content += "</div>";
}
}
// Block for Contactor status and component request status
// Start a new block with gray background color
content += "<div style='background-color: #333; padding: 10px; margin-bottom: 10px;border-radius: 50px'>";
if (emulator_pause_status == NORMAL) {
content += "<h4>Power status: " + String(get_emulator_pause_status().c_str()) + " </h4>";
} else {
content += "<h4 style='color: red;'>Power status: " + String(get_emulator_pause_status().c_str()) + " </h4>";
}
content += "<h4>Emulator allows contactor closing: ";
if (datalayer.battery.status.bms_status == FAULT) {
content += "<span style='color: red;'>&#10005;</span>";
} else {
content += "<span>&#10003;</span>";
}
content += " Inverter allows contactor closing: ";
if (datalayer.system.status.inverter_allows_contactor_closing == true) {
content += "<span>&#10003;</span></h4>";
} else {
content += "<span style='color: red;'>&#10005;</span></h4>";
}
if (battery2) {
content += "<h4>Secondary battery allowed to join ";
if (datalayer.system.status.battery2_allowed_contactor_closing == true) {
content += "<span>&#10003;</span>";
} else {
content += "<span style='color: red;'>&#10005; (voltage mismatch)</span>";
}
}
if (!contactor_control_enabled) {
content += "<div class=\"tooltip\">";
content += "<h4>Contactors not fully controlled via emulator <span style=\"color:orange\">[?]</span></h4>";
content +=
"<span class=\"tooltiptext\">This means you are either running CAN controlled contactors OR manually "
"powering the contactors. Battery-Emulator will have limited amount of control over the contactors!</span>";
content += "</div>";
} else { //contactor_control_enabled TRUE
content += "<div class=\"tooltip\"><h4>Contactors controlled by emulator, state: ";
if (datalayer.system.status.contactors_engaged == 0) {
content += "<span style='color: green;'>PRECHARGE</span>";
} else if (datalayer.system.status.contactors_engaged == 1) {
content += "<span style='color: green;'>ON</span>";
} else if (datalayer.system.status.contactors_engaged == 2) {
content += "<span style='color: red;'>OFF</span>";
content += "<span class=\"tooltip-icon\"> [!]</span>";
content +=
"<span class=\"tooltiptext\">Emulator spent too much time in critical FAULT event. Investigate event "
"causing this via Events page. Reboot required to resume operation!</span>";
}
content += "</h4></div>";
if (contactor_control_enabled_double_battery && battery2) {
content += "<h4>Secondary battery contactor, state: ";
if (pwm_contactor_control) {
if (datalayer.system.status.contactors_battery2_engaged) {
content += "<span style='color: green;'>Economized</span>";
} else {
content += "<span style='color: red;'>OFF</span>";
}
} else if (
esp32hal->SECOND_BATTERY_CONTACTORS_PIN() !=
GPIO_NUM_NC) { // No PWM_CONTACTOR_CONTROL , we can read the pin and see feedback. Helpful if channel overloaded
if (digitalRead(esp32hal->SECOND_BATTERY_CONTACTORS_PIN()) == HIGH) {
content += "<span style='color: green;'>ON</span>";
} else {
content += "<span style='color: red;'>OFF</span>";
}
} //no PWM_CONTACTOR_CONTROL
content += "</h4>";
}
}
// Close the block
content += "</div>";
if (charger) {
// Start a new block with orange background color
@ -1390,9 +1400,9 @@ String processor(const String& var) {
content += "<button onclick='Advanced()'>More Battery Info</button> ";
content += "<button onclick='CANlog()'>CAN logger</button> ";
content += "<button onclick='CANreplay()'>CAN replay</button> ";
#if defined(DEBUG_VIA_WEB) || defined(LOG_TO_SD)
content += "<button onclick='Log()'>Log</button> ";
#endif // DEBUG_VIA_WEB
if (datalayer.system.info.web_logging_active || datalayer.system.info.SD_logging_active) {
content += "<button onclick='Log()'>Log</button> ";
}
content += "<button onclick='Cellmon()'>Cellmonitor</button> ";
content += "<button onclick='Events()'>Events</button> ";
content += "<button onclick='askReboot()'>Reboot Emulator</button>";
@ -1472,9 +1482,7 @@ void onOTAProgress(size_t current, size_t final) {
// Log every 1 second
if (millis() - ota_progress_millis > 1000) {
ota_progress_millis = millis();
#ifdef DEBUG_LOG
logging.printf("OTA Progress Current: %u bytes, Final: %u bytes\n", current, final);
#endif // DEBUG_LOG
// Reset the "watchdog"
ota_timeout_timer.reset();
}
@ -1491,13 +1499,9 @@ void onOTAEnd(bool success) {
// Max Charge/Discharge = 0; CAN = stop; contactors = open
setBatteryPause(true, true, true, false);
// a reboot will be done by the OTA library. no need to do anything here
#ifdef DEBUG_LOG
logging.println("OTA update finished successfully!");
#endif // DEBUG_LOG
} else {
#ifdef DEBUG_LOG
logging.println("There was an error during OTA update!");
#endif // DEBUG_LOG
//try to Resume the battery pause and CAN communication
setBatteryPause(false, false);
}

View file

@ -130,33 +130,22 @@ void wifi_monitor() {
// Try WiFi.reconnect() if it was successfully connected at least once
if (hasConnectedBefore) {
lastReconnectAttempt = currentMillis; // Reset reconnection attempt timer
#ifdef DEBUG_LOG
logging.println("Wi-Fi reconnect attempt...");
#endif
if (WiFi.reconnect()) {
#ifdef DEBUG_LOG
logging.println("Wi-Fi reconnect attempt sucess...");
#endif
reconnectAttempts = 0; // Reset the attempt counter on successful reconnect
} else {
#ifdef DEBUG_LOG
logging.println("Wi-Fi reconnect attempt error...");
#endif
reconnectAttempts++;
if (reconnectAttempts >= MAX_RECONNECT_ATTEMPTS) {
#ifdef DEBUG_LOG
logging.println("Failed to reconnect multiple times, forcing a full connection attempt...");
#endif
FullReconnectToWiFi();
}
}
} else {
// If no previous connection, force a full connection attempt
if (currentMillis - lastReconnectAttempt > current_full_reconnect_interval) {
#ifdef DEBUG_LOG
logging.println("No previous OK connection, force a full connection attempt...");
#endif
wifiap_enabled = true;
WiFi.mode(WIFI_AP_STA);
init_WiFi_AP();
@ -188,17 +177,13 @@ void connectToWiFi() {
if (WiFi.status() != WL_CONNECTED) {
lastReconnectAttempt = millis(); // Reset the reconnect attempt timer
#ifdef DEBUG_LOG
logging.println("Connecting to Wi-Fi...");
#endif
DEBUG_PRINTF("Connecting to Wi-Fi SSID: %s, password: %s, Channel: %d\n", ssid.c_str(), password.c_str(),
wifi_channel);
WiFi.begin(ssid.c_str(), password.c_str(), wifi_channel);
} else {
#ifdef DEBUG_LOG
logging.println("Wi-Fi already connected.");
#endif
}
}
@ -220,11 +205,9 @@ void onWifiConnect(WiFiEvent_t event, WiFiEventInfo_t info) {
void onWifiGotIP(WiFiEvent_t event, WiFiEventInfo_t info) {
//clear disconnects events if we got a IP
clear_event(EVENT_WIFI_DISCONNECT);
#ifdef DEBUG_LOG
logging.print("Wi-Fi Got IP. ");
logging.print("IP address: ");
logging.println(WiFi.localIP().toString());
#endif
}
// Event handler for Wi-Fi disconnection
@ -233,9 +216,7 @@ void onWifiDisconnect(WiFiEvent_t event, WiFiEventInfo_t info) {
if (connected_once) {
set_event(EVENT_WIFI_DISCONNECT, 0);
}
#ifdef DEBUG_LOG
logging.println("Wi-Fi disconnected.");
#endif
//we dont do anything here, the reconnect will be handled by the monitor
//too many events received when the connection is lost
//normal reconnect retry start at first 2 seconds
@ -254,9 +235,7 @@ void init_mDNS() {
// Initialize mDNS .local resolution
if (!MDNS.begin(mdnsHost)) {
#ifdef DEBUG_LOG
logging.println("Error setting up MDNS responder!");
#endif
} else {
// Advertise via bonjour the service so we can auto discover these battery emulators on the local network.
MDNS.addService(mdnsHost, "tcp", 80);

View file

@ -1,6 +1,7 @@
#include "FERROAMP-CAN.h"
#include "../communication/can/comm_can.h"
#include "../datalayer/datalayer.h"
#include "../inverter/INVERTERS.h"
//#define SEND_0 //If defined, the messages will have ID ending with 0 (useful for some inverters)
#define SEND_1 //If defined, the messages will have ID ending with 1 (useful for some inverters)
@ -364,3 +365,38 @@ void FerroampCanInverter::send_system_data() { //System equipment information
transmit_can_frame(&PYLON_4291);
#endif
}
bool FerroampCanInverter::setup() {
if (user_selected_inverter_cells > 0) {
PYLON_7320.data.u8[0] = user_selected_inverter_cells & 0xff;
PYLON_7320.data.u8[1] = (uint8_t)(user_selected_inverter_cells >> 8);
PYLON_7321.data.u8[0] = user_selected_inverter_cells & 0xff;
PYLON_7321.data.u8[1] = (uint8_t)(user_selected_inverter_cells >> 8);
}
if (user_selected_inverter_modules > 0) {
PYLON_7320.data.u8[2] = user_selected_inverter_modules;
PYLON_7321.data.u8[2] = user_selected_inverter_modules;
}
if (user_selected_inverter_cells_per_module > 0) {
PYLON_7320.data.u8[3] = user_selected_inverter_cells_per_module;
PYLON_7321.data.u8[3] = user_selected_inverter_cells_per_module;
}
if (user_selected_inverter_voltage_level > 0) {
PYLON_7320.data.u8[4] = user_selected_inverter_voltage_level & 0xff;
PYLON_7320.data.u8[5] = (uint8_t)(user_selected_inverter_voltage_level >> 8);
PYLON_7321.data.u8[4] = user_selected_inverter_voltage_level & 0xff;
PYLON_7321.data.u8[5] = (uint8_t)(user_selected_inverter_voltage_level >> 8);
}
if (user_selected_inverter_ah_capacity > 0) {
PYLON_7320.data.u8[6] = user_selected_inverter_ah_capacity & 0xff;
PYLON_7320.data.u8[7] = (uint8_t)(user_selected_inverter_ah_capacity >> 8);
PYLON_7321.data.u8[6] = user_selected_inverter_ah_capacity & 0xff;
PYLON_7321.data.u8[7] = (uint8_t)(user_selected_inverter_ah_capacity >> 8);
}
return true;
}

View file

@ -10,6 +10,7 @@
class FerroampCanInverter : public CanInverterProtocol {
public:
const char* name() override { return Name; }
bool setup() override;
void update_values();
void transmit_can(unsigned long currentMillis);
void map_can_frame_to_variable(CAN_frame rx_frame);

View file

@ -523,40 +523,23 @@ void FoxessCanInverter::map_can_frame_to_variable(CAN_frame rx_frame) {
if (rx_frame.ID == 0x1871) {
datalayer.system.status.CAN_inverter_still_alive = CAN_STILL_ALIVE;
if (rx_frame.data.u8[0] == 0x03) { //0x1871 [0x03, 0x06, 0x17, 0x05, 0x09, 0x09, 0x28, 0x22]
//This message is sent by the inverter every '6' seconds (0.5s after the pack serial numbers)
//and contains a timestamp in bytes 2-7 i.e. <YY>,<MM>,<DD>,<HH>,<mm>,<ss>
#ifdef DEBUG_LOG
logging.println("Inverter sends current time and date");
#endif
//This message is sent by the inverter every '6' seconds (0.5s after the pack serial numbers)
//and contains a timestamp in bytes 2-7 i.e. <YY>,<MM>,<DD>,<HH>,<mm>,<ss>
} else if (rx_frame.data.u8[0] == 0x01) {
if (rx_frame.data.u8[4] == 0x00) {
// Inverter wants to know bms info (every 1s)
#ifdef DEBUG_LOG
logging.println("Inverter requests 1s BMS info, we reply");
#endif
// Inverter wants to know bms info (every 1s)
send_bms_info = true;
} else if (rx_frame.data.u8[4] == 0x01) { // b4 0x01 , 0x1871 [0x01, 0x00, 0x01, 0x00, 0x01, 0x00, 0x00, 0x00]
//Inverter wants to know all individual cellvoltages (occurs 6 seconds after valid BMS reply)
#ifdef DEBUG_LOG
logging.println("Inverter requests individual battery pack status, we reply");
#endif
send_individual_pack_status = true;
} else if (rx_frame.data.u8[4] == 0x04) { // b4 0x01 , 0x1871 [0x01, 0x00, 0x01, 0x00, 0x01, 0x00, 0x00, 0x00]
//Inverter wants to know all individual cellvoltages (occurs 6 seconds after valid BMS reply)
#ifdef DEBUG_LOG
logging.println("Inverter requests cellvoltages and temps, we reply");
#endif
send_cellvoltages = true;
}
} else if (rx_frame.data.u8[0] == 0x02) { //0x1871 [0x02, 0x00, 0x01, 0x00, 0x01, 0x00, 0x00, 0x00]
// Ack message
#ifdef DEBUG_LOG
logging.println("Inverter acks, no reply needed");
#endif
// Ack message
} else if (rx_frame.data.u8[0] == 0x05) { //0x1871 [0x05, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00]
#ifdef DEBUG_LOG
logging.println("Inverter wants to know serial numbers, we reply");
#endif
// Inverter wants to know serial numbers, we reply
send_serial_numbers = true;
}
}

View file

@ -4,6 +4,17 @@ InverterProtocol* inverter = nullptr;
InverterProtocolType user_selected_inverter_protocol = InverterProtocolType::BydModbus;
// Some user-configurable settings that can be used by inverters. These
// inverters should use sensible defaults if the corresponding user_selected
// value is zero.
uint16_t user_selected_inverter_cells = 0;
uint16_t user_selected_inverter_modules = 0;
uint16_t user_selected_inverter_cells_per_module = 0;
uint16_t user_selected_inverter_voltage_level = 0;
uint16_t user_selected_inverter_ah_capacity = 0;
uint16_t user_selected_inverter_battery_type = 0;
bool user_selected_inverter_ignore_contactors = false;
std::vector<InverterProtocolType> supported_inverter_protocols() {
std::vector<InverterProtocolType> types;

View file

@ -36,4 +36,12 @@ extern InverterProtocol* inverter;
// Call to initialize the build-time selected inverter. Safe to call even though inverter was not selected.
bool setup_inverter();
extern uint16_t user_selected_inverter_cells;
extern uint16_t user_selected_inverter_modules;
extern uint16_t user_selected_inverter_cells_per_module;
extern uint16_t user_selected_inverter_voltage_level;
extern uint16_t user_selected_inverter_ah_capacity;
extern uint16_t user_selected_inverter_battery_type;
extern bool user_selected_inverter_ignore_contactors;
#endif

View file

@ -5,27 +5,27 @@
enum class InverterProtocolType {
None = 0,
AforeCan,
BydCan,
BydModbus,
FerroampCan,
Foxess,
GrowattHv,
GrowattLv,
GrowattWit,
Kostal,
Pylon,
PylonLv,
Schneider,
SmaBydH,
SmaBydHvs,
SmaLv,
SmaTripower,
Sofar,
Solax,
Solxpow,
SolArkLv,
Sungrow,
AforeCan = 1,
BydCan = 2,
BydModbus = 3,
FerroampCan = 4,
Foxess = 5,
GrowattHv = 6,
GrowattLv = 7,
GrowattWit = 8,
Kostal = 9,
Pylon = 10,
PylonLv = 11,
Schneider = 12,
SmaBydH = 13,
SmaBydHvs = 14,
SmaLv = 15,
SmaTripower = 16,
Sofar = 17,
Solax = 18,
Solxpow = 19,
SolArkLv = 20,
Sungrow = 21,
Highest
};

View file

@ -14,16 +14,13 @@ void KostalInverterProtocol::float2frame(uint8_t* arr, float value, uint8_t fram
}
static void dbg_timestamp(void) {
#ifdef DEBUG_KOSTAL_RS485_DATA
logging.print("[");
logging.print(millis());
logging.print(" ms] ");
#endif
}
static void dbg_frame(uint8_t* frame, int len, const char* prefix) {
dbg_timestamp();
#ifdef DEBUG_KOSTAL_RS485_DATA
logging.print(prefix);
logging.print(": ");
for (uint8_t i = 0; i < len; i++) {
@ -34,26 +31,11 @@ static void dbg_frame(uint8_t* frame, int len, const char* prefix) {
logging.print(" ");
}
logging.println("");
#endif
#ifdef DEBUG_KOSTAL_RS485_DATA_USB
Serial.print(prefix);
Serial.print(": ");
for (uint8_t i = 0; i < len; i++) {
if (frame[i] < 0x10) {
Serial.print("0");
}
Serial.print(frame[i], HEX);
Serial.print(" ");
}
Serial.println("");
#endif
}
static void dbg_message(const char* msg) {
dbg_timestamp();
#ifdef DEBUG_KOSTAL_RS485_DATA
logging.println(msg);
#endif
}
/* https://en.wikipedia.org/wiki/Consistent_Overhead_Byte_Stuffing#Encoding_examples */
@ -154,24 +136,18 @@ void KostalInverterProtocol::update_values() {
float2frame(CYCLIC_DATA, (float)datalayer.battery.status.current_dA / 10, 18); // Last current
float2frame(CYCLIC_DATA, (float)datalayer.battery.status.current_dA / 10, 22); // Should be Avg current(1s)
// Close contactors after 7 battery info frames requested
if (f2_startup_count > 7) {
// Close contactors after 20 battery info frames requested
if (f2_startup_count > 20) {
datalayer.system.status.inverter_allows_contactor_closing = true;
dbg_message("inverter_allows_contactor_closing -> true");
dbg_message("inverter_allows_contactor_closing -> true (info frame)");
}
// On startup, byte 56 seems to be always 0x00 couple of frames,.
if (f2_startup_count < 9) {
CYCLIC_DATA[56] = 0x00;
} else {
if (datalayer.system.status.inverter_allows_contactor_closing) {
CYCLIC_DATA[56] = 0x01;
}
// On startup, byte 59 seems to be always 0x02 couple of frames,.
if (f2_startup_count < 14) {
CYCLIC_DATA[59] = 0x02;
} else {
CYCLIC_DATA[59] = 0x00;
} else {
CYCLIC_DATA[56] = 0x00;
CYCLIC_DATA[59] = 0x02;
}
#endif
@ -214,6 +190,12 @@ void KostalInverterProtocol::receive() // Runs as fast as possible to handle th
{
currentMillis = millis();
// Auto-reset contactor_test_active after 5 seconds
if (contactortestTimerActive && (millis() - contactortestTimerStart >= 5000)) {
datalayer.system.status.inverter_allows_contactor_closing = true;
dbg_message("inverter_allows_contactor_closing -> true (Contactor test ended)");
contactortestTimerActive = false;
}
if (datalayer.system.status.battery_allows_contactor_closing & !contactorMillis) {
contactorMillis = currentMillis;
}
@ -240,9 +222,17 @@ void KostalInverterProtocol::receive() // Runs as fast as possible to handle th
if (RS485_RXFRAME[6] == 0x5E) {
// Set State function
if (RS485_RXFRAME[7] == 0x00) {
// Allow contactor closing
datalayer.system.status.inverter_allows_contactor_closing = true;
dbg_message("inverter_allows_contactor_closing -> true (5E 02)");
send_kostal(ACK_FRAME, 8); // ACK
} else if (RS485_RXFRAME[7] == 0x04) {
// contactor test STATE, ACK sent
datalayer.system.status.inverter_allows_contactor_closing = false;
dbg_message("inverter_allows_contactor_closing -> false (Contactor test start)");
send_kostal(ACK_FRAME, 8); // ACK
contactortestTimerStart = currentMillis;
contactortestTimerActive = true;
} else if (RS485_RXFRAME[7] == 0xFF) {
// no ACK sent
} else {
@ -279,6 +269,8 @@ void KostalInverterProtocol::receive() // Runs as fast as possible to handle th
tmpframe[38] = calculate_kostal_crc(tmpframe, 38);
null_stuffer(tmpframe, 40);
send_kostal(tmpframe, 40);
datalayer.system.status.inverter_allows_contactor_closing = false;
dbg_message("inverter_allows_contactor_closing -> false (battery info sent)");
info_sent = true;
if (!startupMillis) {
startupMillis = currentMillis;

View file

@ -8,13 +8,6 @@
#define SELECTED_INVERTER_CLASS KostalInverterProtocol
#endif
//#define DEBUG_KOSTAL_RS485_DATA // Enable this line to get TX / RX printed out via logging
//#define DEBUG_KOSTAL_RS485_DATA_USB // Enable this line to get TX / RX printed out via USB
#if defined(DEBUG_KOSTAL_RS485_DATA) && !defined(DEBUG_LOG)
#error "enable LOG_TO_SD, DEBUG_VIA_USB or DEBUG_VIA_WEB in order to use DEBUG_KOSTAL_RS485_DATA"
#endif
class KostalInverterProtocol : public Rs485InverterProtocol {
public:
const char* name() override { return Name; }
@ -43,6 +36,8 @@ class KostalInverterProtocol : public Rs485InverterProtocol {
unsigned long currentMillis;
unsigned long startupMillis = 0;
unsigned long contactorMillis = 0;
unsigned long contactortestTimerStart = 0;
bool contactortestTimerActive = false;
uint16_t rx_index = 0;
bool RX_allow = false;

View file

@ -35,9 +35,7 @@ ModbusMessage ModbusInverterProtocol::FC03(ModbusMessage request) {
if ((addr + words) > MBPV_MAX) {
// Yes - send respective error response
response.setError(request.getServerID(), request.getFunctionCode(), ILLEGAL_DATA_ADDRESS);
#ifdef DEBUG_LOG
logging.printf("Modbus FC03 error: illegal request addr=%d words=%d\n", addr, words);
#endif
return response;
}
@ -48,10 +46,6 @@ ModbusMessage ModbusInverterProtocol::FC03(ModbusMessage request) {
response.add((uint16_t)(mbPV[addr + i]));
}
// #ifdef DEBUG_LOG
// logging.printf("Modbus FC03 response: %d %d\n", addr, mbPV[addr]);
// #endif
return response;
}
@ -67,9 +61,7 @@ ModbusMessage ModbusInverterProtocol::FC06(ModbusMessage request) {
if ((addr) > MBPV_MAX) {
// Yes - send respective error response
response.setError(request.getServerID(), request.getFunctionCode(), ILLEGAL_DATA_ADDRESS);
#ifdef DEBUG_LOG
logging.printf("Modbus FC06 error: illegal request addr=%d val=%d\n", addr, val);
#endif
return response;
}
@ -97,18 +89,14 @@ ModbusMessage ModbusInverterProtocol::FC16(ModbusMessage request) {
|| (words > 123)) // can't support more than this in request packet
{ // Yes - send respective error response
response.setError(request.getServerID(), request.getFunctionCode(), ILLEGAL_DATA_VALUE);
#ifdef DEBUG_LOG
logging.printf("Modbus FC16 error: bad registers addr=%d words=%d bytes=%d\n", addr, words, bytes);
#endif
return response;
}
// Address overflow?
if ((addr + words) > MBPV_MAX) {
// Yes - send respective error response
response.setError(request.getServerID(), request.getFunctionCode(), ILLEGAL_DATA_ADDRESS);
#ifdef DEBUG_LOG
logging.printf("Modbus FC16 error: overflow addr=%d words=%d\n", addr, words);
#endif
return response;
}
@ -145,20 +133,16 @@ ModbusMessage ModbusInverterProtocol::FC23(ModbusMessage request) {
|| (read_words > 125)) // can't fit more than this in the response packet
{ // Yes - send respective error response
response.setError(request.getServerID(), request.getFunctionCode(), ILLEGAL_DATA_VALUE);
#ifdef DEBUG_LOG
logging.printf("Modbus FC23 error: bad registers write_addr=%d write_words=%d write_bytes=%d read_words=%d\n",
write_addr, write_words, write_bytes, read_words);
#endif
return response;
}
// Address overflow?
if (((write_addr + write_words) > MBPV_MAX) ||
((read_addr + read_words) > MBPV_MAX)) { // Yes - send respective error response
response.setError(request.getServerID(), request.getFunctionCode(), ILLEGAL_DATA_ADDRESS);
#ifdef DEBUG_LOG
logging.printf("Modbus FC23 error: overflow write_addr=%d write_words=%d read_addr=%d read_words=%d\n", write_addr,
write_words, read_addr, read_words);
#endif
return response;
}

View file

@ -1,6 +1,7 @@
#include "PYLON-CAN.h"
#include "../communication/can/comm_can.h"
#include "../datalayer/datalayer.h"
#include "../inverter/INVERTERS.h"
#define SEND_0 //If defined, the messages will have ID ending with 0 (useful for some inverters)
//#define SEND_1 //If defined, the messages will have ID ending with 1 (useful for some inverters)
@ -351,3 +352,38 @@ void PylonInverter::send_system_data() { //System equipment information
transmit_can_frame(&PYLON_4291);
#endif
}
bool PylonInverter::setup() {
if (user_selected_inverter_cells > 0) {
PYLON_7320.data.u8[0] = user_selected_inverter_cells & 0xff;
PYLON_7320.data.u8[1] = (uint8_t)(user_selected_inverter_cells >> 8);
PYLON_7321.data.u8[0] = user_selected_inverter_cells & 0xff;
PYLON_7321.data.u8[1] = (uint8_t)(user_selected_inverter_cells >> 8);
}
if (user_selected_inverter_modules > 0) {
PYLON_7320.data.u8[2] = user_selected_inverter_modules;
PYLON_7321.data.u8[2] = user_selected_inverter_modules;
}
if (user_selected_inverter_cells_per_module > 0) {
PYLON_7320.data.u8[3] = user_selected_inverter_cells_per_module;
PYLON_7321.data.u8[3] = user_selected_inverter_cells_per_module;
}
if (user_selected_inverter_voltage_level > 0) {
PYLON_7320.data.u8[4] = user_selected_inverter_voltage_level & 0xff;
PYLON_7320.data.u8[5] = (uint8_t)(user_selected_inverter_voltage_level >> 8);
PYLON_7321.data.u8[4] = user_selected_inverter_voltage_level & 0xff;
PYLON_7321.data.u8[5] = (uint8_t)(user_selected_inverter_voltage_level >> 8);
}
if (user_selected_inverter_ah_capacity > 0) {
PYLON_7320.data.u8[6] = user_selected_inverter_ah_capacity & 0xff;
PYLON_7320.data.u8[7] = (uint8_t)(user_selected_inverter_ah_capacity >> 8);
PYLON_7321.data.u8[6] = user_selected_inverter_ah_capacity & 0xff;
PYLON_7321.data.u8[7] = (uint8_t)(user_selected_inverter_ah_capacity >> 8);
}
return true;
}

View file

@ -10,6 +10,7 @@
class PylonInverter : public CanInverterProtocol {
public:
const char* name() override { return Name; }
bool setup() override;
void update_values();
void transmit_can(unsigned long currentMillis);
void map_can_frame_to_variable(CAN_frame rx_frame);

View file

@ -107,34 +107,11 @@ void PylonLvInverter::map_can_frame_to_variable(CAN_frame rx_frame) {
}
}
#ifdef DEBUG_VIA_USB
void dump_frame(CAN_frame* frame) {
Serial.print("[PYLON-LV] sending CAN frame ");
Serial.print(frame->ID, HEX);
Serial.print(": ");
for (int i = 0; i < 8; i++) {
Serial.print(frame->data.u8[i] >> 4, HEX);
Serial.print(frame->data.u8[i] & 0xf, HEX);
Serial.print(" ");
}
Serial.println();
}
#endif
void PylonLvInverter::transmit_can(unsigned long currentMillis) {
if (currentMillis - previousMillis1000ms >= 1000) {
previousMillis1000ms = currentMillis;
#ifdef DEBUG_VIA_USB
dump_frame(&PYLON_351);
dump_frame(&PYLON_355);
dump_frame(&PYLON_356);
dump_frame(&PYLON_359);
dump_frame(&PYLON_35C);
dump_frame(&PYLON_35E);
#endif
transmit_can_frame(&PYLON_351);
transmit_can_frame(&PYLON_355);
transmit_can_frame(&PYLON_356);

View file

@ -227,9 +227,7 @@ void SmaBydHInverter::map_can_frame_to_variable(CAN_frame rx_frame) {
break;
case 0x5E7: //Message originating from SMA inverter - Pairing request
case 0x660: //Message originating from SMA inverter - Pairing request
#ifdef DEBUG_LOG
logging.println("Received SMA pairing request");
#endif // DEBUG_LOG
pairing_events++;
set_event(EVENT_SMA_PAIRING, pairing_events);
datalayer.system.status.CAN_inverter_still_alive = CAN_STILL_ALIVE;

View file

@ -218,9 +218,7 @@ void SmaBydHvsInverter::map_can_frame_to_variable(CAN_frame rx_frame) {
break;
case 0x5E7: //Message originating from SMA inverter - Pairing request
case 0x660: //Message originating from SMA inverter - Pairing request
#ifdef DEBUG_LOG
logging.println("Received SMA pairing request");
#endif // DEBUG_LOG
pairing_events++;
set_event(EVENT_SMA_PAIRING, pairing_events);
datalayer.system.status.CAN_inverter_still_alive = CAN_STILL_ALIVE;

View file

@ -126,9 +126,7 @@ void SmaTripowerInverter::map_can_frame_to_variable(CAN_frame rx_frame) {
break;
case 0x5E7: //Message originating from SMA inverter - Pairing request
case 0x660: //Message originating from SMA inverter - Pairing request
#ifdef DEBUG_LOG
logging.println("Received SMA pairing request");
#endif // DEBUG_LOG
pairing_events++;
set_event(EVENT_SMA_PAIRING, pairing_events);
datalayer.system.status.CAN_inverter_still_alive = CAN_STILL_ALIVE;

View file

@ -4,11 +4,7 @@
#include "../datalayer/datalayer.h"
#include "../devboard/utils/events.h"
#include "../devboard/utils/logging.h"
#define NUMBER_OF_MODULES 0
#define BATTERY_TYPE 0x50
// If you are having BattVoltFault issues, configure the above values according to wiki page
// https://github.com/dalathegreat/Battery-Emulator/wiki/Solax-inverters
#include "../inverter/INVERTERS.h"
// __builtin_bswap64 needed to convert to ESP32 little endian format
// Byte[4] defines the requested contactor state: 1 = Closed , 0 = Open
@ -18,7 +14,7 @@
void SolaxInverter::
update_values() { //This function maps all the values fetched from battery CAN to the correct CAN messages
// If not receiveing any communication from the inverter, open contactors and return to battery announce state
if (millis() - LastFrameTime >= SolaxTimeout) {
if (millis() - LastFrameTime >= SolaxTimeout && !configured_ignore_contactors) {
datalayer.system.status.inverter_allows_contactor_closing = false;
STATE = BATTERY_ANNOUNCE;
}
@ -73,8 +69,8 @@ void SolaxInverter::
//BMS_Status
SOLAX_1875.data.u8[0] = (uint8_t)temperature_average;
SOLAX_1875.data.u8[1] = (temperature_average >> 8);
SOLAX_1875.data.u8[2] = (uint8_t)NUMBER_OF_MODULES; // Number of slave batteries
SOLAX_1875.data.u8[4] = (uint8_t)0; // Contactor Status 0=off, 1=on.
SOLAX_1875.data.u8[2] = (uint8_t)configured_number_of_modules; // Number of slave batteries
SOLAX_1875.data.u8[4] = (uint8_t)0; // Contactor Status 0=off, 1=on.
//BMS_PackTemps (strange name, since it has voltages?)
SOLAX_1876.data.u8[0] = (int8_t)datalayer.battery.status.temperature_max_dC;
@ -88,8 +84,8 @@ void SolaxInverter::
SOLAX_1876.data.u8[7] = (datalayer.battery.status.cell_min_voltage_mV >> 8);
//Unknown
SOLAX_1877.data.u8[4] = (uint8_t)BATTERY_TYPE; // Battery type (Default 0x50)
SOLAX_1877.data.u8[6] = (uint8_t)0x22; // Firmware version?
SOLAX_1877.data.u8[4] = (uint8_t)configured_battery_type; // Battery type (Default 0x50)
SOLAX_1877.data.u8[6] = (uint8_t)0x22; // Firmware version?
SOLAX_1877.data.u8[7] =
(uint8_t)0x02; // The above firmware version applies to:02 = Master BMS, 10 = S1, 20 = S2, 30 = S3, 40 = S4
@ -129,11 +125,29 @@ void SolaxInverter::map_can_frame_to_variable(CAN_frame rx_frame) {
if (rx_frame.ID == 0x1871 && rx_frame.data.u8[0] == (0x01) ||
rx_frame.ID == 0x1871 && rx_frame.data.u8[0] == (0x02)) {
LastFrameTime = millis();
if (configured_ignore_contactors) {
// Skip the state machine since we're not going to open/close contactors,
// and the Solax would otherwise wait forever for us to do so.
datalayer.system.status.inverter_allows_contactor_closing = true;
SOLAX_1875.data.u8[4] = (0x01); // Inform Inverter: Contactor 0=off, 1=on.
transmit_can_frame(&SOLAX_187E);
transmit_can_frame(&SOLAX_187A);
transmit_can_frame(&SOLAX_1872);
transmit_can_frame(&SOLAX_1873);
transmit_can_frame(&SOLAX_1874);
transmit_can_frame(&SOLAX_1875);
transmit_can_frame(&SOLAX_1876);
transmit_can_frame(&SOLAX_1877);
transmit_can_frame(&SOLAX_1878);
transmit_can_frame(&SOLAX_100A001);
return;
}
switch (STATE) {
case (BATTERY_ANNOUNCE):
#ifdef DEBUG_LOG
logging.println("Solax Battery State: Announce");
#endif
datalayer.system.status.inverter_allows_contactor_closing = false;
SOLAX_1875.data.u8[4] = (0x00); // Inform Inverter: Contactor 0=off, 1=on.
for (uint8_t i = 0; i < number_of_batteries; i++) {
@ -167,9 +181,7 @@ void SolaxInverter::map_can_frame_to_variable(CAN_frame rx_frame) {
transmit_can_frame(&SOLAX_1878);
transmit_can_frame(&SOLAX_1801); // Announce that the battery will be connected
STATE = CONTACTOR_CLOSED; // Jump to Contactor Closed State
#ifdef DEBUG_LOG
logging.println("Solax Battery State: Contactor Closed");
#endif
break;
case (CONTACTOR_CLOSED):
@ -197,18 +209,33 @@ void SolaxInverter::map_can_frame_to_variable(CAN_frame rx_frame) {
if (rx_frame.ID == 0x1871 && rx_frame.data.u64 == __builtin_bswap64(0x0500010000000000)) {
transmit_can_frame(&SOLAX_1881);
transmit_can_frame(&SOLAX_1882);
#ifdef DEBUG_LOG
logging.println("1871 05-frame received from inverter");
#endif
}
if (rx_frame.ID == 0x1871 && rx_frame.data.u8[0] == (0x03)) {
#ifdef DEBUG_LOG
logging.println("1871 03-frame received from inverter");
#endif
}
}
bool SolaxInverter::setup(void) { // Performs one time setup at startup
datalayer.system.status.inverter_allows_contactor_closing = false; // The inverter needs to allow first
bool SolaxInverter::setup(void) { // Performs one time setup at startup
// Use user selected values if nonzero, otherwise use defaults
if (user_selected_inverter_modules > 0) {
configured_number_of_modules = user_selected_inverter_modules;
} else {
configured_number_of_modules = NUMBER_OF_MODULES;
}
if (user_selected_inverter_battery_type > 0) {
configured_battery_type = user_selected_inverter_battery_type;
} else {
configured_battery_type = BATTERY_TYPE;
}
configured_ignore_contactors = user_selected_inverter_ignore_contactors;
if (!configured_ignore_contactors) {
// Only prevent closing if we're not ignoring contactors
datalayer.system.status.inverter_allows_contactor_closing = false; // The inverter needs to allow first
}
return true;
}

View file

@ -17,6 +17,11 @@ class SolaxInverter : public CanInverterProtocol {
static constexpr const char* Name = "SolaX Triple Power LFP over CAN bus";
private:
static const int NUMBER_OF_MODULES = 0;
static const int BATTERY_TYPE = 0x50;
// If you are having BattVoltFault issues, configure the above values according to wiki page
// https://github.com/dalathegreat/Battery-Emulator/wiki/Solax-inverters
// Timeout in milliseconds
static const int SolaxTimeout = 2000;
@ -34,6 +39,13 @@ class SolaxInverter : public CanInverterProtocol {
uint16_t capped_capacity_Wh;
uint16_t capped_remaining_capacity_Wh;
int configured_number_of_modules = 0;
int configured_battery_type = 0;
// If true, the integration will ignore the inverter's requests to open the
// battery contactors. Useful for batteries that can't open contactors on
// request.
bool configured_ignore_contactors = false;
//CAN message translations from this amazing repository: https://github.com/rand12345/solax_can_bus
CAN_frame SOLAX_1801 = {.FD = false,

View file

@ -1,6 +1,7 @@
#include "SOLXPOW-CAN.h"
#include "../communication/can/comm_can.h"
#include "../datalayer/datalayer.h"
#include "../inverter/INVERTERS.h"
#define SEND_0 //If defined, the messages will have ID ending with 0 (useful for some inverters)
//#define SEND_1 //If defined, the messages will have ID ending with 1 (useful for some inverters)
@ -353,3 +354,38 @@ void SolxpowInverter::send_system_data() { //System equipment information
transmit_can_frame(&SOLXPOW_4291);
#endif
}
bool SolxpowInverter::setup() {
if (user_selected_inverter_cells > 0) {
SOLXPOW_7320.data.u8[0] = user_selected_inverter_cells & 0xff;
SOLXPOW_7320.data.u8[1] = (uint8_t)(user_selected_inverter_cells >> 8);
SOLXPOW_7321.data.u8[0] = user_selected_inverter_cells & 0xff;
SOLXPOW_7321.data.u8[1] = (uint8_t)(user_selected_inverter_cells >> 8);
}
if (user_selected_inverter_modules > 0) {
SOLXPOW_7320.data.u8[2] = user_selected_inverter_modules;
SOLXPOW_7321.data.u8[2] = user_selected_inverter_modules;
}
if (user_selected_inverter_cells_per_module > 0) {
SOLXPOW_7320.data.u8[3] = user_selected_inverter_cells_per_module;
SOLXPOW_7321.data.u8[3] = user_selected_inverter_cells_per_module;
}
if (user_selected_inverter_voltage_level > 0) {
SOLXPOW_7320.data.u8[4] = user_selected_inverter_voltage_level & 0xff;
SOLXPOW_7320.data.u8[5] = (uint8_t)(user_selected_inverter_voltage_level >> 8);
SOLXPOW_7321.data.u8[4] = user_selected_inverter_voltage_level & 0xff;
SOLXPOW_7321.data.u8[5] = (uint8_t)(user_selected_inverter_voltage_level >> 8);
}
if (user_selected_inverter_ah_capacity > 0) {
SOLXPOW_7320.data.u8[6] = user_selected_inverter_ah_capacity & 0xff;
SOLXPOW_7320.data.u8[7] = (uint8_t)(user_selected_inverter_ah_capacity >> 8);
SOLXPOW_7321.data.u8[6] = user_selected_inverter_ah_capacity & 0xff;
SOLXPOW_7321.data.u8[7] = (uint8_t)(user_selected_inverter_ah_capacity >> 8);
}
return true;
}

View file

@ -10,6 +10,7 @@
class SolxpowInverter : public CanInverterProtocol {
public:
const char* name() override { return Name; }
bool setup() override;
void update_values();
void transmit_can(unsigned long currentMillis);
void map_can_frame_to_variable(CAN_frame rx_frame);