Plane: move try_send_message of heartbeats up to GCS_MAVLINK

This commit is contained in:
Peter Barker 2018-05-02 18:37:51 +10:00 committed by WickedShell
parent 75ad33ddcd
commit 8df625e81a

View File

@ -414,11 +414,6 @@ bool GCS_MAVLINK_Plane::try_send_message(enum ap_message id)
}
switch (id) {
case MSG_HEARTBEAT:
CHECK_PAYLOAD_SIZE(HEARTBEAT);
last_heartbeat_time = AP_HAL::millis();
send_heartbeat();
return true;
case MSG_EXTENDED_STATUS1:
CHECK_PAYLOAD_SIZE(SYS_STATUS);