autotest: improve deadreckoning test

autotest: use location_offset rather than coordinates in Deadreckoning test
This commit is contained in:
Peter Barker 2021-03-02 12:58:00 +11:00 committed by Peter Barker
parent 425ab1358a
commit bdeadce95b
2 changed files with 26 additions and 5 deletions

View File

@ -0,0 +1,13 @@
QGC WPL 110
0 0 0 16 0.000000 0.000000 0.000000 0.000000 -35.363262 149.165237 584.390015 1
1 0 3 22 15.000000 0.000000 0.000000 0.000000 -35.361279 149.164230 30.000000 1
2 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.361229 149.163025 80.000000 1
3 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.364563 149.163773 80.000000 1
4 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.364384 149.164795 80.000000 1
5 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.361027 149.164093 80.000000 1
6 0 0 177 2.000000 3.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1
7 0 3 189 0.000000 0.000000 0.000000 0.000000 -35.362915 149.162613 60.000000 1
8 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.363136 149.162750 60.000000 1
9 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.365467 149.164215 55.000000 1
10 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.365009 149.165482 39.889999 1
11 0 3 21 0.000000 0.000000 0.000000 1.000000 -35.363041 149.165222 0.000000 1

View File

@ -1537,13 +1537,16 @@ class AutoTestPlane(AutoTest):
return return
divergence = self.get_distance_int(self.gpi, self.simstate) divergence = self.get_distance_int(self.gpi, self.simstate)
max_allowed_divergence = 200 max_allowed_divergence = 200
if time.time() - self.last_print > 1: if (time.time() - self.last_print > 1 or
divergence > self.max_divergence):
self.progress("position-estimate-divergence=%fm" % (divergence,)) self.progress("position-estimate-divergence=%fm" % (divergence,))
self.last_print = time.time() self.last_print = time.time()
if divergence > max_allowed_divergence:
raise NotAchievedException("global-position-int diverged from simstate by >%fm" % (max_allowed_divergence,))
if divergence > self.max_divergence: if divergence > self.max_divergence:
self.max_divergence = divergence self.max_divergence = divergence
if divergence > max_allowed_divergence:
raise NotAchievedException(
"global-position-int diverged from simstate by %fm (max=%fm" %
(divergence, max_allowed_divergence,))
self.install_message_hook(validate_global_position_int_against_simstate) self.install_message_hook(validate_global_position_int_against_simstate)
@ -1557,8 +1560,7 @@ class AutoTestPlane(AutoTest):
self.takeoff(50) self.takeoff(50)
loc = self.mav.location() loc = self.mav.location()
loc.lat = -35.35690712 self.location_offset_ne(loc, 500, 500)
loc.lng = 149.17083386
self.run_cmd_int( self.run_cmd_int(
mavutil.mavlink.MAV_CMD_DO_REPOSITION, mavutil.mavlink.MAV_CMD_DO_REPOSITION,
0, 0,
@ -1588,6 +1590,8 @@ class AutoTestPlane(AutoTest):
def deadreckoning(self): def deadreckoning(self):
self.deadreckoning_main() self.deadreckoning_main()
def deadreckoning_no_airspeed_sensor(self):
self.deadreckoning_main(disable_airspeed_sensor=True) self.deadreckoning_main(disable_airspeed_sensor=True)
def rtl_climb_min(self): def rtl_climb_min(self):
@ -2785,6 +2789,10 @@ class AutoTestPlane(AutoTest):
"Test deadreckoning support", "Test deadreckoning support",
self.deadreckoning), self.deadreckoning),
("DeadreckoningNoAirSpeed",
"Test deadreckoning support with no airspeed sensor",
self.deadreckoning_no_airspeed_sensor),
("EKFlaneswitch", ("EKFlaneswitch",
"Test EKF3 Affinity and Lane Switching", "Test EKF3 Affinity and Lane Switching",
self.ekf_lane_switch), self.ekf_lane_switch),