AP_BattMonitor: switch to Log_Write for BCL2

Just for the flash savings on smaller boards
This commit is contained in:
Peter Barker 2021-06-08 15:21:10 +10:00 committed by Andrew Tridgell
parent 61fda691f2
commit bf9937489b
2 changed files with 28 additions and 33 deletions

View File

@ -29,32 +29,43 @@ void AP_BattMonitor_Backend::Log_Write_BCL(const uint8_t instance, const uint64_
if (!has_cell_voltages()) {
return;
}
struct log_BCL cell_pkt{
LOG_PACKET_HEADER_INIT(LOG_BCL_MSG),
time_us : time_us,
instance : instance,
voltage : _state.voltage
};
// we pack the entire BCL message - we must have at least that
// many supported cells or the loop below will over-read
static_assert(ARRAY_SIZE(_state.cell_voltages.cells) >= ARRAY_SIZE(cell_pkt.cell_voltages));
for (uint8_t i = 0; i < ARRAY_SIZE(cell_pkt.cell_voltages); i++) {
cell_pkt.cell_voltages[i] = _state.cell_voltages.cells[i] + 1; // add 1mv
}
AP::logger().WriteBlock(&cell_pkt, sizeof(cell_pkt));
#if AP_BATT_MONITOR_CELLS_MAX > 12
if (_state.cell_voltages.cells[12] != UINT16_MAX || _state.cell_voltages.cells[13] != UINT16_MAX)
{
struct log_BCL2 cell_pkt2{
LOG_PACKET_HEADER_INIT(LOG_BCL2_MSG),
time_us : time_us,
instance : instance
};
for (uint8_t i = 0; i < ARRAY_SIZE(cell_pkt2.cell_voltages); i++) {
cell_pkt2.cell_voltages[i] = _state.cell_voltages.cells[ARRAY_SIZE(cell_pkt.cell_voltages)+i] + 1; // add 1mv
}
AP::logger().WriteBlock(&cell_pkt2, sizeof(cell_pkt2));
// check battery structure can hold all cells
static_assert(ARRAY_SIZE(_state.cell_voltages.cells) == ARRAY_SIZE(cell_pkt.cell_voltages) + ARRAY_SIZE(cell_pkt2.cell_voltages),
"Battery cell number doesn't match in library and log structures");
// @LoggerMessage: BCL2
// @Description: Battery cell voltage information
// @Field: TimeUS: Time since system startup
// @Field: Instance: battery instance number
// @Field: V13: thirteenth cell voltage
// @Field: V14: fourteenth cell voltage
AP::logger().Write(
"BCL2",
"TimeUS,Instance,V13,V14",
"s#vv",
"F-CC",
"QBHH",
time_us,
instance,
_state.cell_voltages.cells[ARRAY_SIZE(cell_pkt.cell_voltages)+0] + 1, // add 1mv
_state.cell_voltages.cells[ARRAY_SIZE(cell_pkt.cell_voltages)+1] + 1 // add 1mv
);
}
#endif
}

View File

@ -4,8 +4,7 @@
#define LOG_IDS_FROM_BATTMONITOR \
LOG_BAT_MSG, \
LOG_BCL_MSG, \
LOG_BCL2_MSG
LOG_BCL_MSG
// @LoggerMessage: BAT
// @Description: Gathered battery data
@ -53,26 +52,11 @@ struct PACKED log_BCL {
uint64_t time_us;
uint8_t instance;
float voltage;
uint16_t cell_voltages[12]; // the format does not support more than 12 cells, the remaining cells are reported in the log_BCL2 structure
};
// @LoggerMessage: BCL2
// @Description: Battery cell voltage information
// @Field: TimeUS: Time since system startup
// @Field: Instance: battery instance number
// @Field: V13: thirteenth cell voltage
// @Field: V14: fourteenth cell voltage
struct PACKED log_BCL2 {
LOG_PACKET_HEADER;
uint64_t time_us;
uint8_t instance;
uint16_t cell_voltages[2];
uint16_t cell_voltages[12]; // the format does not support more than 12 cells, the remaining cells are reported in the BCL2 message
};
#define LOG_STRUCTURE_FROM_BATTMONITOR \
{ LOG_BAT_MSG, sizeof(log_BAT), \
"BAT", "QBfffffcf", "TimeUS,Instance,Volt,VoltR,Curr,CurrTot,EnrgTot,Temp,Res", "s#vvAiJOw", "F-000!/?0" }, \
{ LOG_BCL_MSG, sizeof(log_BCL), \
"BCL", "QBfHHHHHHHHHHHH", "TimeUS,Instance,Volt,V1,V2,V3,V4,V5,V6,V7,V8,V9,V10,V11,V12", "s#vvvvvvvvvvvvv", "F-0CCCCCCCCCCCC" }, \
{ LOG_BCL2_MSG, sizeof(log_BCL2), \
"BCL2", "QBHH", "TimeUS,Instance,V13,V14", "s#vv", "F-CC" },
"BCL", "QBfHHHHHHHHHHHH", "TimeUS,Instance,Volt,V1,V2,V3,V4,V5,V6,V7,V8,V9,V10,V11,V12", "s#vvvvvvvvvvvvv", "F-0CCCCCCCCCCCC" },