From c9c4b31e998678c56a16699a53819e48257190f3 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 12 Jul 2017 17:41:28 +1000 Subject: [PATCH] Plane: move handling of incoming statutext messages up --- ArduPlane/GCS_Mavlink.cpp | 19 +++++-------------- ArduPlane/GCS_Mavlink.h | 2 ++ 2 files changed, 7 insertions(+), 14 deletions(-) diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 2bbfc42e06..7a9313c2c2 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -419,6 +419,11 @@ void Plane::send_current_waypoint(mavlink_channel_t chan) mavlink_msg_mission_current_send(chan, mission.get_current_nav_index()); } +uint8_t GCS_MAVLINK_Plane::sysid_my_gcs() const +{ + return plane.g.sysid_my_gcs; +} + uint32_t GCS_MAVLINK_Plane::telem_delay() const { return (uint32_t)(plane.g.telem_delay); @@ -970,20 +975,6 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg) break; } - case MAVLINK_MSG_ID_STATUSTEXT: - { - // ignore any statustext messages not from our GCS: - if (msg->sysid != plane.g.sysid_my_gcs) { - break; - } - mavlink_statustext_t packet; - mavlink_msg_statustext_decode(msg, &packet); - char text[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1+4] = { 'G','C','S',':'}; - memcpy(&text[4], packet.text, MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN); - plane.DataFlash.Log_Write_Message(text); - break; - } - case MAVLINK_MSG_ID_COMMAND_INT: { // decode diff --git a/ArduPlane/GCS_Mavlink.h b/ArduPlane/GCS_Mavlink.h index e2e41272fd..3e7c39b9d8 100644 --- a/ArduPlane/GCS_Mavlink.h +++ b/ArduPlane/GCS_Mavlink.h @@ -21,6 +21,8 @@ protected: AP_Mission *get_mission() override; void handle_mission_set_current(AP_Mission &mission, mavlink_message_t *msg) override; + uint8_t sysid_my_gcs() const override; + private: void handleMessage(mavlink_message_t * msg) override;