Tools: autotest: improve autotest output

This commit is contained in:
Peter Barker 2018-07-02 13:22:54 +10:00 committed by Peter Barker
parent 584013de58
commit fe2f9f1f14
2 changed files with 17 additions and 16 deletions

View File

@ -369,7 +369,7 @@ class AutoTestCopter(AutoTest):
home = ""
if alt <= 1 and home_distance < 10:
home = "HOME"
self.progress("Alt: %u HomeDist: %.0f %s" %
self.progress("Alt: %.02f HomeDist: %.02f %s" %
(alt, home_distance, home))
# our post-condition is that we are disarmed:
if not self.armed():
@ -480,7 +480,7 @@ class AutoTestCopter(AutoTest):
alt = m.relative_alt / 1000.0 # mm -> m
pos = self.mav.location()
home_distance = self.get_distance(home, pos )
self.progress("Alt: %u HomeDist: %.0f" % (alt, home_distance))
self.progress("Alt: %.02f HomeDist: %.0f" % (alt, home_distance))
# check if we've reached home
if alt <= 1 and home_distance < 10:
# reduce throttle
@ -602,7 +602,7 @@ class AutoTestCopter(AutoTest):
alt = m.relative_alt / 1000.0 # mm -> m
pos = self.mav.location()
home_distance = self.get_distance(HOME, pos)
self.progress("Alt: %f HomeDistance: %.0f" %
self.progress("Alt: %.02f HomeDistance: %.02f" %
(alt, home_distance))
# recenter pitch sticks once we're home so we don't fly off again
if pitching_forward and home_distance < 10:
@ -766,7 +766,8 @@ class AutoTestCopter(AutoTest):
alt = m.alt/1000.0 # mm -> m
curr_pos = self.sim_location()
moved_distance = self.get_distance(curr_pos, start_pos)
self.progress("Alt: %u Moved: %.0f" % (alt, moved_distance))
self.progress("Alt: %.02f Moved: %.0f" %
(alt, moved_distance))
if moved_distance > max_distance:
raise NotAchievedException(
"Moved over %u meters, Failed!" % max_distance)
@ -885,7 +886,7 @@ class AutoTestCopter(AutoTest):
self.mav.recv_match(type='VFR_HUD', blocking=True)
pos = self.mav.location()
dist_to_home = self.get_distance(HOME, pos)
self.progress("Dist from home: %u" % dist_to_home)
self.progress("Dist from home: %.02f" % dist_to_home)
# turn off simulator display of gps and actual position
if self.use_map:
@ -1017,7 +1018,7 @@ class AutoTestCopter(AutoTest):
(start_altitude, holdtime))
while self.get_sim_time() < tstart + holdtime:
m = self.mav.recv_match(type='VFR_HUD', blocking=True)
self.progress("heading %u" % m.heading)
self.progress("heading %d" % m.heading)
self.progress("CIRCLE OK for %u seconds" % holdtime)

View File

@ -1176,7 +1176,7 @@ class AutoTest(ABC):
if self.get_sim_time() - tstart > 200:
raise NotAchievedException("Did not achieve heading")
m = self.mav.recv_match(type='VFR_HUD', blocking=True)
self.progress("heading=%f want=%f" % (m.heading, heading))
self.progress("heading=%d want=%f" % (m.heading, heading))
if m.heading == heading:
return
@ -1195,7 +1195,7 @@ class AutoTest(ABC):
previous_alt = 0
tstart = self.get_sim_time()
self.progress("Waiting for altitude between %u and %u" %
self.progress("Waiting for altitude between %.02f and %.02f" %
(alt_min, alt_max))
last_wait_alt_msg = 0
while self.get_sim_time_cached() < tstart + timeout:
@ -1210,7 +1210,7 @@ class AutoTest(ABC):
climb_rate = alt - previous_alt
previous_alt = alt
if self.get_sim_time_cached() - last_wait_alt_msg > 1:
self.progress("Wait Altitude: Cur:%u, min_alt:%u, climb_rate: %u"
self.progress("Wait Altitude: Cur:%.02f min_alt:%.02f climb_rate: %.02f"
% (alt, alt_min, climb_rate))
last_wait_alt_msg = self.get_sim_time_cached()
if alt >= alt_min and alt <= alt_max:
@ -1251,7 +1251,7 @@ class AutoTest(ABC):
def wait_pitch(self, pitch, accuracy, timeout=30):
"""Wait for a given pitch in degrees."""
tstart = self.get_sim_time()
self.progress("Waiting for pitch of %u at %s" % (pitch, time.ctime()))
self.progress("Waiting for pitch of %.02f at %s" % (pitch, time.ctime()))
while self.get_sim_time() < tstart + timeout:
m = self.mav.recv_match(type='ATTITUDE', blocking=True)
p = math.degrees(m.pitch)
@ -1265,7 +1265,7 @@ class AutoTest(ABC):
def wait_heading(self, heading, accuracy=5, timeout=30):
"""Wait for a given heading."""
tstart = self.get_sim_time()
self.progress("Waiting for heading %u with accuracy %u" %
self.progress("Waiting for heading %.02f with accuracy %.02f" %
(heading, accuracy))
last_print_time = 0
while True:
@ -1274,13 +1274,13 @@ class AutoTest(ABC):
break
m = self.mav.recv_match(type='VFR_HUD', blocking=True)
if now - last_print_time > 1:
self.progress("Heading %u (want %f +- %f)" %
self.progress("Heading %d (want %f +- %f)" %
(m.heading, heading, accuracy))
last_print_time = now
if math.fabs(m.heading - heading) <= accuracy:
self.progress("Attained heading %u" % heading)
self.progress("Attained heading %d" % heading)
return True
raise WaitHeadingTimeout("Failed to attain heading %u" % heading)
raise WaitHeadingTimeout("Failed to attain heading %d" % heading)
def wait_distance(self, distance, accuracy=5, timeout=30):
"""Wait for flight of a given distance."""
@ -1295,7 +1295,7 @@ class AutoTest(ABC):
(delta, distance))
last_distance_message = self.get_sim_time_cached()
if math.fabs(delta - distance) <= accuracy:
self.progress("Attained distance %.2f meters OK" % delta)
self.progress("Attained distance %.02f meters OK" % delta)
return True
if delta > (distance + accuracy):
raise WaitDistanceTimeout("Failed distance - overshoot delta=%f dist=%f"
@ -1393,7 +1393,7 @@ class AutoTest(ABC):
raise WaitWaypointTimeout('Exited %s mode' % mode)
if self.get_sim_time_cached() - last_wp_msg > 1:
self.progress("WP %u (wp_dist=%u Alt=%d), current_wp: %u,"
self.progress("WP %u (wp_dist=%u Alt=%.02f), current_wp: %u,"
"wpnum_end: %u" %
(seq, wp_dist, m.alt, current_wp, wpnum_end))
last_wp_msg = self.get_sim_time_cached()