diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index bb4e83e0d5662f..9c4317f54e9572 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -999,6 +999,7 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c { MAVLINK_MSG_ID_CAMERA_FEEDBACK, MSG_CAMERA_FEEDBACK}, { MAVLINK_MSG_ID_CAMERA_INFORMATION, MSG_CAMERA_INFORMATION}, { MAVLINK_MSG_ID_CAMERA_SETTINGS, MSG_CAMERA_SETTINGS}, + { MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS, MSG_CAMERA_CAPTURE_STATUS}, #endif #if HAL_MOUNT_ENABLED { MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS, MSG_GIMBAL_DEVICE_ATTITUDE_STATUS}, @@ -5759,6 +5760,16 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) camera->send_camera_settings(chan); } break; + case MSG_CAMERA_CAPTURE_STATUS: + { + AP_Camera *camera = AP::camera(); + if (camera == nullptr) { + break; + } + CHECK_PAYLOAD_SIZE(CAMERA_CAPTURE_STATUS); + camera->send_camera_capture_status(chan); + } + break; #endif case MSG_SYSTEM_TIME: diff --git a/libraries/GCS_MAVLink/ap_message.h b/libraries/GCS_MAVLink/ap_message.h index 6b4fbb0e295878..95eb2d6bc07be0 100644 --- a/libraries/GCS_MAVLink/ap_message.h +++ b/libraries/GCS_MAVLink/ap_message.h @@ -51,6 +51,7 @@ enum ap_message : uint8_t { MSG_CAMERA_FEEDBACK, MSG_CAMERA_INFORMATION, MSG_CAMERA_SETTINGS, + MSG_CAMERA_CAPTURE_STATUS, MSG_GIMBAL_DEVICE_ATTITUDE_STATUS, MSG_GIMBAL_MANAGER_INFORMATION, MSG_GIMBAL_MANAGER_STATUS,