mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
made missions work with index of 1
This commit is contained in:
parent
1833f69961
commit
5a75ef1356
@ -170,8 +170,8 @@ def fly_mission(mavproxy, mav, height_accuracy=-1, target_altitude=None):
|
||||
'''fly a mission from a file'''
|
||||
global homeloc
|
||||
global num_wp
|
||||
print("test: Fly a mission from 0 to %u" % num_wp)
|
||||
mavproxy.send('wp set 0\n')
|
||||
print("test: Fly a mission from 1 to %u" % num_wp)
|
||||
mavproxy.send('wp set 1\n')
|
||||
mavproxy.send('switch 4\n') # auto mode
|
||||
wait_mode(mav, 'AUTO')
|
||||
#wait_altitude(mav, 30, 40)
|
||||
|
Loading…
Reference in New Issue
Block a user