mirror of
https://github.com/doppelhub/Honda_Insight_LiBCM.git
synced 2026-06-10 23:47:28 -04:00
TODO items
This commit is contained in:
Binary file not shown.
Binary file not shown.
@@ -7,8 +7,8 @@
|
||||
#define config_h
|
||||
#include "src/libcm.h"
|
||||
|
||||
#define FW_VERSION "0.9.4a"
|
||||
#define BUILD_DATE "2024MAY13"
|
||||
#define FW_VERSION "0.9.4b"
|
||||
#define BUILD_DATE "2024JUL09"
|
||||
|
||||
//////////////////////////////////////////////////////////////////
|
||||
|
||||
|
||||
@@ -6,9 +6,9 @@
|
||||
#include "libcm.h"
|
||||
|
||||
uint8_t isoSPI_errorCount = 0;
|
||||
uint8_t LTC68042result_errorCount_get (void ) { return isoSPI_errorCount; }
|
||||
void LTC68042result_errorCount_set (uint8_t newErrorCount) { isoSPI_errorCount = newErrorCount; }
|
||||
void LTC68042result_errorCount_increment (void ) { isoSPI_errorCount++; }
|
||||
uint8_t LTC68042result_errorCount_get (void ) { return isoSPI_errorCount; }
|
||||
void LTC68042result_errorCount_set (uint8_t newErrorCount) { isoSPI_errorCount = newErrorCount; }
|
||||
void LTC68042result_errorCount_increment (void ) { isoSPI_errorCount++; Serial.print('@'); }
|
||||
|
||||
uint8_t packVoltage_actual = 170;
|
||||
void LTC68042result_packVoltage_set (uint8_t voltage) { packVoltage_actual = voltage; }
|
||||
|
||||
@@ -146,6 +146,10 @@ void printHelp(void)
|
||||
"\n -'$LOOP: LiBCM loop period. '$LOOP=___' to set (1 to 255 ms)"
|
||||
"\n -'$SCIms': period between BATTSCI frames. '$SCIms=___' to set (0 to 255 ms)"
|
||||
"\n"
|
||||
"\nLiBCM sends the following debug characters each time:"
|
||||
"\n -'@': isoSPI errors occur"
|
||||
"\n -'*': loop period exceeded"
|
||||
"\n"
|
||||
/*
|
||||
"\nFuture LiBCM commands (not presently supported"
|
||||
"\n -'$DEFAULT' restore all EEPROM values to default"
|
||||
|
||||
@@ -18,6 +18,7 @@ int16_t spoofedCurrentToSend_Counts = 0; //formatted as MCM expects to see it (2
|
||||
|
||||
uint8_t framePeriod_ms = 33;
|
||||
|
||||
//JTS2doLater: post#3093 (http://insightcentral.net/threads/libcm-open-beta-support-thread.128957) explains how make the OEM SoC gauge update
|
||||
//JTS2doLater: Add different SoC profile for "charges every day" crew
|
||||
//JTS2doLater: store in 'PROGMEM' to keep out of RAM (but note array elements must be indexed differently)
|
||||
//LUT remaps actual lithium battery SoC (unit: percent) to mimic OEM NiMH behavior (unit: deciPercent)
|
||||
|
||||
@@ -39,6 +39,7 @@ bool cellBalance_areCellsBalancing(void) { return cellsAreBalancing; }
|
||||
|
||||
/////////////////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
//JTS2doLater: Always allow discharge balancing when a cell is overcharged (for safety)
|
||||
//JTS2doLater: Write keyOff test that measures each cell voltage twice: once with discharge resistor off, and again with resistor on.
|
||||
// Then verify voltage drop, which means the discharge resistor is turning off and on. If there isn't enough resolution,
|
||||
// another method would be to wait a few hours for pack voltages to settle, then log all cell voltages an hour apart.
|
||||
|
||||
@@ -63,7 +63,8 @@ void gpio_begin(void)
|
||||
//JTS2doLater: Turn all this stuff off when the key is off
|
||||
TCCR1B = (TCCR1B & B11111000) | B00000001; // Set F_PWM to 31372.55 Hz //pins D11(fan) & D12()
|
||||
TCCR3B = (TCCR3B & B11111000) | B00000001; // Set F_PWM to 31372.55 Hz //pins D2() & D3() & D5(VPIN_OUT)
|
||||
TCCR4B = (TCCR4B & B11111000) | B00000010; // Set F_PWM to 3921.16 Hz //pins D7(MCMe) & D8(gridPWM) & D9()
|
||||
TCCR4B = (TCCR4B & B11111000) | B00000010; // Set F_PWM to 3921.16 Hz //pins D7(MCMe) & D8(gridPWM) & D9() //JTS2doLater: use higher frequency when keyOn
|
||||
//TCCR4B = (TCCR4B & B11111000) | B00000100; // Set F_PWM to 122.55 Hz //pins D7(MCMe) & D8(gridPWM) & D9() //JTS2doLater: use lower frequency when charging
|
||||
//TCCR5B is set in Buzzer functions
|
||||
}
|
||||
|
||||
|
||||
@@ -575,7 +575,12 @@ void lcdTransmit_displayOff(void)
|
||||
|
||||
/////////////////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
//JTS2doNow: Add a one-time "firmware updated" LCD message, each time the firmware updates
|
||||
/*JTS2doLater: Add the following alert if LiBCM loses control
|
||||
LiBCM DETECTED A
|
||||
DANGEROUS CONDITION.
|
||||
TURN OFF IMA SWITCH
|
||||
IMMEDIATELY!!!!!!
|
||||
*/
|
||||
void lcdTransmit_Warning(uint8_t warningToDisplay)
|
||||
{
|
||||
static uint8_t whichRowToPrint = 0;
|
||||
|
||||
@@ -37,6 +37,12 @@
|
||||
|
||||
#define KEY_OFF_UPDATE_PERIOD_ONE_SECOND_ms ( 1 * 1000)
|
||||
#define KEY_OFF_UPDATE_PERIOD_TEN_MINUTES_ms (10 * 60000)
|
||||
//JTS2doLater: When the key is on - but the IMA switch is off (or fuse blown) - reduce LTC6804 update period to minimize LTC6804 power consumption
|
||||
//Tests to determine whether the IMA switch is on or off:
|
||||
//1) compare the VPIN input signal (HVDC voltage inside the PDU) with the pack voltage (as determined by the LTC6804 ICs).
|
||||
//1) After keyOn, if the delta varies wildly over a given time period, LiBCM can conclude that the IMA switch is off.
|
||||
//2) LiBCM can reset a timer each time the battery current sensor magnitude exceeds 0 amps (which can only happen if the IMA switch is on).
|
||||
//2) If the timer overflows (e.g. after an hour with 0 amps through the pack), LiBCM can likely conclude that the IMA switch is off.
|
||||
|
||||
#define MILLISECONDS_PER_HOUR 3600000
|
||||
|
||||
|
||||
Reference in New Issue
Block a user