mirror of https://github.com/ArduPilot/ardupilot
RC_Channel: camera focus controls use set_focus
This commit is contained in:
parent
020a505d78
commit
d187368b33
|
@ -968,7 +968,7 @@ bool RC_Channel::do_aux_function_camera_manual_focus(const AuxSwitchPos ch_flag)
|
|||
focus_step = -1;
|
||||
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)
|
||||
|
@ -978,7 +978,7 @@ bool RC_Channel::do_aux_function_camera_auto_focus(const AuxSwitchPos ch_flag)
|
|||
if (camera == nullptr) {
|
||||
return false;
|
||||
}
|
||||
return camera->set_auto_focus();
|
||||
return camera->set_focus(FocusType::AUTO, 0);
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue