mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: move sending of heartbeats up to GCS_MAVLINK
This commit is contained in:
parent
5bad067a8d
commit
eecdcacf3e
|
@ -150,7 +150,7 @@ public:
|
|||
uint16_t mission_item_reached_index = AP_MISSION_CMD_INDEX_NONE;
|
||||
|
||||
// common send functions
|
||||
void send_heartbeat(void);
|
||||
void send_heartbeat(void) const;
|
||||
void send_meminfo(void);
|
||||
void send_power_status(void);
|
||||
void send_battery_status(const AP_BattMonitor &battery, const uint8_t instance) const;
|
||||
|
|
|
@ -1544,7 +1544,7 @@ void GCS_MAVLINK::send_ekf_origin(const Location &ekf_origin) const
|
|||
/*
|
||||
Send MAVLink heartbeat
|
||||
*/
|
||||
void GCS_MAVLINK::send_heartbeat()
|
||||
void GCS_MAVLINK::send_heartbeat() const
|
||||
{
|
||||
mavlink_msg_heartbeat_send(
|
||||
chan,
|
||||
|
@ -2621,6 +2621,12 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
|
|||
ret = true;
|
||||
break;
|
||||
|
||||
case MSG_HEARTBEAT:
|
||||
CHECK_PAYLOAD_SIZE(HEARTBEAT);
|
||||
last_heartbeat_time = AP_HAL::millis();
|
||||
send_heartbeat();
|
||||
break;
|
||||
|
||||
case MSG_HWSTATUS:
|
||||
CHECK_PAYLOAD_SIZE(HWSTATUS);
|
||||
send_hwstatus();
|
||||
|
|
Loading…
Reference in New Issue