From 2039222c7edf2d32a80317efbbd5cb170079dd17 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 9 Jul 2017 10:28:33 +1000 Subject: [PATCH] Tracker: use send_text method on the GCS singleton --- AntennaTracker/GCS_Mavlink.cpp | 22 +--------------------- AntennaTracker/Tracker.h | 2 -- AntennaTracker/sensors.cpp | 4 ++-- AntennaTracker/system.cpp | 4 ++-- 4 files changed, 5 insertions(+), 27 deletions(-) diff --git a/AntennaTracker/GCS_Mavlink.cpp b/AntennaTracker/GCS_Mavlink.cpp index a5afc38300..f57e8c5b76 100644 --- a/AntennaTracker/GCS_Mavlink.cpp +++ b/AntennaTracker/GCS_Mavlink.cpp @@ -868,7 +868,7 @@ void Tracker::mavlink_delay_cb() } if (tnow - last_5s > 5000) { last_5s = tnow; - gcs_send_text(MAV_SEVERITY_INFO, "Initialising APM"); + gcs().send_text(MAV_SEVERITY_INFO, "Initialising APM"); } DataFlash.EnableWrites(true); tracker.in_mavlink_delay = false; @@ -898,26 +898,6 @@ void Tracker::gcs_update(void) gcs().update(); } -void Tracker::gcs_send_text(MAV_SEVERITY severity, const char *str) -{ - gcs().send_statustext(severity, 0xFF, str); -} - -/* - * send a low priority formatted message to the GCS - * only one fits in the queue, so if you send more than one before the - * last one gets into the serial buffer then the old one will be lost - */ -void Tracker::gcs_send_text_fmt(MAV_SEVERITY severity, const char *fmt, ...) -{ - char str[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN] {}; - va_list arg_list; - va_start(arg_list, fmt); - hal.util->vsnprintf((char *)str, sizeof(str), fmt, arg_list); - va_end(arg_list); - gcs().send_statustext(severity, 0xFF, str); -} - /** retry any deferred messages */ diff --git a/AntennaTracker/Tracker.h b/AntennaTracker/Tracker.h index e8e8c5d339..bef4193c66 100644 --- a/AntennaTracker/Tracker.h +++ b/AntennaTracker/Tracker.h @@ -207,7 +207,6 @@ private: void gcs_send_message(enum ap_message id); void gcs_data_stream_send(void); void gcs_update(void); - void gcs_send_text(MAV_SEVERITY severity, const char *str); void gcs_retry_deferred(void); void load_parameters(void); void update_auto(void); @@ -255,7 +254,6 @@ private: void tracking_update_pressure(const mavlink_scaled_pressure_t &msg); void tracking_manual_control(const mavlink_manual_control_t &msg); void update_armed_disarmed(); - void gcs_send_text_fmt(MAV_SEVERITY severity, const char *fmt, ...); void init_capabilities(void); void compass_cal_update(); void Log_Write_Attitude(); diff --git a/AntennaTracker/sensors.cpp b/AntennaTracker/sensors.cpp index 63a0f065fa..9a4854ccdc 100644 --- a/AntennaTracker/sensors.cpp +++ b/AntennaTracker/sensors.cpp @@ -2,13 +2,13 @@ void Tracker::init_barometer(bool full_calibration) { - gcs_send_text(MAV_SEVERITY_INFO, "Calibrating barometer"); + gcs().send_text(MAV_SEVERITY_INFO, "Calibrating barometer"); if (full_calibration) { barometer.calibrate(); } else { barometer.update_calibration(); } - gcs_send_text(MAV_SEVERITY_INFO, "Barometer calibration complete"); + gcs().send_text(MAV_SEVERITY_INFO, "Barometer calibration complete"); } // read the barometer and return the updated altitude in meters diff --git a/AntennaTracker/system.cpp b/AntennaTracker/system.cpp index eb839eb6e0..b6ac384772 100644 --- a/AntennaTracker/system.cpp +++ b/AntennaTracker/system.cpp @@ -98,7 +98,7 @@ void Tracker::init_tracker() current_loc.lat = g.start_latitude * 1.0e7f; current_loc.lng = g.start_longitude * 1.0e7f; } else { - gcs_send_text(MAV_SEVERITY_NOTICE, "Ignoring invalid START_LATITUDE or START_LONGITUDE parameter"); + gcs().send_text(MAV_SEVERITY_NOTICE, "Ignoring invalid START_LATITUDE or START_LONGITUDE parameter"); } // see if EEPROM has a default location as well @@ -108,7 +108,7 @@ void Tracker::init_tracker() init_capabilities(); - gcs_send_text(MAV_SEVERITY_INFO,"Ready to track"); + gcs().send_text(MAV_SEVERITY_INFO,"Ready to track"); hal.scheduler->delay(1000); // Why???? set_mode(AUTO); // tracking