Skip to content

Commit

Permalink
GCS_MAVLink: move switch for sending camera messages into AP_Camera
Browse files Browse the repository at this point in the history
neatens GCS_Common a bit, reduces repetitive code
  • Loading branch information
peterbarker committed Jun 5, 2024
1 parent 5538f67 commit 78fcf70
Showing 1 changed file with 2 additions and 40 deletions.
42 changes: 2 additions & 40 deletions libraries/GCS_MAVLink/GCS_Common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6014,58 +6014,20 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)

#if AP_CAMERA_ENABLED
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:
{
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_SETTINGS);
camera->send_camera_settings(chan);
}
break;
#if AP_CAMERA_SEND_FOV_STATUS_ENABLED
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
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);
return camera->send_mavlink_message(*this, id);
}
break;
#endif
#endif // AP_CAMERA_ENABLED

case MSG_SYSTEM_TIME:
CHECK_PAYLOAD_SIZE(SYSTEM_TIME);
Expand Down

0 comments on commit 78fcf70

Please sign in to comment.