DataFlash: Log battery temperature and cell voltages
This commit is contained in:
parent
341ac701d1
commit
3b6d348241
@ -1872,24 +1872,43 @@ void DataFlash_Class::Log_Write_AttitudeView(AP_AHRS_View &ahrs, const Vector3f
|
||||
void DataFlash_Class::Log_Write_Current(const AP_BattMonitor &battery)
|
||||
{
|
||||
if (battery.num_instances() >= 1) {
|
||||
float temp;
|
||||
bool has_temp = battery.get_temperature(temp, 0);
|
||||
struct log_Current pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_CURRENT_MSG),
|
||||
time_us : AP_HAL::micros64(),
|
||||
battery_voltage : battery.voltage(0),
|
||||
current_amps : battery.current_amps(0),
|
||||
current_total : battery.current_total_mah(0),
|
||||
temperature : (int16_t)(has_temp ? (temp * 100) : 0),
|
||||
};
|
||||
AP_BattMonitor::cells cells = battery.get_cell_voltages(0);
|
||||
|
||||
// check battery structure can hold all cells
|
||||
static_assert(ARRAY_SIZE(cells.cells) == (sizeof(pkt.cell_voltages) / sizeof(pkt.cell_voltages[0])),
|
||||
"Battery cell number doesn't match in library and log structure");
|
||||
|
||||
for (uint8_t i = 0; i < ARRAY_SIZE(cells.cells); i++) {
|
||||
pkt.cell_voltages[i] = cells.cells[i] + 1;
|
||||
}
|
||||
WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
|
||||
if (battery.num_instances() >= 2) {
|
||||
float temp;
|
||||
bool has_temp = battery.get_temperature(temp, 1);
|
||||
struct log_Current pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_CURRENT2_MSG),
|
||||
time_us : AP_HAL::micros64(),
|
||||
battery_voltage : battery.voltage(1),
|
||||
current_amps : battery.current_amps(1),
|
||||
current_total : battery.current_total_mah(1),
|
||||
temperature : (int16_t)(has_temp ? (temp * 100) : 0),
|
||||
};
|
||||
AP_BattMonitor::cells cells = battery.get_cell_voltages(1);
|
||||
for (uint8_t i = 0; i < ARRAY_SIZE(cells.cells); i++) {
|
||||
pkt.cell_voltages[i] = cells.cells[i] + 1;
|
||||
}
|
||||
WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
}
|
||||
|
@ -515,6 +515,8 @@ struct PACKED log_Current {
|
||||
float battery_voltage;
|
||||
float current_amps;
|
||||
float current_total;
|
||||
int16_t temperature; // degrees C * 100
|
||||
uint16_t cell_voltages[10];
|
||||
};
|
||||
|
||||
struct PACKED log_Compass {
|
||||
@ -831,6 +833,8 @@ struct PACKED log_AOA_SSA {
|
||||
#define QUAT_LABELS "TimeUS,Q1,Q2,Q3,Q4"
|
||||
#define QUAT_FMT "Qffff"
|
||||
|
||||
#define CURR_LABELS "TimeUS,Volt,Curr,CurrTot,Temp,V1,V2,V3,V4,V5,V6,V7,V8,V9,V10"
|
||||
#define CURR_FMT "QfffcHHHHHHHHHH"
|
||||
|
||||
/*
|
||||
Format characters in the format string for binary log messages
|
||||
@ -898,9 +902,9 @@ Format characters in the format string for binary log messages
|
||||
{ LOG_ARSP_MSG, sizeof(log_AIRSPEED), \
|
||||
"ARSP", "QffcffB", "TimeUS,Airspeed,DiffPress,Temp,RawPress,Offset,U" }, \
|
||||
{ LOG_CURRENT_MSG, sizeof(log_Current), \
|
||||
"CURR", "Qfff","TimeUS,Volt,Curr,CurrTot" },\
|
||||
"CURR", CURR_FMT,CURR_LABELS }, \
|
||||
{ LOG_CURRENT2_MSG, sizeof(log_Current), \
|
||||
"CUR2", "Qfff","TimeUS,Volt,Curr,CurrTot" }, \
|
||||
"CUR2", CURR_FMT,CURR_LABELS }, \
|
||||
{ LOG_ATTITUDE_MSG, sizeof(log_Attitude),\
|
||||
"ATT", "QccccCCCC", "TimeUS,DesRoll,Roll,DesPitch,Pitch,DesYaw,Yaw,ErrRP,ErrYaw" }, \
|
||||
{ LOG_COMPASS_MSG, sizeof(log_Compass), \
|
||||
|
Loading…
Reference in New Issue
Block a user