Browse Source

Plane: move handling of incoming statutext messages up

mission-4.1.18
Peter Barker 8 years ago committed by Francisco Ferreira
parent
commit
c9c4b31e99
  1. 19
      ArduPlane/GCS_Mavlink.cpp
  2. 2
      ArduPlane/GCS_Mavlink.h

19
ArduPlane/GCS_Mavlink.cpp

@ -419,6 +419,11 @@ void Plane::send_current_waypoint(mavlink_channel_t chan) @@ -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) @@ -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

2
ArduPlane/GCS_Mavlink.h

@ -21,6 +21,8 @@ protected: @@ -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;

Loading…
Cancel
Save