diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index b25ba2fb0666f7..411e3ae7327761 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -12253,8 +12253,8 @@ def assert_home_position_not_set(self): raise NotAchievedException("Home is set when it shouldn't be") - def REQUIRE_POSITION_FOR_ARMING(self): - '''check FlightOption::REQUIRE_POSITION_FOR_ARMING works''' + def REQUIRE_LOCATION_FOR_ARMING(self): + '''check AP_Arming::Option::REQUIRE_LOCATION_FOR_ARMING works''' self.context_push() self.set_parameters({ "SIM_GPS1_NUMSATS": 3, # EKF does not like < 6 @@ -12270,7 +12270,7 @@ def REQUIRE_POSITION_FOR_ARMING(self): self.change_mode('STABILIZE') self.set_parameters({ - "FLIGHT_OPTIONS": 8, + "ARMING_NEED_LOC": 1, }) self.assert_prearm_failure("Need Position Estimate", other_prearm_failures_fatal=False) self.context_pop() @@ -12685,7 +12685,7 @@ def tests2b(self): # this block currently around 9.5mins here self.GuidedWeatherVane, self.Clamp, self.GripperReleaseOnThrustLoss, - self.REQUIRE_POSITION_FOR_ARMING, + self.REQUIRE_LOCATION_FOR_ARMING, self.LoggingFormat, self.MissionRTLYawBehaviour, self.BatteryInternalUseOnly,