diff --git a/ArduSub/GCS_Mavlink.cpp b/ArduSub/GCS_Mavlink.cpp index f828b13732..01d27d0b62 100644 --- a/ArduSub/GCS_Mavlink.cpp +++ b/ArduSub/GCS_Mavlink.cpp @@ -62,7 +62,7 @@ uint32_t GCS_Sub::custom_mode() const return sub.control_mode; } -MAV_STATE GCS_MAVLINK_Sub::system_status() const +MAV_STATE GCS_MAVLINK_Sub::vehicle_system_status() const { // set system as critical if any failsafe have triggered if (sub.any_failsafe_triggered()) { diff --git a/ArduSub/GCS_Mavlink.h b/ArduSub/GCS_Mavlink.h index 3921ee59f7..298939bfa1 100644 --- a/ArduSub/GCS_Mavlink.h +++ b/ArduSub/GCS_Mavlink.h @@ -50,7 +50,7 @@ private: bool send_info(void); 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;