Copter: move sending of battery data up

This commit is contained in:
Peter Barker 2018-05-02 18:11:02 +10:00 committed by WickedShell
parent b38d23d542
commit ec6fb0c612

View File

@ -408,11 +408,6 @@ bool GCS_MAVLINK_Copter::try_send_message(enum ap_message id)
#endif // MOUNT == ENABLED
break;
case MSG_BATTERY2:
CHECK_PAYLOAD_SIZE(BATTERY2);
send_battery2(copter.battery);
break;
case MSG_OPTICAL_FLOW:
#if OPTFLOW == ENABLED
CHECK_PAYLOAD_SIZE(OPTICAL_FLOW);
@ -452,9 +447,7 @@ bool GCS_MAVLINK_Copter::try_send_message(enum ap_message id)
copter.adsb.send_adsb_vehicle(chan);
#endif
break;
case MSG_BATTERY_STATUS:
send_battery_status(copter.battery);
break;
default:
return GCS_MAVLINK::try_send_message(id);
}