Copter: Remove wrapper around MAVLink send heartbeat

This commit is contained in:
Michael du Breuil 2019-06-18 01:20:22 -07:00 committed by Francisco Ferreira
parent 97b339f6af
commit df37a3d603
2 changed files with 1 additions and 10 deletions

View File

@ -718,9 +718,6 @@ private:
// fence.cpp
void fence_check();
// GCS_Mavlink.cpp
void gcs_send_heartbeat(void);
// heli.cpp
void heli_init();
void check_dynamic_flight(void);

View File

@ -2,12 +2,6 @@
#include "GCS_Mavlink.h"
void Copter::gcs_send_heartbeat(void)
{
gcs().send_message(MSG_HEARTBEAT);
}
/*
* !!NOTE!!
*
@ -1261,7 +1255,7 @@ void Copter::mavlink_delay_cb()
uint32_t tnow = millis();
if (tnow - last_1hz > 1000) {
last_1hz = tnow;
gcs_send_heartbeat();
gcs().send_message(MSG_HEARTBEAT);
gcs().send_message(MSG_SYS_STATUS);
}
if (tnow - last_50hz > 20) {