GCS_MAVLink: tidy sending of queued mount messages

This commit is contained in:
Peter Barker 2023-10-27 18:10:36 +11:00 committed by Andrew Tridgell
parent 229916a48c
commit c017c8acf4

View File

@ -5837,30 +5837,25 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
send_local_position();
break;
case MSG_GIMBAL_DEVICE_ATTITUDE_STATUS:
#if HAL_MOUNT_ENABLED
case MSG_GIMBAL_DEVICE_ATTITUDE_STATUS:
CHECK_PAYLOAD_SIZE(GIMBAL_DEVICE_ATTITUDE_STATUS);
send_gimbal_device_attitude_status();
#endif
break;
case MSG_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE:
#if HAL_MOUNT_ENABLED
CHECK_PAYLOAD_SIZE(AUTOPILOT_STATE_FOR_GIMBAL_DEVICE);
send_autopilot_state_for_gimbal_device();
#endif
break;
case MSG_GIMBAL_MANAGER_INFORMATION:
#if HAL_MOUNT_ENABLED
CHECK_PAYLOAD_SIZE(GIMBAL_MANAGER_INFORMATION);
send_gimbal_manager_information();
#endif
break;
case MSG_GIMBAL_MANAGER_STATUS:
#if HAL_MOUNT_ENABLED
CHECK_PAYLOAD_SIZE(GIMBAL_MANAGER_STATUS);
send_gimbal_manager_status();
#endif
break;
#endif // HAL_MOUNT_ENABLED
case MSG_OPTICAL_FLOW:
#if AP_OPTICALFLOW_ENABLED
CHECK_PAYLOAD_SIZE(OPTICAL_FLOW);