diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index afc9d7e43d..0e1f3daa33 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -72,7 +72,7 @@ uint32_t GCS_Copter::custom_mode() const return (uint32_t)copter.control_mode; } -MAV_STATE GCS_MAVLINK_Copter::system_status() const +MAV_STATE GCS_MAVLINK_Copter::vehicle_system_status() const { // set system as critical if any failsafe have triggered if (copter.any_failsafe_triggered()) { diff --git a/ArduCopter/GCS_Mavlink.h b/ArduCopter/GCS_Mavlink.h index 81fb8e1623..0aff8d1434 100644 --- a/ArduCopter/GCS_Mavlink.h +++ b/ArduCopter/GCS_Mavlink.h @@ -57,7 +57,7 @@ private: 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; float vfr_hud_alt() const override;