Sub: move try_send_message of heartbeats up to GCS_MAVLINK

This commit is contained in:
Peter Barker 2018-05-02 18:38:00 +10:00 committed by WickedShell
parent 8df625e81a
commit f075d6bd93
1 changed files with 0 additions and 7 deletions

View File

@ -506,13 +506,6 @@ bool GCS_MAVLINK_Sub::try_send_message(enum ap_message id)
sub.send_info(chan);
break;
case MSG_HEARTBEAT:
CHECK_PAYLOAD_SIZE(HEARTBEAT);
last_heartbeat_time = AP_HAL::millis();
send_heartbeat();
sub.send_info(chan);
break;
case MSG_EXTENDED_STATUS1:
// send extended status only once vehicle has been initialised
// to avoid unnecessary errors being reported to user