diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index adc325f6dc..a8fc9bfded 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -98,6 +98,7 @@ enum ap_message : uint8_t { MSG_ORIGIN, MSG_HOME, MSG_NAMED_FLOAT, + MSG_EXTENDED_SYS_STATE, MSG_LAST // MSG_LAST must be the last entry in this enum }; @@ -216,6 +217,7 @@ public: #endif virtual void send_attitude() const; void send_autopilot_version() const; + void send_extended_sys_state() const; void send_local_position() const; void send_vfr_hud(); void send_vibration() const; @@ -305,6 +307,9 @@ protected: virtual uint32_t custom_mode() const = 0; virtual MAV_STATE system_status() const = 0; + virtual MAV_VTOL_STATE vtol_state() const { return MAV_VTOL_STATE_UNDEFINED; } + virtual MAV_LANDED_STATE landed_state() const { return MAV_LANDED_STATE_UNDEFINED; } + bool waypoint_receiving; // currently receiving // the following two variables are only here because of Tracker uint16_t waypoint_request_i; // request index diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index eb32038c8f..14c40f2159 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -946,6 +946,7 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c { MAVLINK_MSG_ID_BATTERY_STATUS, MSG_BATTERY_STATUS}, { MAVLINK_MSG_ID_AOA_SSA, MSG_AOA_SSA}, { MAVLINK_MSG_ID_DEEPSTALL, MSG_LANDING}, + { MAVLINK_MSG_ID_EXTENDED_SYS_STATE, MSG_EXTENDED_SYS_STATE}, }; for (uint8_t i=0; i