Browse Source

GCS_MAVLink: support send_extended_sys_state

master
Peter Barker 7 years ago committed by Randy Mackay
parent
commit
34e09a55be
  1. 5
      libraries/GCS_MAVLink/GCS.h
  2. 11
      libraries/GCS_MAVLink/GCS_Common.cpp

5
libraries/GCS_MAVLink/GCS.h

@ -98,6 +98,7 @@ enum ap_message : uint8_t { @@ -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: @@ -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: @@ -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

11
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 @@ -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<ARRAY_SIZE(map); i++) {
@ -3855,6 +3856,11 @@ void GCS_MAVLINK::send_sys_status() @@ -3855,6 +3856,11 @@ void GCS_MAVLINK::send_sys_status()
0, 0, 0, 0);
}
void GCS_MAVLINK::send_extended_sys_state() const
{
mavlink_msg_extended_sys_state_send(chan, vtol_state(), landed_state());
}
void GCS_MAVLINK::send_attitude() const
{
const AP_AHRS &ahrs = AP::ahrs();
@ -4154,6 +4160,11 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) @@ -4154,6 +4160,11 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
send_ahrs();
break;
case MSG_EXTENDED_SYS_STATE:
CHECK_PAYLOAD_SIZE(EXTENDED_SYS_STATE);
send_extended_sys_state();
break;
case MSG_VFR_HUD:
CHECK_PAYLOAD_SIZE(VFR_HUD);
send_vfr_hud();

Loading…
Cancel
Save