mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
DataFlash: Add voltage2 data to Current log, to be used by plane.
This commit is contained in:
parent
1b152cf2bf
commit
392e5257cc
@ -429,6 +429,7 @@ struct PACKED log_Current {
|
||||
int16_t current_amps;
|
||||
uint16_t board_voltage;
|
||||
float current_total;
|
||||
int16_t battery2_voltage;
|
||||
};
|
||||
|
||||
/*
|
||||
@ -529,7 +530,7 @@ struct PACKED log_AIRSPEED {
|
||||
{ LOG_ARSP_MSG, sizeof(log_AIRSPEED), \
|
||||
"ARSP", "Iffcff", "TimeMS,Airspeed,DiffPress,Temp,RawPress,Offset" }
|
||||
{ LOG_CURRENT_MSG, sizeof(log_Current), \
|
||||
"CURR", "Ihhhhf","TimeMS,ThrOut,Volt,Curr,Vcc,CurrTot" }
|
||||
"CURR", "Ihhhhfh","TimeMS,Throttle,Volt,Curr,Vcc,CurrTot,Volt2" }
|
||||
|
||||
// messages for more advanced boards
|
||||
#define LOG_EXTRA_STRUCTURES \
|
||||
|
@ -1135,6 +1135,7 @@ void DataFlash_Class::Log_Write_Attitude(AP_AHRS &ahrs, Vector3f targets)
|
||||
// Write an Current data packet
|
||||
void DataFlash_Class::Log_Write_Current(AP_BattMonitor battery, int16_t throttle)
|
||||
{
|
||||
float voltage2 = battery.voltage2();
|
||||
struct log_Current pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_CURRENT_MSG),
|
||||
time_ms : hal.scheduler->millis(),
|
||||
@ -1142,7 +1143,8 @@ void DataFlash_Class::Log_Write_Current(AP_BattMonitor battery, int16_t throttl
|
||||
battery_voltage : (int16_t) (battery.voltage() * 100.0f),
|
||||
current_amps : (int16_t) (battery.current_amps() * 100.0f),
|
||||
board_voltage : (uint16_t)(hal.analogin->board_voltage()*1000),
|
||||
current_total : battery.current_total_mah()
|
||||
current_total : battery.current_total_mah(),
|
||||
battery2_voltage : (int16_t)(voltage2 * 100.0f)
|
||||
};
|
||||
WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user