mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
autotest: correct SetHome test for single precision
This commit is contained in:
parent
f726ca1809
commit
0665ac0f4f
@ -8450,11 +8450,11 @@ Also, ignores heartbeats not from our target system'''
|
|||||||
start_loc = self.sitl_start_location()
|
start_loc = self.sitl_start_location()
|
||||||
self.progress("SITL start loc: %s" % str(start_loc))
|
self.progress("SITL start loc: %s" % str(start_loc))
|
||||||
delta = abs(orig_home.latitude * 1.0e-7 - start_loc.lat)
|
delta = abs(orig_home.latitude * 1.0e-7 - start_loc.lat)
|
||||||
if delta > 0.000001:
|
if delta > 0.000002:
|
||||||
raise ValueError("homes differ in lat got=%f vs want=%f delta=%f" %
|
raise ValueError("homes differ in lat got=%f vs want=%f delta=%f" %
|
||||||
(orig_home.latitude * 1.0e-7, start_loc.lat, delta))
|
(orig_home.latitude * 1.0e-7, start_loc.lat, delta))
|
||||||
delta = abs(orig_home.longitude * 1.0e-7 - start_loc.lng)
|
delta = abs(orig_home.longitude * 1.0e-7 - start_loc.lng)
|
||||||
if delta > 0.000001:
|
if delta > 0.000002:
|
||||||
raise ValueError("homes differ in lon got=%f vs want=%f delta=%f" %
|
raise ValueError("homes differ in lon got=%f vs want=%f delta=%f" %
|
||||||
(orig_home.longitude * 1.0e-7, start_loc.lng, delta))
|
(orig_home.longitude * 1.0e-7, start_loc.lng, delta))
|
||||||
if self.is_rover():
|
if self.is_rover():
|
||||||
|
Loading…
Reference in New Issue
Block a user