mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
autotest: updated string for "Flight plan received"
This commit is contained in:
parent
e80ca592c4
commit
084b607862
@ -66,7 +66,7 @@ def drive_mission(mavproxy, mav, filename):
|
||||
global homeloc
|
||||
print("Driving mission %s" % filename)
|
||||
mavproxy.send('wp load %s\n' % filename)
|
||||
mavproxy.expect('flight plan received')
|
||||
mavproxy.expect('Flight plan received')
|
||||
mavproxy.send('wp list\n')
|
||||
mavproxy.expect('Requesting [0-9]+ waypoints')
|
||||
mavproxy.send('switch 4\n') # auto mode
|
||||
|
@ -880,7 +880,7 @@ def load_mission_from_file(mavproxy, mav, filename):
|
||||
'''Load a mission from a file to flight controller'''
|
||||
global num_wp
|
||||
mavproxy.send('wp load %s\n' % filename)
|
||||
mavproxy.expect('flight plan received')
|
||||
mavproxy.expect('Flight plan received')
|
||||
mavproxy.send('wp list\n')
|
||||
mavproxy.expect('Requesting [0-9]+ waypoints')
|
||||
|
||||
|
@ -413,7 +413,7 @@ def fly_mission(mavproxy, mav, filename, height_accuracy=-1, target_altitude=Non
|
||||
global homeloc
|
||||
print("Flying mission %s" % filename)
|
||||
mavproxy.send('wp load %s\n' % filename)
|
||||
mavproxy.expect('flight plan received')
|
||||
mavproxy.expect('Flight plan received')
|
||||
mavproxy.send('wp list\n')
|
||||
mavproxy.expect('Requesting [0-9]+ waypoints')
|
||||
mavproxy.send('switch 1\n') # auto mode
|
||||
|
Loading…
Reference in New Issue
Block a user