Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_Mount: SWITCH statement to table reference #24992

Merged
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
45 changes: 15 additions & 30 deletions libraries/AP_Mount/AP_Mount_Siyi.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -916,39 +916,24 @@ bool AP_Mount_Siyi::set_lens(uint8_t lens)
}

// maps lens to siyi camera image type so that lens of 0, 1, 2 are more useful
CameraImageType cam_image_type = CameraImageType::MAIN_ZOOM_SUB_THERMAL;
switch (lens) {
case 0:
cam_image_type = CameraImageType::MAIN_ZOOM_SUB_THERMAL; // 3
break;
case 1:
cam_image_type = CameraImageType::MAIN_WIDEANGLE_SUB_THERMAL; // 5
break;
case 2:
cam_image_type = CameraImageType::MAIN_THERMAL_SUB_ZOOM; // 7
break;
case 3:
cam_image_type = CameraImageType::MAIN_PIP_ZOOM_THERMAL_SUB_WIDEANGLE; // 0
break;
case 4:
cam_image_type = CameraImageType::MAIN_PIP_WIDEANGLE_THERMAL_SUB_ZOOM; // 1
break;
case 5:
cam_image_type = CameraImageType::MAIN_PIP_ZOOM_WIDEANGLE_SUB_THERMAL; // 2
break;
case 6:
cam_image_type = CameraImageType::MAIN_ZOOM_SUB_WIDEANGLE; // 4
break;
case 7:
cam_image_type = CameraImageType::MAIN_WIDEANGLE_SUB_ZOOM; // 6
break;
case 8:
cam_image_type = CameraImageType::MAIN_THERMAL_SUB_WIDEANGLE; // 8
break;
static const CameraImageType cam_image_type_table[] {
CameraImageType::MAIN_ZOOM_SUB_THERMAL, // 3
CameraImageType::MAIN_WIDEANGLE_SUB_THERMAL, // 5
CameraImageType::MAIN_THERMAL_SUB_ZOOM, // 7
CameraImageType::MAIN_PIP_ZOOM_THERMAL_SUB_WIDEANGLE, // 0
CameraImageType::MAIN_PIP_WIDEANGLE_THERMAL_SUB_ZOOM, // 1
CameraImageType::MAIN_PIP_ZOOM_WIDEANGLE_SUB_THERMAL, // 2
CameraImageType::MAIN_ZOOM_SUB_WIDEANGLE, // 4
CameraImageType::MAIN_WIDEANGLE_SUB_ZOOM, // 6
CameraImageType::MAIN_THERMAL_SUB_WIDEANGLE, // 8
};

if (lens >= ARRAY_SIZE(cam_image_type_table)) {
return false;
}

// send desired image type to camera
return send_1byte_packet(SiyiCommandId::SET_CAMERA_IMAGE_TYPE, (uint8_t)cam_image_type);
return send_1byte_packet(SiyiCommandId::SET_CAMERA_IMAGE_TYPE, (uint8_t)cam_image_type_table[lens]);
peterbarker marked this conversation as resolved.
Show resolved Hide resolved
}

// set_camera_source is functionally the same as set_lens except primary and secondary lenses are specified by type
Expand Down
Loading