mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-06 07:58:28 -04:00
AutoTest: relax stability patch max distance
This commit is contained in:
parent
345924ddec
commit
0ba6bf8721
@ -283,7 +283,7 @@ def fly_throttle_failsafe(mavproxy, mav, side=60, timeout=180):
|
|||||||
return False
|
return False
|
||||||
|
|
||||||
# fly_stability_patch - fly south, then hold loiter within 5m position and altitude and reduce 1 motor to 60% efficiency
|
# fly_stability_patch - fly south, then hold loiter within 5m position and altitude and reduce 1 motor to 60% efficiency
|
||||||
def fly_stability_patch(mavproxy, mav, holdtime=30, maxaltchange=5, maxdistchange=5):
|
def fly_stability_patch(mavproxy, mav, holdtime=30, maxaltchange=5, maxdistchange=10):
|
||||||
'''hold loiter position'''
|
'''hold loiter position'''
|
||||||
mavproxy.send('switch 5\n') # loiter mode
|
mavproxy.send('switch 5\n') # loiter mode
|
||||||
wait_mode(mav, 'LOITER')
|
wait_mode(mav, 'LOITER')
|
||||||
@ -331,6 +331,8 @@ def fly_stability_patch(mavproxy, mav, holdtime=30, maxaltchange=5, maxdistchang
|
|||||||
mavproxy.send('param set SIM_ENGINE_MUL 1.0\n')
|
mavproxy.send('param set SIM_ENGINE_MUL 1.0\n')
|
||||||
return True
|
return True
|
||||||
print("Stability Patch FAILED")
|
print("Stability Patch FAILED")
|
||||||
|
# restore motor 1 to 100% efficiency
|
||||||
|
mavproxy.send('param set SIM_ENGINE_MUL 1.0\n')
|
||||||
return False
|
return False
|
||||||
|
|
||||||
# fly_fence_test - fly east until you hit the horizontal circular fence
|
# fly_fence_test - fly east until you hit the horizontal circular fence
|
||||||
|
Loading…
Reference in New Issue
Block a user