diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 9809935c1b..4c47c28412 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -93,7 +93,7 @@ uint32_t GCS_Plane::custom_mode() const return plane.control_mode->mode_number(); } -MAV_STATE GCS_MAVLINK_Plane::system_status() const +MAV_STATE GCS_MAVLINK_Plane::vehicle_system_status() const { if (plane.control_mode == &plane.mode_initializing) { return MAV_STATE_CALIBRATING; diff --git a/ArduPlane/GCS_Mavlink.h b/ArduPlane/GCS_Mavlink.h index a240016e1d..dd7676c594 100644 --- a/ArduPlane/GCS_Mavlink.h +++ b/ArduPlane/GCS_Mavlink.h @@ -55,7 +55,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; uint8_t radio_in_rssi() const;