mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
autotest: make dataflash-over-mavlink test more accomodating
Saw <100kB/s on autotest server, so can't look for minimum 100kB/s. Also fixed disarmed-at-end-of-test
This commit is contained in:
parent
6f5d9a686e
commit
091d3e042b
@ -2640,9 +2640,15 @@ class AutoTest(ABC):
|
||||
if now - last_status > 5:
|
||||
last_status = now
|
||||
self.mavproxy.send('dataflash_logger status\n')
|
||||
self.mavproxy.expect("Active Rate\([0-9]s\):([1234])([0-9][0-9])[.]")
|
||||
# seen on autotest: Active Rate(3s):97.790kB/s Block:164 Missing:0 Fixed:0 Abandoned:0
|
||||
self.mavproxy.expect("Active Rate\([0-9]s\):([0-9]+[.][0-9]+)")
|
||||
rate = self.mavproxy.match.group(1)
|
||||
self.progress("Rate: %f" % float(rate))
|
||||
if rate < 50:
|
||||
raise NotAchievedException("Exceptionally low transfer rate")
|
||||
self.disarm_vehicle()
|
||||
except Exception as e:
|
||||
self.disarm_vehicle()
|
||||
self.progress("Exception (%s) caught" % str(e))
|
||||
ex = e
|
||||
self.context_pop()
|
||||
|
Loading…
Reference in New Issue
Block a user