mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 17:18:28 -04:00
AP_BattMonitor: Increase the max. nr. of supported battery cells from 12 to 14
Uses a second message, because the original message does not support any more fields
This commit is contained in:
parent
06e64b5585
commit
222ef40321
@ -19,7 +19,11 @@
|
||||
#define AP_BATT_MONITOR_RES_EST_TC_1 0.5f
|
||||
#define AP_BATT_MONITOR_RES_EST_TC_2 0.1f
|
||||
|
||||
#if !HAL_MINIMIZE_FEATURES && BOARD_FLASH_SIZE > 1024
|
||||
#define AP_BATT_MONITOR_CELLS_MAX 14
|
||||
#else
|
||||
#define AP_BATT_MONITOR_CELLS_MAX 12
|
||||
#endif
|
||||
|
||||
#ifndef HAL_BATTMON_SMBUS_ENABLE
|
||||
#define HAL_BATTMON_SMBUS_ENABLE 1
|
||||
|
@ -36,12 +36,25 @@ void AP_BattMonitor_Backend::Log_Write_BCL(const uint8_t instance, const uint64_
|
||||
instance : instance,
|
||||
voltage : _state.voltage
|
||||
};
|
||||
for (uint8_t i = 0; i < ARRAY_SIZE(_state.cell_voltages.cells); i++) {
|
||||
cell_pkt.cell_voltages[i] = _state.cell_voltages.cells[i] + 1;
|
||||
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));
|
||||
|
||||
// check battery structure can hold all cells
|
||||
static_assert(ARRAY_SIZE(_state.cell_voltages.cells) == ARRAY_SIZE(cell_pkt.cell_voltages),
|
||||
"Battery cell number doesn't match in library and log structure");
|
||||
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");
|
||||
}
|
||||
}
|
||||
|
@ -4,7 +4,8 @@
|
||||
|
||||
#define LOG_IDS_FROM_BATTMONITOR \
|
||||
LOG_BAT_MSG, \
|
||||
LOG_BCL_MSG
|
||||
LOG_BCL_MSG, \
|
||||
LOG_BCL2_MSG
|
||||
|
||||
// @LoggerMessage: BAT
|
||||
// @Description: Gathered battery data
|
||||
@ -52,11 +53,26 @@ struct PACKED log_BCL {
|
||||
uint64_t time_us;
|
||||
uint8_t instance;
|
||||
float voltage;
|
||||
uint16_t cell_voltages[12];
|
||||
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];
|
||||
};
|
||||
|
||||
#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" },
|
||||
"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" },
|
||||
|
Loading…
Reference in New Issue
Block a user