mirror of https://github.com/ArduPilot/ardupilot
AP_Mount: Siyi driver comment re zoom decrement
This commit is contained in:
parent
9c72cf2a1e
commit
a8c593d44c
|
@ -634,6 +634,7 @@ bool AP_Mount_Siyi::set_zoom(AP_Camera::ZoomType zoom_type, float zoom_value)
|
|||
zoom_step = 1;
|
||||
}
|
||||
if (zoom_value < 0) {
|
||||
// Siyi API specifies -1 should be sent as 255
|
||||
zoom_step = UINT8_MAX;
|
||||
}
|
||||
return send_1byte_packet(SiyiCommandId::MANUAL_ZOOM_AND_AUTO_FOCUS, zoom_step);
|
||||
|
|
Loading…
Reference in New Issue