diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index c3e584124d..388fb2c746 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -1689,24 +1689,37 @@ class AutoTestPlane(AutoTest): self.progress("Ensure no AIRSPEED_AUTOCAL on ground") self.set_parameters({ "ARSPD_AUTOCAL": 1, + "ARSPD_PIN": 2, + "ARSPD_RATIO": 0, + "ARSPD2_RATIO": 4, + "ARSPD2_TYPE": 3, # MS5525 + "ARSPD2_BUS": 1, + "ARSPD2_AUTOCAL": 1, + "SIM_ARSPD2_OFS": 1900, # default is 2013 + "RTL_AUTOLAND": 1, }) - m = self.mav.recv_match(type='AIRSPEED_AUTOCAL', - blocking=True, - timeout=5) - if m is not None: - raise NotAchievedException("Got autocal on ground") + self.context_collect('STATUSTEXT') + self.reboot_sitl() + + self.assert_not_receive_message('AIRSPEED_AUTOCAL', timeout=5) + + # these are boot-time calibration messages: + self.wait_statustext('Airspeed 1 calibrated', check_context=True, timeout=30) + self.wait_statustext('Airspeed 2 calibrated', check_context=True) + mission_filepath = "flaps.txt" - num_wp = self.load_mission(mission_filepath) + self.load_mission(mission_filepath) self.wait_ready_to_arm() self.arm_vehicle() self.change_mode("AUTO") self.progress("Ensure AIRSPEED_AUTOCAL in air") - m = self.mav.recv_match(type='AIRSPEED_AUTOCAL', - blocking=True, - timeout=5) - self.wait_waypoint(7, num_wp-1, max_dist=5, timeout=500) - self.wait_disarmed(timeout=120) + self.assert_receive_message('AIRSPEED_AUTOCAL') + self.wait_statustext("Airspeed 0 ratio reset", check_context=True, timeout=70) + # we only autocal the primary sensor?! + self.set_parameter('ARSPD_PRIMARY', 1) + self.wait_statustext("Airspeed 1 ratio reset", check_context=True, timeout=70) + self.fly_home_land_and_disarm() def deadreckoning_main(self, disable_airspeed_sensor=False): self.wait_ready_to_arm()