autotest: autotest gets GSF_reset test

This commit is contained in:
Randy Mackay 2023-08-03 15:41:04 +09:00 committed by Peter Barker
parent 14c3b80c9c
commit ba72c58659
1 changed files with 41 additions and 0 deletions

View File

@ -7709,6 +7709,46 @@ class AutoTestCopter(AutoTest):
raise NotAchievedException("Did not get %s" % want) raise NotAchievedException("Did not get %s" % want)
still_want.remove(m.get_type()) still_want.remove(m.get_type())
def GSF_reset(self):
'''test the Gaussian Sum filter based Emergency reset'''
self.context_push()
self.set_parameters({
"COMPASS_ORIENT": 4, # yaw 180
"COMPASS_USE2": 0, # disable backup compasses to avoid pre-arm failures
"COMPASS_USE3": 0,
})
self.reboot_sitl()
self.change_mode('GUIDED')
self.wait_ready_to_arm()
# record starting position
startpos = self.mav.recv_match(type='LOCAL_POSITION_NED', blocking=True)
self.progress("startpos=%s" % str(startpos))
# arm vehicle and takeoff to at least 5m
self.arm_vehicle()
expected_alt = 5
self.user_takeoff(alt_min=expected_alt)
# watch for emergency yaw reset
self.wait_text("EKF3 IMU. emergency yaw reset", timeout=5, regex=True)
# record how far vehicle flew off
endpos = self.mav.recv_match(type='LOCAL_POSITION_NED', blocking=True)
delta_x = endpos.x - startpos.x
delta_y = endpos.y - startpos.y
dist_m = math.sqrt(delta_x*delta_x + delta_y*delta_y)
self.progress("GSF yaw reset triggered at %f meters" % dist_m)
self.do_RTL()
self.context_pop()
self.reboot_sitl()
# ensure vehicle did not fly too far
dist_m_max = 8
if dist_m > dist_m_max:
raise NotAchievedException("GSF reset failed, vehicle flew too far (%f > %f)" % (dist_m, dist_m_max))
def fly_rangefinder_mavlink(self): def fly_rangefinder_mavlink(self):
self.fly_rangefinder_mavlink_distance_sensor() self.fly_rangefinder_mavlink_distance_sensor()
@ -9851,6 +9891,7 @@ class AutoTestCopter(AutoTest):
self.AltEstimation, self.AltEstimation,
self.EKFSource, self.EKFSource,
self.GSF, self.GSF,
self.GSF_reset,
self.AP_Avoidance, self.AP_Avoidance,
self.SMART_RTL, self.SMART_RTL,
self.RTL_TO_RALLY, self.RTL_TO_RALLY,