GCS_MAVLink: support camera info and settings

This commit is contained in:
Randy Mackay 2023-06-10 11:16:53 +09:00
parent 63b4b8b7d3
commit 02fdb8272f
2 changed files with 24 additions and 0 deletions

View File

@ -986,6 +986,8 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c
{ MAVLINK_MSG_ID_BATTERY2, MSG_BATTERY2}, { MAVLINK_MSG_ID_BATTERY2, MSG_BATTERY2},
#endif #endif
{ MAVLINK_MSG_ID_CAMERA_FEEDBACK, MSG_CAMERA_FEEDBACK}, { MAVLINK_MSG_ID_CAMERA_FEEDBACK, MSG_CAMERA_FEEDBACK},
{ MAVLINK_MSG_ID_CAMERA_INFORMATION, MSG_CAMERA_INFORMATION},
{ MAVLINK_MSG_ID_CAMERA_SETTINGS, MSG_CAMERA_SETTINGS},
#if HAL_MOUNT_ENABLED #if HAL_MOUNT_ENABLED
{ MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS, MSG_GIMBAL_DEVICE_ATTITUDE_STATUS}, { MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS, MSG_GIMBAL_DEVICE_ATTITUDE_STATUS},
{ MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE, MSG_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE}, { MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE, MSG_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE},
@ -5689,6 +5691,26 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
camera->send_feedback(chan); camera->send_feedback(chan);
} }
break; break;
case MSG_CAMERA_INFORMATION:
{
AP_Camera *camera = AP::camera();
if (camera == nullptr) {
break;
}
CHECK_PAYLOAD_SIZE(CAMERA_INFORMATION);
camera->send_camera_information(chan);
}
break;
case MSG_CAMERA_SETTINGS:
{
AP_Camera *camera = AP::camera();
if (camera == nullptr) {
break;
}
CHECK_PAYLOAD_SIZE(CAMERA_INFORMATION);
camera->send_camera_settings(chan);
}
break;
#endif #endif
case MSG_SYSTEM_TIME: case MSG_SYSTEM_TIME:

View File

@ -49,6 +49,8 @@ enum ap_message : uint8_t {
MSG_TERRAIN, MSG_TERRAIN,
MSG_BATTERY2, MSG_BATTERY2,
MSG_CAMERA_FEEDBACK, MSG_CAMERA_FEEDBACK,
MSG_CAMERA_INFORMATION,
MSG_CAMERA_SETTINGS,
MSG_GIMBAL_DEVICE_ATTITUDE_STATUS, MSG_GIMBAL_DEVICE_ATTITUDE_STATUS,
MSG_GIMBAL_MANAGER_INFORMATION, MSG_GIMBAL_MANAGER_INFORMATION,
MSG_GIMBAL_MANAGER_STATUS, MSG_GIMBAL_MANAGER_STATUS,