mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
autotest: recover from flip in althold to remove stabilise throttle problem
This commit is contained in:
parent
a4a5d52c35
commit
44ec74030e
@ -1728,10 +1728,8 @@ class AutoTestCopter(AutoTest):
|
|||||||
self.wait_attitude(despitch=0, desroll=0, tolerance=5)
|
self.wait_attitude(despitch=0, desroll=0, tolerance=5)
|
||||||
|
|
||||||
self.progress("Regaining altitude")
|
self.progress("Regaining altitude")
|
||||||
self.change_mode('STABILIZE')
|
self.change_mode('ALT_HOLD')
|
||||||
self.set_rc(3, 1650)
|
|
||||||
self.wait_for_alt(20, max_err=40)
|
self.wait_for_alt(20, max_err=40)
|
||||||
self.hover()
|
|
||||||
|
|
||||||
self.progress("Flipping in pitch")
|
self.progress("Flipping in pitch")
|
||||||
self.set_rc(2, 1700)
|
self.set_rc(2, 1700)
|
||||||
|
Loading…
Reference in New Issue
Block a user