mirror of https://github.com/ArduPilot/ardupilot
Sub: Remove wrapper around MAVLink send heartbeat
This commit is contained in:
parent
df37a3d603
commit
ba65b163f7
|
@ -2,11 +2,6 @@
|
|||
|
||||
#include "GCS_Mavlink.h"
|
||||
|
||||
void Sub::gcs_send_heartbeat()
|
||||
{
|
||||
gcs().send_message(MSG_HEARTBEAT);
|
||||
}
|
||||
|
||||
/*
|
||||
* !!NOTE!!
|
||||
*
|
||||
|
@ -815,7 +810,7 @@ void Sub::mavlink_delay_cb()
|
|||
uint32_t tnow = AP_HAL::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) {
|
||||
|
|
|
@ -476,7 +476,6 @@ private:
|
|||
float get_surface_tracking_climb_rate(int16_t target_rate, float current_alt_target, float dt);
|
||||
void update_poscon_alt_max();
|
||||
void rotate_body_frame_to_NE(float &x, float &y);
|
||||
void gcs_send_heartbeat(void);
|
||||
void send_heartbeat(mavlink_channel_t chan);
|
||||
#if RPM_ENABLED == ENABLED
|
||||
void rpm_update();
|
||||
|
|
Loading…
Reference in New Issue