Rover: move try_send_message of heartbeats up to GCS_MAVLINK

This commit is contained in:
Peter Barker 2018-05-02 18:37:32 +10:00 committed by WickedShell
parent eecdcacf3e
commit 1bc208584f
1 changed files with 0 additions and 5 deletions

View File

@ -299,11 +299,6 @@ bool GCS_MAVLINK_Rover::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:
// send extended status only once vehicle has been initialised