Browse Source

Rover: log power status on Pixhawk

master
Andrew Tridgell 11 years ago
parent
commit
9d6005edd8
  1. 2
      APMrover2/GCS_Mavlink.pde
  2. 3
      APMrover2/Log.pde

2
APMrover2/GCS_Mavlink.pde

@ -517,6 +517,8 @@ static bool mavlink_try_send_message(mavlink_channel_t chan, enum ap_message id, @@ -517,6 +517,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, packet_drops);
CHECK_PAYLOAD_SIZE(POWER_STATUS);
gcs[chan-MAVLINK_COMM_0].send_power_status();
break;
case MSG_EXTENDED_STATUS2:

3
APMrover2/Log.pde

@ -454,6 +454,9 @@ static void Log_Write_Current() @@ -454,6 +454,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();
}
struct PACKED log_Compass {

Loading…
Cancel
Save