From c74aff56c16726023bdfb95bba1d52c6bdfcb49d Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 17 Nov 2014 15:52:01 -0800 Subject: [PATCH] Plane: move MOUNT_STATUS lower in GCS_MAVLink --- ArduPlane/GCS_Mavlink.pde | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index e073828f50..da1ed7c53b 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -636,13 +636,6 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id) gcs[chan-MAVLINK_COMM_0].send_ahrs2(ahrs); break; - case MSG_MOUNT_STATUS: -#if MOUNT == ENABLED - CHECK_PAYLOAD_SIZE(MOUNT_STATUS); - camera_mount.status_msg(chan); -#endif // MOUNT == ENABLED - break; - case MSG_HWSTATUS: CHECK_PAYLOAD_SIZE(HWSTATUS); send_hwstatus(chan); @@ -677,6 +670,13 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id) send_wind(chan); break; + case MSG_MOUNT_STATUS: +#if MOUNT == ENABLED + CHECK_PAYLOAD_SIZE(MOUNT_STATUS); + camera_mount.status_msg(chan); +#endif // MOUNT == ENABLED + break; + case MSG_RETRY_DEFERRED: break; // just here to prevent a warning @@ -905,11 +905,11 @@ GCS_MAVLINK::data_stream_send(void) send_message(MSG_WIND); send_message(MSG_RANGEFINDER); send_message(MSG_SYSTEM_TIME); - send_message(MSG_MOUNT_STATUS); #if AP_TERRAIN_AVAILABLE send_message(MSG_TERRAIN); #endif send_message(MSG_BATTERY2); + send_message(MSG_MOUNT_STATUS); } }