mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Tools: autotest: increase throttle in stabilize mode to account for pitching
This commit is contained in:
parent
b35cb4d814
commit
38ae0765ff
@ -266,10 +266,12 @@ class AutoTestCopter(AutoTest):
|
|||||||
self.save_wp()
|
self.save_wp()
|
||||||
|
|
||||||
# switch back to stabilize mode
|
# switch back to stabilize mode
|
||||||
self.set_rc(3, 1500)
|
|
||||||
self.mavproxy.send('switch 6\n')
|
self.mavproxy.send('switch 6\n')
|
||||||
self.wait_mode('STABILIZE')
|
self.wait_mode('STABILIZE')
|
||||||
|
|
||||||
|
# increase throttle a bit because we're about to pitch:
|
||||||
|
self.set_rc(3, 1525)
|
||||||
|
|
||||||
# pitch forward to fly north
|
# pitch forward to fly north
|
||||||
self.progress("Going north %u meters" % side)
|
self.progress("Going north %u meters" % side)
|
||||||
self.set_rc(2, 1300)
|
self.set_rc(2, 1300)
|
||||||
@ -310,6 +312,9 @@ class AutoTestCopter(AutoTest):
|
|||||||
self.progress("Save WP 6")
|
self.progress("Save WP 6")
|
||||||
self.save_wp()
|
self.save_wp()
|
||||||
|
|
||||||
|
# reduce throttle again
|
||||||
|
self.set_rc(3, 1500)
|
||||||
|
|
||||||
# descend to 10m
|
# descend to 10m
|
||||||
self.progress("Descend to 10m in Loiter")
|
self.progress("Descend to 10m in Loiter")
|
||||||
self.mavproxy.send('switch 5\n') # loiter mode
|
self.mavproxy.send('switch 5\n') # loiter mode
|
||||||
|
Loading…
Reference in New Issue
Block a user