Separated grid charging from balancing

New Features in LiBCM v0.7.0:
-default current hack value is now +40%.
-Removed RevB HW support (all Open Beta customers have RevC HW).
-Can now disable assist and/or regen (as requested by Balto).  See config.h>>DISABLE_ASSIST & DISABLE_REGEN.
-Cell balancing now runs independently from grid charging.
-Cells now balance to 0.5 mV (previously 1.0 mV).
-Cell balancing now occurs as needed whenever the key is off (even when grid charger unplugged).  When the grid charger is unplugged, cell balancing is disabled if SoC drops below 40% (see config.h>>CELL_BALANCE_MIN_SoC).  If you prefer the old behavior, see config.h>>ONLY_BALANCE_CELLS_WHEN_GRID_CHARGER_PLUGGED_IN.
-Added hysteresis to grid charging and cell balancing.
-Cell balancing now twice as fast.
-Grid charger now always charges pack to 75% SoC (rather than stopping somewhere between 60%:75%).
-Fans no longer tied to grid charger status; now controlled by balancing routine.  Fans now run as needed to cool discharge resistors.
-LiBCM will not boot unless the safety cover is installed (see config.h>>PREVENT_BOOT_WITHOUT_SAFETY_COVER to disable).
-LiBCM now turns off completely if the SoC gets too low (see config.h>>CELL_VMIN_KEYOFF).
-Fan speed now ramps as needed for cooling
-LiBCM will now discharge over-charged cells when the key is off.  Cells shouldn't ever over-charge, but just in case.
-4x20 display now shows isoSPI error rate "ex: E00"
-4x20 display now shows grid charger status: 'G' = grid charger charging, 'g' = grid charger plugged in, but hasn't charged yet, ' ' = grid charger plugged in and finished charging.
-fixed an issue where 4x20 battery temperature wouldn't display if starting temperature was 0 degC, until temperature != 0 degC.
-streamlined 4x20 display logic code.
-renamed confusing variables/functions.

Caveat:
-v0.7.0 has much higher keyOFF power consumption!  Expect to lose 8% SoC per day.
-v0.7.1 will reduce keyOFF power consumption (to even less than v0.6.8).
This commit is contained in:
John Sullivan
2022-03-10 02:37:20 -05:00
parent c04f38f4d4
commit bf7d1a86c5
30 changed files with 1705 additions and 9371 deletions

View File

@@ -0,0 +1,16 @@
Running 3.5 amps thru TRIAC causes it to overheat
Tested with HLG-480H-2100 charger
TRIAC (T810-600B) is rated to handle 8 amps, but that requires a much larger copper pour. Looks like there's room on the PCB for that. Look at "Figure 12: DPAK and D2PAK thermal resistance junction to ambient versus copper surface under tab" (page 6/21) for theta j-a values. Looks like we'd need at least 4 square cm to appreciably improve performance.
Another option is to add gull-wing heatsink:
V-1100-SMD/B
V-1100-SMD/B-L
ATS-PCBT1095
573100D00010G
Looking at "Figure 3: RMS on-state current versus ambient temperature" (page 4/21), the existing part isn't rated to carry more than 1.25 amps when the ambient temp is 55 degC.
That's what the existing grid charger pulls... so probably can't use a larger grid charger unless the TRIAC itself is replaced.

File diff suppressed because it is too large Load Diff

View File

