DataFlash: Log new CUR2 entry for battery2 data

This commit is contained in:
Tom Pittenger 2016-06-02 14:00:57 -07:00
parent a596aa5907
commit 3ed2fafefa
2 changed files with 27 additions and 18 deletions

View File

@ -1640,18 +1640,27 @@ void DataFlash_Class::Log_Write_Attitude(AP_AHRS &ahrs, const Vector3f &targets)
// Write an Current data packet // Write an Current data packet
void DataFlash_Class::Log_Write_Current(const AP_BattMonitor &battery) void DataFlash_Class::Log_Write_Current(const AP_BattMonitor &battery)
{ {
float voltage2 = battery.voltage2(); if (battery.num_instances() >= 1) {
struct log_Current pkt = { struct log_Current pkt = {
LOG_PACKET_HEADER_INIT(LOG_CURRENT_MSG), LOG_PACKET_HEADER_INIT(LOG_CURRENT_MSG),
time_us : AP_HAL::micros64(), time_us : AP_HAL::micros64(),
throttle : throttle, battery_voltage : battery.voltage(0),
battery_voltage : (int16_t) (battery.voltage() * 100.0f), current_amps : battery.current_amps(0),
current_amps : (int16_t) (battery.current_amps() * 100.0f), current_total : battery.current_total_mah(0),
board_voltage : (uint16_t)(hal.analogin->board_voltage()*1000), };
current_total : battery.current_total_mah(), WriteBlock(&pkt, sizeof(pkt));
battery2_voltage : (int16_t)(voltage2 * 100.0f) }
};
WriteBlock(&pkt, sizeof(pkt)); if (battery.num_instances() >= 2) {
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),
};
WriteBlock(&pkt, sizeof(pkt));
}
} }
// Write a Compass packet // Write a Compass packet

View File

@ -421,12 +421,9 @@ struct PACKED log_PID {
struct PACKED log_Current { struct PACKED log_Current {
LOG_PACKET_HEADER; LOG_PACKET_HEADER;
uint64_t time_us; uint64_t time_us;
int16_t throttle; float battery_voltage;
int16_t battery_voltage; float current_amps;
int16_t current_amps;
uint16_t board_voltage;
float current_total; float current_total;
int16_t battery2_voltage;
}; };
struct PACKED log_Compass { struct PACKED log_Compass {
@ -751,7 +748,9 @@ Format characters in the format string for binary log messages
{ LOG_ARSP_MSG, sizeof(log_AIRSPEED), \ { LOG_ARSP_MSG, sizeof(log_AIRSPEED), \
"ARSP", "QffcffB", "TimeUS,Airspeed,DiffPress,Temp,RawPress,Offset,U" }, \ "ARSP", "QffcffB", "TimeUS,Airspeed,DiffPress,Temp,RawPress,Offset,U" }, \
{ LOG_CURRENT_MSG, sizeof(log_Current), \ { LOG_CURRENT_MSG, sizeof(log_Current), \
"CURR", "QhhhHfh","TimeUS,Throttle,Volt,Curr,Vcc,CurrTot,Volt2" },\ "CURR", "Qfff","TimeUS,Volt,Curr,CurrTot" },\
{ LOG_CURRENT2_MSG, sizeof(log_Current), \
"CUR2", "Qfff","TimeUS,Volt,Curr,CurrTot" }, \
{ LOG_ATTITUDE_MSG, sizeof(log_Attitude),\ { LOG_ATTITUDE_MSG, sizeof(log_Attitude),\
"ATT", "QccccCCCC", "TimeUS,DesRoll,Roll,DesPitch,Pitch,DesYaw,Yaw,ErrRP,ErrYaw" }, \ "ATT", "QccccCCCC", "TimeUS,DesRoll,Roll,DesPitch,Pitch,DesYaw,Yaw,ErrRP,ErrYaw" }, \
{ LOG_COMPASS_MSG, sizeof(log_Compass), \ { LOG_COMPASS_MSG, sizeof(log_Compass), \
@ -945,6 +944,7 @@ enum LogMessages {
LOG_ARSP_MSG, LOG_ARSP_MSG,
LOG_ATTITUDE_MSG, LOG_ATTITUDE_MSG,
LOG_CURRENT_MSG, LOG_CURRENT_MSG,
LOG_CURRENT2_MSG,
LOG_COMPASS_MSG, LOG_COMPASS_MSG,
LOG_COMPASS2_MSG, LOG_COMPASS2_MSG,
LOG_COMPASS3_MSG, LOG_COMPASS3_MSG,