mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Plane: log power status on Pixhawk
This commit is contained in:
parent
bea0a46410
commit
7de8be1956
@ -239,7 +239,6 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan)
|
||||
0, // comm drops %,
|
||||
0, // comm drops in pkts,
|
||||
0, 0, 0, 0);
|
||||
|
||||
}
|
||||
|
||||
static void NOINLINE send_location(mavlink_channel_t chan)
|
||||
@ -619,6 +618,8 @@ static bool mavlink_try_send_message(mavlink_channel_t chan, enum ap_message id)
|
||||
case MSG_EXTENDED_STATUS1:
|
||||
CHECK_PAYLOAD_SIZE(SYS_STATUS);
|
||||
send_extended_status1(chan);
|
||||
CHECK_PAYLOAD_SIZE(POWER_STATUS);
|
||||
gcs[chan-MAVLINK_COMM_0].send_power_status();
|
||||
break;
|
||||
|
||||
case MSG_EXTENDED_STATUS2:
|
||||
|
@ -445,6 +445,9 @@ static void Log_Write_Current()
|
||||
current_total : battery.current_total_mah()
|
||||
};
|
||||
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
||||
|
||||
// also write power status
|
||||
DataFlash.Log_Write_Power();
|
||||
}
|
||||
|
||||
static void Log_Arm_Disarm() {
|
||||
|
Loading…
Reference in New Issue
Block a user