@@ -100,9 +100,9 @@ void bringupTester_run(void)
//Turn 4x20 screen on
Serial.print(F("\nWriting Data to 4x20 LCD"));
serialUSB_waitForEmptyBuffer();
lcd_initialize();
lcd_begin();
lcd_printStaticText();
lcd_displayON();
lcd_displayOn();
//test if 4x20 screen dims when 5V buck turned off (USB powers at lower voltage)
for(int ii=0; ii<6; ii++)
@@ -271,7 +271,7 @@ void bringupTester_run(void)
serialUSB_waitForEmptyBuffer();
{
gpio_setFanSpeed_OEM('0'); //turn all FETs off (0A thru sensor)
gpio_setFanSpeed('0'); //turn all FETs off (0A thru sensor)
gpio_setFanSpeed('0', ABSOLUTE_FAN_SPEED); //turn all FETs off (0A thru sensor)
delay(10);
uint16_t resultADC = analogRead(PIN_BATTCURRENT); // 0A is 330 counts
@@ -285,7 +285,7 @@ void bringupTester_run(void)
serialUSB_waitForEmptyBuffer();
{
gpio_setFanSpeed_OEM('L'); //test OEM fan low speed relay
gpio_setFanSpeed('0');
gpio_setFanSpeed('0', ABSOLUTE_FAN_SPEED);
delay(500);
uint16_t resultADC = analogRead(PIN_BATTCURRENT); // 3A * 19 turns = '57 A' = 595 counts
@@ -299,7 +299,7 @@ void bringupTester_run(void)
serialUSB_waitForEmptyBuffer();
{
gpio_setFanSpeed_OEM('H'); //test OEM fan low speed relay
gpio_setFanSpeed('0');
gpio_setFanSpeed('0', ABSOLUTE_FAN_SPEED);
delay(500);
uint16_t resultADC = analogRead(PIN_BATTCURRENT); // 3A * 19 turns = '57 A' = 595 counts
@@ -313,7 +313,7 @@ void bringupTester_run(void)
serialUSB_waitForEmptyBuffer();
{
gpio_setFanSpeed_OEM('0'); //test OEM fan low speed relay
gpio_setFanSpeed('H');
gpio_setFanSpeed('H', ABSOLUTE_FAN_SPEED);
delay(500);
uint16_t resultADC = analogRead(PIN_BATTCURRENT); // 3A * 19 turns = '57 A' = 595 counts
@@ -330,7 +330,7 @@ void bringupTester_run(void)
gpio_turnPowerSensors_off();
delay(500);
gpio_setFanSpeed('H'); //should already be here
gpio_setFanSpeed('H', ABSOLUTE_FAN_SPEED); //should already be here
delay(100);
uint16_t resultADC = analogRead(PIN_BATTCURRENT); // 0A is 330 counts
@@ -339,7 +339,7 @@ void bringupTester_run(void)
}
//turn all FETs off (so they don't overheat)
gpio_setFanSpeed('0');
gpio_setFanSpeed('0', ABSOLUTE_FAN_SPEED);
gpio_setFanSpeed_OEM('0');
/////////////////////////////////////////////////////////////////////
@@ -470,17 +470,17 @@ void bringupTester_run(void)
gpio_turnBuzzer_off();
uint16_t cellDischargeBitmap = 0b0000010101010101; //discharge cells 1/3/5/7/9/11
LTC68042configure_cellBalancing_setCells( (FIRST_IC_ADDR + ii), cellDischargeBitmap);
LTC68042configure_setBalanceResistors( (FIRST_IC_ADDR + ii), cellDischargeBitmap);
delay(1800); //wait for visual inspection
LTC68042configure_cellBalancing_disable(); //disable all discharge FETs
LTC68042configure_programVolatileDefaults(); //disables all discharge FETs
delay(1800); //wait for cool down
cellDischargeBitmap = 0b0000101010101010; //discharge cells 2/4/6/8/10/12
LTC68042configure_cellBalancing_setCells( (FIRST_IC_ADDR + ii), cellDischargeBitmap);
LTC68042configure_setBalanceResistors( (FIRST_IC_ADDR + ii), cellDischargeBitmap);
delay(1800); //wait for visual inspection
LTC68042configure_cellBalancing_disable(); //disable all discharge FETs
LTC68042configure_programVolatileDefaults(); //disables all discharge FETs
delay(1800); //wait for cool down
}
}

View File

@@ -68,22 +68,23 @@ void LTC68042configure_writeConfigurationRegisters(uint8_t icAddress)
//---------------------------------------------------------------------------------------
void LTC68042configure_cellBalancing_setCells(uint8_t icAddress, uint16_t cellBitmap)
//configure discharge resistor states on a single LTC6804 IC
void LTC68042configure_setBalanceResistors(uint8_t icAddress, uint16_t cellBitmap)
{
//Each bit in cellBitmap corresponds to a specific cell's DCCn discharge bit
//Example: cellBitmap = 0b0000 1000 0000 0011 enables discharge on cells 12, 2, and 1 //LSB is cell01
//Example: cellBitmap = 0b0000 1111 1111 1111 enables discharge on all cells
configurationRegisterData[4] = (uint8_t)(cellBitmap); //LSByte
configurationRegisterData[5] = (( (uint8_t)(cellBitmap >> 8) ) & 0b00001111); //MSByte's lower nibble
configurationRegisterData[5] = ( ((uint8_t)(cellBitmap >> 8)) & 0b00001111 ); //MSByte's lower nibble
LTC68042configure_writeConfigurationRegisters(icAddress);
}
//---------------------------------------------------------------------------------------
//Turn off discharge FETs, turn reference on and configure ADC LPF to '2 kHz mode' (1.7 kHz LPF)
//program configuration register values onto each LTC6804 IC
//configuration register data resets if LTC watchdog timer expires (~2000 milliseconds)
void LTC68042configure_cellBalancing_disable()
void LTC68042configure_programVolatileDefaults(void)
{ // BIT7 BIT6 BIT5 BIT4 BIT3 BIT2 BIT1 BIT0
///////////////////////////////////////////////////////////////
configurationRegisterData[0] = 0b11111111 ; //GPIO5 GPIO4 GPIO3 GPIO2 GPIO1 REFON SWTRD ADCOPT
@@ -92,8 +93,8 @@ void LTC68042configure_cellBalancing_disable()
configurationRegisterData[3] = 0x00 ; //VOV[11] VOV[10] VOV[9] VOV[8] VOV[7] VOV[6] VOV[5] VOV[4]
configurationRegisterData[4] = 0x00 ; //DCC8 DCC7 DCC6 DCC5 DCC4 DCC3 DCC2 DCC1
configurationRegisterData[5] = 0x00 ; //DCTO[3] DCTO[2] DCTO[1] DCTO[0] DCC12 DCC11 DCC10 DCC9
//Above values turn off all discharge FETs, turns reference on, and configure ADC LPF to '2 kHz mode' (1.7 kHz LPF)
//t=2.2 milliseconds (ICs initially off)
for(int ii = FIRST_IC_ADDR; ii < (FIRST_IC_ADDR + TOTAL_IC); ii++)
{
LTC68042configure_writeConfigurationRegisters(ii); //t=450 us
@@ -112,7 +113,7 @@ void LTC68042configure_cellBalancing_disable()
//---------------------------------------------------------------------------------------
void LTC68042configure_initialize()
void LTC68042configure_initialize(void)
{
spi_enable(SPI_CLOCK_DIV64); //JTS2doLater: See how fast we can use SPI without transmission errors
//LTC6804configure_calculate_CFGRn();
@@ -121,7 +122,7 @@ void LTC68042configure_initialize()
//---------------------------------------------------------------------------------------
void LTC68042configure_wakeupIsoSPI()
void LTC68042configure_wakeupIsoSPI(void)
{
const uint8_t T_IDLE_isoSPI_millis = 4; //'tidle' (absMIN) = 4.3 ms
@@ -136,7 +137,7 @@ void LTC68042configure_wakeupIsoSPI()
//---------------------------------------------------------------------------------------
//wake up LTC ICs after watchdog timeout
void LTC68042configure_wakeupCore()
void LTC68042configure_wakeupCore(void)
{
const uint16_t T_SLEEP_WATCHDOG_MILLIS = 1800; //'tsleep' (absMIN) = 1800 ms
@@ -190,7 +191,7 @@ void LTC68042configure_spiWriteRead(uint8_t tx_Data[],//array of data to be writ
//---------------------------------------------------------------------------------------
void LTC6804configure_handleKeyOff(void)
void LTC68042configure_handleKeyStateChange(void)
{
LTC68042result_errorCount_set(0);
LTC68042result_maxEverCellVoltage_set(0);

View File

@@ -139,13 +139,13 @@
}
*/
void LTC68042configure_initialize();
void LTC68042configure_initialize(void);
void LTC6804configure_handleKeyOff(void);
void LTC68042configure_handleKeyStateChange(void);
void LTC68042configure_wakeupIsoSPI();
void LTC68042configure_wakeupIsoSPI(void);
void LTC68042configure_wakeupCore();
void LTC68042configure_wakeupCore(void);
uint16_t LTC68042configure_calcPEC15(uint8_t len, uint8_t *data);
@@ -153,8 +153,8 @@
void LTC68042configure_spiWriteRead(uint8_t *TxData, uint8_t TXlen, uint8_t *rx_data, uint8_t RXlen);
void LTC68042configure_cellBalancing_disable();
void LTC68042configure_programVolatileDefaults(void);
void LTC68042configure_cellBalancing_setCells(uint8_t icAddress, uint16_t cellBitmap);
void LTC68042configure_setBalanceResistors(uint8_t icAddress, uint16_t cellBitmap);
#endif

View File

@@ -12,16 +12,15 @@ void setup() //~t=2 milliseconds, BUT NOTE this doesn't include CPU_CLOCK warmup
METSCI_begin();
BATTSCI_begin();
LiDisplay_begin();
lcd_begin();
LTC68042configure_initialize();
if( gpio_keyStateNow() == KEYON ){ LED(3,ON); } //turn LED3 on if LiBCM (re)boots while keyON (e.g. while driving)
//JTS2doLater: Configure watchdog
gpio_safetyCoverCheck(); //this function never returns if safety cover isn't installed during initial powerup
#ifdef HW_REVB
gpio_turnBuzzer_on_lowFreq(); //enable buzzer if RevB firmware loaded onto RevC+ hardware (RevB hardware doesn't have a buzzer)
#endif
//JTS2doLater: Configure watchdog
#ifdef RUN_BRINGUP_TESTER
bringupTester_run(); //this function never returns
@@ -33,13 +32,12 @@ void setup() //~t=2 milliseconds, BUT NOTE this doesn't include CPU_CLOCK warmup
void loop()
{
key_stateChangeHandler();
gridCharger_handler();
SoC_handler();
temperature_handler();
SoC_handler();
if( key_getSampledState() == KEYON )
{
if( gpio_isGridChargerPluggedInNow() == PLUGGED_IN ) { lcd_gridChargerWarning(); } //P1648 occurs if grid charger powered while keyON
if( gpio_isGridChargerPluggedInNow() == PLUGGED_IN ) { lcd_Warning_gridCharger(); } //P1648 occurs if grid charger powered while keyON
else if( EEPROM_firmwareStatus_get() != FIRMWARE_STATUS_EXPIRED ) { BATTSCI_sendFrames(); } //P1648 occurs if firmware is expired
LTC68042cell_nextVoltages(); //round-robin handler measures QTY3 cell voltages per call
@@ -56,7 +54,24 @@ void loop()
}
else if( key_getSampledState() == KEYOFF )
{
SoC_openCircuitVoltage_handler(); //periodically check pack voltage
// //JTS2doNow: Use this to control LTC6804 measurement rate
// if( gpio_isGridChargerPluggedInNow() == true ) { delayPeriodToReadCellVoltages_seconds = 1; }
//else /* grid charger unplugged */ { delayPeriodToReadCellVoltages_seconds = 600; }
//JTS2doNow: Put this somewhere
if( LTC68042cell_nextVoltages() == PROCESSED_LTC6804_DATA )
{
//all cells measured
SoC_setBatteryStateNow_percent( SoC_estimateFromRestingCellVoltage_percent() );
SoC_turnOffLiBCM_ifPackEmpty();
}
//SoC_keyOff_cellMeasurement_handler();
gridCharger_handler();
cellBalance_handler();
}
//JTS2doLater: Check for Serial Input from user
@@ -69,9 +84,8 @@ void loop()
{
static uint32_t previousMillis = millis();
LED(4,HIGH); //LED4 brightness proportional to how much CPU time is left //if off, exceeding LOOP_RATE_MILLISECONDS
while( (millis() - previousMillis) < LOOP_RATE_MILLISECONDS ) { ; } //wait here to start next loop //JTS2doLater: Determine Behavior after overflow (50 days)
//JTS2doLater: Feed watchdog
LED(4,HIGH); //LED4 brightness proportional to how much CPU time is left //if off, code takes longer to run than LOOP_RATE_MILLISECONDS
while( (millis() - previousMillis) < LOOP_RATE_MILLISECONDS ) { ; } //wait here to start next loop //JTS2doLater: Determine behavior after overflow (50 days)
LED(4,LOW);
previousMillis = millis(); //placed at end to prevent delay at keyON event

View File

@@ -19,7 +19,7 @@ uint8_t SoC_getBatteryStateNow_percent(void) { return packCharge_Now_percent; }
void SoC_setBatteryStateNow_percent(uint8_t newSoC_percent) { packCharge_Now_mAh = (stackFull_Calculated_mAh * 0.01) * newSoC_percent; } //JTS2doNow: Is this cast correctly?
//uses SoC percentage to update mAh value (LiBCM stores battery SoC in mAh, not %)
void SoC_updateBatteryStateNow_percent(void) { packCharge_Now_percent = (uint8_t)(((uint32_t)packCharge_Now_mAh * 100) / stackFull_Calculated_mAh); }
void SoC_calculateBatteryStateNow_percent(void) { packCharge_Now_percent = (uint8_t)(((uint32_t)packCharge_Now_mAh * 100) / stackFull_Calculated_mAh); }
/////////////////////////////////////////////////////////////////////
@@ -92,39 +92,50 @@ void SoC_updateUsingOpenCircuitVoltage(void)
/////////////////////////////////////////////////////////////////////
//JTS2doNow: Still used anywhere?
//only call this function when the key is off (or you'll get a check engine light)
void SoC_openCircuitVoltage_handler(void)
void SoC_keyOff_cellMeasurement_handler(void)
{
#define KEY_OFF_SoC_UPDATE_PERIOD_MINUTES 10
#define KEY_OFF_SoC_UPDATE_PERIOD_MILLISECONDS (KEY_OFF_SoC_UPDATE_PERIOD_MINUTES * 60000)
static uint32_t SoC_latestUpdate_milliseconds = 0;
if( ( (millis() - SoC_latestUpdate_milliseconds ) >= KEY_OFF_SoC_UPDATE_PERIOD_MILLISECONDS ) && //more than ten minutes since last measurement
( (millis() - key_latestTurnOffTime_ms_get()) >= KEY_OFF_SoC_UPDATE_PERIOD_MILLISECONDS ) ) //more than ten minutes since key turned off
//JTS2doNow: Grid charger routine also updates SoC... so no need to run this function if grid charger plugged in (see gridCharger_chargePack())
{
SoC_latestUpdate_milliseconds = millis();
debugUSB_displayUptime_seconds();
if( key_hasKeyOff_updatePeriodElapsed() == true )
{
SoC_updateUsingOpenCircuitVoltage();
static bool wasCellVoltagePreviouslyTooLow = false;
//turn LiBCM off if any cell voltage is too low
//LiBCM remains off until the next keyON occurs
if( LTC68042result_loCellVoltage_get() < CELL_VMIN_KEYOFF)
{
if(wasCellVoltagePreviouslyTooLow == false) { wasCellVoltagePreviouslyTooLow = true; } //do nothing the first time cell voltage is too low
else /* second time voltage is too low */ { Serial.print(F("\nLow cell voltage")); gpio_turnLiBCM_off(); } //game over, thanks for playing
}
else { wasCellVoltagePreviouslyTooLow = false; } //pack is charged enough for LiBCM to stay on
}
}
/////////////////////////////////////////////////////////////////////
//turn LiBCM off if any cell voltage is too low
//LiBCM remains off until the next keyON occurs
//prevents over-discharge during extended keyOFF
void SoC_turnOffLiBCM_ifPackEmpty(void)
{
static uint8_t numConsecutiveTimesCellVoltageTooLow = 0;
#define NUM_CELLS_MEASURED_PER_LOOP 3
#define NUM_CELLS_PER_IC 12
#define NUM_LOOPS_TO_MEASURE_ALL_CELLS (TOTAL_IC * NUM_CELLS_PER_IC / NUM_CELLS_MEASURED_PER_LOOP) //math handled by preprocessor
if( LTC68042result_loCellVoltage_get() < CELL_VMIN_KEYOFF)
{
if(numConsecutiveTimesCellVoltageTooLow <= (NUM_LOOPS_TO_MEASURE_ALL_CELLS << 2) )
{
//verify voltage remains low for several LTC6804 measurement cycles
numConsecutiveTimesCellVoltageTooLow++;
}
else
{
//cell remained below minimum voltage for several LTC6804 mesurement cycles
Serial.print(F("\nLow cell voltage"));
gpio_turnLiBCM_off(); //turn LiBCM off... game over, thanks for playing
}
}
else { numConsecutiveTimesCellVoltageTooLow = 0; } //pack is charged enough for LiBCM to stay on
}
/////////////////////////////////////////////////////////////////////
//Don't call this function when current is flowing through the current sensor
//Wait at least ten minutes after keyOff for most accurate results
uint8_t SoC_estimateFromRestingCellVoltage_percent(void)
@@ -246,17 +257,16 @@ uint8_t SoC_estimateFromRestingCellVoltage_percent(void)
void SoC_handler(void)
{
SoC_updateBatteryStateNow_percent();
SoC_calculateBatteryStateNow_percent();
}
/////////////////////////////////////////////////////////////////////
/*
JTS2doLater:
-Save SoC(RAM) to EEPROM
-If value in RAM is more than 10% different from EEPROM value, update EEPROM.
-Also store if key recently turned off (keyState_previous == on && keyState_now == off)
-EEPROM writes require 3.3. ms blocking time (interrupts must be disabled)
-Example EEPROM code p24 MEGA2560 manual
*/

View File

@@ -14,9 +14,11 @@
uint8_t SoC_estimateFromRestingCellVoltage_percent(void);
void SoC_openCircuitVoltage_handler(void);
void SoC_keyOff_cellMeasurement_handler(void);
void SoC_updateUsingOpenCircuitVoltage(void);
void SoC_turnOffLiBCM_ifPackEmpty(void);
void SoC_handler(void);
#endif

View File

@@ -66,16 +66,10 @@ int16_t adc_measureBatteryCurrent_amps(void)
SoC_integrateCharge_adcCounts(latest_battCurrent_counts);
//convert current sensor result into approximate amperage for MCM & user-display
#ifdef HW_REVB
//The approximation equation below is accurate to within 3.7 amps of actual value
latest_battCurrent_amps = ((int16_t)((((uint16_t)latest_battCurrent_counts) * 13) >> 6)) - 67;
#elif defined HW_REVC
//see SPICE simulation for complete derivation
//see "RevC/V&V/OEM Current Sensor.ods" for measured results
//The approximation equation below is accurate to within 1.0 amps of actual value
latest_battCurrent_amps = ((int16_t)((((uint16_t)latest_battCurrent_counts) * 55) >> 8)) - 71;
#endif
//see SPICE simulation for complete derivation
//see "RevC/V&V/OEM Current Sensor.ods" for measured results
//The approximation equation below is accurate to within 1.0 amps of actual value
latest_battCurrent_amps = ((int16_t)((((uint16_t)latest_battCurrent_counts) * 55) >> 8)) - 71;
}
return latest_battCurrent_amps;

View File

@@ -20,16 +20,10 @@
void adc_calibrateBatteryCurrentSensorOffset(void);
#ifdef HW_REVB
#define ADC_NUMSAMPLES_PER_RESULT 64 //Valid values: 1,2,4,8,16,32,64 //MUST ALSO CHANGE next line!
#define ADC_NUMSAMPLES_2_TO_THE_N 6 //Valid values: 0,1,2,3, 4, 5, 6 //2^N = ADC_NUMSAMPLES_PER_RESULT
#define ADC_NUMSAMPLES_PER_CALL 4 //Must be divisible into ADC_NUMSAMPLES_PER_RESULT!
#elif defined HW_REVC
#define ADC_NUMSAMPLES_PER_RESULT 8 //Valid values: 1,2,4,8,16,32,64 //MUST ALSO CHANGE next line!
#define ADC_NUMSAMPLES_2_TO_THE_N 3 //Valid values: 0,1,2,3, 4, 5, 6 //2^N = ADC_NUMSAMPLES_PER_RESULT
#define ADC_NUMSAMPLES_PER_CALL 2 //Must be divisible into ADC_NUMSAMPLES_PER_RESULT!
#define ADC_NUMLOOPS_PER_RESULT (ADC_NUMSAMPLES_PER_RESULT / ADC_NUMSAMPLES_PER_CALL) //division constants are handled by pre-processor
#endif
#define ADC_NUMSAMPLES_PER_RESULT 8 //Valid values: 1,2,4,8,16,32,64 //MUST ALSO CHANGE next line!
#define ADC_NUMSAMPLES_2_TO_THE_N 3 //Valid values: 0,1,2,3, 4, 5, 6 //2^N = ADC_NUMSAMPLES_PER_RESULT
#define ADC_NUMSAMPLES_PER_CALL 2 //Must be divisible into ADC_NUMSAMPLES_PER_RESULT!
#define ADC_NUMLOOPS_PER_RESULT (ADC_NUMSAMPLES_PER_RESULT / ADC_NUMSAMPLES_PER_CALL) //division constants are handled by pre-processor
#define ADC_NOMINAL_0A_COUNTS 332 //calculated ADC 10b result when no current flows through sensor
#define ADC_MILLIAMPS_PER_COUNT 215 //Derivation here: ~/Electronics/PCB (KiCAD)/RevC/V&V/OEM Current Sensor.ods

View File

@@ -148,7 +148,7 @@ bool BATTSCI_isPackFull(void)
bool BATTSCI_isPackEmpty(void)
{
uint16_t currentAdjusted_Vmin = CELL_VMIN_ASSIST;
//uint16_t currentAdjusted_Vmin = CELL_VMIN_ASSIST;
//account for additional cell voltage drop during assist
//if(adc_getLatestBatteryCurrent_amps() > 0) { currentAdjusted_Vmin = CELL_VMIN_ASSIST - cellVoltageOffsetDueToESR(); }
@@ -172,8 +172,15 @@ uint8_t BATTSCI_calculateRegenAssistFlags(void)
uint8_t flags = 0;
if(BATTSCI_isPackEmpty() == true) { flags |= BATTSCI_DISABLE_ASSIST_FLAG; }
if(BATTSCI_isPackFull() == true) { flags |= BATTSCI_DISABLE_REGEN_FLAG; }
#ifndef DISABLE_ASSIST
if(BATTSCI_isPackEmpty() == true)
#endif
{ flags |= BATTSCI_DISABLE_ASSIST_FLAG; }
#ifndef DISABLE_REGEN
if(BATTSCI_isPackFull() == true)
#endif
{ flags |= BATTSCI_DISABLE_REGEN_FLAG; }
return flags;
}

90
Firmware/MVP/cellBalance.cpp Executable file
View File

@@ -0,0 +1,90 @@
//Copyright 2021(c) John Sullivan
//github.com/doppelhub/Honda_Insight_LiBCM
//cell balancing Functions
#include "libcm.h"
/////////////////////////////////////////////////////////////////////////////////////////////
void cellBalance_disableBalanceResistors(void)
{
for(uint8_t ic = 0; ic < TOTAL_IC; ic++)
{
LTC68042configure_setBalanceResistors( (ic + FIRST_IC_ADDR), 0 );
}
}
/////////////////////////////////////////////////////////////////////////////////////////////
void cellBalance_configureDischargeResistors(void)
{
uint16_t cellsToDischarge[TOTAL_IC] = {0}; //each uint16's QTY12 LSBs correspond to each LTC6804's QTY12 cells
static uint8_t balanceHysteresis = CELL_BALANCE_TO_WITHIN_COUNTS_TIGHT;
bool cellsAreBalanced = true;
uint16_t cellDischargeVoltageThreshold = 0; //cells above this value will get discharged
//determine cellDischargeVoltageThreshold
if (LTC68042result_hiCellVoltage_get() > CELL_VMAX_REGEN )
{
//pack is overcharged
cellDischargeVoltageThreshold = CELL_VMAX_REGEN;
Serial.print(F("\nDANGER: Cells Overcharged!!"));
}
else { cellDischargeVoltageThreshold = LTC68042result_loCellVoltage_get(); } //pack isn't overcharged //balance to minimum cell voltage
//determine which cells to balance
for(uint8_t ic = 0; ic < TOTAL_IC; ic++)
{
for (uint8_t cell = 0; cell < CELLS_PER_IC; cell++)
{
if(LTC68042result_specificCellVoltage_get(ic, cell) > (cellDischargeVoltageThreshold + balanceHysteresis) )
{
//this cell voltage is higher than the lowest cell voltage
cellsToDischarge[ic] |= (1 << cell);
cellsAreBalanced = false;
gpio_setFanSpeed('M', RAMP_FAN_SPEED);
balanceHysteresis = CELL_BALANCE_TO_WITHIN_COUNTS_TIGHT;
}
}
debugUSB_setCellBalanceStatus(ic, cellsToDischarge[ic]);
LTC68042configure_setBalanceResistors( (ic + FIRST_IC_ADDR), cellsToDischarge[ic] );
}
if(cellsAreBalanced == true)
{
balanceHysteresis = CELL_BALANCE_TO_WITHIN_COUNTS_LOOSE;
gpio_setFanSpeed('0', RAMP_FAN_SPEED);
}
else { gpio_setFanSpeed('H', RAMP_FAN_SPEED); } //cool discharge resistors
}
/////////////////////////////////////////////////////////////////////////////////////////////
void cellBalance_handler(void)
{
static uint8_t balanceState = BALANCING_DISABLED;
#ifdef ONLY_BALANCE_CELLS_WHEN_GRID_CHARGER_PLUGGED_IN
if( gpio_isGridChargerPluggedInNow() == PLUGGED_IN )
#else
if( (gpio_isGridChargerPluggedInNow() == PLUGGED_IN) ||
(SoC_getBatteryStateNow_percent() > CELL_BALANCE_MIN_SoC) )
#endif
{
//balance cells (if needed)
cellBalance_configureDischargeResistors();
balanceState = BALANCING_ALLOWED;
}
else if(balanceState == BALANCING_ALLOWED)
{
//pack SoC previously high enough to balance, but isn't now
cellBalance_disableBalanceResistors(); //only send this command once //saves power
gpio_setFanSpeed('0', ABSOLUTE_FAN_SPEED);
balanceState = BALANCING_DISABLED;
}
}

14
Firmware/MVP/cellBalance.h Executable file
View File

@@ -0,0 +1,14 @@
//Copyright 2021(c) John Sullivan
//github.com/doppelhub/Honda_Insight_LiBCM
#ifndef cellbalance_h
#define cellbalance_h
#define BALANCING_DISABLED 0
#define BALANCING_ALLOWED 1
void cellBalance_handler(void);
void cellBalance_disableBalanceResistors(void);
#endif

View File

@@ -7,19 +7,16 @@
#define config_h
#include "libcm.h" //For Arduino IDE compatibility
#define FW_VERSION "0.6.8"
#define BUILD_DATE "2022FEB03"
#define FW_VERSION "0.7.0"
#define BUILD_DATE "2022MAR04"
#define CPU_MAP_MEGA2560
//chose ONE of the following:
//#define HW_REVB
#define HW_REVC
#define HW_REVC
//choose ONE of the following:
#define SET_CURRENT_HACK_00 //OEM configuration (no current hack installed inside MCM)
//#define SET_CURRENT_HACK_00 //OEM configuration (no current hack installed inside MCM)
//#define SET_CURRENT_HACK_20 //+20%
//#define SET_CURRENT_HACK_40 //+40%
#define SET_CURRENT_HACK_40 //+40%
//#define SET_CURRENT_HACK_60 //+60% //Note: LiBCM can only measure between 71 A regen & 147 A assist //higher current values will (safely) rail the ADC
//choose ONE of the following:
@@ -28,32 +25,23 @@
//#define VOLTAGE_SPOOFING_ASSIST_ONLY_BINARY //only spoof during assist, using either 120 volts or (vPackActual-12)
#define VOLTAGE_SPOOFING_ASSIST_AND_REGEN //always spoof voltage (enables stronger regen)
//#define DISABLE_ASSIST //uncomment to (always) disable assist
//#define DISABLE_REGEN //uncomment to (always) disable regen
//#define REDUCE_BACKGROUND_REGEN_UNLESS_BRAKING //EXPERIMENTAL! //JTS2doNow: Make it better
//#define PRINT_ALL_CELL_VOLTAGES_TO_USB //Uncomment to print all cell voltages while driving //Grid charger always prints all cell voltages
//#define DISABLE_ASSIST_AND_REGEN //Uncomment to disable regen and assist entirely //JTS2doNow: add feature
#define MCME_VOLTAGE_OFFSET_ADJUST 12 //difference between OBDIIC&C and LiBCM spoofed pack voltage (Subtract LiBCM voltage from OBDIIC&C Bvo. Default is 12.)
#define LCD_4X20_CONNECTED //Comment to disable all 4x20 LCD commands
//choose which functions control the LEDs
#define LED_NORMAL //enable "LED()" functions (see debug.c)
//#define LED_DEBUG //enable "debugLED()" functions (FYI: blinkLED functions won't work)
#define LED_NORMAL //enable "LED()" functions (see debug.c)
//#define LED_DEBUG //enable "debugLED()" functions (FYI: blinkLED functions won't work)
#define PRINT_USB_DEBUG_TEXT //prints text sent via debugUSB_debugText() //JTS2doLater: NOT IMPLEMENTED YET
#define DEBUG_USB_UPDATE_PERIOD_MS 250 //250 = send data every 250 ms
#define LOOP_RATE_MILLISECONDS 10 // Superloop execution rate: 1/LOOP_RATE_MILLISECONDS (e.g. LOOP_RATE_MILLISECONDS==10 is 100 Hz)
#define CELL_VMAX_REGEN 42000 //42000 = 4.2000 volts
#define CELL_VMIN_ASSIST 31900 //allows for ESR-based voltage drop
#define CELL_VMAX_GRIDCHARGER 39000 //3.9 volts is 75% SoC //other values: See SoC.cpp
#define CELL_VMIN_GRIDCHARGER 30000 //grid charger will not charge severely empty cells
#define CELL_VMIN_KEYOFF 34400 //When car is off, LiBCM turns off below this voltage
#define LTC68042_ENABLE_C19_VOLTAGE_CORRECTION //Uncomment if using stock Honda EHW5 lithium modules
#define LOOP_RATE_MILLISECONDS 10 // Superloop execution rate: 1/LOOP_RATE_MILLISECONDS //'10' = 100 Hz
#define STACK_mAh_NOM 5000 //nominal pack size (0:100% SoC) //LiBCM uses this value until it determines the actual pack capacity
#define STACK_SoC_MAX 85 //maximum state of charge before regen is disabled
@@ -61,6 +49,20 @@
#define CELL_VREST_85_PERCENT_SoC 40100 //for maximum life, resting cell voltage should remain below 85% SoC
#define CELL_VREST_10_PERCENT_SoC 34700 //for maximum life, resting cell voltage should remain above 10% SoC
#define CELL_VMAX_REGEN 42000 //42000 = 4.2000 volts
#define CELL_VMIN_ASSIST 31900 //allows for ESR-based voltage drop
#define CELL_VMAX_GRIDCHARGER 39000 //3.9 volts is 75% SoC //other values: See SoC.cpp //MUST be less than 'CELL_VREST_85_PERCENT_SoC'
#define CELL_VMIN_GRIDCHARGER 30000 //grid charger will not charge severely empty cells
#define CELL_VMIN_KEYOFF CELL_VREST_10_PERCENT_SoC //when car is off, LiBCM turns off below this voltage
#define CELL_BALANCE_MIN_SoC 40 //when car is off, cell balancing is disabled below this percentage
#define CELL_BALANCE_TO_WITHIN_COUNTS_LOOSE 20 //'20' = 2.0 mV //CANNOT exceed 255 counts (25.5 mV)
#define CELL_BALANCE_TO_WITHIN_COUNTS_TIGHT 5 // '5' = 0.5 mV //MUST be less than CELL_BALANCE_TO_WITHIN_COUNTS_LOOSE
//#define ONLY_BALANCE_CELLS_WHEN_GRID_CHARGER_PLUGGED_IN //uncomment to prevent keyOFF cell balancing, unless the grid charger is plugged in
#define LTC68042_ENABLE_C19_VOLTAGE_CORRECTION //uncomment if using stock Honda EHW5 lithium modules
#define PREVENT_BOOT_WITHOUT_SAFETY_COVER //comment if testing LiBCM without the cover
//#define RUN_BRINGUP_TESTER //requires external test PCB (that you don't have)
#endif
@@ -69,7 +71,7 @@ Features to add later:
#define DISPLAY_OEM_CURRENT_SIGN //JTS2doNow: add feature
#define PCODE_IF_COVER_NOT_INSTALLED //JRS2doNow
//Define realtime commands that are immediately picked off from the serial stream.
//These characters are not passed to the serial parser, and are executed immediately.
@@ -78,17 +80,14 @@ Features to add later:
//Define battery parameters
#define STACK_CELLS_IN_SERIES 48
#define STACK_CURRENT_MAX_ASSIST 200 //disable assist above this current
#define STACK_CURRENT_MAX_REGEN 100 //disable regen above this current
#define STACK_CURRENT_MAX_ASSIST 140 //disable assist above this current
#define STACK_CURRENT_MAX_REGEN 70 //disable regen above this current
//Configure when LiBCM turns off when the key is not on.
//LiBCM will turn off when ANY condition below occurs
#define KEYOFF_TURNOFF_HOURS 4 //LiBCM turns off after this much time, -1 to disable
#define KEYOFF_TURNOFF_BELOW_SoC 50 //LiBCM turns off when SoC drops below this value
#define KEYOFF_TURNOFF_HOURS 4 //LiBCM turns off after this much time, -1 to disable
//Configure fan behavior when key is off
#define KEYOFF_FANS_ALLOWED YES //'NO' to prevent fan usage when key is off
#define KEYOFF_FANS_MIN_SoC 60 //Fans are disabled below this SoC
#define KEYOFF_FAN_COOLING_ALLOWED YES //'NO' to prevent fan usage when key is off
#define KEYOFF_FAN_COOLING_MIN_SoC 60 //Fans are disabled below this SoC
//Configure fan temperature setpoints
//All temperatures are in Celsius
@@ -96,9 +95,6 @@ Features to add later:
#define TEMP_OEMFAN_HIGH 40 //enable OEM fan at high speed above this value
#define TEMP_FAN_MIN 30 //enable onboard fans at lowest speed
#define TEMP_FAN_MAX 40 //enable onboard fans at highest speed
"Allow Cooling When Key OFF"
"When key OFF, Turn LiBCM off below ____ SoC" ("Key OFF fan minimum SoC Level")
#SPOOF_TEMP_FOR_MAX_POWER YES
//Define which parameters are reported over the USB serial bus
#define USB_REPORT_ALLOWED YES //if disabled, no data is reported
@@ -119,12 +115,8 @@ Features to add later:
#define USB_REPORT_SoC YES
//Grid charger behavior
#define GRID_CHARGE_ALLOWED YES
#define GRID_CHARGE_TEMP_MIN //grid charging disabled below this temperature
#define GRID_CHARGE_TEMP_MAX //grid charging disabled above this temperature
#define GRID_CHARGE_CURRENT_MAX_mA //specifies grid charger's maximum current output in mA
#define SERIAL_H_LINE_CONNECTED NO //H-Line wire connected to OEM BCM connector pin B01
#define SERIAL_I2C_CONNECTED YES //Serial display connected to SDA/SDL lines
#define SERIAL_HMI_CONNECTED NO //Nextion touch screen connected to J14
*/
*/

View File

@@ -9,57 +9,6 @@
#ifdef CPU_MAP_MEGA2560
#ifdef HW_REVB
#define PIN_BATTCURRENT A0
#define PIN_FANOEM_LOW A1
#define PIN_FANOEM_HI A2
#define PIN_TEMP_YEL A3
#define PIN_TEMP_GRN A4
#define PIN_TEMP_WHT A5
#define PIN_TEMP_BLU A6
#define PIN_VPIN_IN A7
#define PIN_TURNOFFLiBCM A8
#define PIN_HMI_EN A9
#define PIN_BATTSCI_DE A10
#define PIN_BATTSCI_REn A11
#define PIN_LED1 A12
#define PIN_LED2 A13
#define PIN_LED3 A14
#define PIN_LED4 A15
#define PIN_METSCI_DE 2
#define PIN_METSCI_REn 3
#define PIN_VPIN_OUT_PWM 4
#define PIN_SPI_EXT_CS 5
#define PIN_TEMP_EN 6
#define PIN_MCME_PWM 7
#define PIN_GRID_PWM 8
#define PIN_GRID_SENSE 9
#define PIN_GRID_EN 10
#define PIN_FAN_PWM 11
#define PIN_SENSOR_EN 12
#define PIN_IGNITION_SENSE 13
#define PIN_SPI_CS SS
#define PIN_BUZZER_PWM 45 //RevB doesn't have a buzzer. Added so that buzzer turns on if you try to load RevB fiwmare onto RevC+ hardware
#define PIN_GPIO1 48
#define PIN_USER_SW 49
//Serial3
#define METSCI_TX 14
#define METSCI_RX 15
//Serial2
#define BATTSCI_TX 16
#define BATTSCI_RX 17
//Serial1
#define HMI_TX 18
#define HMI_RX 19
#define DEBUG_SDA 20
#define DEBUG_CLK 21
#elif defined HW_REVC
#define PIN_BATTCURRENT A0
#define PIN_USER_SW A1
#define PIN_VPIN_IN A2
@@ -117,15 +66,11 @@
#define DEBUG_SDA 20
#define DEBUG_CLK 21
#else
#error (Hardware Revision not selected in config.c)
#endif
#endif
#endif
//JTS2doLater: Replace Arduino I/O functions as shown in example code below
//JTS2doLater: Replace Arduino I/O functions
/*
#define DIRECTION_DDR DDRD
#define DIRECTION_PORT PORTD

View File

@@ -8,7 +8,7 @@
#include "libcm.h"
char debugCharacter = '.';
uint16_t cellBitmaps[TOTAL_IC] = {0};
/////////////////////////////////////////////////////////////////////////////////////////////
@@ -33,21 +33,11 @@ void debugUSB_printOneICsCellVoltages(uint8_t icToPrint, uint8_t decimalPlaces)
/////////////////////////////////////////////////////////////////////////////////////////////
uint16_t cellBitmaps[TOTAL_IC] = {0};
void debugUSB_setCellBalanceStatus(uint8_t icNumber, uint16_t cellBitmap)
{
cellBitmaps[icNumber] = cellBitmap;
}
/////////////////////////////////////////////////////////////////////////////////////////////
void debugUSB_displayUptime_seconds(void)
{
Serial.print(F("\nUptime(s): "));
Serial.print( String(millis() * 0.001) );
}
/////////////////////////////////////////////////////////////////////////////////////////////
void debugUSB_printCellBalanceStatus(void)
{
@@ -61,6 +51,14 @@ void debugUSB_printCellBalanceStatus(void)
/////////////////////////////////////////////////////////////////////////////////////////////
void debugUSB_displayUptime_seconds(void)
{
Serial.print(F("\nUptime(s): "));
Serial.print( String(millis() * 0.001) );
}
/////////////////////////////////////////////////////////////////////////////////////////////
//This function can print more than 63 characters in a single call
void debugUSB_printLatest_data_gridCharger(void)
{
@@ -171,11 +169,4 @@ uint8_t debugUSB_getUserInput(void)
}
return userEntry;
}
/////////////////////////////////////////////////////////////////////////////////////////////
void debugUSB_sendChar(char characterToSend)
{
debugCharacter = characterToSend;
}

View File

@@ -14,9 +14,9 @@
uint8_t debugUSB_getUserInput(void);
void debugUSB_sendChar(char characterToSend);
void debugUSB_setCellBalanceStatus(uint8_t icNumber, uint16_t cellBitmap);
void debugUSB_displayUptime_seconds(void);
void debugUSB_printCellBalanceStatus(void);
#endif

View File

@@ -133,7 +133,7 @@ void EEPROM_checkForExpiredFirmware(void)
if(newUptime_hours == REQUIRED_FIRMWARE_UPDATE_PERIOD_HOURS) //newUptime_hours is bounded to REQUIRED_FW_UPDATE_PERIOD_HOURS
{
Serial.print(F("\nOpen Beta ALERT: Firmware update required (linsight.org/downloads)\nLiBCM disabled until firmware is updated"));
lcd_firmwareUpdateWarning();
lcd_Warning_firmwareUpdate();
EEPROM_firmwareStatus_set(FIRMWARE_STATUS_EXPIRED);
delay(5000); //give user time to read display
}

View File

@@ -72,16 +72,34 @@ void gpio_setFanSpeed_OEM(char speed)
////////////////////////////////////////////////////////////////////////////////////
void gpio_setFanSpeed(char speed)
void gpio_setFanSpeed(uint8_t speed, bool isSpeedRamped)
{
static uint8_t actualFanPWM = 0;
uint8_t goalFanPWM = 0;
const uint8_t RAMP_UPDATE_PERIOD_ms = 50;
static uint32_t millis_previous = 0;
switch(speed)
{
case '0': pinMode(PIN_FAN_PWM, INPUT); break; //high impedance
case 'L': analogWrite(PIN_FAN_PWM, 30); break;
case 'M': analogWrite(PIN_FAN_PWM, 75); break;
case 'H': analogWrite(PIN_FAN_PWM, 255); break;
default : analogWrite(PIN_FAN_PWM, speed); break;
case '0': goalFanPWM = 0; break;
case 'L': goalFanPWM = 30; break;
case 'M': goalFanPWM = 75; break;
case 'H': goalFanPWM = 255; break;
default : goalFanPWM = speed; break;
}
if ( (isSpeedRamped == RAMP_FAN_SPEED) &&
( millis() - millis_previous >= RAMP_UPDATE_PERIOD_ms) )
{
//slowly ramp fan speed
if (actualFanPWM > goalFanPWM) { actualFanPWM--; }
else if(actualFanPWM < goalFanPWM) { actualFanPWM++; }
}
else if(isSpeedRamped == ABSOLUTE_FAN_SPEED) { actualFanPWM = goalFanPWM; } //immediately adjust fan speed
if (actualFanPWM == 0) { pinMode(PIN_FAN_PWM, INPUT); } //saves power when fan is off
else { analogWrite(PIN_FAN_PWM, actualFanPWM); }
}
////////////////////////////////////////////////////////////////////////////////////
@@ -98,6 +116,7 @@ void gpio_turnHMI_off(void) { digitalWrite(PIN_HMI_EN, LOW); }
////////////////////////////////////////////////////////////////////////////////////
bool gpio_isGridChargerPluggedInNow(void) { return !(digitalRead(PIN_GRID_SENSE)); }
bool gpio_isGridChargerChargingNow(void) { return digitalRead(PIN_GRID_EN); }
////////////////////////////////////////////////////////////////////////////////////
@@ -155,17 +174,28 @@ void gpio_playSound_firmwareUpdated(void)
////////////////////////////////////////////////////////////////////////////////////
#ifdef HW_REVB
//features unique to RevB
#else
//RevC+ supports the following
bool gpio_isCoverInstalled(void)
{
if(digitalRead(PIN_COVER_SWITCH) == 1 ) {return true;}
else {return false;}
}
bool gpio_isCoverInstalled(void)
{
if(digitalRead(PIN_COVER_SWITCH) == 1 ) {return true;}
else {return false;}
}
#endif
////////////////////////////////////////////////////////////////////////////////////
void gpio_safetyCoverCheck(void)
{
#ifdef PREVENT_BOOT_WITHOUT_SAFETY_COVER
if( gpio_isCoverInstalled() == false)
{
gpio_turnBuzzer_on_lowFreq();
lcd_Warning_coverNotInstalled();
Serial.print(F("\nInstall safety cover, then power cycle. LiBCM Disabled.\nSee config.h>>'PREVENT_BOOT_WITHOUT_SAFETY_COVER' to disable"));
delay(5000);
gpio_turnBuzzer_off();
while(1) { ; } //hang here forever
}
#endif
}
////////////////////////////////////////////////////////////////////////////////////

View File

@@ -6,12 +6,13 @@
bool gpio_keyStateNow(void);
void gpio_setFanSpeed_OEM(char speed);
void gpio_setFanSpeed(char speed);
void gpio_setFanSpeed(uint8_t speed, bool isSpeedRamped);
void gpio_turnPowerSensors_on( void);
void gpio_turnPowerSensors_off(void);
bool gpio_isGridChargerPluggedInNow(void);
bool gpio_isGridChargerChargingNow(void);
void gpio_turnGridCharger_on( void);
void gpio_turnGridCharger_off(void);
@@ -24,6 +25,7 @@
void gpio_playSound_firmwareUpdated(void);
bool gpio_isCoverInstalled(void);
void gpio_safetyCoverCheck(void);
void gpio_turnHMI_on(void);
void gpio_turnHMI_off(void);
@@ -33,4 +35,7 @@
void gpio_turnLiBCM_off(void);
#define RAMP_FAN_SPEED 1
#define ABSOLUTE_FAN_SPEED 0
#endif

View File

@@ -2,27 +2,21 @@
//github.com/doppelhub/Honda_Insight_LiBCM
#include "libcm.h"
//updated by gridCharger_handler() (prevents mid-loop state changes from affecting loop logic)
//updated by gridCharger_handler() //prevents mid-loop state changes from affecting loop logic
bool gridChargerState_sampled = PLUGGED_IN;
//////////////////////////////////////////////////////////////////////////////////
bool gridCharger_getSampledState(void) { return gridChargerState_sampled; }
//////////////////////////////////////////////////////////////////////////////////
bool gridCharger_didStateChange(void)
{
gridChargerState_sampled = gpio_isGridChargerPluggedInNow(); //this is the only time LiBCM samples if plugged in
static bool gridChargerState_previous = UNPLUGGED;
bool didGridChargerStateChange = NO;
if( gridCharger_getSampledState() != gridChargerState_previous )
if( gridChargerState_sampled != gridChargerState_previous )
{
didGridChargerStateChange = YES;
gridChargerState_previous = gridCharger_getSampledState();
gridChargerState_previous = gridChargerState_sampled;
}
return didGridChargerStateChange;
@@ -33,10 +27,10 @@ bool gridCharger_didStateChange(void)
void gridCharger_handleUnplugEvent(void)
{
Serial.print(F("Unplugged"));
gpio_setFanSpeed('0');
gpio_turnGridCharger_off();
lcd_displayOFF();
gpio_setGridCharger_powerLevel('H'); //reduces power consumption
gpio_turnBuzzer_off(); //if issue persists, something else will turn buzzer back on
SoC_updateUsingOpenCircuitVoltage();
}
@@ -45,133 +39,86 @@ void gridCharger_handleUnplugEvent(void)
void gridCharger_handlePluginEvent(void)
{
Serial.print(F("Plugged In"));
lcd_displayON();
gpio_turnGridCharger_on(); //set charger initial condition //gridCharger_balanceCells() will immediately disable if full.
gpio_setFanSpeed('M');
lcd_displayOn();
}
//////////////////////////////////////////////////////////////////////////////////
//JTS2doNow: Separate grid charging from balancing... balancing should occur independently from grid charging
//JTS2doNow: Think this through to make sure it won't over-discharge cells
//only call when:
//grid charger is plugged in
//minimum cell voltage above safe minimum
//no cell is severely overcharged
void gridCharger_balanceCells(void)
{
uint16_t cellsToDischarge[TOTAL_IC] = {0}; //each uint16's QTY12 LSBs correspond to each cell
bool isAtLeastOneCellUnbalanced = false;
if(LTC68042result_loCellVoltage_get() > 32000) //32000 = 3.2000 volts //prevent lowest cell overdischarge (in a severely unbalanced pack)
{ //all cells above minimum balancing voltage
for(uint8_t ic = 0; ic < TOTAL_IC; ic++)
{
for (uint8_t cell = 0; cell < CELLS_PER_IC; cell++)
{
if(LTC68042result_specificCellVoltage_get(ic, cell) > (LTC68042result_loCellVoltage_get() + BALANCE_TO_WITHIN_COUNTS) )
{ //this particular cell's voltage is higher than the lowest cell's voltage
cellsToDischarge[ic] |= (1 << cell);
isAtLeastOneCellUnbalanced = true;
}
}
debugUSB_setCellBalanceStatus(ic, cellsToDischarge[ic]);
LTC68042configure_cellBalancing_setCells( (ic + FIRST_IC_ADDR), cellsToDischarge[ic] );
}
}
else
{
Serial.println(F("Cells too unbalanced to safely grid charge."));
}
if(isAtLeastOneCellUnbalanced == true) { gpio_setFanSpeed('H'); } //full blast to cool discharge resistors
else { gpio_setFanSpeed('0'); } //pack is balanced
}
//////////////////////////////////////////////////////////////////////////////////
//JTS2doNow: Separate balancing routine entirely from charging routine
void gridCharger_chargePack(void)
{
static uint8_t cellState = CELLSTATE_UNINITIALIZED;
static uint8_t cellStatePrevious = CELLSTATE_UNINITIALIZED;
cellStatePrevious = cellState;
lcd_refresh();
LTC68042cell_nextVoltages();
SoC_setBatteryStateNow_percent( SoC_estimateFromRestingCellVoltage_percent() ); //LiBCM's low grid charge current hardly changes cell voltage
lcd_refresh();
debugUSB_printLatest_data_gridCharger();
//JTS2doNow: Prevent grid charging if any cell is too discharged (CELL_VMIN_GRIDCHARGER)
//at least one cell is severely overcharged
if( LTC68042result_hiCellVoltage_get() > (CELL_VMAX_GRIDCHARGER + VCELL_HYSTERESIS) )
if( LTC68042result_hiCellVoltage_get() > CELL_VREST_85_PERCENT_SoC )
{
//at least one cell is overcharged
cellState = CELLSTATE_OVERCHARGED;
gpio_turnGridCharger_off();
gpio_setFanSpeed('H'); //cool pack and discharge
gpio_setGridCharger_powerLevel('0');
//JTS2doLater: display Warning on LCD
//JTS2doNow: display Warning on LCD
gpio_turnBuzzer_on_highFreq();
}
else if( (LTC68042result_loCellVoltage_get() < CELL_VMIN_GRIDCHARGER) )
{
//at least one cell is too empty to safely grid charge
cellState = CELLSTATE_OVERDISCHARGED;
gpio_turnGridCharger_off();
gpio_setGridCharger_powerLevel('0');
//JTS2doNow: display Warning on LCD
gpio_turnBuzzer_on_highFreq();
}
//at least one cell is full
else if( (LTC68042result_hiCellVoltage_get() > CELL_VMAX_GRIDCHARGER) )
{
cellState = CELLSTATE_ONECELLFULL;
//at least one cell is full
cellState = CELLSTATE_SOMECELLSFULL;
gpio_turnGridCharger_off();
gpio_setFanSpeed('0'); //set inside balanceCells()
gpio_setGridCharger_powerLevel('0');
gpio_turnBuzzer_off();
}
//grid charger plugged in and all cells less than full
else if( LTC68042result_hiCellVoltage_get() <= (CELL_VMAX_GRIDCHARGER - VCELL_HYSTERESIS) )
{
cellState = CELLSTATE_NOCELLSFULL;
//no cells are full
cellState = CELLSTATE_ZEROCELLSFULL;
gpio_turnGridCharger_on();
gpio_setFanSpeed('M');
gpio_setGridCharger_powerLevel('H');
gpio_turnBuzzer_off();
}
//grid charger plugged in and all cells almost full
else if( (LTC68042result_hiCellVoltage_get() <= CELL_VMAX_GRIDCHARGER) )
{
cellState = CELLSTATE_BALANCING;
//gpio_setFanSpeed('0'); //set inside balanceCells()
gridCharger_balanceCells();
gpio_turnBuzzer_off();
}
if (cellStatePrevious != cellState)
{
//state has changed
Serial.print(F(" grid:"));
//charging state has changed
Serial.print(F("\nGrid: "));
switch (cellState)
{
case CELLSTATE_UNINITIALIZED: Serial.print(F("init") ); break;
case CELLSTATE_BALANCING: Serial.print(F("balancing") ); break;
case CELLSTATE_OVERCHARGED: Serial.print(F("overcharged")); break;
case CELLSTATE_ONECELLFULL: Serial.print(F("oneCellFull")); break;
case CELLSTATE_NOCELLSFULL: Serial.print(F("charging") ); break;
case CELLSTATE_UNINITIALIZED: Serial.print(F("init") ); break;
case CELLSTATE_OVERCHARGED: Serial.print(F("Overcharged") ); break;
case CELLSTATE_OVERDISCHARGED: Serial.print(F("Overdischarged")); break;
case CELLSTATE_SOMECELLSFULL: Serial.print(F("Charged") ); break;
case CELLSTATE_ZEROCELLSFULL: Serial.print(F("Charging") ); break;
}
}
cellStatePrevious = cellState;
}
//////////////////////////////////////////////////////////////////////////////////
void gridCharger_handler(void)
{
gridChargerState_sampled = gpio_isGridChargerPluggedInNow(); //Nowhere else in this file should query actual I/O... use this variable instead
if( gridCharger_didStateChange() == YES )
{
Serial.print(F("\nGrid Charger: "));
if (gridCharger_getSampledState() == PLUGGED_IN) { gridCharger_handlePluginEvent(); }
if (gridCharger_getSampledState() == UNPLUGGED ) { gridCharger_handleUnplugEvent(); }
Serial.print(F("\nCharger: "));
if (gridChargerState_sampled == PLUGGED_IN) { gridCharger_handlePluginEvent(); }
if (gridChargerState_sampled == UNPLUGGED ) { gridCharger_handleUnplugEvent(); }
}
if(gridCharger_getSampledState() == PLUGGED_IN) { gridCharger_chargePack(); }
if(gridChargerState_sampled == PLUGGED_IN) { gridCharger_chargePack(); }
}

View File

@@ -7,19 +7,15 @@
#define PLUGGED_IN true
#define UNPLUGGED false
#define BALANCE_TO_WITHIN_COUNTS 10 // '20' = 2 mV
#define MIN_DISCHARGE_VOLTAGE_COUNTS 36000
#define VCELL_HYSTERESIS 1000 // '1000' = 100 mV prevents rapid grid charger on/off toggling when first cell is full
#define VCELL_HYSTERESIS 200 // '200' = 20 mV //prevents rapid grid charger on/off toggling when first cell is full
void gridCharger_handler(void);
#define CELLSTATE_OVERCHARGED 4
#define CELLSTATE_ONECELLFULL 3
#define CELLSTATE_NOCELLSFULL 2
#define CELLSTATE_BALANCING 1
#define CELLSTATE_UNINITIALIZED 0
#define CELLSTATE_OVERDISCHARGED 4
#define CELLSTATE_OVERCHARGED 3
#define CELLSTATE_SOMECELLSFULL 2
#define CELLSTATE_ZEROCELLSFULL 1
#define CELLSTATE_UNINITIALIZED 0
#endif

View File

@@ -27,11 +27,10 @@ void key_handleKeyEvent_off(void)
BATTSCI_disable(); //Must disable BATTSCI when key is off to prevent backdriving MCM
METSCI_disable();
gpio_setFanSpeed_OEM('0');
gpio_setFanSpeed('0');
SoC_updateUsingOpenCircuitVoltage();
SoC_updateUsingOpenCircuitVoltage(); //JTS2doNow: Is this required? I believe the goal is to make sure some SoC value exists when LiBCM first powers on. See also: SoC_keyOff_cellMeasurement_handler()
adc_calibrateBatteryCurrentSensorOffset();
gpio_turnPowerSensors_off();
LTC6804configure_handleKeyOff();
LTC68042configure_handleKeyStateChange();
vPackSpoof_handleKeyOFF();
gpio_turnHMI_off();
gpio_turnTemperatureSensors_off();
@@ -51,11 +50,12 @@ void key_handleKeyEvent_on(void)
gpio_turnTemperatureSensors_on();
gpio_turnHMI_on();
gpio_turnPowerSensors_on();
lcd_displayON();
lcd_displayOn();
gpio_setFanSpeed_OEM('L');
LTC68042result_maxEverCellVoltage_set(0 ); //reset maxEver cell voltage
LTC68042result_minEverCellVoltage_set(65535); //reset minEver cell voltage
LTC68042configure_cellBalancing_disable();
gpio_turnGridCharger_off();
LTC68042configure_programVolatileDefaults(); //turn discharge resistors off, set ADC LPF, etc.
//cellBalance_disableBalanceResistors(); //not required //handled by LTC68042configure_programVolatileDefaults()
LTC68042configure_handleKeyStateChange();
LED(1,HIGH);
key_latestTurnOnTime_ms_set(millis()); //MUST RUN LAST!
@@ -78,8 +78,7 @@ bool key_didStateChange(void)
else if( (keyState_sampled == KEYON) && (keyState_previous == KEYOFF_JUSTOCCURRED) )
{ //key is now 'ON', but last time was 'OFF', and the time before that it was 'ON'
//therefore the previous 'OFF' reading was noise... the key was actually ON all along
//no need to do anything.
;
keyState_previous = KEYON;
}
else if(keyState_sampled != keyState_previous)
{
@@ -109,3 +108,23 @@ uint8_t key_getSampledState(void)
if(keyState_previous == KEYOFF_JUSTOCCURRED) { return KEYON; } //prevent noise from accidentally turning LiBCM off
else { return keyState_sampled; }
}
////////////////////////////////////////////////////////////////////////////////////
bool key_hasKeyOff_updatePeriodElapsed(void)
{
static uint32_t latestUpdate_milliseconds = 0;
uint32_t updatePeriod_milliseconds = 0;
if( gpio_isGridChargerPluggedInNow() == true ) { updatePeriod_milliseconds = 1000; }
else { updatePeriod_milliseconds = 600000; } //600000 ms = 10 minutes
if( ( (millis() - latestUpdate_milliseconds ) >= updatePeriod_milliseconds ) && //time has elapsed since last measurement
( (millis() - key_latestTurnOffTime_ms_get()) >= updatePeriod_milliseconds ) ) //time has elapsed since last key off
{
latestUpdate_milliseconds = millis();
return true;
}
return false;
}

View File

@@ -11,5 +11,6 @@
uint8_t key_getSampledState(void);
uint32_t key_latestTurnOnTime_ms_get(void);
uint32_t key_latestTurnOffTime_ms_get(void);
bool key_hasKeyOff_updatePeriodElapsed(void);
#endif

View File

@@ -16,15 +16,15 @@ lcd_I2C_jts lcd2(0x27);
//These variables are reset during key change
uint8_t packVoltageActual_onScreen = 0;
uint8_t packVoltageSpoofed_onScreen = 0;
uint8_t errorCount_onScreen = 0;
uint8_t errorCount_onScreen = 99;
uint16_t maxEverCellVoltage_onScreen = 0;
uint16_t minEverCellVoltage_onScreen = 0;
uint8_t SoC_onScreen = 0;
int8_t temp_onScreen = 0;
int8_t temp_onScreen = 99;
////////////////////////////////////////////////////////////////////////
void lcd_initialize(void)
void lcd_begin(void)
{
#ifdef LCD_4X20_CONNECTED
lcd2.begin(20,4);
@@ -159,7 +159,8 @@ bool lcd_printNumErrors(void)
if( errorCount_onScreen != LTC68042result_errorCount_get() )
{
errorCount_onScreen = LTC68042result_errorCount_get();
lcd2.setCursor(2,3);
lcd2.setCursor(17,2);
if(errorCount_onScreen < 10) { lcd2.print(' '); } //leading space on " 0" to " 9" errors
lcd2.print(errorCount_onScreen);
didscreenUpdateOccur = SCREEN_UPDATED;
@@ -378,13 +379,37 @@ bool lcd_printPower(void)
////////////////////////////////////////////////////////////////////////
bool lcd_printGridChargerStatus(void)
{
bool didscreenUpdateOccur = SCREEN_DIDNT_UPDATE;
#ifdef LCD_4X20_CONNECTED
static bool gridChargerState_onScreen = true;
if( gridChargerState_onScreen != gpio_isGridChargerChargingNow() )
{
gridChargerState_onScreen = gpio_isGridChargerChargingNow();
lcd2.setCursor(19,2); //grid charger status position
if(gpio_isGridChargerChargingNow() == true) { lcd2.print('G'); }
else { lcd2.print(' '); }
didscreenUpdateOccur = SCREEN_UPDATED;
}
#endif
return didscreenUpdateOccur;
}
////////////////////////////////////////////////////////////////////////
//calling directly always updates screen immediately
//lcd_refresh() round-robins through these values
bool lcd_updateValue(uint8_t stateToUpdate)
{
bool didScreenUpdateOccur = SCREEN_DIDNT_UPDATE;
switch(stateToUpdate)
{
case LCDUPDATE_LOOPCOUNT : didScreenUpdateOccur = lcd_printTime_seconds(); break;
case LCDUPDATE_SECONDS : didScreenUpdateOccur = lcd_printTime_seconds(); break;
case LCDUPDATE_VPACK_ACTUAL : didScreenUpdateOccur = lcd_printStackVoltage_actual(); break;
case LCDUPDATE_VPACK_SPOOFED: didScreenUpdateOccur = lcd_printStackVoltage_spoofed(); break;
case LCDUPDATE_NUMERRORS : didScreenUpdateOccur = lcd_printNumErrors(); break;
@@ -397,7 +422,8 @@ bool lcd_updateValue(uint8_t stateToUpdate)
case LCDUPDATE_SoC : didScreenUpdateOccur = lcd_printSoC(); break;
case LCDUPDATE_CURRENT : didScreenUpdateOccur = lcd_printCurrent(); break;
case LCDUPDATE_TEMP_BATTERY : didScreenUpdateOccur = lcd_printTempBattery(); break;
default : didScreenUpdateOccur = SCREEN_UPDATED; break; //if illigal input, exit immediately
case LCDUPDATE_GRID_STATUS : didScreenUpdateOccur = lcd_printGridChargerStatus(); break;
default : didScreenUpdateOccur = SCREEN_UPDATED; break; //if illegal input, exit immediately
}
return didScreenUpdateOccur;
@@ -411,40 +437,27 @@ void lcd_refresh(void)
{
#ifdef LCD_4X20_CONNECTED
static uint8_t lcdUpdate_state = LCDUPDATE_NUMERRORS; //init round-robin with least likely state to have changed
static uint8_t lastElementUpdated = LCDUPDATE_NUMERRORS; //last LCD screen element updated //cannot = LCDUPDATE_NO_UPDATE
static uint8_t lcdElementToUpdate = LCDUPDATE_NUMERRORS; //init round-robin with least likely state to have changed
static uint32_t millis_previous = 0;
#define SCREEN_UPDATE_RATE_MILLIS 32
#define SCREEN_UPDATE_RATE_MILLIS 32 //one element is updated each time
// Number of screen element updates per second = (1.0 / SCREEN_UPDATE_RATE_MILLIS)
// Since only one screen element updates at a time, the per-element update rate is:
// ( (1.0 / SCREEN_UPDATE_RATE_MILLIS) / LCDUPDATE_MAX_VALUE)
// Ex:( (1.0 / 32E-3 ) / 8 ) = each screen element updates 3.9x/second
// Ex:( (1.0 / 32E-3 ) / 14 ) = worst case (all elements have changed), each screen element updates 2.2x/second
//Only update screen at a human-readable rate
if(millis() - millis_previous > SCREEN_UPDATE_RATE_MILLIS)
{ //update which screen element is allowed to update (if changed via another lcd_ function)
{
millis_previous = millis();
//always true unless Superloop hangs longer than SCREEN_UPDATE_RATE_MILLIS
if(lcdUpdate_state == LCDUPDATE_NO_UPDATE) { lcdUpdate_state = lastElementUpdated; } //restore last updated screen element
#define MAX_LCDUPDATE_ATTEMPTS LCDUPDATE_MAX_VALUE
#define MAX_LCDUPDATE_ATTEMPTS LCDUPDATE_MAX_VALUE
uint8_t updateAttempts = 0;
do
{ //repeats until ONE screen element update occurs
lcdUpdate_state++; //select which LCD variable is next in line to update
if(lcdUpdate_state > LCDUPDATE_MAX_VALUE) {lcdUpdate_state = 1;} //reset to first element
{
if( (++lcdElementToUpdate) > LCDUPDATE_MAX_VALUE ) { lcdElementToUpdate = 1; } //reset to first element
updateAttempts++;
} while( (lcd_updateValue(lcdUpdate_state) == SCREEN_DIDNT_UPDATE) && (updateAttempts < MAX_LCDUPDATE_ATTEMPTS) );
lastElementUpdated = lcdUpdate_state; //store last updated screen element
}
else
{
lcdUpdate_state = LCDUPDATE_NO_UPDATE; //disable screen updates until SCREEN_UPDATE_RATE_MILLIS time has passed
} while( (lcd_updateValue(lcdElementToUpdate) == SCREEN_DIDNT_UPDATE) && (updateAttempts < MAX_LCDUPDATE_ATTEMPTS) );
}
#endif
@@ -470,13 +483,13 @@ void lcd_printStaticText(void)
// 01234567890123456789
//4x20 screen text display format: ********************
lcd2.setCursor(0,0); lcd2.print(F("Hx.xxx(y.yyy) dz.zzz")); //row0: x.xxx=(1,0) y.yyy=(7,0) z.zzz=(15,0)
// x.xxx:cellHI y.yyy:Vmax z.zzz:deltaV
// x.xxx:cellHI y.yyy:Vmax z.zzz:deltaV
lcd2.setCursor(0,1); lcd2.print(F("La.aaa(b.bbb) A-ccc ")); //row1: a.aaa=(1,1) b.bbb=(7,1) ccc=(15,1)
// a.aaa:cellLO b.bbb:Vmin ccc:current
lcd2.setCursor(0,2); lcd2.print(F("Vprrr(fff) TggC ")); //row2: rrr=(2,2) fff=(6,2) gg=(12,2)
// rrr:Vpack fff:Vspoof gg:hiTemp hh:loTemp
// a.aaa:cellLO b.bbb:Vmin ccc:current
lcd2.setCursor(0,2); lcd2.print(F("Vprrr(fff) ThhC Eeeg")); //row2: rrr=(2,2) fff=(6,2) hh=(12,2) ee=(17,2) p=(19,2)
// rrr:Vpack fff:Vspoof hh:T_batt ee:errors g:gridFlag
lcd2.setCursor(0,3); lcd2.print(F("Tuuuuu SoCss kW-kk.k")); //row3: uuuuu=(1,3) ss=(10,3) kk.k=(15,3)
// uuuuu:T_keyOn ss:SoC(%) kk.k:power
// uuuuu:T_keyOn ss:SoC(%) kk.k:power
#endif
}
@@ -492,12 +505,12 @@ void lcd_displayOFF(void)
lcd2.print(F("FW Hours Left: "));
lcd2.print(String(REQUIRED_FIRMWARE_UPDATE_PERIOD_HOURS - EEPROM_uptimeStoredInEEPROM_hours_get() ));
delay(1000); //allow time for operator to read firmware version
delay(1000); //allow time for operator to read firmware version //blocking
//Refresh lcd (can't do this while key on)
Wire.end();
delay(50);
lcd_initialize();
lcd_begin();
delay(50);
lcd_printStaticText();
@@ -515,7 +528,7 @@ void lcd_displayOFF(void)
////////////////////////////////////////////////////////////////////////
void lcd_displayON(void)
void lcd_displayOn(void)
{
#ifdef LCD_4X20_CONNECTED
lcd2.backlight();
@@ -525,7 +538,7 @@ void lcd_displayON(void)
////////////////////////////////////////////////////////////////////////
void lcd_gridChargerWarning(void)
void lcd_Warning_gridCharger(void)
{
gpio_turnBuzzer_on_highFreq();
lcd2.backlight();
@@ -542,7 +555,7 @@ void lcd_gridChargerWarning(void)
////////////////////////////////////////////////////////////////////////
void lcd_firmwareUpdateWarning(void)
void lcd_Warning_firmwareUpdate(void)
{
lcd2.backlight();
lcd2.display();
@@ -552,4 +565,18 @@ void lcd_firmwareUpdateWarning(void)
lcd2.setCursor(0,1); lcd2.print(F("required during beta"));
lcd2.setCursor(0,2); lcd2.print(F(" --LiBCM disabled-- "));
lcd2.setCursor(0,3); lcd2.print(F(" www.linsight.org "));
}
////////////////////////////////////////////////////////////////////////
void lcd_Warning_coverNotInstalled(void)
{
lcd2.backlight();
lcd2.display();
lcd2.clear();
// ********************
lcd2.setCursor(0,0); lcd2.print(F("ALERT: Safety cover "));
lcd2.setCursor(0,1); lcd2.print(F(" not installed"));
lcd2.setCursor(0,2); lcd2.print(F(" --LiBCM disabled-- "));
lcd2.setCursor(0,3); lcd2.print(F(" www.linsight.org "));
}

View File

@@ -7,9 +7,9 @@
#define SCREEN_DIDNT_UPDATE false
#define SCREEN_UPDATED true
//define round-robin states //one screen element is updated at a time
//define screen elements //one screen element is updated at a time, using round robbin state machine
#define LCDUPDATE_NO_UPDATE 0
#define LCDUPDATE_LOOPCOUNT 1
#define LCDUPDATE_SECONDS 1
#define LCDUPDATE_VPACK_ACTUAL 2
#define LCDUPDATE_VPACK_SPOOFED 3
#define LCDUPDATE_NUMERRORS 4
@@ -22,21 +22,23 @@
#define LCDUPDATE_SoC 11
#define LCDUPDATE_CURRENT 12
#define LCDUPDATE_TEMP_BATTERY 13
#define LCDUPDATE_GRID_STATUS 14
#define LCDUPDATE_MAX_VALUE 14 //must be equal to the highest defined number (above)
#define LCDUPDATE_MAX_VALUE 13 //must be equal to the highest defined number (above)
void lcd_initialize(void);
void lcd_begin(void);
void lcd_refresh(void); //primary interface //each call updates one screen element
void lcd_displayON(void);
void lcd_displayOn(void);
void lcd_displayOFF(void);
void lcd_printStaticText(void);
void lcd_gridChargerWarning(void);
void lcd_Warning_gridCharger(void);
void lcd_firmwareUpdateWarning(void);
void lcd_Warning_firmwareUpdate(void);
void lcd_Warning_coverNotInstalled(void);
#endif

View File

@@ -41,5 +41,6 @@
#include "SoC.h"
#include "temperature.h"
#include "eepromAccess.h"
#include "cellBalance.h"
#endif

View File

@@ -87,7 +87,6 @@ void temperature_handler(void)
static uint8_t keyStatePrevious = KEYOFF;
uint8_t keyState_Now = key_getSampledState();
//JTS2doNow: Logic doesn't seem right. Verify behavior.
if(keyState_Now != keyStatePrevious) { tempSensorState = TEMP_SENSORS_OFF; } //key state just changed (keyON->OFF or keyOFF->ON)
keyStatePrevious = keyState_Now;

View File

@@ -10,13 +10,13 @@ https://www.aliexpress.com/item/4000906238501.html?spm=a2g0o.store_pc_allProduct
18S ("HD281"):
https://www.yqwakan.com/product_7738_autowiringharnessplugcableelectricunsealedplugconnectorHD281072221.html
https://www.yqwakan.com/product_7737_autowiringharnessplugcableelectricunsealedplugconnectorHD281072211.html
https://www.aliexpress.com/item/4000265656537.html?spm=a2g0o.productlist.0.0.32e242db7hOdvD&algo_pvid=a6a5434e-fd09-4a5c-b7b5-11ec6cdfd513&algo_expid=a6a5434e-fd09-4a5c-b7b5-11ec6cdfd513-16&btsid=0b0a555916220955166888686e56b2&ws_ab_test=searchweb0_0,searchweb201602_,searchweb201603_
...
https://www.yqwakan.com/product_7737_autowiringharnessplugcableelectricunsealedplugconnectorHD281072211.html
http://www.hdconnectorstore.com/productdetail/3156.html