mirror of
https://github.com/doppelhub/Honda_Insight_LiBCM.git
synced 2026-06-10 23:47:28 -04:00
(new) energy.c
This commit is contained in:
@@ -0,0 +1,27 @@
|
|||||||
|
RevD schematic shows (incorrect) AP62301 buck configuration.
|
||||||
|
All shipped RevD boards use AP63205 buck configuration; the AP62301 buck never shipped.
|
||||||
|
The changes below are for the (correct) AP63205 configuration.
|
||||||
|
|
||||||
|
All RevD PCBs I've shipped are assembled correctly.
|
||||||
|
This issue only applies to the schematic.
|
||||||
|
|
||||||
|
Schematic value assignment (existing)(correct)(location)(note):
|
||||||
|
C143:(DNP)(22u)(Arduino Vin)(move schematic symbol next to D5).
|
||||||
|
C18: (DNP)(22u)(AP63205 Vout)()
|
||||||
|
C19: (DNP)(22u)(AP63205 Vout)()
|
||||||
|
C17: (22u)(22u)(AP63205 Vout)(move schematic symbol next to AP53205)
|
||||||
|
|
||||||
|
C184:(22u)(DNP)(AP62301 Vout)()
|
||||||
|
C185:(22u)(DNP)(AP62301 Vout)()
|
||||||
|
C186:(22u)(DNP)(AP62301 Vout)()
|
||||||
|
C153:(22u)(DNP)(AP62301 Vout)(part populated on existing PCBs, but doesn't need to be)
|
||||||
|
|
||||||
|
C8: (DNP)(22u)(AP63205 Vin)()
|
||||||
|
C32: (22u)(DNP)(AP63201 Vin)()
|
||||||
|
C11: (DNP)(1u) (AP63205 Vin)()
|
||||||
|
C179:(1u) (DNP)(AP62301 Vin)
|
||||||
|
|
||||||
|
C26: (22u)(22u)(fan)(no change)
|
||||||
|
C23: (22u)(22u)(HVDCDC Vout)(no change)
|
||||||
|
C25: (22u)(22u)(HVDCDC Vout)(no change)
|
||||||
|
C146:(22u)(22u)(HVDCDC Vout)(no change)
|
||||||
Binary file not shown.
@@ -9,7 +9,7 @@
|
|||||||
#define TEMP_BIN_WIDTH_DEGC 4 //must be 2^n //e.g. -26 to -23, -22 d to -19, etc
|
#define TEMP_BIN_WIDTH_DEGC 4 //must be 2^n //e.g. -26 to -23, -22 d to -19, etc
|
||||||
#define TEMP_BIN_WIDTH_RIGHTSHIFTS 2 //must match above (DEGC = 2^RIGHTSHIFTS)
|
#define TEMP_BIN_WIDTH_RIGHTSHIFTS 2 //must match above (DEGC = 2^RIGHTSHIFTS)
|
||||||
#define LO_TEMP_BIN_TOP_DEGC (-27)// lowest bin's high count (e.g. temps up to -27 degC)
|
#define LO_TEMP_BIN_TOP_DEGC (-27)// lowest bin's high count (e.g. temps up to -27 degC)
|
||||||
#define HI_TEMP_BIN_TOP_DEGC 69 //highest bin's high count (e.g. temps from 65 to 69)
|
#define HI_TEMP_BIN_TOP_DEGC 69 //highest bin's high count (e.g. temps from 66 to 69)
|
||||||
#define TOTAL_TEMP_BINS (((HI_TEMP_BIN_TOP_DEGC - LO_TEMP_BIN_TOP_DEGC) >> TEMP_BIN_WIDTH_RIGHTSHIFTS) + 2)
|
#define TOTAL_TEMP_BINS (((HI_TEMP_BIN_TOP_DEGC - LO_TEMP_BIN_TOP_DEGC) >> TEMP_BIN_WIDTH_RIGHTSHIFTS) + 2)
|
||||||
//bin# 0, 1, 2, 3, 4, 5, 6,7,8,9,10,11,12,13,14,15,16,17,18,19,20,21,22,23,24,25
|
//bin# 0, 1, 2, 3, 4, 5, 6,7,8,9,10,11,12,13,14,15,16,17,18,19,20,21,22,23,24,25
|
||||||
//degC:up to -27,-23,-19,-15,-11,-7,-3,1,5,9,13,17,21,25,29,33,37,41,45,49,53,57,61,65,69,70+
|
//degC:up to -27,-23,-19,-15,-11,-7,-3,1,5,9,13,17,21,25,29,33,37,41,45,49,53,57,61,65,69,70+
|
||||||
|
|||||||
28
Firmware/firmwareLiBCM/src/energy.cpp
Normal file
28
Firmware/firmwareLiBCM/src/energy.cpp
Normal file
@@ -0,0 +1,28 @@
|
|||||||
|
//Copyright 2021-2024(c) John Sullivan
|
||||||
|
//github.com/doppelhub/Honda_Insight_LiBCM
|
||||||
|
|
||||||
|
//maintains battery assist and regen watt hour counts
|
||||||
|
|
||||||
|
#include "libcm.h"
|
||||||
|
|
||||||
|
|
||||||
|
/////////////////////////////////////////////////////////////////////////////////////////
|
||||||
|
|
||||||
|
void energy_integrate_centiJoules(void);
|
||||||
|
{
|
||||||
|
static uint32_t timestamp_lastCall_ms = 0;
|
||||||
|
|
||||||
|
uint32_t milliseconds_now = millis();
|
||||||
|
uint8_t periodBetweenCalls_ms = (uint8_t)(milliseconds_now - timestamp_lastCall_ms);
|
||||||
|
timestamp_lastCall_ms = milliseconds_now;
|
||||||
|
|
||||||
|
uint32_t power_deciWatts = LTC68042result_packVoltage_get() * (uint32_t)adc_getLatestBatteryCurrent_deciAmps();
|
||||||
|
|
||||||
|
// centiJoules_sinceLastUpdate = (power_deciWatts / 10) * (loopPeriod_ms / 1000) * (100 cJ/J)
|
||||||
|
// centiJoules_sinceLastUpdate = (power_deciWatts * loopPeriod_ms ) / 100
|
||||||
|
// centiJoules_sinceLastUpdate = (power_deciWatts * loopPeriod_ms ) * 0.01
|
||||||
|
// centiJoules_sinceLastUpdate = ((power_deciWatts * loopPeriod_ms ) * 41) >> 12
|
||||||
|
uint16_t centiJoules_sinceLastUpdate = (uint16_t)((power_deciWatts * periodBetweenCalls_ms ) * 41) >> 12;
|
||||||
|
}
|
||||||
|
|
||||||
|
/////////////////////////////////////////////////////////////////////////////////////////
|
||||||
9
Firmware/firmwareLiBCM/src/energy.h
Normal file
9
Firmware/firmwareLiBCM/src/energy.h
Normal file
@@ -0,0 +1,9 @@
|
|||||||
|
//Copyright 2021-2024(c) John Sullivan
|
||||||
|
//github.com/doppelhub/Honda_Insight_LiBCM
|
||||||
|
|
||||||
|
#ifndef wattHours_h
|
||||||
|
#define wattHours_h
|
||||||
|
|
||||||
|
void energy_integrate_centiJoules(void);
|
||||||
|
|
||||||
|
#endif
|
||||||
@@ -52,5 +52,6 @@
|
|||||||
#include "LiControl.h"
|
#include "LiControl.h"
|
||||||
#include "batteryHistory.h"
|
#include "batteryHistory.h"
|
||||||
#include "powerSave.h"
|
#include "powerSave.h"
|
||||||
|
#include "energy.h"
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|||||||
Binary file not shown.
Reference in New Issue
Block a user