mirror of https://github.com/ArduPilot/ardupilot
Sub: remove redundant home_is_set check
this is already guaranteed to be the case
This commit is contained in:
parent
43995763db
commit
860498d30e
|
@ -120,7 +120,7 @@ bool AP_Arming_Sub::arm(AP_Arming::Method method, bool do_arming_checks)
|
|||
// Always use absolute altitude for ROV
|
||||
// ahrs.resetHeightDatum();
|
||||
// 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)
|
||||
if (!sub.set_home_to_current_location(false)) {
|
||||
// ignore this failure
|
||||
|
|
Loading…
Reference in New Issue