mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AutoTest: add copter battery failsafe test
This commit is contained in:
parent
db2975901d
commit
5f1ba85ce4
@ -282,6 +282,36 @@ def fly_throttle_failsafe(mavproxy, mav, side=60, timeout=180):
|
|||||||
wait_mode(mav, 'STABILIZE')
|
wait_mode(mav, 'STABILIZE')
|
||||||
return False
|
return False
|
||||||
|
|
||||||
|
def fly_battery_failsafe(mavproxy, mav, timeout=30):
|
||||||
|
# assume failure
|
||||||
|
success = False
|
||||||
|
|
||||||
|
# switch to loiter mode so that we hold position
|
||||||
|
mavproxy.send('switch 5\n')
|
||||||
|
wait_mode(mav, 'LOITER')
|
||||||
|
mavproxy.send("rc 3 1500\n")
|
||||||
|
|
||||||
|
# enable battery failsafe
|
||||||
|
mavproxy.send("param set FS_BATT_ENABLE 1\n")
|
||||||
|
|
||||||
|
# trigger low voltage
|
||||||
|
mavproxy.send('param set SIM_BATT_VOLTAGE 10\n')
|
||||||
|
|
||||||
|
# wait for LAND mode
|
||||||
|
if wait_mode(mav, 'LAND', timeout) == 'LAND':
|
||||||
|
success = True
|
||||||
|
|
||||||
|
# disable battery failsafe
|
||||||
|
mavproxy.send('param set FS_BATT_ENABLE 0\n')
|
||||||
|
|
||||||
|
# return status
|
||||||
|
if success:
|
||||||
|
print("Successfully entered LAND mode after battery failsafe")
|
||||||
|
else:
|
||||||
|
print("Failed to neter LAND mode after battery failsafe")
|
||||||
|
|
||||||
|
return success
|
||||||
|
|
||||||
# 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=10):
|
def fly_stability_patch(mavproxy, mav, holdtime=30, maxaltchange=5, maxdistchange=10):
|
||||||
'''hold loiter position'''
|
'''hold loiter position'''
|
||||||
@ -859,6 +889,17 @@ def fly_ArduCopter(viewerip=None, map=False):
|
|||||||
print("takeoff failed")
|
print("takeoff failed")
|
||||||
failed = True
|
failed = True
|
||||||
|
|
||||||
|
# Battery failsafe
|
||||||
|
if not fly_battery_failsafe(mavproxy, mav):
|
||||||
|
print("battery failsafe failed")
|
||||||
|
failed = True
|
||||||
|
|
||||||
|
# Takeoff
|
||||||
|
print("# Takeoff")
|
||||||
|
if not takeoff(mavproxy, mav, 10):
|
||||||
|
print("takeoff failed")
|
||||||
|
failed = True
|
||||||
|
|
||||||
# Stability patch
|
# Stability patch
|
||||||
print("#")
|
print("#")
|
||||||
print("########## Test Stability Patch ##########")
|
print("########## Test Stability Patch ##########")
|
||||||
|
@ -211,11 +211,11 @@ def save_wp(mavproxy, mav):
|
|||||||
mavproxy.send('rc 7 1000\n')
|
mavproxy.send('rc 7 1000\n')
|
||||||
mav.recv_match(condition='RC_CHANNELS_RAW.chan7_raw==1000', blocking=True)
|
mav.recv_match(condition='RC_CHANNELS_RAW.chan7_raw==1000', blocking=True)
|
||||||
|
|
||||||
def wait_mode(mav, mode):
|
def wait_mode(mav, mode, timeout=None):
|
||||||
'''wait for a flight mode to be engaged'''
|
|
||||||
print("Waiting for mode %s" % mode)
|
print("Waiting for mode %s" % mode)
|
||||||
mav.recv_match(condition='MAV.flightmode.upper()=="%s".upper()' % mode, blocking=True)
|
mav.recv_match(condition='MAV.flightmode.upper()=="%s".upper()' % mode, timeout=timeout, blocking=True)
|
||||||
print("Got mode %s" % mode)
|
print("Got mode %s" % mode)
|
||||||
|
return mav.flightmode
|
||||||
|
|
||||||
def mission_count(filename):
|
def mission_count(filename):
|
||||||
'''load a mission from a file and return number of waypoints'''
|
'''load a mission from a file and return number of waypoints'''
|
||||||
|
Loading…
Reference in New Issue
Block a user