mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Plane: move MOUNT_STATUS lower in GCS_MAVLink
This commit is contained in:
parent
c6e70179d2
commit
c74aff56c1
@ -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);
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user