mirror of https://github.com/ArduPilot/ardupilot
AP_Mission: set_zoom replaces set_zoom_step
This commit is contained in:
parent
9100123efe
commit
ddaff85166
|
@ -131,8 +131,10 @@ bool AP_Mission::start_command_camera(const AP_Mission::Mission_Command& cmd)
|
|||
|
||||
case MAV_CMD_SET_CAMERA_ZOOM:
|
||||
if (cmd.content.set_camera_zoom.zoom_type == ZOOM_TYPE_CONTINUOUS) {
|
||||
camera->set_zoom_step(cmd.content.set_camera_zoom.zoom_value);
|
||||
return true;
|
||||
return camera->set_zoom(AP_Camera::ZoomType::RATE, cmd.content.set_camera_zoom.zoom_value);
|
||||
}
|
||||
if (cmd.content.set_camera_zoom.zoom_type == ZOOM_TYPE_RANGE) {
|
||||
return camera->set_zoom(AP_Camera::ZoomType::PCT, cmd.content.set_camera_zoom.zoom_value);
|
||||
}
|
||||
return false;
|
||||
|
||||
|
|
Loading…
Reference in New Issue