mirror of
https://github.com/dalathegreat/Battery-Emulator.git
synced 2025-10-04 18:29:48 +02:00
Tesla webserver
Add multiplex messages to Tesla Battery, update datalayer exptended and add lines for advanced battery.
This commit is contained in:
parent
32e75bab04
commit
7eaeb7e15e
3 changed files with 296 additions and 99 deletions
|
@ -25,20 +25,21 @@ CAN_frame TESLA_221_2 = {
|
||||||
static uint16_t sendContactorClosingMessagesStill = 300;
|
static uint16_t sendContactorClosingMessagesStill = 300;
|
||||||
static uint32_t battery_total_discharge = 0;
|
static uint32_t battery_total_discharge = 0;
|
||||||
static uint32_t battery_total_charge = 0;
|
static uint32_t battery_total_charge = 0;
|
||||||
static uint16_t battery_volts = 0; // V
|
static uint16_t battery_volts = 0; // V
|
||||||
static int16_t battery_amps = 0; // A
|
static int16_t battery_amps = 0; // A
|
||||||
static uint16_t battery_raw_amps = 0; // A
|
static uint16_t battery_raw_amps = 0; // A
|
||||||
static int16_t battery_max_temp = 0; // C*
|
static int16_t battery_max_temp = 0; // C*
|
||||||
static int16_t battery_min_temp = 0; // C*
|
static int16_t battery_min_temp = 0; // C*
|
||||||
static uint16_t battery_energy_buffer = 0;
|
static uint16_t battery_energy_buffer = 0; // kWh
|
||||||
static uint16_t battery_energy_to_charge_complete = 0;
|
static uint16_t battery_energy_to_charge_complete = 0; // kWh
|
||||||
static uint16_t battery_expected_energy_remaining = 0;
|
static uint16_t battery_expected_energy_remaining = 0; // kWh
|
||||||
static uint8_t battery_full_charge_complete = 0;
|
static uint8_t battery_full_charge_complete = 0; // kWh
|
||||||
static uint16_t battery_ideal_energy_remaining = 0;
|
static uint8_t battery_fully_charged = 0; // kWh
|
||||||
static uint16_t battery_nominal_energy_remaining = 0;
|
static uint16_t battery_ideal_energy_remaining = 0; // kWh
|
||||||
static uint16_t battery_nominal_full_pack_energy = 600;
|
static uint16_t battery_nominal_energy_remaining = 0; // kWh
|
||||||
static uint16_t battery_beginning_of_life = 600;
|
static uint16_t battery_nominal_full_pack_energy = 600; // Kwh
|
||||||
static uint16_t battery_charge_time_remaining = 0; // Minutes
|
static uint16_t battery_beginning_of_life = 600; // kWh
|
||||||
|
static uint16_t battery_charge_time_remaining = 0; // Minutes
|
||||||
static uint16_t battery_regenerative_limit = 0;
|
static uint16_t battery_regenerative_limit = 0;
|
||||||
static uint16_t battery_discharge_limit = 0;
|
static uint16_t battery_discharge_limit = 0;
|
||||||
static uint16_t battery_max_heat_park = 0;
|
static uint16_t battery_max_heat_park = 0;
|
||||||
|
@ -47,12 +48,13 @@ static uint16_t battery_max_discharge_current = 0;
|
||||||
static uint16_t battery_max_charge_current = 0;
|
static uint16_t battery_max_charge_current = 0;
|
||||||
static uint16_t battery_bms_max_voltage = 0;
|
static uint16_t battery_bms_max_voltage = 0;
|
||||||
static uint16_t battery_bms_min_voltage = 0;
|
static uint16_t battery_bms_min_voltage = 0;
|
||||||
static uint16_t battery_high_voltage = 0;
|
static uint16_t battery_dcdcHvBusVolt = 0; // Change name from battery_high_voltage to battery_dcdcHvBusVolt
|
||||||
static uint16_t battery_low_voltage = 0;
|
static uint16_t battery_dcdcLvBusVolt = 0; // Change name from battery_low_voltage to battery_dcdcLvBusVolt
|
||||||
static uint16_t battery_output_current = 0;
|
static uint16_t battery_dcdcLvOutputCurrent =
|
||||||
|
0; // Change name from battery_output_current to battery_dcdcLvOutputCurrent
|
||||||
static uint16_t battery_soc_min = 0;
|
static uint16_t battery_soc_min = 0;
|
||||||
static uint16_t battery_soc_max = 0;
|
static uint16_t battery_soc_max = 0;
|
||||||
static uint16_t battery_soc_vi = 0;
|
static uint16_t battery_soc_ui = 0; //Change name from battery_soc_vi to reflect DBC battery_soc_ui
|
||||||
static uint16_t battery_soc_ave = 0;
|
static uint16_t battery_soc_ave = 0;
|
||||||
static uint16_t battery_cell_max_v = 3700;
|
static uint16_t battery_cell_max_v = 3700;
|
||||||
static uint16_t battery_cell_min_v = 3700;
|
static uint16_t battery_cell_min_v = 3700;
|
||||||
|
@ -66,6 +68,12 @@ static uint8_t battery_packContPositiveState = 0;
|
||||||
static uint8_t battery_packContactorSetState = 0;
|
static uint8_t battery_packContactorSetState = 0;
|
||||||
static uint8_t battery_packCtrsClosingAllowed = 0;
|
static uint8_t battery_packCtrsClosingAllowed = 0;
|
||||||
static uint8_t battery_pyroTestInProgress = 0;
|
static uint8_t battery_pyroTestInProgress = 0;
|
||||||
|
static uint8_t battery_battTempPct = 0;
|
||||||
|
static uint32_t battery_packMass = 0;
|
||||||
|
static uint32_t battery_platformMaxBusVoltage = 0;
|
||||||
|
static uint32_t battery_packConfigMultiplexer = 0;
|
||||||
|
static uint32_t battery_moduleType = 0;
|
||||||
|
static uint32_t battery_reservedConfig = 0;
|
||||||
//Fault codes
|
//Fault codes
|
||||||
static uint8_t battery_WatchdogReset = 0; //Warns if the processor has experienced a reset due to watchdog reset.
|
static uint8_t battery_WatchdogReset = 0; //Warns if the processor has experienced a reset due to watchdog reset.
|
||||||
static uint8_t battery_PowerLossReset = 0; //Warns if the processor has experienced a reset due to power loss.
|
static uint8_t battery_PowerLossReset = 0; //Warns if the processor has experienced a reset due to power loss.
|
||||||
|
@ -138,6 +146,7 @@ static uint16_t battery2_energy_buffer = 0;
|
||||||
static uint16_t battery2_energy_to_charge_complete = 0;
|
static uint16_t battery2_energy_to_charge_complete = 0;
|
||||||
static uint16_t battery2_expected_energy_remaining = 0;
|
static uint16_t battery2_expected_energy_remaining = 0;
|
||||||
static uint8_t battery2_full_charge_complete = 0;
|
static uint8_t battery2_full_charge_complete = 0;
|
||||||
|
static uint8_t battery2_fully_charged = 0;
|
||||||
static uint16_t battery2_ideal_energy_remaining = 0;
|
static uint16_t battery2_ideal_energy_remaining = 0;
|
||||||
static uint16_t battery2_nominal_energy_remaining = 0;
|
static uint16_t battery2_nominal_energy_remaining = 0;
|
||||||
static uint16_t battery2_nominal_full_pack_energy = 600;
|
static uint16_t battery2_nominal_full_pack_energy = 600;
|
||||||
|
@ -151,12 +160,12 @@ static uint16_t battery2_max_discharge_current = 0;
|
||||||
static uint16_t battery2_max_charge_current = 0;
|
static uint16_t battery2_max_charge_current = 0;
|
||||||
static uint16_t battery2_bms_max_voltage = 0;
|
static uint16_t battery2_bms_max_voltage = 0;
|
||||||
static uint16_t battery2_bms_min_voltage = 0;
|
static uint16_t battery2_bms_min_voltage = 0;
|
||||||
static uint16_t battery2_high_voltage = 0;
|
static uint16_t battery2_dcdcHvBusVolt = 0; //update name
|
||||||
static uint16_t battery2_low_voltage = 0;
|
static uint16_t battery2_dcdcLvBusVolt = 0; //update name
|
||||||
static uint16_t battery2_output_current = 0;
|
static uint16_t battery2_dcdcLvOutputCurrent = 0; //update name
|
||||||
static uint16_t battery2_soc_min = 0;
|
static uint16_t battery2_soc_min = 0;
|
||||||
static uint16_t battery2_soc_max = 0;
|
static uint16_t battery2_soc_max = 0;
|
||||||
static uint16_t battery2_soc_vi = 0;
|
static uint16_t battery2_soc_ui = 0;
|
||||||
static uint16_t battery2_soc_ave = 0;
|
static uint16_t battery2_soc_ave = 0;
|
||||||
static uint16_t battery2_cell_max_v = 3700;
|
static uint16_t battery2_cell_max_v = 3700;
|
||||||
static uint16_t battery2_cell_min_v = 3700;
|
static uint16_t battery2_cell_min_v = 3700;
|
||||||
|
@ -170,6 +179,12 @@ static uint8_t battery2_packContPositiveState = 0;
|
||||||
static uint8_t battery2_packContactorSetState = 0;
|
static uint8_t battery2_packContactorSetState = 0;
|
||||||
static uint8_t battery2_packCtrsClosingAllowed = 0;
|
static uint8_t battery2_packCtrsClosingAllowed = 0;
|
||||||
static uint8_t battery2_pyroTestInProgress = 0;
|
static uint8_t battery2_pyroTestInProgress = 0;
|
||||||
|
static uint8_t battery2_battTempPct = 0;
|
||||||
|
static uint32_t battery2_packMass = 0;
|
||||||
|
static uint32_t battery2_platformMaxBusVoltage = 0;
|
||||||
|
static uint32_t battery2_packConfigMultiplexer = 0;
|
||||||
|
static uint32_t battery2_moduleType = 0;
|
||||||
|
static uint32_t battery2_reservedConfig = 0;
|
||||||
//Fault codes
|
//Fault codes
|
||||||
static uint8_t battery2_WatchdogReset = 0; //Warns if the processor has experienced a reset due to watchdog reset.
|
static uint8_t battery2_WatchdogReset = 0; //Warns if the processor has experienced a reset due to watchdog reset.
|
||||||
static uint8_t battery2_PowerLossReset = 0; //Warns if the processor has experienced a reset due to power loss.
|
static uint8_t battery2_PowerLossReset = 0; //Warns if the processor has experienced a reset due to power loss.
|
||||||
|
@ -259,7 +274,7 @@ void update_values_battery() { //This function maps all the values fetched via
|
||||||
|
|
||||||
datalayer.battery.status.soh_pptt = 9900; //Tesla batteries do not send a SOH% value on bus. Hardcode to 99%
|
datalayer.battery.status.soh_pptt = 9900; //Tesla batteries do not send a SOH% value on bus. Hardcode to 99%
|
||||||
|
|
||||||
datalayer.battery.status.real_soc = (battery_soc_vi * 10); //increase SOC range from 0-100.0 -> 100.00
|
datalayer.battery.status.real_soc = (battery_soc_ui * 10); //increase SOC range from 0-100.0 -> 100.00
|
||||||
|
|
||||||
datalayer.battery.status.voltage_dV = (battery_volts * 10); //One more decimal needed (370 -> 3700)
|
datalayer.battery.status.voltage_dV = (battery_volts * 10); //One more decimal needed (370 -> 3700)
|
||||||
|
|
||||||
|
@ -277,12 +292,12 @@ void update_values_battery() { //This function maps all the values fetched via
|
||||||
}
|
}
|
||||||
|
|
||||||
//The allowed charge power behaves strangely. We instead estimate this value
|
//The allowed charge power behaves strangely. We instead estimate this value
|
||||||
if (battery_soc_vi > 990) {
|
if (battery_soc_ui > 990) {
|
||||||
datalayer.battery.status.max_charge_power_W = FLOAT_MAX_POWER_W;
|
datalayer.battery.status.max_charge_power_W = FLOAT_MAX_POWER_W;
|
||||||
} else if (battery_soc_vi >
|
} else if (battery_soc_ui >
|
||||||
RAMPDOWN_SOC) { // When real SOC is between RAMPDOWN_SOC-99%, ramp the value between Max<->0
|
RAMPDOWN_SOC) { // When real SOC is between RAMPDOWN_SOC-99%, ramp the value between Max<->0
|
||||||
datalayer.battery.status.max_charge_power_W =
|
datalayer.battery.status.max_charge_power_W =
|
||||||
RAMPDOWNPOWERALLOWED * (1 - (battery_soc_vi - RAMPDOWN_SOC) / (1000.0 - RAMPDOWN_SOC));
|
RAMPDOWNPOWERALLOWED * (1 - (battery_soc_ui - RAMPDOWN_SOC) / (1000.0 - RAMPDOWN_SOC));
|
||||||
//If the cellvoltages start to reach overvoltage, only allow a small amount of power in
|
//If the cellvoltages start to reach overvoltage, only allow a small amount of power in
|
||||||
if (datalayer.battery.info.chemistry == battery_chemistry_enum::LFP) {
|
if (datalayer.battery.info.chemistry == battery_chemistry_enum::LFP) {
|
||||||
if (battery_cell_max_v > (MAX_CELL_VOLTAGE_LFP - FLOAT_START_MV)) {
|
if (battery_cell_max_v > (MAX_CELL_VOLTAGE_LFP - FLOAT_START_MV)) {
|
||||||
|
@ -348,6 +363,33 @@ void update_values_battery() { //This function maps all the values fetched via
|
||||||
datalayer_extended.tesla.packContactorSetState = battery_packContactorSetState;
|
datalayer_extended.tesla.packContactorSetState = battery_packContactorSetState;
|
||||||
datalayer_extended.tesla.packCtrsClosingAllowed = battery_packCtrsClosingAllowed;
|
datalayer_extended.tesla.packCtrsClosingAllowed = battery_packCtrsClosingAllowed;
|
||||||
datalayer_extended.tesla.pyroTestInProgress = battery_pyroTestInProgress;
|
datalayer_extended.tesla.pyroTestInProgress = battery_pyroTestInProgress;
|
||||||
|
datalayer_extended.tesla.battery_beginning_of_life = battery_beginning_of_life; //add from her down
|
||||||
|
datalayer_extended.tesla.battery_battTempPct = battery_battTempPct;
|
||||||
|
datalayer_extended.tesla.battery_dcdcLvBusVolt = battery_dcdcLvBusVolt;
|
||||||
|
datalayer_extended.tesla.battery_dcdcHvBusVolt = battery_dcdcHvBusVolt;
|
||||||
|
datalayer_extended.tesla.battery_dcdcLvOutputCurrent = battery_dcdcLvOutputCurrent;
|
||||||
|
datalayer_extended.tesla.battery_nominal_full_pack_energy = battery_nominal_full_pack_energy;
|
||||||
|
datalayer_extended.tesla.battery_nominal_energy_remaining = battery_nominal_energy_remaining;
|
||||||
|
datalayer_extended.tesla.battery_ideal_energy_remaining = battery_ideal_energy_remaining;
|
||||||
|
datalayer_extended.tesla.battery_energy_to_charge_complete = battery_energy_to_charge_complete;
|
||||||
|
datalayer_extended.tesla.battery_energy_buffer = battery_energy_buffer;
|
||||||
|
datalayer_extended.tesla.battery_full_charge_complete = battery_full_charge_complete;
|
||||||
|
datalayer_extended.tesla.battery_total_discharge = battery_total_discharge;
|
||||||
|
datalayer_extended.tesla.battery_total_charge = battery_total_charge;
|
||||||
|
datalayer_extended.tesla.battery_fully_charged = battery_fully_charged;
|
||||||
|
datalayer_extended.tesla.battery_packConfigMultiplexer = battery_packConfigMultiplexer;
|
||||||
|
datalayer_extended.tesla.battery_moduleType = battery_moduleType;
|
||||||
|
datalayer_extended.tesla.battery_reservedConfig = battery_reservedConfig;
|
||||||
|
datalayer_extended.tesla.battery_packMass = battery_packMass;
|
||||||
|
datalayer_extended.tesla.battery_platformMaxBusVoltage = battery_platformMaxBusVoltage;
|
||||||
|
datalayer_extended.tesla.battery_bms_min_voltage = battery_bms_min_voltage;
|
||||||
|
datalayer_extended.tesla.battery_bms_max_voltage = battery_bms_max_voltage;
|
||||||
|
datalayer_extended.tesla.battery_max_charge_current = battery_max_charge_current;
|
||||||
|
datalayer_extended.tesla.battery_max_discharge_current = battery_max_discharge_current;
|
||||||
|
datalayer_extended.tesla.battery_soc_ave = battery_soc_ave;
|
||||||
|
datalayer_extended.tesla.battery_soc_max = battery_soc_max;
|
||||||
|
datalayer_extended.tesla.battery_soc_min = battery_soc_min;
|
||||||
|
datalayer_extended.tesla.battery_soc_ui = battery_soc_ui;
|
||||||
|
|
||||||
#ifdef DEBUG_VIA_USB
|
#ifdef DEBUG_VIA_USB
|
||||||
|
|
||||||
|
@ -370,7 +412,7 @@ void update_values_battery() { //This function maps all the values fetched via
|
||||||
|
|
||||||
Serial.print("Battery values: ");
|
Serial.print("Battery values: ");
|
||||||
Serial.print("Real SOC: ");
|
Serial.print("Real SOC: ");
|
||||||
Serial.print(battery_soc_vi / 10.0, 1);
|
Serial.print(battery_soc_ui / 10.0, 1);
|
||||||
print_int_with_units(", Battery voltage: ", battery_volts, "V");
|
print_int_with_units(", Battery voltage: ", battery_volts, "V");
|
||||||
print_int_with_units(", Battery HV current: ", (battery_amps * 0.1), "A");
|
print_int_with_units(", Battery HV current: ", (battery_amps * 0.1), "A");
|
||||||
Serial.print(", Fully charged?: ");
|
Serial.print(", Fully charged?: ");
|
||||||
|
@ -394,11 +436,11 @@ void update_values_battery() { //This function maps all the values fetched via
|
||||||
Serial.print(battery_cell_deviation_mV);
|
Serial.print(battery_cell_deviation_mV);
|
||||||
Serial.println("mV.");
|
Serial.println("mV.");
|
||||||
|
|
||||||
print_int_with_units("High Voltage Output Pins: ", battery_high_voltage, "V");
|
print_int_with_units("High Voltage Output Pins: ", battery_dcdcHvBusVolt, "V");
|
||||||
Serial.print(", ");
|
Serial.print(", ");
|
||||||
print_int_with_units("Low Voltage: ", battery_low_voltage, "V");
|
print_int_with_units("Low Voltage: ", battery_dcdcLvBusVolt, "V");
|
||||||
Serial.println("");
|
Serial.println("");
|
||||||
print_int_with_units("DC/DC 12V current: ", battery_output_current, "A");
|
print_int_with_units("DC/DC 12V current: ", battery_dcdcLvOutputCurrent, "A");
|
||||||
Serial.println("");
|
Serial.println("");
|
||||||
|
|
||||||
Serial.println("Values passed to the inverter: ");
|
Serial.println("Values passed to the inverter: ");
|
||||||
|
@ -420,20 +462,47 @@ void receive_can_battery(CAN_frame rx_frame) {
|
||||||
|
|
||||||
switch (rx_frame.ID) {
|
switch (rx_frame.ID) {
|
||||||
case 0x352:
|
case 0x352:
|
||||||
//SOC
|
mux = (rx_frame.data.u8[0] & 0x02); //BMS_energyStatusIndex M : 0|2@1+ (1,0) [0|0] "" X
|
||||||
battery_nominal_full_pack_energy =
|
if (mux == 3) {
|
||||||
(((rx_frame.data.u8[1] & 0x0F) << 8) | (rx_frame.data.u8[0])); //Example 752 (75.2kWh)
|
battery_nominal_full_pack_energy = //BMS_nominalFullPackEnergy : 0|11@1+ (0.1,0) [0|204.6] "KWh" //((_d[1] & (0x07U)) << 8) | (_d[0] & (0xFFU));
|
||||||
battery_nominal_energy_remaining = (((rx_frame.data.u8[2] & 0x3F) << 5) | ((rx_frame.data.u8[1] & 0xF8) >> 3)) *
|
(((rx_frame.data.u8[1] & 0x07) << 8) | (rx_frame.data.u8[0])); //Example 752 (75.2kWh)
|
||||||
0.1; //Example 1247 * 0.1 = 124.7kWh
|
battery_nominal_energy_remaining = //BMS_nominalEnergyRemaining : 11|11@1+ (0.1,0) [0|204.6] "KWh" //((_d[2] & (0x3FU)) << 5) | ((_d[1] >> 3) & (0x1FU));
|
||||||
battery_expected_energy_remaining = (((rx_frame.data.u8[4] & 0x01) << 10) | (rx_frame.data.u8[3] << 2) |
|
(((rx_frame.data.u8[2] & 0x3F) << 5) |
|
||||||
((rx_frame.data.u8[2] & 0xC0) >> 6)); //Example 622 (62.2kWh)
|
((rx_frame.data.u8[1] & 0x1F) >> 3)); //Example 1247 * 0.1 = 124.7kWh
|
||||||
battery_ideal_energy_remaining = (((rx_frame.data.u8[5] & 0x0F) << 7) | ((rx_frame.data.u8[4] & 0xFE) >> 1)) *
|
battery_expected_energy_remaining = //BMS_expectedEnergyRemaining : 22|11@1+ (0.1,0) [0|204.6] "KWh"// ((_d[4] & (0x01U)) << 10) | ((_d[3] & (0xFFU)) << 2) | ((_d[2] >> 6) & (0x03U));
|
||||||
0.1; //Example 311 * 0.1 = 31.1kWh
|
(((rx_frame.data.u8[4] & 0x01) << 10) | (rx_frame.data.u8[3] << 2) |
|
||||||
battery_energy_to_charge_complete = (((rx_frame.data.u8[6] & 0x7F) << 4) | ((rx_frame.data.u8[5] & 0xF0) >> 4)) *
|
((rx_frame.data.u8[2] & 0x03) >> 6)); //Example 622 (62.2kWh)
|
||||||
0.1; //Example 147 * 0.1 = 14.7kWh
|
battery_ideal_energy_remaining = //BMS_idealEnergyRemaining : 33|11@1+ (0.1,0) [0|204.6] "KWh" //((_d[5] & (0x0FU)) << 7) | ((_d[4] >> 1) & (0x7FU));
|
||||||
battery_energy_buffer =
|
(((rx_frame.data.u8[5] & 0x0F) << 7) | ((rx_frame.data.u8[4] & 0x7F) >> 1)); //Example 311 * 0.1 = 31.1kWh
|
||||||
(((rx_frame.data.u8[7] & 0x7F) << 1) | ((rx_frame.data.u8[6] & 0x80) >> 7)) * 0.1; //Example 1 * 0.1 = 0
|
battery_energy_to_charge_complete = // BMS_energyToChargeComplete : 44|11@1+ (0.1,0) [0|204.6] "KWh"// ((_d[6] & (0x7FU)) << 4) | ((_d[5] >> 4) & (0x0FU));
|
||||||
battery_full_charge_complete = ((rx_frame.data.u8[7] & 0x80) >> 7);
|
(((rx_frame.data.u8[6] & 0x7F) << 4) | ((rx_frame.data.u8[5] & 0x0F) << 4)); //Example 147 * 0.1 = 14.7kWh
|
||||||
|
battery_energy_buffer = //BMS_energyBuffer : 55|8@1+ (0.1,0) [0|25.4] "KWh"// ((_d[7] & (0x7FU)) << 1) | ((_d[6] >> 7) & (0x01U));
|
||||||
|
(((rx_frame.data.u8[7] & 0x7F) << 1) | ((rx_frame.data.u8[6] & 0x01) >> 7)); //Example 1 * 0.1 = 0
|
||||||
|
battery_full_charge_complete = //BMS_fullChargeComplete : 63|1@1+ (1,0) [0|1] ""//((_d[7] >> 7) & (0x01U));
|
||||||
|
((rx_frame.data.u8[7] & 0x01) >> 7);
|
||||||
|
}
|
||||||
|
if (mux == 0) {
|
||||||
|
battery_nominal_full_pack_energy =
|
||||||
|
(rx_frame.data.u8[3] |
|
||||||
|
rx_frame.data.u8[2]); //SG_ BMS_nominalFullPackEnergy m0 : 16|16@1+ (0.02,0) [0|0] "kWh" X
|
||||||
|
battery_nominal_energy_remaining =
|
||||||
|
(rx_frame.data.u8[5] |
|
||||||
|
rx_frame.data.u8[4]); //SG_ BMS_nominalEnergyRemaining m0 : 32|16@1+ (0.02,0) [0|0] "kWh" X
|
||||||
|
battery_ideal_energy_remaining =
|
||||||
|
(rx_frame.data.u8[7] |
|
||||||
|
rx_frame.data.u8[6]); //SG_ BMS_idealEnergyRemaining m0 : 48|16@1+ (0.02,0) [0|0] "kWh" X
|
||||||
|
}
|
||||||
|
if (mux == 1) {
|
||||||
|
battery_fully_charged = (rx_frame.data.u8[1] & 0x01); //SG_ BMS_fullyCharged m1 : 15|1@1+ (1,0) [0|1] "" X
|
||||||
|
battery_energy_buffer =
|
||||||
|
(rx_frame.data.u8[3] | rx_frame.data.u8[2]); //SG_ BMS_energyBuffer m1 : 16|16@1+ (0.01,0) [0|0] "kWh" X
|
||||||
|
battery_expected_energy_remaining =
|
||||||
|
(rx_frame.data.u8[5] |
|
||||||
|
rx_frame.data.u8[4]); //SG_ BMS_expectedEnergyRemaining m1 : 32|16@1+ (0.02,0) [0|0] "kWh" X
|
||||||
|
battery_energy_to_charge_complete =
|
||||||
|
(rx_frame.data.u8[7] |
|
||||||
|
rx_frame.data.u8[6]); //SG_ BMS_energyToChargeComplete m1 : 48|16@1+ (0.02,0) [0|0] "kWh" X
|
||||||
|
}
|
||||||
break;
|
break;
|
||||||
case 0x20A:
|
case 0x20A:
|
||||||
//Contactor state
|
//Contactor state
|
||||||
|
@ -471,11 +540,9 @@ void receive_can_battery(CAN_frame rx_frame) {
|
||||||
case 0x3D2:
|
case 0x3D2:
|
||||||
// total charge/discharge kwh
|
// total charge/discharge kwh
|
||||||
battery_total_discharge = ((rx_frame.data.u8[3] << 24) | (rx_frame.data.u8[2] << 16) |
|
battery_total_discharge = ((rx_frame.data.u8[3] << 24) | (rx_frame.data.u8[2] << 16) |
|
||||||
(rx_frame.data.u8[1] << 8) | rx_frame.data.u8[0]) *
|
(rx_frame.data.u8[1] << 8) | rx_frame.data.u8[0]);
|
||||||
0.001;
|
|
||||||
battery_total_charge = ((rx_frame.data.u8[7] << 24) | (rx_frame.data.u8[6] << 16) | (rx_frame.data.u8[5] << 8) |
|
battery_total_charge = ((rx_frame.data.u8[7] << 24) | (rx_frame.data.u8[6] << 16) | (rx_frame.data.u8[5] << 8) |
|
||||||
rx_frame.data.u8[4]) *
|
rx_frame.data.u8[4]);
|
||||||
0.001;
|
|
||||||
break;
|
break;
|
||||||
case 0x332:
|
case 0x332:
|
||||||
//min/max hist values
|
//min/max hist values
|
||||||
|
@ -531,28 +598,41 @@ void receive_can_battery(CAN_frame rx_frame) {
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case 0x2d2:
|
case 0x2d2:
|
||||||
//Min / max limits
|
//Min / max limits //BMSVAlimits: //move factoring to datalayer?
|
||||||
battery_bms_min_voltage =
|
battery_bms_min_voltage = ((rx_frame.data.u8[1] << 8) | rx_frame.data.u8[0]); //Example 24148mv * 0.01 = 241.48 V
|
||||||
((rx_frame.data.u8[1] << 8) | rx_frame.data.u8[0]) * 0.01 * 2; //Example 24148mv * 0.01 = 241.48 V
|
battery_bms_max_voltage = ((rx_frame.data.u8[3] << 8) | rx_frame.data.u8[2]); //Example 40282mv * 0.01 = 402.82 V
|
||||||
battery_bms_max_voltage =
|
|
||||||
((rx_frame.data.u8[3] << 8) | rx_frame.data.u8[2]) * 0.01 * 2; //Example 40282mv * 0.01 = 402.82 V
|
|
||||||
battery_max_charge_current =
|
battery_max_charge_current =
|
||||||
(((rx_frame.data.u8[5] & 0x3F) << 8) | rx_frame.data.u8[4]) * 0.1; //Example 1301? * 0.1 = 130.1?
|
(((rx_frame.data.u8[5] & 0x3F) << 8) | rx_frame.data.u8[4]); //Example 1301? * 0.1 = 130.1?
|
||||||
battery_max_discharge_current =
|
battery_max_discharge_current =
|
||||||
(((rx_frame.data.u8[7] & 0x3F) << 8) | rx_frame.data.u8[6]) * 0.128; //Example 430? * 0.128 = 55.4?
|
(((rx_frame.data.u8[7] & 0x3F) << 8) | rx_frame.data.u8[6]); //Example 430? * 0.128 = 55.4?
|
||||||
break;
|
break;
|
||||||
case 0x2b4:
|
case 0x2b4: //PCS_dcdcRailStatus:
|
||||||
battery_low_voltage = (((rx_frame.data.u8[1] & 0x03) << 8) | rx_frame.data.u8[0]) * 0.0390625;
|
battery_dcdcLvBusVolt = (((rx_frame.data.u8[1] & 0x03) << 8) | rx_frame.data.u8[0]); //update name move factoring
|
||||||
battery_high_voltage = ((((rx_frame.data.u8[2] & 0x3F) << 6) | ((rx_frame.data.u8[1] & 0xFC) >> 2))) * 0.146484;
|
battery_dcdcHvBusVolt =
|
||||||
battery_output_current = (((rx_frame.data.u8[4] & 0x0F) << 8) | rx_frame.data.u8[3]) / 100;
|
((((rx_frame.data.u8[2] & 0x3F) << 6) | ((rx_frame.data.u8[1] & 0xFC) >> 2))); //update name move factoring
|
||||||
|
battery_dcdcLvOutputCurrent =
|
||||||
|
(((rx_frame.data.u8[4] & 0x0F) << 8) | rx_frame.data.u8[3]); //update name move factoring
|
||||||
break;
|
break;
|
||||||
case 0x292:
|
case 0x292: //BMS_socStatus
|
||||||
datalayer.battery.status.CAN_battery_still_alive = CAN_STILL_ALIVE; //We are getting CAN messages from the BMS
|
datalayer.battery.status.CAN_battery_still_alive = CAN_STILL_ALIVE; //We are getting CAN messages from the BMS
|
||||||
battery_beginning_of_life = (((rx_frame.data.u8[6] & 0x03) << 8) | rx_frame.data.u8[5]);
|
battery_beginning_of_life = (((rx_frame.data.u8[6] & 0x03) << 8) | rx_frame.data.u8[5]);
|
||||||
battery_soc_min = (((rx_frame.data.u8[1] & 0x03) << 8) | rx_frame.data.u8[0]);
|
battery_soc_min = (((rx_frame.data.u8[1] & 0x03) << 8) | rx_frame.data.u8[0]);
|
||||||
battery_soc_vi = (((rx_frame.data.u8[2] & 0x0F) << 6) | ((rx_frame.data.u8[1] & 0xFC) >> 2));
|
battery_soc_ui = (((rx_frame.data.u8[2] & 0x0F) << 6) | ((rx_frame.data.u8[1] & 0xFC) >> 2));
|
||||||
battery_soc_max = (((rx_frame.data.u8[3] & 0x3F) << 4) | ((rx_frame.data.u8[2] & 0xF0) >> 4));
|
battery_soc_max = (((rx_frame.data.u8[3] & 0x3F) << 4) | ((rx_frame.data.u8[2] & 0xF0) >> 4));
|
||||||
battery_soc_ave = ((rx_frame.data.u8[4] << 2) | ((rx_frame.data.u8[3] & 0xC0) >> 6));
|
battery_soc_ave = ((rx_frame.data.u8[4] << 2) | ((rx_frame.data.u8[3] & 0xC0) >> 6));
|
||||||
|
battery_battTempPct = ((rx_frame.data.u8[7] & 0x03) << 6) | (rx_frame.data.u8[6] & (0x3F) >> 2);
|
||||||
|
break;
|
||||||
|
case 0x392: //BMS_packConfig
|
||||||
|
mux = (rx_frame.data.u8[0] & (0xFF));
|
||||||
|
if (mux == 1) {
|
||||||
|
battery_packConfigMultiplexer = (rx_frame.data.u8[0] & (0xff));
|
||||||
|
battery_moduleType = (rx_frame.data.u8[1] & (0x07));
|
||||||
|
battery_packMass = (rx_frame.data.u8[2]);
|
||||||
|
battery_platformMaxBusVoltage = ((rx_frame.data.u8[4] & 0x03) << 8) | (rx_frame.data.u8[3]);
|
||||||
|
}
|
||||||
|
if (mux == 0) {
|
||||||
|
battery_reservedConfig = (rx_frame.data.u8[1] & (0x1F));
|
||||||
|
}
|
||||||
break;
|
break;
|
||||||
case 0x3aa: //HVP_alertMatrix1
|
case 0x3aa: //HVP_alertMatrix1
|
||||||
battery_WatchdogReset = (rx_frame.data.u8[0] & 0x01);
|
battery_WatchdogReset = (rx_frame.data.u8[0] & 0x01);
|
||||||
|
@ -620,20 +700,47 @@ void receive_can_battery2(CAN_frame rx_frame) {
|
||||||
|
|
||||||
switch (rx_frame.ID) {
|
switch (rx_frame.ID) {
|
||||||
case 0x352:
|
case 0x352:
|
||||||
//SOC
|
mux = (rx_frame.data.u8[0] & 0x02); //BMS_energyStatusIndex M : 0|2@1+ (1,0) [0|0] "" X
|
||||||
battery2_nominal_full_pack_energy =
|
if (mux == 3) {
|
||||||
(((rx_frame.data.u8[1] & 0x0F) << 8) | (rx_frame.data.u8[0])); //Example 752 (75.2kWh)
|
battery2_nominal_full_pack_energy = //BMS_nominalFullPackEnergy : 0|11@1+ (0.1,0) [0|204.6] "KWh" //((_d[1] & (0x07U)) << 8) | (_d[0] & (0xFFU));
|
||||||
battery2_nominal_energy_remaining = (((rx_frame.data.u8[2] & 0x3F) << 5) | ((rx_frame.data.u8[1] & 0xF8) >> 3)) *
|
(((rx_frame.data.u8[1] & 0x07) << 8) | (rx_frame.data.u8[0])); //Example 752 (75.2kWh)
|
||||||
0.1; //Example 1247 * 0.1 = 124.7kWh
|
battery2_nominal_energy_remaining = //BMS_nominalEnergyRemaining : 11|11@1+ (0.1,0) [0|204.6] "KWh" //((_d[2] & (0x3FU)) << 5) | ((_d[1] >> 3) & (0x1FU));
|
||||||
battery2_expected_energy_remaining = (((rx_frame.data.u8[4] & 0x01) << 10) | (rx_frame.data.u8[3] << 2) |
|
(((rx_frame.data.u8[2] & 0x3F) << 5) |
|
||||||
((rx_frame.data.u8[2] & 0xC0) >> 6)); //Example 622 (62.2kWh)
|
((rx_frame.data.u8[1] & 0x1F) >> 3)); //Example 1247 * 0.1 = 124.7kWh
|
||||||
battery2_ideal_energy_remaining = (((rx_frame.data.u8[5] & 0x0F) << 7) | ((rx_frame.data.u8[4] & 0xFE) >> 1)) *
|
battery2_expected_energy_remaining = //BMS_expectedEnergyRemaining : 22|11@1+ (0.1,0) [0|204.6] "KWh"// ((_d[4] & (0x01U)) << 10) | ((_d[3] & (0xFFU)) << 2) | ((_d[2] >> 6) & (0x03U));
|
||||||
0.1; //Example 311 * 0.1 = 31.1kWh
|
(((rx_frame.data.u8[4] & 0x01) << 10) | (rx_frame.data.u8[3] << 2) |
|
||||||
battery2_energy_to_charge_complete = (((rx_frame.data.u8[6] & 0x7F) << 4) | ((rx_frame.data.u8[5] & 0xF0) >> 4)) *
|
((rx_frame.data.u8[2] & 0x03) >> 6)); //Example 622 (62.2kWh)
|
||||||
0.1; //Example 147 * 0.1 = 14.7kWh
|
battery2_ideal_energy_remaining = //BMS_idealEnergyRemaining : 33|11@1+ (0.1,0) [0|204.6] "KWh" //((_d[5] & (0x0FU)) << 7) | ((_d[4] >> 1) & (0x7FU));
|
||||||
battery2_energy_buffer =
|
(((rx_frame.data.u8[5] & 0x0F) << 7) | ((rx_frame.data.u8[4] & 0x7F) >> 1)); //Example 311 * 0.1 = 31.1kWh
|
||||||
(((rx_frame.data.u8[7] & 0x7F) << 1) | ((rx_frame.data.u8[6] & 0x80) >> 7)) * 0.1; //Example 1 * 0.1 = 0
|
battery2_energy_to_charge_complete = // BMS_energyToChargeComplete : 44|11@1+ (0.1,0) [0|204.6] "KWh"// ((_d[6] & (0x7FU)) << 4) | ((_d[5] >> 4) & (0x0FU));
|
||||||
battery2_full_charge_complete = ((rx_frame.data.u8[7] & 0x80) >> 7);
|
(((rx_frame.data.u8[6] & 0x7F) << 4) | ((rx_frame.data.u8[5] & 0x0F) << 4)); //Example 147 * 0.1 = 14.7kWh
|
||||||
|
battery2_energy_buffer = //BMS_energyBuffer : 55|8@1+ (0.1,0) [0|25.4] "KWh"// ((_d[7] & (0x7FU)) << 1) | ((_d[6] >> 7) & (0x01U));
|
||||||
|
(((rx_frame.data.u8[7] & 0x7F) << 1) | ((rx_frame.data.u8[6] & 0x01) >> 7)); //Example 1 * 0.1 = 0
|
||||||
|
battery2_full_charge_complete = //BMS_fullChargeComplete : 63|1@1+ (1,0) [0|1] ""//((_d[7] >> 7) & (0x01U));
|
||||||
|
((rx_frame.data.u8[7] & 0x01) >> 7);
|
||||||
|
}
|
||||||
|
if (mux == 0) {
|
||||||
|
battery2_nominal_full_pack_energy =
|
||||||
|
(rx_frame.data.u8[3] |
|
||||||
|
rx_frame.data.u8[2]); //SG_ BMS_nominalFullPackEnergy m0 : 16|16@1+ (0.02,0) [0|0] "kWh" X
|
||||||
|
battery2_nominal_energy_remaining =
|
||||||
|
(rx_frame.data.u8[5] |
|
||||||
|
rx_frame.data.u8[4]); //SG_ BMS_nominalEnergyRemaining m0 : 32|16@1+ (0.02,0) [0|0] "kWh" X
|
||||||
|
battery2_ideal_energy_remaining =
|
||||||
|
(rx_frame.data.u8[7] |
|
||||||
|
rx_frame.data.u8[6]); //SG_ BMS_idealEnergyRemaining m0 : 48|16@1+ (0.02,0) [0|0] "kWh" X
|
||||||
|
}
|
||||||
|
if (mux == 1) {
|
||||||
|
battery2_fully_charged = (rx_frame.data.u8[1] & 0x01); //SG_ BMS_fullyCharged m1 : 15|1@1+ (1,0) [0|1] "" X
|
||||||
|
battery2_energy_buffer =
|
||||||
|
(rx_frame.data.u8[3] | rx_frame.data.u8[2]); //SG_ BMS_energyBuffer m1 : 16|16@1+ (0.01,0) [0|0] "kWh" X
|
||||||
|
battery2_expected_energy_remaining =
|
||||||
|
(rx_frame.data.u8[5] |
|
||||||
|
rx_frame.data.u8[4]); //SG_ BMS_expectedEnergyRemaining m1 : 32|16@1+ (0.02,0) [0|0] "kWh" X
|
||||||
|
battery2_energy_to_charge_complete =
|
||||||
|
(rx_frame.data.u8[7] |
|
||||||
|
rx_frame.data.u8[6]); //SG_ BMS_energyToChargeComplete m1 : 48|16@1+ (0.02,0) [0|0] "kWh" X
|
||||||
|
}
|
||||||
break;
|
break;
|
||||||
case 0x20A:
|
case 0x20A:
|
||||||
//Contactor state
|
//Contactor state
|
||||||
|
@ -671,11 +778,9 @@ void receive_can_battery2(CAN_frame rx_frame) {
|
||||||
case 0x3D2:
|
case 0x3D2:
|
||||||
// total charge/discharge kwh
|
// total charge/discharge kwh
|
||||||
battery2_total_discharge = ((rx_frame.data.u8[3] << 24) | (rx_frame.data.u8[2] << 16) |
|
battery2_total_discharge = ((rx_frame.data.u8[3] << 24) | (rx_frame.data.u8[2] << 16) |
|
||||||
(rx_frame.data.u8[1] << 8) | rx_frame.data.u8[0]) *
|
(rx_frame.data.u8[1] << 8) | rx_frame.data.u8[0]);
|
||||||
0.001;
|
|
||||||
battery2_total_charge = ((rx_frame.data.u8[7] << 24) | (rx_frame.data.u8[6] << 16) | (rx_frame.data.u8[5] << 8) |
|
battery2_total_charge = ((rx_frame.data.u8[7] << 24) | (rx_frame.data.u8[6] << 16) | (rx_frame.data.u8[5] << 8) |
|
||||||
rx_frame.data.u8[4]) *
|
rx_frame.data.u8[4]);
|
||||||
0.001;
|
|
||||||
break;
|
break;
|
||||||
case 0x332:
|
case 0x332:
|
||||||
//min/max hist values
|
//min/max hist values
|
||||||
|
@ -730,29 +835,42 @@ void receive_can_battery2(CAN_frame rx_frame) {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case 0x2d2:
|
case 0x2d2: //BMSVAlimits:
|
||||||
//Min / max limits
|
//Min / max limits
|
||||||
battery2_bms_min_voltage =
|
battery2_bms_min_voltage =
|
||||||
((rx_frame.data.u8[1] << 8) | rx_frame.data.u8[0]) * 0.01 * 2; //Example 24148mv * 0.01 = 241.48 V
|
((rx_frame.data.u8[1] << 8) | rx_frame.data.u8[0]); //Example 24148mv * 0.01 = 241.48 V
|
||||||
battery2_bms_max_voltage =
|
battery2_bms_max_voltage =
|
||||||
((rx_frame.data.u8[3] << 8) | rx_frame.data.u8[2]) * 0.01 * 2; //Example 40282mv * 0.01 = 402.82 V
|
((rx_frame.data.u8[3] << 8) | rx_frame.data.u8[2]); //Example 40282mv * 0.01 = 402.82 V
|
||||||
battery2_max_charge_current =
|
battery2_max_charge_current =
|
||||||
(((rx_frame.data.u8[5] & 0x3F) << 8) | rx_frame.data.u8[4]) * 0.1; //Example 1301? * 0.1 = 130.1?
|
(((rx_frame.data.u8[5] & 0x3F) << 8) | rx_frame.data.u8[4]); //Example 1301? * 0.1 = 130.1?
|
||||||
battery2_max_discharge_current =
|
battery2_max_discharge_current =
|
||||||
(((rx_frame.data.u8[7] & 0x3F) << 8) | rx_frame.data.u8[6]) * 0.128; //Example 430? * 0.128 = 55.4?
|
(((rx_frame.data.u8[7] & 0x3F) << 8) | rx_frame.data.u8[6]); //Example 430? * 0.128 = 55.4?
|
||||||
break;
|
break;
|
||||||
case 0x2b4:
|
case 0x2b4: //PCS_dcdcRailStatus:
|
||||||
battery2_low_voltage = (((rx_frame.data.u8[1] & 0x03) << 8) | rx_frame.data.u8[0]) * 0.0390625;
|
battery2_dcdcLvBusVolt = (((rx_frame.data.u8[1] & 0x03) << 8) | rx_frame.data.u8[0]);
|
||||||
battery2_high_voltage = ((((rx_frame.data.u8[2] & 0x3F) << 6) | ((rx_frame.data.u8[1] & 0xFC) >> 2))) * 0.146484;
|
battery2_dcdcHvBusVolt = ((((rx_frame.data.u8[2] & 0x3F) << 6) | ((rx_frame.data.u8[1] & 0xFC) >> 2)));
|
||||||
battery2_output_current = (((rx_frame.data.u8[4] & 0x0F) << 8) | rx_frame.data.u8[3]) / 100;
|
battery2_dcdcLvOutputCurrent = (((rx_frame.data.u8[4] & 0x0F) << 8) | rx_frame.data.u8[3]);
|
||||||
break;
|
break;
|
||||||
case 0x292:
|
case 0x292: //BMS_socStatus
|
||||||
datalayer.battery2.status.CAN_battery_still_alive = CAN_STILL_ALIVE; //We are getting CAN messages from the BMS
|
datalayer.battery2.status.CAN_battery_still_alive = CAN_STILL_ALIVE; //We are getting CAN messages from the BMS
|
||||||
battery2_beginning_of_life = (((rx_frame.data.u8[6] & 0x03) << 8) | rx_frame.data.u8[5]);
|
battery2_beginning_of_life = (((rx_frame.data.u8[6] & 0x03) << 8) | rx_frame.data.u8[5]);
|
||||||
battery2_soc_min = (((rx_frame.data.u8[1] & 0x03) << 8) | rx_frame.data.u8[0]);
|
battery2_soc_min = (((rx_frame.data.u8[1] & 0x03) << 8) | rx_frame.data.u8[0]);
|
||||||
battery2_soc_vi = (((rx_frame.data.u8[2] & 0x0F) << 6) | ((rx_frame.data.u8[1] & 0xFC) >> 2));
|
battery2_soc_ui = (((rx_frame.data.u8[2] & 0x0F) << 6) | ((rx_frame.data.u8[1] & 0xFC) >> 2));
|
||||||
battery2_soc_max = (((rx_frame.data.u8[3] & 0x3F) << 4) | ((rx_frame.data.u8[2] & 0xF0) >> 4));
|
battery2_soc_max = (((rx_frame.data.u8[3] & 0x3F) << 4) | ((rx_frame.data.u8[2] & 0xF0) >> 4));
|
||||||
battery2_soc_ave = ((rx_frame.data.u8[4] << 2) | ((rx_frame.data.u8[3] & 0xC0) >> 6));
|
battery2_soc_ave = ((rx_frame.data.u8[4] << 2) | ((rx_frame.data.u8[3] & 0xC0) >> 6));
|
||||||
|
battery2_battTempPct = ((rx_frame.data.u8[7] & 0x03) << 6) | (rx_frame.data.u8[6] & (0x3F) >> 2);
|
||||||
|
break;
|
||||||
|
case 0x392: //BMS_packConfig
|
||||||
|
mux = (rx_frame.data.u8[0] & (0xFF));
|
||||||
|
if (mux == 1) {
|
||||||
|
battery2_packConfigMultiplexer = (rx_frame.data.u8[0] & (0xff));
|
||||||
|
battery2_moduleType = (rx_frame.data.u8[1] & (0x07));
|
||||||
|
battery2_packMass = (rx_frame.data.u8[2]);
|
||||||
|
battery2_platformMaxBusVoltage = ((rx_frame.data.u8[4] & 0x03) << 8) | (rx_frame.data.u8[3]);
|
||||||
|
}
|
||||||
|
if (mux == 0) {
|
||||||
|
battery2_reservedConfig = (rx_frame.data.u8[1] & (0x1F));
|
||||||
|
}
|
||||||
break;
|
break;
|
||||||
case 0x3aa: //HVP_alertMatrix1
|
case 0x3aa: //HVP_alertMatrix1
|
||||||
battery2_WatchdogReset = (rx_frame.data.u8[0] & 0x01);
|
battery2_WatchdogReset = (rx_frame.data.u8[0] & 0x01);
|
||||||
|
@ -817,7 +935,7 @@ void update_values_battery2() { //This function maps all the values fetched via
|
||||||
|
|
||||||
datalayer.battery2.status.soh_pptt = 9900; //Tesla batteries do not send a SOH% value on bus. Hardcode to 99%
|
datalayer.battery2.status.soh_pptt = 9900; //Tesla batteries do not send a SOH% value on bus. Hardcode to 99%
|
||||||
|
|
||||||
datalayer.battery2.status.real_soc = (battery2_soc_vi * 10); //increase SOC range from 0-100.0 -> 100.00
|
datalayer.battery2.status.real_soc = (battery2_soc_ui * 10); //increase SOC range from 0-100.0 -> 100.00
|
||||||
|
|
||||||
datalayer.battery2.status.voltage_dV = (battery2_volts * 10); //One more decimal needed (370 -> 3700)
|
datalayer.battery2.status.voltage_dV = (battery2_volts * 10); //One more decimal needed (370 -> 3700)
|
||||||
|
|
||||||
|
@ -835,12 +953,12 @@ void update_values_battery2() { //This function maps all the values fetched via
|
||||||
}
|
}
|
||||||
|
|
||||||
//The allowed charge power behaves strangely. We instead estimate this value
|
//The allowed charge power behaves strangely. We instead estimate this value
|
||||||
if (battery2_soc_vi > 990) {
|
if (battery2_soc_ui > 990) {
|
||||||
datalayer.battery2.status.max_charge_power_W = FLOAT_MAX_POWER_W;
|
datalayer.battery2.status.max_charge_power_W = FLOAT_MAX_POWER_W;
|
||||||
} else if (battery2_soc_vi >
|
} else if (battery2_soc_ui >
|
||||||
RAMPDOWN_SOC) { // When real SOC is between RAMPDOWN_SOC-99%, ramp the value between Max<->0
|
RAMPDOWN_SOC) { // When real SOC is between RAMPDOWN_SOC-99%, ramp the value between Max<->0
|
||||||
datalayer.battery2.status.max_charge_power_W =
|
datalayer.battery2.status.max_charge_power_W =
|
||||||
MAXCHARGEPOWERALLOWED * (1 - (battery2_soc_vi - RAMPDOWN_SOC) / (1000.0 - RAMPDOWN_SOC));
|
MAXCHARGEPOWERALLOWED * (1 - (battery2_soc_ui - RAMPDOWN_SOC) / (1000.0 - RAMPDOWN_SOC));
|
||||||
//If the cellvoltages start to reach overvoltage, only allow a small amount of power in
|
//If the cellvoltages start to reach overvoltage, only allow a small amount of power in
|
||||||
if (datalayer.battery2.info.chemistry == battery_chemistry_enum::LFP) {
|
if (datalayer.battery2.info.chemistry == battery_chemistry_enum::LFP) {
|
||||||
if (battery2_cell_max_v > (MAX_CELL_VOLTAGE_LFP - FLOAT_START_MV)) {
|
if (battery2_cell_max_v > (MAX_CELL_VOLTAGE_LFP - FLOAT_START_MV)) {
|
||||||
|
@ -919,7 +1037,7 @@ void update_values_battery2() { //This function maps all the values fetched via
|
||||||
|
|
||||||
Serial.print("Battery2 values: ");
|
Serial.print("Battery2 values: ");
|
||||||
Serial.print("Real SOC: ");
|
Serial.print("Real SOC: ");
|
||||||
Serial.print(battery2_soc_vi / 10.0, 1);
|
Serial.print(battery2_soc_ui / 10.0, 1);
|
||||||
print_int_with_units(", Battery2 voltage: ", battery2_volts, "V");
|
print_int_with_units(", Battery2 voltage: ", battery2_volts, "V");
|
||||||
print_int_with_units(", Battery2 HV current: ", (battery2_amps * 0.1), "A");
|
print_int_with_units(", Battery2 HV current: ", (battery2_amps * 0.1), "A");
|
||||||
Serial.print(", Fully charged?: ");
|
Serial.print(", Fully charged?: ");
|
||||||
|
@ -943,11 +1061,11 @@ void update_values_battery2() { //This function maps all the values fetched via
|
||||||
Serial.print(battery2_cell_deviation_mV);
|
Serial.print(battery2_cell_deviation_mV);
|
||||||
Serial.println("mV.");
|
Serial.println("mV.");
|
||||||
|
|
||||||
print_int_with_units("High Voltage Output Pins: ", battery2_high_voltage, "V");
|
print_int_with_units("High Voltage Output Pins: ", battery2_dcdcHvBusVolt, "V");
|
||||||
Serial.print(", ");
|
Serial.print(", ");
|
||||||
print_int_with_units("Low Voltage: ", battery2_low_voltage, "V");
|
print_int_with_units("Low Voltage: ", battery2_dcdcLvBusVolt, "V");
|
||||||
Serial.println("");
|
Serial.println("");
|
||||||
print_int_with_units("DC/DC 12V current: ", battery2_output_current, "A");
|
print_int_with_units("DC/DC 12V current: ", battery2_dcdcLvOutputCurrent, "A");
|
||||||
Serial.println("");
|
Serial.println("");
|
||||||
|
|
||||||
Serial.println("Values passed to the inverter: ");
|
Serial.println("Values passed to the inverter: ");
|
||||||
|
|
|
@ -177,7 +177,33 @@ typedef struct {
|
||||||
/** uint8_t */
|
/** uint8_t */
|
||||||
/** Pyro test in progress */
|
/** Pyro test in progress */
|
||||||
uint8_t pyroTestInProgress = 0;
|
uint8_t pyroTestInProgress = 0;
|
||||||
|
uint8_t battery_beginning_of_life = 0;
|
||||||
|
uint8_t battery_battTempPct = 0;
|
||||||
|
uint16_t battery_dcdcLvBusVolt = 0;
|
||||||
|
uint16_t battery_dcdcHvBusVolt = 0;
|
||||||
|
uint16_t battery_dcdcLvOutputCurrent = 0;
|
||||||
|
uint16_t battery_nominal_full_pack_energy = 0;
|
||||||
|
uint16_t battery_nominal_energy_remaining = 0;
|
||||||
|
uint16_t battery_ideal_energy_remaining = 0;
|
||||||
|
uint16_t battery_energy_to_charge_complete = 0;
|
||||||
|
uint16_t battery_energy_buffer = 0;
|
||||||
|
uint16_t battery_full_charge_complete = 0;
|
||||||
|
uint8_t battery_fully_charged = 0;
|
||||||
|
uint16_t battery_total_discharge = 0;
|
||||||
|
uint16_t battery_total_charge = 0;
|
||||||
|
uint16_t battery_packConfigMultiplexer = 0;
|
||||||
|
uint16_t battery_moduleType = 0;
|
||||||
|
uint16_t battery_reservedConfig = 0;
|
||||||
|
uint32_t battery_packMass = 0;
|
||||||
|
uint32_t battery_platformMaxBusVoltage = 0;
|
||||||
|
uint32_t battery_bms_min_voltage = 0;
|
||||||
|
uint32_t battery_bms_max_voltage = 0;
|
||||||
|
uint32_t battery_max_charge_current = 0;
|
||||||
|
uint32_t battery_max_discharge_current = 0;
|
||||||
|
uint32_t battery_soc_min = 0;
|
||||||
|
uint32_t battery_soc_max = 0;
|
||||||
|
uint32_t battery_soc_ave = 0;
|
||||||
|
uint32_t battery_soc_ui = 0;
|
||||||
} DATALAYER_INFO_TESLA;
|
} DATALAYER_INFO_TESLA;
|
||||||
|
|
||||||
typedef struct {
|
typedef struct {
|
||||||
|
|
|
@ -283,6 +283,59 @@ String advanced_battery_processor(const String& var) {
|
||||||
#endif //BYD_ATTO_3_BATTERY
|
#endif //BYD_ATTO_3_BATTERY
|
||||||
|
|
||||||
#ifdef TESLA_BATTERY
|
#ifdef TESLA_BATTERY
|
||||||
|
float beginning_of_life = static_cast<float>(datalayer_extended.tesla.battery_beginning_of_life) * 0.1;
|
||||||
|
content += "<h4>Battery Beginning of Life: " + String(beginning_of_life) + " kWh</h4>";
|
||||||
|
float battTempPct = static_cast<float>(datalayer_extended.tesla.battery_battTempPct) * 0.4;
|
||||||
|
content += "<h4>BattTempPct: " + String(battTempPct) + " </h4>";
|
||||||
|
float dcdcLvBusVolt = static_cast<float>(datalayer_extended.tesla.battery_dcdcLvBusVolt) * 0.0390625;
|
||||||
|
content += "<h4>PCS Lv Bus: " + String(dcdcLvBusVolt) + " V</h4>";
|
||||||
|
float dcdcHvBusVolt = static_cast<float>(datalayer_extended.tesla.battery_dcdcHvBusVolt) * 0.146484;
|
||||||
|
content += "<h4>PCS Hv Bus: " + String(dcdcHvBusVolt) + " V</h4>";
|
||||||
|
float dcdcLvOutputCurrent = static_cast<float>(datalayer_extended.tesla.battery_dcdcLvOutputCurrent) * 0.1;
|
||||||
|
content += "<h4>PCS Lv Output: " + String(dcdcLvOutputCurrent) + " A</h4>";
|
||||||
|
float nominal_full_pack_energy =
|
||||||
|
static_cast<float>(datalayer_extended.tesla.battery_nominal_full_pack_energy) * 0.1;
|
||||||
|
content += "<h4>Nominal Full Pack Energy: " + String(nominal_full_pack_energy) + " kWh</h4>";
|
||||||
|
float nominal_energy_remaining =
|
||||||
|
static_cast<float>(datalayer_extended.tesla.battery_nominal_energy_remaining) * 0.1;
|
||||||
|
content += "<h4>Nominal Energy Remaining: " + String(nominal_energy_remaining) + " kWh</h4>";
|
||||||
|
float ideal_energy_remaining = static_cast<float>(datalayer_extended.tesla.battery_ideal_energy_remaining) * 0.1;
|
||||||
|
content += "<h4>Ideal Energy Remaining: " + String(ideal_energy_remaining) + " kWh</h4>";
|
||||||
|
float energy_to_charge_complete =
|
||||||
|
static_cast<float>(datalayer_extended.tesla.battery_energy_to_charge_complete) * 0.1;
|
||||||
|
content += "<h4>Energy to Charge Complete: " + String(energy_to_charge_complete) + " kWh</h4>";
|
||||||
|
float energy_buffer = static_cast<float>(datalayer_extended.tesla.battery_energy_buffer) * 0.1;
|
||||||
|
content += "<h4>Energy Buffer: " + String(energy_buffer) + " kWh</h4>";
|
||||||
|
content += "<h4>packConfigMultiplexer: " + String(datalayer_extended.tesla.battery_packConfigMultiplexer) + "</h4>";
|
||||||
|
content += "<h4>moduleType: " + String(datalayer_extended.tesla.battery_moduleType) + "</h4>";
|
||||||
|
content += "<h4>reserveConfig: " + String(datalayer_extended.tesla.battery_reservedConfig) + "</h4>";
|
||||||
|
content += "<h4>Full Charge Complete: " + String(datalayer_extended.tesla.battery_full_charge_complete) +
|
||||||
|
"</h4>"; // no float needed
|
||||||
|
float total_discharge = static_cast<float>(datalayer_extended.tesla.battery_total_discharge) * 0.001;
|
||||||
|
content += "<h4>Total Discharge: " + String(total_discharge) + " kWh</h4>";
|
||||||
|
float total_charge = static_cast<float>(datalayer_extended.tesla.battery_total_charge) * 0.001;
|
||||||
|
content += "<h4>Total Charge: " + String(total_charge) + " kWh</h4>";
|
||||||
|
float packMass = static_cast<float>(datalayer_extended.tesla.battery_packMass) + 300;
|
||||||
|
content += "<h4>Battery Pack Mass: " + String(packMass) + " KG</h4>";
|
||||||
|
float platformMaxBusVoltage =
|
||||||
|
static_cast<float>(datalayer_extended.tesla.battery_platformMaxBusVoltage) * 0.1 + 375;
|
||||||
|
content += "<h4>Platform Max Bus Voltage: " + String(platformMaxBusVoltage) + " V</h4>";
|
||||||
|
float bms_min_voltage = static_cast<float>(datalayer_extended.tesla.battery_bms_min_voltage) * 0.01 * 2;
|
||||||
|
content += "<h4>BMS Min Voltage: " + String(bms_min_voltage) + " V</h4>";
|
||||||
|
float bms_max_voltage = static_cast<float>(datalayer_extended.tesla.battery_bms_max_voltage) * 0.01 * 2;
|
||||||
|
content += "<h4>BMS Max Voltage: " + String(bms_max_voltage) + " V</h4>";
|
||||||
|
float max_charge_current = static_cast<float>(datalayer_extended.tesla.battery_max_charge_current) * 0.1;
|
||||||
|
content += "<h4>Max Charge Current: " + String(max_charge_current) + " A</h4>";
|
||||||
|
float max_discharge_current = static_cast<float>(datalayer_extended.tesla.battery_max_discharge_current) * 0.128;
|
||||||
|
content += "<h4>Max Discharge Current: " + String(max_discharge_current) + " A</h4>";
|
||||||
|
float soc_ave = static_cast<float>(datalayer_extended.tesla.battery_soc_ave) * 0.1;
|
||||||
|
content += "<h4>Battery SOC Ave: " + String(soc_ave) + " </h4>";
|
||||||
|
float soc_max = static_cast<float>(datalayer_extended.tesla.battery_soc_max) * 0.1;
|
||||||
|
content += "<h4>Battery SOC Max: " + String(soc_max) + " </h4>";
|
||||||
|
float soc_min = static_cast<float>(datalayer_extended.tesla.battery_soc_min) * 0.1;
|
||||||
|
content += "<h4>Battery SOC Min: " + String(soc_min) + " </h4>";
|
||||||
|
float soc_ui = static_cast<float>(datalayer_extended.tesla.battery_soc_ui) * 0.1;
|
||||||
|
content += "<h4>Battery SOC UI: " + String(soc_ui) + " </h4>";
|
||||||
static const char* contactorText[] = {"UNKNOWN(0)", "OPEN", "CLOSING", "BLOCKED", "OPENING",
|
static const char* contactorText[] = {"UNKNOWN(0)", "OPEN", "CLOSING", "BLOCKED", "OPENING",
|
||||||
"CLOSED", "UNKNOWN(6)", "WELDED", "POS_CL", "NEG_CL",
|
"CLOSED", "UNKNOWN(6)", "WELDED", "POS_CL", "NEG_CL",
|
||||||
"UNKNOWN(10)", "UNKNOWN(11)", "UNKNOWN(12)"};
|
"UNKNOWN(10)", "UNKNOWN(11)", "UNKNOWN(12)"};
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue