mirror of https://github.com/ArduPilot/ardupilot
Copter: Remove wrapper around MAVLink send heartbeat
This commit is contained in:
parent
97b339f6af
commit
df37a3d603
|
@ -718,9 +718,6 @@ private:
|
||||||
// fence.cpp
|
// fence.cpp
|
||||||
void fence_check();
|
void fence_check();
|
||||||
|
|
||||||
// GCS_Mavlink.cpp
|
|
||||||
void gcs_send_heartbeat(void);
|
|
||||||
|
|
||||||
// heli.cpp
|
// heli.cpp
|
||||||
void heli_init();
|
void heli_init();
|
||||||
void check_dynamic_flight(void);
|
void check_dynamic_flight(void);
|
||||||
|
|
|
@ -2,12 +2,6 @@
|
||||||
|
|
||||||
#include "GCS_Mavlink.h"
|
#include "GCS_Mavlink.h"
|
||||||
|
|
||||||
void Copter::gcs_send_heartbeat(void)
|
|
||||||
{
|
|
||||||
gcs().send_message(MSG_HEARTBEAT);
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* !!NOTE!!
|
* !!NOTE!!
|
||||||
*
|
*
|
||||||
|
@ -1261,7 +1255,7 @@ void Copter::mavlink_delay_cb()
|
||||||
uint32_t tnow = millis();
|
uint32_t tnow = millis();
|
||||||
if (tnow - last_1hz > 1000) {
|
if (tnow - last_1hz > 1000) {
|
||||||
last_1hz = tnow;
|
last_1hz = tnow;
|
||||||
gcs_send_heartbeat();
|
gcs().send_message(MSG_HEARTBEAT);
|
||||||
gcs().send_message(MSG_SYS_STATUS);
|
gcs().send_message(MSG_SYS_STATUS);
|
||||||
}
|
}
|
||||||
if (tnow - last_50hz > 20) {
|
if (tnow - last_50hz > 20) {
|
||||||
|
|
Loading…
Reference in New Issue