From e88f43722fc9ba3421462a5173de8661e3facc2d Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 26 Nov 2019 13:46:07 +1100 Subject: [PATCH] Rover: rename system_status as it won't be called from base class --- APMrover2/GCS_Mavlink.cpp | 2 +- APMrover2/GCS_Mavlink.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp index 2e66290c0c..a38505cbba 100644 --- a/APMrover2/GCS_Mavlink.cpp +++ b/APMrover2/GCS_Mavlink.cpp @@ -58,7 +58,7 @@ uint32_t GCS_Rover::custom_mode() const return rover.control_mode->mode_number(); } -MAV_STATE GCS_MAVLINK_Rover::system_status() const +MAV_STATE GCS_MAVLINK_Rover::vehicle_system_status() const { if ((rover.failsafe.triggered != 0) || rover.failsafe.ekf) { return MAV_STATE_CRITICAL; diff --git a/APMrover2/GCS_Mavlink.h b/APMrover2/GCS_Mavlink.h index bfe4f16445..72ca98af77 100644 --- a/APMrover2/GCS_Mavlink.h +++ b/APMrover2/GCS_Mavlink.h @@ -43,7 +43,7 @@ private: void packetReceived(const mavlink_status_t &status, const mavlink_message_t &msg) override; MAV_MODE base_mode() const override; - MAV_STATE system_status() const override; + MAV_STATE vehicle_system_status() const override; int16_t vfr_hud_throttle() const override;