GCS_MAVLink: move switch for sending camera messages into AP_Camera

neatens GCS_Common a bit, reduces repetitive code
This commit is contained in:
Peter Barker 2024-05-29 17:32:06 +10:00 committed by Peter Barker
parent 5538f6735f
commit 78fcf7057c

View File

@ -6014,46 +6014,10 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
#if AP_CAMERA_ENABLED #if AP_CAMERA_ENABLED
case MSG_CAMERA_FEEDBACK: case MSG_CAMERA_FEEDBACK:
{
AP_Camera *camera = AP::camera();
if (camera == nullptr) {
break;
}
CHECK_PAYLOAD_SIZE(CAMERA_FEEDBACK);
camera->send_feedback(chan);
}
break;
case MSG_CAMERA_INFORMATION: 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: case MSG_CAMERA_SETTINGS:
{
AP_Camera *camera = AP::camera();
if (camera == nullptr) {
break;
}
CHECK_PAYLOAD_SIZE(CAMERA_SETTINGS);
camera->send_camera_settings(chan);
}
break;
#if AP_CAMERA_SEND_FOV_STATUS_ENABLED #if AP_CAMERA_SEND_FOV_STATUS_ENABLED
case MSG_CAMERA_FOV_STATUS: case MSG_CAMERA_FOV_STATUS:
{
AP_Camera *camera = AP::camera();
if (camera == nullptr) {
break;
}
CHECK_PAYLOAD_SIZE(CAMERA_FOV_STATUS);
camera->send_camera_fov_status(chan);
}
break;
#endif #endif
case MSG_CAMERA_CAPTURE_STATUS: case MSG_CAMERA_CAPTURE_STATUS:
{ {
@ -6061,11 +6025,9 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
if (camera == nullptr) { if (camera == nullptr) {
break; break;
} }
CHECK_PAYLOAD_SIZE(CAMERA_CAPTURE_STATUS); return camera->send_mavlink_message(*this, id);
camera->send_camera_capture_status(chan);
} }
break; #endif // AP_CAMERA_ENABLED
#endif
case MSG_SYSTEM_TIME: case MSG_SYSTEM_TIME:
CHECK_PAYLOAD_SIZE(SYSTEM_TIME); CHECK_PAYLOAD_SIZE(SYSTEM_TIME);