Tools: autotest: allow imprecise home in set-home test

float<->integer conversion issues means this comes back imprecisely
This commit is contained in:
Peter Barker 2019-03-04 17:51:57 +11:00 committed by Peter Barker
parent 88e3f6f78c
commit 792fbc6240
1 changed files with 14 additions and 11 deletions

View File

@ -1758,24 +1758,27 @@ class AutoTest(ABC):
) )
home = self.poll_home_position() home = self.poll_home_position()
self.progress("int-set home: %s" % str(home)) self.progress("home: %s" % str(home))
if (home.latitude != new_x or got_home_latitude = home.latitude
home.longitude != new_y or got_home_longitude = home.longitude
home.altitude != new_z): got_home_altitude = home.altitude
if (got_home_latitude != new_x or
got_home_longitude != new_y or
abs(got_home_altitude - new_z) > 100): # float-conversion issues
self.reboot_sitl() self.reboot_sitl()
raise NotAchievedException( raise NotAchievedException(
"(%f, %f, %f) != (%f, %f, %f)" % "Home mismatch got=(%f, %f, %f) set=(%f, %f, %f)" %
(home.latitude, home.longitude, home.altitude, (got_home_latitude, got_home_longitude, got_home_altitude,
new_x, new_y, new_z)) new_x, new_y, new_z))
# watch it for a little while to ensure it doesn't drift at all: self.progress("monitoring home to ensure it doesn't drift at all")
tstart = self.get_sim_time() tstart = self.get_sim_time()
while self.get_sim_time() - tstart < 10: while self.get_sim_time() - tstart < 10:
home = self.poll_home_position() home = self.poll_home_position()
self.progress("int-set home: %s" % str(home)) self.progress("home: %s" % str(home))
if (home.latitude != new_x or if (home.latitude != got_home_latitude or
home.longitude != new_y or home.longitude != got_home_longitude or
home.altitude != new_z): home.altitude != got_home_altitude): # float-conversion issues
self.reboot_sitl() self.reboot_sitl()
raise NotAchievedException("home is drifting") raise NotAchievedException("home is drifting")
self.reboot_sitl() self.reboot_sitl()