mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Mount: Siyi ZT6 set lens fix
ZT6 has RGB and Thermal image sensors only
This commit is contained in:
parent
0874202aa1
commit
5bcbf56a47
@ -910,11 +910,11 @@ SetFocusResult AP_Mount_Siyi::set_focus(FocusType focus_type, float focus_value)
|
|||||||
// set camera lens as a value from 0 to 8
|
// set camera lens as a value from 0 to 8
|
||||||
bool AP_Mount_Siyi::set_lens(uint8_t lens)
|
bool AP_Mount_Siyi::set_lens(uint8_t lens)
|
||||||
{
|
{
|
||||||
// only supported on ZT30. sanity check lens values
|
CameraImageType selected_lens;
|
||||||
if ((_hardware_model != HardwareModel::ZT30) || (lens > 8)) {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
|
switch (_hardware_model) {
|
||||||
|
|
||||||
|
case HardwareModel::ZT30: {
|
||||||
// maps lens to siyi camera image type so that lens of 0, 1, 2 are more useful
|
// maps lens to siyi camera image type so that lens of 0, 1, 2 are more useful
|
||||||
static const CameraImageType cam_image_type_table[] {
|
static const CameraImageType cam_image_type_table[] {
|
||||||
CameraImageType::MAIN_ZOOM_SUB_THERMAL, // 3
|
CameraImageType::MAIN_ZOOM_SUB_THERMAL, // 3
|
||||||
@ -928,12 +928,37 @@ bool AP_Mount_Siyi::set_lens(uint8_t lens)
|
|||||||
CameraImageType::MAIN_THERMAL_SUB_WIDEANGLE, // 8
|
CameraImageType::MAIN_THERMAL_SUB_WIDEANGLE, // 8
|
||||||
};
|
};
|
||||||
|
|
||||||
|
// sanity check lens values
|
||||||
if (lens >= ARRAY_SIZE(cam_image_type_table)) {
|
if (lens >= ARRAY_SIZE(cam_image_type_table)) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
selected_lens = cam_image_type_table[lens];
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
case HardwareModel::ZT6: {
|
||||||
|
// maps lens to siyi camera image type so that lens of 0, 1, 2 are more useful
|
||||||
|
static const CameraImageType cam_image_type_table[] {
|
||||||
|
CameraImageType::MAIN_ZOOM_SUB_THERMAL, // 3
|
||||||
|
CameraImageType::MAIN_THERMAL_SUB_ZOOM, // 7
|
||||||
|
CameraImageType::MAIN_PIP_ZOOM_THERMAL_SUB_WIDEANGLE, // 0
|
||||||
|
};
|
||||||
|
|
||||||
|
// sanity check lens values
|
||||||
|
if (lens >= ARRAY_SIZE(cam_image_type_table)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
selected_lens = cam_image_type_table[lens];
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
default:
|
||||||
|
// set lens not supported on this camera
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
// send desired image type to camera
|
// send desired image type to camera
|
||||||
return send_1byte_packet(SiyiCommandId::SET_CAMERA_IMAGE_TYPE, (uint8_t)cam_image_type_table[lens]);
|
return send_1byte_packet(SiyiCommandId::SET_CAMERA_IMAGE_TYPE, (uint8_t)selected_lens);
|
||||||
}
|
}
|
||||||
|
|
||||||
// set_camera_source is functionally the same as set_lens except primary and secondary lenses are specified by type
|
// set_camera_source is functionally the same as set_lens except primary and secondary lenses are specified by type
|
||||||
|
Loading…
Reference in New Issue
Block a user