|
|
|
@ -1150,6 +1150,20 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
@@ -1150,6 +1150,20 @@ 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
|
|
|
|
|