mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Tools: autotest: make rangefinder test more reliable
This commit is contained in:
parent
0bbe049477
commit
6fc22cd5a3
@ -1242,7 +1242,7 @@ class AutoTestPlane(AutoTest):
|
||||
self.wait_ready_to_arm()
|
||||
self.arm_vehicle()
|
||||
home = self.poll_home_position()
|
||||
self.wait_altitude(10, 1000, timeout=30, relative=True)
|
||||
self.wait_waypoint(5, 5, max_dist=100)
|
||||
rf = self.mav.recv_match(type="RANGEFINDER", timeout=1, blocking=True)
|
||||
if rf is None:
|
||||
raise NotAchievedException("Did not receive rangefinder message")
|
||||
|
@ -1,10 +1,10 @@
|
||||
QGC WPL 110
|
||||
0 0 0 16 0.000000 0.000000 0.000000 0.000000 -35.362045 149.165878 584.280029 1
|
||||
1 0 3 22 0.000000 0.000000 0.000000 0.000000 -35.362125 149.165039 10.000000 1
|
||||
2 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.364845 149.163452 11.000000 1
|
||||
2 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.364845 149.163452 10.000000 1
|
||||
3 0 0 211 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1
|
||||
4 0 0 211 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1
|
||||
5 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.365002 149.165665 10.460000 1
|
||||
6 0 3 189 0.000000 0.000000 0.000000 0.000000 -35.364429 149.165558 9.120000 1
|
||||
5 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.365002 149.165665 10.000000 1
|
||||
6 0 3 189 0.000000 0.000000 0.000000 0.000000 -35.364429 149.165558 10.000000 1
|
||||
7 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.362869 149.165161 5.000000 1
|
||||
8 0 3 21 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 1
|
||||
|
Loading…
Reference in New Issue
Block a user