RC_Channel: camera focus controls use set_focus

This commit is contained in:
Randy Mackay 2023-04-24 21:24:10 +09:00 committed by Peter Barker
parent 020a505d78
commit d187368b33
1 changed files with 2 additions and 2 deletions

View File

@ -968,7 +968,7 @@ bool RC_Channel::do_aux_function_camera_manual_focus(const AuxSwitchPos ch_flag)
focus_step = -1; focus_step = -1;
break; break;
} }
return camera->set_manual_focus_step(focus_step); return camera->set_focus(FocusType::RATE, focus_step);
} }
bool RC_Channel::do_aux_function_camera_auto_focus(const AuxSwitchPos ch_flag) bool RC_Channel::do_aux_function_camera_auto_focus(const AuxSwitchPos ch_flag)
@ -978,7 +978,7 @@ bool RC_Channel::do_aux_function_camera_auto_focus(const AuxSwitchPos ch_flag)
if (camera == nullptr) { if (camera == nullptr) {
return false; return false;
} }
return camera->set_auto_focus(); return camera->set_focus(FocusType::AUTO, 0);
} }
return false; return false;
} }