Sub: remove redundant home_is_set check

this is already guaranteed to be the case
This commit is contained in:
Peter Barker 2024-04-11 19:05:57 +10:00 committed by Willian Galvani
parent 43995763db
commit 860498d30e
1 changed files with 1 additions and 1 deletions

View File

@ -120,7 +120,7 @@ bool AP_Arming_Sub::arm(AP_Arming::Method method, bool do_arming_checks)
// Always use absolute altitude for ROV // Always use absolute altitude for ROV
// ahrs.resetHeightDatum(); // ahrs.resetHeightDatum();
// AP::logger().Write_Event(LogEvent::EKF_ALT_RESET); // AP::logger().Write_Event(LogEvent::EKF_ALT_RESET);
} else if (ahrs.home_is_set() && !ahrs.home_is_locked()) { } else if (!ahrs.home_is_locked()) {
// Reset home position if it has already been set before (but not locked) // Reset home position if it has already been set before (but not locked)
if (!sub.set_home_to_current_location(false)) { if (!sub.set_home_to_current_location(false)) {
// ignore this failure // ignore this failure