DataFlash: add resting voltage and resistance to current logging

also log cell voltages in separate message
This commit is contained in:
Randy Mackay 2017-05-31 10:44:40 +09:00
parent 8def1d257e
commit 26845cc66a
2 changed files with 58 additions and 18 deletions

View File

@ -1924,21 +1924,32 @@ void DataFlash_Class::Log_Write_Current(const AP_BattMonitor &battery)
struct log_Current pkt = {
LOG_PACKET_HEADER_INIT(LOG_CURRENT_MSG),
time_us : AP_HAL::micros64(),
battery_voltage : battery.voltage(0),
voltage : battery.voltage(0),
voltage_resting : battery.voltage_resting_estimate(0),
current_amps : battery.current_amps(0),
current_total : battery.current_total_mah(0),
temperature : (int16_t)(has_temp ? (temp * 100) : 0),
resistance : battery.get_resistance(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));
// individual cell voltages
if (battery.has_cell_voltages(0)) {
const AP_BattMonitor::cells &cells = battery.get_cell_voltages(0);
struct log_Current_Cells cell_pkt = {
LOG_PACKET_HEADER_INIT(LOG_CURRENT_CELLS_MSG),
time_us : AP_HAL::micros64(),
voltage : battery.voltage(0)
};
for (uint8_t i = 0; i < ARRAY_SIZE(cells.cells); i++) {
cell_pkt.cell_voltages[i] = cells.cells[i] + 1;
}
WriteBlock(&cell_pkt, sizeof(cell_pkt));
// check battery structure can hold all cells
static_assert(ARRAY_SIZE(cells.cells) == (sizeof(cell_pkt.cell_voltages) / sizeof(cell_pkt.cell_voltages[0])),
"Battery cell number doesn't match in library and log structure");
}
}
if (battery.num_instances() >= 2) {
@ -1947,16 +1958,28 @@ void DataFlash_Class::Log_Write_Current(const AP_BattMonitor &battery)
struct log_Current pkt = {
LOG_PACKET_HEADER_INIT(LOG_CURRENT2_MSG),
time_us : AP_HAL::micros64(),
battery_voltage : battery.voltage(1),
voltage : battery.voltage(1),
voltage_resting : battery.voltage_resting_estimate(1),
current_amps : battery.current_amps(1),
current_total : battery.current_total_mah(1),
temperature : (int16_t)(has_temp ? (temp * 100) : 0),
resistance : battery.get_resistance(1)
};
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));
// individual cell voltages
if (battery.has_cell_voltages(1)) {
const AP_BattMonitor::cells &cells = battery.get_cell_voltages(1);
struct log_Current_Cells cell_pkt = {
LOG_PACKET_HEADER_INIT(LOG_CURRENT_CELLS_MSG),
time_us : AP_HAL::micros64(),
voltage : battery.voltage(1)
};
for (uint8_t i = 0; i < ARRAY_SIZE(cells.cells); i++) {
cell_pkt.cell_voltages[i] = cells.cells[i] + 1;
}
WriteBlock(&cell_pkt, sizeof(cell_pkt));
}
}
}

View File

@ -513,10 +513,18 @@ struct PACKED log_PID {
struct PACKED log_Current {
LOG_PACKET_HEADER;
uint64_t time_us;
float battery_voltage;
float voltage;
float voltage_resting;
float current_amps;
float current_total;
int16_t temperature; // degrees C * 100
float resistance;
};
struct PACKED log_Current_Cells {
LOG_PACKET_HEADER;
uint64_t time_us;
float voltage;
uint16_t cell_voltages[10];
};
@ -848,8 +856,11 @@ struct PACKED log_Beacon {
#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"
#define CURR_LABELS "TimeUS,Volt,VoltR,Curr,CurrTot,Temp,Res"
#define CURR_FMT "Qffffcf"
#define CURR_CELL_LABELS "TimeUS,Volt,V1,V2,V3,V4,V5,V6,V7,V8,V9,V10"
#define CURR_CELL_FMT "QfHHHHHHHHHH"
/*
Format characters in the format string for binary log messages
@ -920,6 +931,10 @@ Format characters in the format string for binary log messages
"CURR", CURR_FMT,CURR_LABELS }, \
{ LOG_CURRENT2_MSG, sizeof(log_Current), \
"CUR2", CURR_FMT,CURR_LABELS }, \
{ LOG_CURRENT_CELLS_MSG, sizeof(log_Current_Cells), \
"BCL", CURR_CELL_FMT, CURR_CELL_LABELS }, \
{ LOG_CURRENT_CELLS2_MSG, sizeof(log_Current_Cells), \
"BCL2", CURR_CELL_FMT, CURR_CELL_LABELS }, \
{ LOG_ATTITUDE_MSG, sizeof(log_Attitude),\
"ATT", "QccccCCCC", "TimeUS,DesRoll,Roll,DesPitch,Pitch,DesYaw,Yaw,ErrRP,ErrYaw" }, \
{ LOG_COMPASS_MSG, sizeof(log_Compass), \
@ -1136,6 +1151,8 @@ enum LogMessages {
LOG_ATTITUDE_MSG,
LOG_CURRENT_MSG,
LOG_CURRENT2_MSG,
LOG_CURRENT_CELLS_MSG,
LOG_CURRENT_CELLS2_MSG,
LOG_COMPASS_MSG,
LOG_COMPASS2_MSG,
LOG_COMPASS3_MSG,