mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
autotest: adjust for low log transfer rate under valgrind
This commit is contained in:
parent
bcc1cb9dbb
commit
ad06a616b8
@ -6568,8 +6568,11 @@ Also, ignores heartbeats not from our target system'''
|
|||||||
self.mavproxy.expect(r"Active Rate\([0-9]+s\):([0-9]+[.][0-9]+)")
|
self.mavproxy.expect(r"Active Rate\([0-9]+s\):([0-9]+[.][0-9]+)")
|
||||||
rate = float(self.mavproxy.match.group(1))
|
rate = float(self.mavproxy.match.group(1))
|
||||||
self.progress("Rate: %f" % rate)
|
self.progress("Rate: %f" % rate)
|
||||||
if rate < 50:
|
desired_rate = 50
|
||||||
raise NotAchievedException("Exceptionally low transfer rate")
|
if self.valgrind:
|
||||||
|
desired_rate /= 10
|
||||||
|
if rate < desired_rate:
|
||||||
|
raise NotAchievedException("Exceptionally low transfer rate (%u < %u)" % (rate, desired_rate))
|
||||||
self.disarm_vehicle()
|
self.disarm_vehicle()
|
||||||
except Exception as e:
|
except Exception as e:
|
||||||
self.progress("Exception caught: %s" %
|
self.progress("Exception caught: %s" %
|
||||||
|
Loading…
Reference in New Issue
Block a user