From 7865d467d3ab0dac8dd784ecf0c900a9dabc5993 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 8 Jul 2017 12:02:52 +1000 Subject: [PATCH] Tracker: eliminate gcs_send_message wraper --- AntennaTracker/AntennaTracker.cpp | 2 +- AntennaTracker/GCS_Mavlink.cpp | 14 +++----------- AntennaTracker/Tracker.h | 1 - 3 files changed, 4 insertions(+), 13 deletions(-) diff --git a/AntennaTracker/AntennaTracker.cpp b/AntennaTracker/AntennaTracker.cpp index f3336f4b13..a5c5de2502 100644 --- a/AntennaTracker/AntennaTracker.cpp +++ b/AntennaTracker/AntennaTracker.cpp @@ -85,7 +85,7 @@ void Tracker::dataflash_periodic(void) void Tracker::one_second_loop() { // send a heartbeat - gcs_send_message(MSG_HEARTBEAT); + gcs().send_message(MSG_HEARTBEAT); // make it possible to change orientation at runtime ahrs.set_orientation(); diff --git a/AntennaTracker/GCS_Mavlink.cpp b/AntennaTracker/GCS_Mavlink.cpp index f57e8c5b76..d00bb4628e 100644 --- a/AntennaTracker/GCS_Mavlink.cpp +++ b/AntennaTracker/GCS_Mavlink.cpp @@ -857,8 +857,8 @@ void Tracker::mavlink_delay_cb() uint32_t tnow = AP_HAL::millis(); if (tnow - last_1hz > 1000) { last_1hz = tnow; - gcs_send_message(MSG_HEARTBEAT); - gcs_send_message(MSG_EXTENDED_STATUS1); + gcs().send_message(MSG_HEARTBEAT); + gcs().send_message(MSG_EXTENDED_STATUS1); } if (tnow - last_50hz > 20) { last_50hz = tnow; @@ -874,14 +874,6 @@ void Tracker::mavlink_delay_cb() tracker.in_mavlink_delay = false; } -/* - * send a message on both GCS links - */ -void Tracker::gcs_send_message(enum ap_message id) -{ - gcs().send_message(id); -} - /* * send data streams in the given rate range on both links */ @@ -903,6 +895,6 @@ void Tracker::gcs_update(void) */ void Tracker::gcs_retry_deferred(void) { - gcs_send_message(MSG_RETRY_DEFERRED); + gcs().send_message(MSG_RETRY_DEFERRED); gcs().service_statustext(); } diff --git a/AntennaTracker/Tracker.h b/AntennaTracker/Tracker.h index bef4193c66..f06406c1b9 100644 --- a/AntennaTracker/Tracker.h +++ b/AntennaTracker/Tracker.h @@ -204,7 +204,6 @@ private: void send_nav_controller_output(mavlink_channel_t chan); void send_simstate(mavlink_channel_t chan); void mavlink_check_target(const mavlink_message_t* msg); - void gcs_send_message(enum ap_message id); void gcs_data_stream_send(void); void gcs_update(void); void gcs_retry_deferred(void);