GCS_MAVLink: Fix CAMERA_SETTINGS payload size check

This commit is contained in:
Nick Exton 2023-09-06 16:50:24 +10:00 committed by Randy Mackay
parent 914c3c702d
commit d47b60b92a
1 changed files with 1 additions and 1 deletions

View File

@ -5755,7 +5755,7 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
if (camera == nullptr) {
break;
}
CHECK_PAYLOAD_SIZE(CAMERA_INFORMATION);
CHECK_PAYLOAD_SIZE(CAMERA_SETTINGS);
camera->send_camera_settings(chan);
}
break;