mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Tracker: move try_send_message of heartbeats up to GCS_MAVLINK
This commit is contained in:
parent
1bc208584f
commit
40a7495967
@ -175,11 +175,6 @@ void GCS_MAVLINK_Tracker::handle_change_alt_request(AP_Mission::Mission_Command&
|
|||||||
bool GCS_MAVLINK_Tracker::try_send_message(enum ap_message id)
|
bool GCS_MAVLINK_Tracker::try_send_message(enum ap_message id)
|
||||||
{
|
{
|
||||||
switch (id) {
|
switch (id) {
|
||||||
case MSG_HEARTBEAT:
|
|
||||||
CHECK_PAYLOAD_SIZE(HEARTBEAT);
|
|
||||||
last_heartbeat_time = AP_HAL::millis();
|
|
||||||
send_heartbeat();
|
|
||||||
return true;
|
|
||||||
|
|
||||||
case MSG_ATTITUDE:
|
case MSG_ATTITUDE:
|
||||||
CHECK_PAYLOAD_SIZE(ATTITUDE);
|
CHECK_PAYLOAD_SIZE(ATTITUDE);
|
||||||
|
Loading…
Reference in New Issue
Block a user