AP_Mission: add and use SetFocusResult

This commit is contained in:
Peter Barker 2023-06-21 16:03:39 +10:00 committed by Peter Barker
parent 82b0630c6a
commit 958622523f
1 changed files with 3 additions and 3 deletions

View File

@ -150,15 +150,15 @@ bool AP_Mission::start_command_camera(const AP_Mission::Mission_Command& cmd)
if ((cmd.content.set_camera_focus.focus_type == FOCUS_TYPE_AUTO) ||
(cmd.content.set_camera_focus.focus_type == FOCUS_TYPE_AUTO_SINGLE) ||
(cmd.content.set_camera_focus.focus_type == FOCUS_TYPE_AUTO_CONTINUOUS)) {
return camera->set_focus(FocusType::AUTO, 0);
return camera->set_focus(FocusType::AUTO, 0) == SetFocusResult::ACCEPTED;
}
// accept continuous manual focus
if (cmd.content.set_camera_focus.focus_type == FOCUS_TYPE_CONTINUOUS) {
return camera->set_focus(FocusType::RATE, cmd.content.set_camera_focus.focus_value);
return camera->set_focus(FocusType::RATE, cmd.content.set_camera_focus.focus_value) == SetFocusResult::ACCEPTED;
}
// accept range manual focus
if (cmd.content.set_camera_focus.focus_type == FOCUS_TYPE_RANGE) {
return camera->set_focus(FocusType::PCT, cmd.content.set_camera_focus.focus_value);
return camera->set_focus(FocusType::PCT, cmd.content.set_camera_focus.focus_value) == SetFocusResult::ACCEPTED;
}
return false;