autotest: add test for calibrating different nos of airspeed sensors

only success is checked for, not the calibration values
This commit is contained in:
Peter Barker 2023-01-30 18:42:44 +11:00 committed by Peter Barker
parent f5bda98a05
commit fab1c47b27

View File

@ -4175,6 +4175,44 @@ class AutoTestPlane(AutoTest):
self.disarm_vehicle() self.disarm_vehicle()
# reboot to clear potentially bad state # reboot to clear potentially bad state
def trigger_airspeed_cal(self):
self.run_cmd(mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION,
0, 0, 1, 0, 0, 0, 0)
def AirspeedCal(self):
'''test Airspeed calibration'''
self.start_subtest('1 airspeed sensor')
self.context_push()
self.context_collect('STATUSTEXT')
self.trigger_airspeed_cal()
self.wait_statustext('Airspeed 1 calibrated', check_context=True)
self.context_pop()
self.context_push()
self.context_collect('STATUSTEXT')
self.start_subtest('0 airspeed sensors')
self.set_parameter('ARSPD_TYPE', 0)
self.reboot_sitl()
self.wait_statustext('No airspeed sensor present or enabled', check_context=True)
self.trigger_airspeed_cal()
self.delay_sim_time(5)
if self.statustext_in_collections('Airspeed 1 calibrated'):
raise NotAchievedException("Did not disable airspeed sensor?!")
self.context_pop()
self.start_subtest('2 airspeed sensors')
self.set_parameter('ARSPD_TYPE', 100)
self.set_parameter('ARSPD2_TYPE', 100)
self.reboot_sitl()
self.context_push()
self.context_collect('STATUSTEXT')
self.trigger_airspeed_cal()
self.wait_statustext('Airspeed 1 calibrated', check_context=True)
self.wait_statustext('Airspeed 2 calibrated', check_context=True)
self.context_pop()
self.reboot_sitl() self.reboot_sitl()
def tests(self): def tests(self):
@ -4258,6 +4296,7 @@ class AutoTestPlane(AutoTest):
self.MANUAL_CONTROL, self.MANUAL_CONTROL,
self.WindEstimates, self.WindEstimates,
self.AltResetBadGPS, self.AltResetBadGPS,
self.AirspeedCal,
]) ])
return ret return ret